SpaceInformation.cpp
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Rice University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Rice University nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #include "ompl/base/SpaceInformation.h"
38 #include <cassert>
39 #include <queue>
40 #include <utility>
41 #include "ompl/base/DiscreteMotionValidator.h"
42 #include "ompl/base/samplers/UniformValidStateSampler.h"
43 #include "ompl/base/spaces/DubinsStateSpace.h"
44 #include "ompl/base/spaces/OwenStateSpace.h"
45 #include "ompl/base/spaces/VanaStateSpace.h"
46 #include "ompl/base/spaces/VanaOwenStateSpace.h"
47 #include "ompl/base/spaces/Dubins3DMotionValidator.h"
48 #include "ompl/base/spaces/ReedsSheppStateSpace.h"
49 #include "ompl/base/spaces/constraint/ConstrainedStateSpace.h"
50 #include "ompl/tools/config/MagicConstants.h"
51 #include "ompl/util/Exception.h"
52 #include "ompl/util/Time.h"
53 
54 ompl::base::SpaceInformation::SpaceInformation(StateSpacePtr space) : stateSpace_(std::move(space)), setup_(false)
55 {
56  if (!stateSpace_)
57  throw Exception("Invalid space definition");
59  params_.include(stateSpace_->params());
60 }
61 
63 {
64  if (!stateValidityChecker_)
65  {
66  stateValidityChecker_ = std::make_shared<AllValidStateValidityChecker>(this);
67  OMPL_WARN("State validity checker not set! No collision checking is performed");
68  }
69 
70  if (!motionValidator_)
71  setDefaultMotionValidator();
72 
73  stateSpace_->setup();
74  if (stateSpace_->getDimension() <= 0)
75  throw Exception("The dimension of the state space we plan in must be > 0");
76 
77  params_.clear();
78  params_.include(stateSpace_->params());
79 
80  setup_ = true;
81 }
82 
84 {
85  return setup_;
86 }
87 
89 {
90  class FnStateValidityChecker : public StateValidityChecker
91  {
92  public:
93  FnStateValidityChecker(SpaceInformation *si, StateValidityCheckerFn fn)
94  : StateValidityChecker(si), fn_(std::move(fn))
95  {
96  }
97 
98  bool isValid(const State *state) const override
99  {
100  return fn_(state);
101  }
102 
103  protected:
105  };
106 
107  if (!svc)
108  throw Exception("Invalid function definition for state validity checking");
109 
110  setStateValidityChecker(std::make_shared<FnStateValidityChecker>(this, svc));
111 }
112 
114 {
115  if (dynamic_cast<ReedsSheppStateSpace *>(stateSpace_.get()))
116  motionValidator_ = std::make_shared<ReedsSheppMotionValidator>(this);
117  else if (dynamic_cast<DubinsStateSpace *>(stateSpace_.get()))
118  motionValidator_ = std::make_shared<DubinsMotionValidator>(this);
119  else if (dynamic_cast<OwenStateSpace *>(stateSpace_.get()))
120  motionValidator_ = std::make_shared<Dubins3DMotionValidator<OwenStateSpace>>(this);
121  else if (dynamic_cast<VanaStateSpace *>(stateSpace_.get()))
122  motionValidator_ = std::make_shared<Dubins3DMotionValidator<VanaStateSpace>>(this);
123  else if (dynamic_cast<VanaOwenStateSpace *>(stateSpace_.get()))
124  motionValidator_ = std::make_shared<Dubins3DMotionValidator<VanaOwenStateSpace>>(this);
125  else if (dynamic_cast<ConstrainedStateSpace *>(stateSpace_.get()))
126  motionValidator_ = std::make_shared<ConstrainedMotionValidator>(this);
127  else
128  motionValidator_ = std::make_shared<DiscreteMotionValidator>(this);
129 }
130 
132 {
133  vssa_ = vssa;
134  setup_ = false;
135 }
136 
138 {
139  vssa_ = ValidStateSamplerAllocator();
140  setup_ = false;
141 }
142 
144  unsigned int steps, std::vector<State *> &states,
145  bool alloc) const
146 {
147  if (alloc)
148  {
149  states.resize(steps);
150  for (unsigned int i = 0; i < steps; ++i)
151  states[i] = allocState();
152  }
153  else if (states.size() < steps)
154  steps = states.size();
155 
156  const State *prev = start;
157  std::pair<State *, double> lastValid;
158  unsigned int j = 0;
159  for (unsigned int i = 0; i < steps; ++i)
160  {
161  sss->sampleUniform(states[j]);
162  lastValid.first = states[j];
163  if (checkMotion(prev, states[j], lastValid) || lastValid.second > std::numeric_limits<double>::epsilon())
164  prev = states[j++];
165  }
166 
167  return j;
168 }
169 
171  const State *near, double distance) const
172 {
173  if (state != near)
174  copyState(state, near);
175 
176  // fix bounds, if needed
177  if (!satisfiesBounds(state))
178  enforceBounds(state);
179 
180  bool result = isValid(state);
181 
182  if (!result)
183  {
184  // try to find a valid state nearby
185  State *temp = cloneState(state);
186  result = sampler->sampleNear(state, temp, distance);
187  freeState(temp);
188  }
189 
190  return result;
191 }
192 
193 bool ompl::base::SpaceInformation::searchValidNearby(State *state, const State *near, double distance,
194  unsigned int attempts) const
195 {
196  if (satisfiesBounds(near) && isValid(near))
197  {
198  if (state != near)
199  copyState(state, near);
200  return true;
201  }
202  else
203  {
204  // try to find a valid state nearby
205  auto uvss = std::make_shared<UniformValidStateSampler>(this);
206  uvss->setNrAttempts(attempts);
207  return searchValidNearby(uvss, state, near, distance);
208  }
209 }
210 
212  std::vector<State *> &states, unsigned int count,
213  bool endpoints, bool alloc) const
214 {
215  // add 1 to the number of states we want to add between s1 & s2. This gives us the number of segments to split the
216  // motion into
217  count++;
218 
219  if (count < 2)
220  {
221  unsigned int added = 0;
222 
223  // if they want endpoints, then at most endpoints are included
224  if (endpoints)
225  {
226  if (alloc)
227  {
228  states.resize(2);
229  states[0] = allocState();
230  states[1] = allocState();
231  }
232  if (states.size() > 0)
233  {
234  copyState(states[0], s1);
235  added++;
236  }
237 
238  if (states.size() > 1)
239  {
240  copyState(states[1], s2);
241  added++;
242  }
243  }
244  else if (alloc)
245  states.resize(0);
246  return added;
247  }
248 
249  if (alloc)
250  {
251  states.resize(count + (endpoints ? 1 : -1));
252  if (endpoints)
253  states[0] = allocState();
254  }
255 
256  unsigned int added = 0;
257 
258  if (endpoints && states.size() > 0)
259  {
260  copyState(states[0], s1);
261  added++;
262  }
263 
264  /* find the states in between */
265  for (unsigned int j = 1; j < count && added < states.size(); ++j)
266  {
267  if (alloc)
268  states[added] = allocState();
269  stateSpace_->interpolate(s1, s2, (double)j / (double)count, states[added]);
270  added++;
271  }
272 
273  if (added < states.size() && endpoints)
274  {
275  if (alloc)
276  states[added] = allocState();
277  copyState(states[added], s2);
278  added++;
279  }
280 
281  return added;
282 }
283 
284 bool ompl::base::SpaceInformation::checkMotion(const std::vector<State *> &states, unsigned int count,
285  unsigned int &firstInvalidStateIndex) const
286 {
287  assert(states.size() >= count);
288  for (unsigned int i = 0; i < count; ++i)
289  if (!isValid(states[i]))
290  {
291  firstInvalidStateIndex = i;
292  return false;
293  }
294  return true;
295 }
296 
297 bool ompl::base::SpaceInformation::checkMotion(const std::vector<State *> &states, unsigned int count) const
298 {
299  assert(states.size() >= count);
300  if (count > 0)
301  {
302  if (count > 1)
303  {
304  if (!isValid(states.front()))
305  return false;
306  if (!isValid(states[count - 1]))
307  return false;
308 
309  // we have 2 or more states, and the first and last states are valid
310 
311  if (count > 2)
312  {
313  std::queue<std::pair<int, int>> pos;
314  pos.emplace(0, count - 1);
315 
316  while (!pos.empty())
317  {
318  std::pair<int, int> x = pos.front();
319 
320  int mid = (x.first + x.second) / 2;
321  if (!isValid(states[mid]))
322  return false;
323 
324  pos.pop();
325 
326  if (x.first < mid - 1)
327  pos.emplace(x.first, mid);
328  if (x.second > mid + 1)
329  pos.emplace(mid, x.second);
330  }
331  }
332  }
333  else
334  return isValid(states.front());
335  }
336  return true;
337 }
338 
340 {
341  if (vssa_)
342  return vssa_(this);
343  else
344  return std::make_shared<UniformValidStateSampler>(this);
345 }
346 
347 double ompl::base::SpaceInformation::probabilityOfValidState(unsigned int attempts) const
348 {
349  if (attempts == 0)
350  return 0.0;
351 
352  unsigned int valid = 0;
353  unsigned int invalid = 0;
354 
355  StateSamplerPtr ss = allocStateSampler();
356  State *s = allocState();
357 
358  for (unsigned int i = 0; i < attempts; ++i)
359  {
360  ss->sampleUniform(s);
361  if (isValid(s))
362  ++valid;
363  else
364  ++invalid;
365  }
366 
367  freeState(s);
368 
369  return (double)valid / (double)(valid + invalid);
370 }
371 
373 {
374  // take the square root here because we in fact have a nested for loop
375  // where each loop executes #attempts steps (the sample() function of the UniformValidStateSampler if a for loop
376  // too)
377  attempts = std::max((unsigned int)floor(sqrt((double)attempts) + 0.5), 2u);
378 
379  StateSamplerPtr ss = allocStateSampler();
380  auto uvss(std::make_shared<UniformValidStateSampler>(this));
381  uvss->setNrAttempts(attempts);
382 
383  State *s1 = allocState();
384  State *s2 = allocState();
385 
386  std::pair<State *, double> lastValid;
387  lastValid.first = nullptr;
388 
389  double d = 0.0;
390  unsigned int count = 0;
391  for (unsigned int i = 0; i < attempts; ++i)
392  if (uvss->sample(s1))
393  {
394  ++count;
395  ss->sampleUniform(s2);
396  if (checkMotion(s1, s2, lastValid))
397  d += distance(s1, s2);
398  else
399  d += distance(s1, s2) * lastValid.second;
400  }
401 
402  freeState(s2);
403  freeState(s1);
404 
405  if (count > 0)
406  return d / (double)count;
407  else
408  return 0.0;
409 }
410 
411 void ompl::base::SpaceInformation::samplesPerSecond(double &uniform, double &near, double &gaussian,
412  unsigned int attempts) const
413 {
414  StateSamplerPtr ss = allocStateSampler();
415  std::vector<State *> states(attempts + 1);
416  allocStates(states);
417 
418  time::point start = time::now();
419  for (unsigned int i = 0; i < attempts; ++i)
420  ss->sampleUniform(states[i]);
421  uniform = (double)attempts / time::seconds(time::now() - start);
422 
423  double d = getMaximumExtent() / 10.0;
424  ss->sampleUniform(states[attempts]);
425 
426  start = time::now();
427  for (unsigned int i = 1; i <= attempts; ++i)
428  ss->sampleUniformNear(states[i - 1], states[i], d);
429  near = (double)attempts / time::seconds(time::now() - start);
430 
431  start = time::now();
432  for (unsigned int i = 1; i <= attempts; ++i)
433  ss->sampleGaussian(states[i - 1], states[i], d);
434  gaussian = (double)attempts / time::seconds(time::now() - start);
435 
436  freeStates(states);
437 }
438 
439 void ompl::base::SpaceInformation::printSettings(std::ostream &out) const
440 {
441  out << "Settings for the state space '" << stateSpace_->getName() << "'" << std::endl;
442  out << " - state validity check resolution: " << (getStateValidityCheckingResolution() * 100.0) << '%'
443  << std::endl;
444  out << " - valid segment count factor: " << stateSpace_->getValidSegmentCountFactor() << std::endl;
445  out << " - state space:" << std::endl;
446  stateSpace_->printSettings(out);
447  out << std::endl << "Declared parameters:" << std::endl;
448  params_.print(out);
449  ValidStateSamplerPtr vss = allocValidStateSampler();
450  out << "Valid state sampler named " << vss->getName() << " with parameters:" << std::endl;
451  vss->params().print(out);
452 }
453 
455 {
456  out << "Properties of the state space '" << stateSpace_->getName() << "'" << std::endl;
457  out << " - signature: ";
458  std::vector<int> sig;
459  stateSpace_->computeSignature(sig);
460  for (int i : sig)
461  out << i << " ";
462  out << std::endl;
463  out << " - dimension: " << stateSpace_->getDimension() << std::endl;
464  out << " - extent: " << stateSpace_->getMaximumExtent() << std::endl;
465  if (isSetup())
466  {
467  bool result = true;
468  try
469  {
470  stateSpace_->sanityChecks();
471  }
472  catch (Exception &e)
473  {
474  result = false;
475  out << std::endl
476  << " - SANITY CHECKS FOR STATE SPACE ***DID NOT PASS*** (" << e.what() << ")" << std::endl
477  << std::endl;
478  OMPL_ERROR(e.what());
479  }
480  if (result)
481  out << " - sanity checks for state space passed" << std::endl;
482  out << " - probability of valid states: " << probabilityOfValidState(magic::TEST_STATE_COUNT) << std::endl;
483  out << " - average length of a valid motion: " << averageValidMotionLength(magic::TEST_STATE_COUNT)
484  << std::endl;
485  double uniform, near, gaussian;
486  samplesPerSecond(uniform, near, gaussian, magic::TEST_STATE_COUNT);
487  out << " - average number of samples drawn per second: sampleUniform()=" << uniform
488  << " sampleUniformNear()=" << near << " sampleGaussian()=" << gaussian << std::endl;
489  }
490  else
491  out << "Call setup() before to get more information" << std::endl;
492 }
The base class for space information. This contains all the information about the space planning is d...
static const unsigned int TEST_STATE_COUNT
When multiple states need to be generated as part of the computation of various information (usually ...
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves.
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition: Time.h:116
virtual unsigned int getMotionStates(const State *s1, const State *s2, std::vector< State * > &states, unsigned int count, bool endpoints, bool alloc) const
Get count states that make up a motion between s1 and s2. Returns the number of states that were adde...
An R^4 x SO(2) state space where distance is measured by the length of a type of Dubins airplane curv...
Definition of an abstract state.
Definition: State.h:113
virtual bool checkMotion(const State *s1, const State *s2, std::pair< State *, double > &lastValid) const
Incrementally check if the path between two motions is valid. Also compute the last state that was va...
void setDefaultMotionValidator()
Set default motion validator for the state space.
A 3D Dubins plane motion validator that only uses the state validity checker. Motions are checked for...
double averageValidMotionLength(unsigned int attempts) const
Estimate the length of a valid motion. setup() is assumed to have been called.
StateSpacePtr stateSpace_
The state space planning is to be performed in.
point now()
Get the current time point.
Definition: Time.h:122
void clearValidStateSamplerAllocator()
Clear the allocator used for the valid state sampler. This will revert to using the uniform valid sta...
std::function< ValidStateSamplerPtr(const SpaceInformation *)> ValidStateSamplerAllocator
Definition of a function that can allocate a valid state sampler.
double probabilityOfValidState(unsigned int attempts) const
Estimate probability of sampling a valid state. setup() is assumed to have been called.
An R^4 x SO(2) state space where distance is measured by the length of a type Dubins airplane curves.
An SE(2) state space where distance is measured by the length of Dubins curves.
void samplesPerSecond(double &uniform, double &near, double &gaussian, unsigned int attempts) const
Estimate the number of samples that can be drawn per second, using the sampler returned by allocState...
A StateSpace that has a Constraint imposed upon it. Underlying space functions are passed to the ambi...
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
unsigned int randomBounceMotion(const StateSamplerPtr &sss, const State *start, unsigned int steps, std::vector< State * > &states, bool alloc) const
Produce a valid motion starting at start by randomly bouncing off of invalid states....
An R^3 x SO(2) state space where distance is measured by the length of a type Dubins airplane curves.
virtual void printSettings(std::ostream &out=std::cout) const
Print information about the current instance of the state space.
void setValidStateSamplerAllocator(const ValidStateSamplerAllocator &vssa)
Set the allocator to use for a valid state sampler. This replaces the default uniform valid state sam...
void setStateValidityChecker(const StateValidityCheckerPtr &svc)
Set the instance of the state validity checker to use. Parallel implementations of planners assume th...
std::function< bool(const State *)> StateValidityCheckerFn
If no state validity checking class is specified (StateValidityChecker), a std::function can be speci...
ParamSet params_
Combined parameters for the contained classes.
virtual void printProperties(std::ostream &out=std::cout) const
Print properties of the current instance of the state space.
ValidStateSamplerPtr allocValidStateSampler() const
Allocate an instance of a valid state sampler for this space. If setValidStateSamplerAllocator() was ...
A shared pointer wrapper for ompl::base::StateSpace.
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
A shared pointer wrapper for ompl::base::StateSampler.
bool searchValidNearby(State *state, const State *near, double distance, unsigned int attempts) const
Find a valid state near a given one. If the given state is valid, it will be returned itself....
A shared pointer wrapper for ompl::base::ValidStateSampler.
virtual void setup()
Perform additional setup tasks (run once, before use). If state validity checking resolution has not ...
The exception type for ompl.
Definition: Exception.h:78
Abstract definition for a class checking the validity of states. The implementation of this class mus...
bool isSetup() const
Return true if setup was called.
duration seconds(double sec)
Return the time duration representing a given number of seconds.
Definition: Time.h:128
void include(const ParamSet &other, const std::string &prefix="")
Include the params of a different ParamSet into this one. Optionally include a prefix for each of the...