Loading...
Searching...
No Matches
ompl::geometric::pSBL Class Reference

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

#include <ompl/geometric/planners/sbl/pSBL.h>

Inheritance diagram for ompl::geometric::pSBL:

Classes

class  Motion
struct  MotionInfo
 A struct containing an array of motions and a corresponding PDF element. More...
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 () const
 Get the projection evaluator.
void setRange (double distance)
 Set the range the planner is supposed to use.
double getRange () 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 () const
 Get the thread count.
void setup () override
 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.
base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc) override
 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 for 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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.
void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
void getPlannerData (base::PlannerData &data) const override
 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).
Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
Planneroperator= (const Planner &)=delete
 Planner (SpaceInformationPtr si, std::string name)
 Constructor.
virtual ~Planner ()=default
 Destructor.
template<class T>
T * as ()
 Cast this instance to a desired type.
template<class T>
const T * as () const
 Cast this instance to a desired type.
const SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using.
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
const PlannerInputStatesgetPlannerInputStates () const
 Get the planner input states.
virtual void setProblemDefinition (const ProblemDefinitionPtr &pdef)
 Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear() or clearQuery().
PlannerStatus solve (const PlannerTerminationConditionFn &ptc, double checkInterval)
 Same as above except the termination condition is only evaluated at a specified interval.
PlannerStatus solve (double solveTime)
 Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning.
virtual void clearQuery ()
 Clears internal datastructures of any query-specific information from the previous query. Planner settings are not affected. The planner, if able, should retain all datastructures generated from previous queries that can be used to help solve the next query. Note that clear() should also clear all query-specific information along with all other datastructures in the planner. By default clearQuery() calls clear().
const std::string & getName () const
 Get the name of the planner.
void setName (const std::string &name)
 Set the name of the planner.
const PlannerSpecsgetSpecs () const
 Return the specifications (capabilities of this planner)
virtual void checkValidity ()
 Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception.
bool isSetup () const
 Check if setup() was called for this planner.
ParamSetparams ()
 Get the parameters for this planner.
const ParamSetparams () const
 Get the parameters for this planner.
const PlannerProgressPropertiesgetPlannerProgressProperties () const
 Retrieve a planner's planner progress property map.
virtual void printProperties (std::ostream &out) const
 Print properties of the motion planner.
virtual void printSettings (std::ostream &out) const
 Print information about the motion planner's settings.

Protected Types

using GridCell = Grid<MotionInfo>::Cell
 A grid cell.
using CellPDF = PDF<GridCell *>
 A PDF of grid cells.

Protected Member Functions

void threadSolve (unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol)
void freeMemory ()
void freeGridMotions (Grid< MotionInfo > &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 Member Functions inherited from ompl::base::Planner
template<typename T, typename PlannerType, typename SetterType, typename GetterType>
void declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const GetterType &getter, const std::string &rangeSuggestion="")
 This function declares a parameter for this planner instance, and specifies the setter and getter functions.
template<typename T, typename PlannerType, typename SetterType>
void declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const std::string &rangeSuggestion="")
 This function declares a parameter for this planner instance, and specifies the setter function.
void addPlannerProgressProperty (const std::string &progressPropertyName, const PlannerProgressProperty &prop)
 Add a planner progress property called progressPropertyName with a property querying function prop to this planner's progress property map.

Protected Attributes

base::StateSamplerArray< base::ValidStateSamplersamplerArray_
base::ProjectionEvaluatorPtr projectionEvaluator_
TreeData tStart_
TreeData tGoal_
MotionsToBeRemoved removeList_
std::mutex loopLock_
std::mutex loopLockCounter_
unsigned int loopCounter_
double maxDistance_ {0.}
unsigned int threadCount_
std::pair< base::State *, base::State * > connectionPoint_ {nullptr, nullptr}
 The pair of states in each tree connected during planning. Used for PlannerData computation.
Protected Attributes inherited from ompl::base::Planner
SpaceInformationPtr si_
 The space information for which planning is done.
ProblemDefinitionPtr pdef_
 The user set problem definition.
PlannerInputStates pis_
 Utility class to extract valid input states.
std::string name_
 The name of this planner.
PlannerSpecs specs_
 The specifications of the planner (its capabilities)
ParamSet params_
 A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function.
PlannerProgressProperties plannerProgressProperties_
 A mapping between this planner's progress property names and the functions used for querying those progress properties.
bool setup_
 Flag indicating whether setup() has been called.

Additional Inherited Members

Public Types inherited from ompl::base::Planner
using PlannerProgressProperty = std::function<std::string()>
 Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine.
using PlannerProgressProperties = std::map<std::string, PlannerProgressProperty>
 A dictionary which maps the name of a progress property to the function to be used for querying that property.

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

Member Typedef Documentation

◆ CellPDF

A PDF of grid cells.

Definition at line 154 of file pSBL.h.

