|
| 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. More...
|
|
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).
|
|
| Planner (const Planner &)=delete |
|
Planner & | operator= (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. More...
|
|
template<class T > |
const T * | as () const |
| Cast this instance to a desired type. More...
|
|
const SpaceInformationPtr & | getSpaceInformation () const |
| Get the space information this planner is using.
|
|
const ProblemDefinitionPtr & | getProblemDefinition () const |
| Get the problem definition the planner is trying to solve.
|
|
ProblemDefinitionPtr & | getProblemDefinition () |
| Get the problem definition the planner is trying to solve.
|
|
const PlannerInputStates & | getPlannerInputStates () 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 PlannerSpecs & | getSpecs () 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.
|
|
ParamSet & | params () |
| Get the parameters for this planner.
|
|
const ParamSet & | params () const |
| Get the parameters for this planner.
|
|
const PlannerProgressProperties & | getPlannerProgressProperties () 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.
|
|
|
void | threadSolve (unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol) |
|
void | freeMemory () |
|
void | freeGridMotions (Grid< MotionInfo > &grid) |
|
void | addMotion (TreeData &tree, Motion *motion) |
|
Motion * | selectMotion (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) |
|
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.
|
|
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 150 of file pSBL.h.