ompl::geometric::pSBL Class Reference

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

#include <pSBL.h>

Inheritance diagram for ompl::geometric::pSBL:
Inheritance graph
[legend]

List of all members.

Classes

class  Motion
struct  MotionsToBeRemoved
struct  PendingRemoveMotion
struct  SolutionInfo
struct  TreeData

Public Member Functions

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).
const
base::ProjectionEvaluatorPtr
getProjectionEvaluator (void) const
 Get the projection evaluator.
double getRange (void) const
 Get the range the planner is using.
unsigned int getThreadCount (void) const
 Get the thread count.
 pSBL (const base::SpaceInformationPtr &si)
void setProjectionEvaluator (const std::string &name)
 Set the projection evaluator (select one from the ones registered with the state space).
void setProjectionEvaluator (const base::ProjectionEvaluatorPtr &projectionEvaluator)
 Set the projection evaluator. This class is able to compute the projection of a given state.
void setRange (double distance)
 Set the range the planner is supposed to use.
void setThreadCount (unsigned int nthreads)
 Set the number of threads the planner should use. Default is 2.
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 ~pSBL (void)

Protected Types

typedef std::vector< Motion * > MotionSet

Protected Member Functions

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

Protected Attributes

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

Detailed Description

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

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 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.
External documentation
G. Sánchez and J.-C. Latombe, A single-query bi-directional probabilistic roadmap planner with lazy collision checking, in The Tenth International Symposium on Robotics Research, pp. 403–417, 2001. DOI: 10.1007/3-540-36460-9_27
[PDF]

Definition at line 88 of file pSBL.h.


Member Typedef Documentation

typedef std::vector<Motion*> ompl::geometric::pSBL::MotionSet [protected]

Definition at line 160 of file pSBL.h.


Constructor & Destructor Documentation

ompl::geometric::pSBL::pSBL ( const base::SpaceInformationPtr si  )  [inline]

Definition at line 92 of file pSBL.h.

virtual ompl::geometric::pSBL::~pSBL ( void   )  [inline, virtual]

Definition at line 100 of file pSBL.h.


Member Function Documentation

void ompl::geometric::pSBL::addMotion ( TreeData tree,
Motion motion 
) [protected]
bool ompl::geometric::pSBL::checkSolution ( RNG rng,
bool  start,
TreeData tree,
TreeData otherTree,
Motion motion,
std::vector< Motion * > &  solution 
) [protected]
virtual void ompl::geometric::pSBL::clear ( void   )  [virtual]

Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.

Reimplemented from ompl::base::Planner.

void ompl::geometric::pSBL::freeGridMotions ( Grid< MotionSet > &  grid  )  [protected]
void ompl::geometric::pSBL::freeMemory ( void   )  [inline, protected]

Definition at line 219 of file pSBL.h.

virtual void ompl::geometric::pSBL::getPlannerData ( base::PlannerData data  )  const [virtual]

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).

Reimplemented from ompl::base::Planner.

const base::ProjectionEvaluatorPtr& ompl::geometric::pSBL::getProjectionEvaluator ( void   )  const [inline]

Get the projection evaluator.

Definition at line 120 of file pSBL.h.

double ompl::geometric::pSBL::getRange ( void   )  const [inline]

Get the range the planner is using.

Definition at line 136 of file pSBL.h.

unsigned int ompl::geometric::pSBL::getThreadCount ( void   )  const [inline]

Get the thread count.

Definition at line 145 of file pSBL.h.

bool ompl::geometric::pSBL::isPathValid ( TreeData tree,
Motion motion 
) [protected]
void ompl::geometric::pSBL::removeMotion ( TreeData tree,
Motion motion,
std::map< Motion *, bool > &  seen 
) [protected]
Motion* ompl::geometric::pSBL::selectMotion ( RNG rng,
TreeData tree 
) [protected]
void ompl::geometric::pSBL::setProjectionEvaluator ( const std::string &  name  )  [inline]

Set the projection evaluator (select one from the ones registered with the state space).

Definition at line 114 of file pSBL.h.

void ompl::geometric::pSBL::setProjectionEvaluator ( const base::ProjectionEvaluatorPtr projectionEvaluator  )  [inline]

Set the projection evaluator. This class is able to compute the projection of a given state.

Definition at line 107 of file pSBL.h.

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 130 of file pSBL.h.

void ompl::geometric::pSBL::setThreadCount ( unsigned int  nthreads  ) 

Set the number of threads the planner should use. Default is 2.

virtual void ompl::geometric::pSBL::setup ( void   )  [virtual]

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.

Reimplemented from ompl::base::Planner.

virtual bool ompl::geometric::pSBL::solve ( const base::PlannerTerminationCondition ptc  )  [virtual]

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.

Implements ompl::base::Planner.

void ompl::geometric::pSBL::threadSolve ( unsigned int  tid,
const base::PlannerTerminationCondition ptc,
SolutionInfo sol 
) [protected]

Member Data Documentation

unsigned int ompl::geometric::pSBL::loopCounter_ [protected]

Definition at line 243 of file pSBL.h.

boost::mutex ompl::geometric::pSBL::loopLock_ [protected]

Definition at line 241 of file pSBL.h.

boost::mutex ompl::geometric::pSBL::loopLockCounter_ [protected]

Definition at line 242 of file pSBL.h.

Definition at line 245 of file pSBL.h.

Definition at line 235 of file pSBL.h.

Definition at line 240 of file pSBL.h.

Definition at line 234 of file pSBL.h.

Definition at line 238 of file pSBL.h.

unsigned int ompl::geometric::pSBL::threadCount_ [protected]

Definition at line 247 of file pSBL.h.

Definition at line 237 of file pSBL.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:34:03 2013