◆ GridCell

A grid cell.

Definition at line 151 of file pSBL.h.

Constructor & Destructor Documentation

◆ pSBL()

ompl::geometric::pSBL::pSBL ( const base::SpaceInformationPtr & si)

Definition at line 43 of file pSBL.cpp.

◆ ~pSBL()

ompl::geometric::pSBL::~pSBL ( )
override

Definition at line 53 of file pSBL.cpp.

Member Function Documentation

◆ addMotion()

void ompl::geometric::pSBL::addMotion ( TreeData & tree,
Motion * motion )
protected

Definition at line 429 of file pSBL.cpp.

◆ checkSolution()

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

Definition at line 259 of file pSBL.cpp.

◆ clear()

void ompl::geometric::pSBL::clear ( )
overridevirtual

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

Reimplemented from ompl::base::Planner.

Definition at line 69 of file pSBL.cpp.

◆ freeGridMotions()

void ompl::geometric::pSBL::freeGridMotions ( Grid< MotionInfo > & grid)
protected

Definition at line 89 of file pSBL.cpp.

◆ freeMemory()

void ompl::geometric::pSBL::freeMemory ( )
inlineprotected

Definition at line 238 of file pSBL.h.

◆ getPlannerData()

void ompl::geometric::pSBL::getPlannerData ( base::PlannerData & data) const
overridevirtual

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.

Definition at line 451 of file pSBL.cpp.

◆ getProjectionEvaluator()

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

Get the projection evaluator.

Definition at line 108 of file pSBL.h.

◆ getRange()

double ompl::geometric::pSBL::getRange ( ) const
inline

Get the range the planner is using.

Definition at line 124 of file pSBL.h.

◆ getThreadCount()

unsigned int ompl::geometric::pSBL::getThreadCount ( ) const
inline

Get the thread count.

Definition at line 133 of file pSBL.h.

◆ isPathValid()

bool ompl::geometric::pSBL::isPathValid ( TreeData & tree,
Motion * motion )
protected

Definition at line 328 of file pSBL.cpp.

◆ removeMotion()

void ompl::geometric::pSBL::removeMotion ( TreeData & tree,
Motion * motion,
std::map< Motion *, bool > & seen )
protected

Definition at line 376 of file pSBL.cpp.

◆ selectMotion()

ompl::geometric::pSBL::Motion * ompl::geometric::pSBL::selectMotion ( RNG & rng,
TreeData & tree )
protected

Definition at line 367 of file pSBL.cpp.

◆ setProjectionEvaluator() [1/2]

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

◆ setProjectionEvaluator() [2/2]

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

◆ setRange()

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

◆ setThreadCount()

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

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

Definition at line 480 of file pSBL.cpp.

◆ setup()

void ompl::geometric::pSBL::setup ( )
overridevirtual

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.

Definition at line 58 of file pSBL.cpp.

◆ solve()

ompl::base::PlannerStatus ompl::geometric::pSBL::solve ( const base::PlannerTerminationCondition & ptc)
overridevirtual

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 for 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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.

Implements ompl::base::Planner.

Definition at line 188 of file pSBL.cpp.

◆ threadSolve()

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

Definition at line 102 of file pSBL.cpp.

Member Data Documentation

◆ connectionPoint_

std::pair<base::State *, base::State *> ompl::geometric::pSBL::connectionPoint_ {nullptr, nullptr}
protected

The pair of states in each tree connected during planning. Used for PlannerData computation.

Definition at line 269 of file pSBL.h.

◆ loopCounter_

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

Definition at line 262 of file pSBL.h.

◆ loopLock_

std::mutex ompl::geometric::pSBL::loopLock_
protected

Definition at line 260 of file pSBL.h.

◆ loopLockCounter_

std::mutex ompl::geometric::pSBL::loopLockCounter_
protected

Definition at line 261 of file pSBL.h.

◆ maxDistance_

double ompl::geometric::pSBL::maxDistance_ {0.}
protected

Definition at line 264 of file pSBL.h.

◆ projectionEvaluator_

base::ProjectionEvaluatorPtr ompl::geometric::pSBL::projectionEvaluator_
protected

Definition at line 254 of file pSBL.h.

◆ removeList_

MotionsToBeRemoved ompl::geometric::pSBL::removeList_
protected

Definition at line 259 of file pSBL.h.

◆ samplerArray_

base::StateSamplerArray<base::ValidStateSampler> ompl::geometric::pSBL::samplerArray_
protected

Definition at line 253 of file pSBL.h.

◆ tGoal_

TreeData ompl::geometric::pSBL::tGoal_
protected

Definition at line 257 of file pSBL.h.

◆ threadCount_

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

Definition at line 266 of file pSBL.h.

◆ tStart_

TreeData ompl::geometric::pSBL::tStart_
protected

Definition at line 256 of file pSBL.h.


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