ompl::geometric::SBL Class Reference

Single-Query Bi-Directional Probabilistic Roadmap Planner with Lazy Collision Checking. More...

#include <SBL.h>

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

List of all members.

Classes

class  Motion
 Representation of a motion. More...
struct  TreeData
 Representation of a search tree. Two instances will be used. One for start and one for goal. More...

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.
 SBL (const base::SpaceInformationPtr &si)
 The constructor needs the instance of the space information.
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.
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 ~SBL (void)

Protected Types

typedef std::vector< Motion * > MotionSet
 An array of motions.

Protected Member Functions

void addMotion (TreeData &tree, Motion *motion)
 Add a motion to a tree.
bool checkSolution (bool start, TreeData &tree, TreeData &otherTree, Motion *motion, std::vector< Motion * > &solution)
 Check if a solution can be obtained by connecting two trees using a specified motion.
void freeGridMotions (Grid< MotionSet > &grid)
 Free the memory used by the motions contained in a grid.
void freeMemory (void)
 Free the memory allocated by the planner.
bool isPathValid (TreeData &tree, Motion *motion)
 Since solutions are computed in a lazy fashion, once trees are connected, the solution found needs to be checked for validity. This function checks whether the reverse path from a given motion to a root is valid. If this is not the case, invalid motions are removed.
void removeMotion (TreeData &tree, Motion *motion)
 Remove a motion from a tree.
MotionselectMotion (TreeData &tree)
 Select a motion from a tree.

Protected Attributes

double maxDistance_
 The maximum length of a motion to be added in the tree.
base::ProjectionEvaluatorPtr projectionEvaluator_
 The employed projection evaluator.
RNG rng_
 The random number generator to be used.
base::ValidStateSamplerPtr sampler_
 The employed state sampler.
TreeData tGoal_
 The goal tree.
TreeData tStart_
 The start tree.

Detailed Description

Single-Query Bi-Directional Probabilistic Roadmap Planner with Lazy Collision Checking.

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 86 of file SBL.h.


Member Typedef Documentation

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

An array of motions.

Definition at line 149 of file SBL.h.


Constructor & Destructor Documentation

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

The constructor needs the instance of the space information.

Definition at line 91 of file SBL.h.

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

Definition at line 98 of file SBL.h.


Member Function Documentation

void ompl::geometric::SBL::addMotion ( TreeData tree,
Motion motion 
) [protected]

Add a motion to a tree.

bool ompl::geometric::SBL::checkSolution ( bool  start,
TreeData tree,
TreeData otherTree,
Motion motion,
std::vector< Motion * > &  solution 
) [protected]

Check if a solution can be obtained by connecting two trees using a specified motion.

virtual void ompl::geometric::SBL::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::SBL::freeGridMotions ( Grid< MotionSet > &  grid  )  [protected]

Free the memory used by the motions contained in a grid.

void ompl::geometric::SBL::freeMemory ( void   )  [inline, protected]

Free the memory allocated by the planner.

Definition at line 204 of file SBL.h.

virtual void ompl::geometric::SBL::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::SBL::getProjectionEvaluator ( void   )  const [inline]

Get the projection evaluator.

Definition at line 118 of file SBL.h.

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

Get the range the planner is using.

Definition at line 134 of file SBL.h.

bool ompl::geometric::SBL::isPathValid ( TreeData tree,
Motion motion 
) [protected]

Since solutions are computed in a lazy fashion, once trees are connected, the solution found needs to be checked for validity. This function checks whether the reverse path from a given motion to a root is valid. If this is not the case, invalid motions are removed.

void ompl::geometric::SBL::removeMotion ( TreeData tree,
Motion motion 
) [protected]

Remove a motion from a tree.

Motion* ompl::geometric::SBL::selectMotion ( TreeData tree  )  [protected]

Select a motion from a tree.

void ompl::geometric::SBL::setProjectionEvaluator ( const std::string &  name  )  [inline]

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

Definition at line 112 of file SBL.h.

void ompl::geometric::SBL::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 105 of file SBL.h.

void ompl::geometric::SBL::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 128 of file SBL.h.

virtual void ompl::geometric::SBL::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::SBL::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.


Member Data Documentation

The maximum length of a motion to be added in the tree.

Definition at line 245 of file SBL.h.

The employed projection evaluator.

Definition at line 236 of file SBL.h.

The random number generator to be used.

Definition at line 248 of file SBL.h.

The employed state sampler.

Definition at line 233 of file SBL.h.

The goal tree.

Definition at line 242 of file SBL.h.

The start tree.

Definition at line 239 of file SBL.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