All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator

Parallel Single-query Bi-directional Lazy collision checking planner. More...

#include <pSBL.h>

Inheritance diagram for ompl::geometric::pSBL:

List of all members.

Classes

class  Motion
struct  MotionsToBeRemoved
struct  PendingRemoveMotion
struct  SolutionInfo
struct  TreeData

Public Member Functions

 pSBL (const base::SpaceInformationPtr &si)
void setProjectionEvaluator (const base::ProjectionEvaluatorPtr &projectionEvaluator)
 Set the projection evaluator. This class is able to compute the projection of a given state.
void setProjectionEvaluator (const std::string &name)
 Set the projection evaluator (select one from the ones registered with the state space).
const
base::ProjectionEvaluatorPtr
getProjectionEvaluator (void) const
 Get the projection evaluator.
void setRange (double distance)
 Set the range the planner is supposed to use.
double getRange (void) const
 Get the range the planner is using.
void setThreadCount (unsigned int nthreads)
 Set the number of threads the planner should use. Default is 2.
unsigned int getThreadCount (void) const
 Get the thread count.
virtual void setup (void)
 Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving.
virtual bool solve (const base::PlannerTerminationCondition &ptc)
 Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). The function terminates if the call to ptc returns true.
virtual void clear (void)
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
virtual void getPlannerData (base::PlannerData &data) const
 Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).

Protected Types

typedef std::vector< Motion * > MotionSet

Protected Member Functions

void threadSolve (unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol)
void freeMemory (void)
void freeGridMotions (Grid< MotionSet > &grid)
void addMotion (TreeData &tree, Motion *motion)
MotionselectMotion (RNG &rng, TreeData &tree)
void removeMotion (TreeData &tree, Motion *motion, std::map< Motion *, bool > &seen)
bool isPathValid (TreeData &tree, Motion *motion)
bool checkSolution (RNG &rng, bool start, TreeData &tree, TreeData &otherTree, Motion *motion, std::vector< Motion * > &solution)

Protected Attributes

base::StateSamplerArray
< base::ValidStateSampler
samplerArray_
base::ProjectionEvaluatorPtr projectionEvaluator_
TreeData tStart_
TreeData tGoal_
MotionsToBeRemoved removeList_
boost::mutex loopLock_
boost::mutex loopLockCounter_
unsigned int loopCounter_
double maxDistance_
unsigned int threadCount_

Detailed Description

Parallel Single-query Bi-directional Lazy collision checking planner.

      @par Short description
      SBL is a tree-based motion planner that attempts to grow two
      trees at once: one grows from the starting state and the other
      from the goal state. The tree expansion strategy is the same as for \ref gEST "EST".
      Attempts are made to connect these trees
      at every step of the expansion. If they are connected, a
      solution path is obtained. However, this solution path is not
      certain to be valid (the lazy part of the algorithm) so it is
      checked for validity. If invalid parts are found, they are
      removed from the tree and exploration of the state space
      continues until a solution is found.
      To guide the exploration, an additional grid data
      structure is maintained. Grid cells contain states that
      have been previously visited. When deciding which state to
      use for further expansion, this grid is used;
      least-filled grid cells have most chances of being selected. The
      grid is usually imposed on a projection of the state
      space. This projection needs to be set before using the
      planner (setProjectionEvaluator() function). Connection of states in different trees is
      attempted if they fall in the same grid cell. If no projection is
      set, the planner will attempt to use the default projection
      associated to the state space. An exception is thrown if
      no default projection is available either.

      @par External documentation
      G. Sánchez and J.-C. Latombe, A single-query bi-directional probabilistic roadmap planner with lazy collision checking, in <em>The Tenth International Symposium on Robotics Research</em>, pp. 403–417, 2001.
      DOI: <a href="http://dx.doi.org/10.1007/3-540-36460-9_27">10.1007/3-540-36460-9_27</a><br>
      <a href="http://www.springerlink.com/content/9843341054386hh6/fulltext.pdf">[PDF]</a>

Definition at line 88 of file pSBL.h.


Member Function Documentation

void ompl::geometric::pSBL::setRange ( double  distance) [inline]

Set the range the planner is supposed to use.

This parameter greatly influences the runtime of the algorithm. It represents the maximum length of a motion to be added in the tree of motions.

Definition at line 131 of file pSBL.h.


The documentation for this class was generated from the following files:
  • src/ompl/geometric/planners/sbl/pSBL.h
  • src/ompl/geometric/planners/sbl/src/pSBL.cpp