Base class for a planner.
More...
#include <ompl/base/Planner.h>
Inherited by RandomWalkPlanner.RandomWalkPlanner, ompl::control::EST, ompl::control::HyRRT, ompl::control::HySST, ompl::control::KPIECE1, ompl::control::LTLPlanner, ompl::control::PDST, ompl::control::RRT, ompl::control::SST, ompl::control::Syclop, ompl::geometric::AITstar, ompl::geometric::AORRTC, ompl::geometric::AOXRRTConnect, ompl::geometric::ATRRT, ompl::geometric::AnytimePathShortening, ompl::geometric::BFMT, ompl::geometric::BITstar, ompl::geometric::BKPIECE1, ompl::geometric::BLITstar, ompl::geometric::BiEST, ompl::geometric::BiRLRT, ompl::geometric::BiTRRT, ompl::geometric::CForest, ompl::geometric::EITstar, ompl::geometric::EST, ompl::geometric::FMT, ompl::geometric::KPIECE1, ompl::geometric::LBKPIECE1, ompl::geometric::LBTRRT, ompl::geometric::LazyLBTRRT, ompl::geometric::LazyPRM, ompl::geometric::LazyRRT, ompl::geometric::LightningRetrieveRepair, ompl::geometric::PDST, ompl::geometric::PRM, ompl::geometric::ProjEST, ompl::geometric::RLRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::RRTXstatic, ompl::geometric::RRTstar, ompl::geometric::SBL, ompl::geometric::SPARS, ompl::geometric::SPARSdb, ompl::geometric::SPARStwo, ompl::geometric::SST, ompl::geometric::STRIDE, ompl::geometric::STRRTstar, ompl::geometric::TRRT, ompl::geometric::TRRTstar, ompl::geometric::TSRRT, ompl::geometric::ThunderRetrieveRepair, ompl::geometric::XXL, ompl::geometric::pRRT, ompl::geometric::pSBL, ompl::multilevel::BundleSpace, and ompl::multilevel::PlannerMultiLevel.
|
| 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.
|
|
|
| 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.
|
| template<class T> |
| const T * | as () const |
| | Cast this instance to a desired type.
|
| 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().
|
| virtual PlannerStatus | solve (const PlannerTerminationCondition &ptc)=0 |
| | 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.
|
| 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 | clear () |
| | Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
|
| 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().
|
| virtual void | getPlannerData (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 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 | setup () |
| | 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 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.
|
|
| 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.
|
Base class for a planner.
Definition at line 215 of file Planner.h.
◆ PlannerProgressProperties
A dictionary which maps the name of a progress property to the function to be used for querying that property.
Definition at line 353 of file Planner.h.
◆ PlannerProgressProperty
Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine.
Definition at line 349 of file Planner.h.
◆ Planner()
◆ addPlannerProgressProperty()
| void ompl::base::Planner::addPlannerProgressProperty |
( |
const std::string & | progressPropertyName, |
|
|
const PlannerProgressProperty & | prop ) |
|
inlineprotected |
Add a planner progress property called progressPropertyName with a property querying function prop to this planner's progress property map.
Definition at line 394 of file Planner.h.
◆ as() [1/2]
template<class T>
| T * ompl::base::Planner::as |
( |
| ) |
|
|
inline |
Cast this instance to a desired type.
Make sure the type we are casting to is indeed a planner
Definition at line 230 of file Planner.h.
◆ as() [2/2]
template<class T>
| const T * ompl::base::Planner::as |
( |
| ) |
const |
|
inline |
Cast this instance to a desired type.
Make sure the type we are casting to is indeed a Planner
Definition at line 240 of file Planner.h.
◆ checkValidity()
| void ompl::base::Planner::checkValidity |
( |
| ) |
|
|
virtual |
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.
Reimplemented in ompl::geometric::AnytimePathShortening.
Definition at line 106 of file Planner.cpp.
◆ clear()
| void ompl::base::Planner::clear |
( |
| ) |
|
|
virtual |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
Reimplemented in ompl::control::EST, ompl::control::HyRRT, ompl::control::HySST, ompl::control::KPIECE1, ompl::control::LTLPlanner, ompl::control::PDST, ompl::control::RRT, ompl::control::SST, ompl::control::Syclop, ompl::control::SyclopEST, ompl::control::SyclopRRT, ompl::geometric::AITstar, ompl::geometric::AnytimePathShortening, ompl::geometric::AORRTC, ompl::geometric::ATRRT, ompl::geometric::BFMT, ompl::geometric::BiEST, ompl::geometric::BiRLRT, ompl::geometric::BiTRRT, ompl::geometric::BITstar, ompl::geometric::BKPIECE1, ompl::geometric::BLITstar, ompl::geometric::CForest, ompl::geometric::EITstar, ompl::geometric::EST, ompl::geometric::FMT, ompl::geometric::KPIECE1, ompl::geometric::LazyLBTRRT, ompl::geometric::LazyPRM, ompl::geometric::LazyRRT, ompl::geometric::LBKPIECE1, ompl::geometric::LBTRRT, ompl::geometric::LightningRetrieveRepair, ompl::geometric::PDST, ompl::geometric::PRM, ompl::geometric::ProjEST, ompl::geometric::pRRT, ompl::geometric::pSBL, ompl::geometric::RLRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::RRTstar, ompl::geometric::RRTXstatic, ompl::geometric::SBL, ompl::geometric::SPARS, ompl::geometric::SPARSdb, ompl::geometric::SPARStwo, ompl::geometric::SST, ompl::geometric::STRIDE, ompl::geometric::STRRTstar, ompl::geometric::ThunderRetrieveRepair, ompl::geometric::TRRT, ompl::geometric::TRRTstar, ompl::geometric::TSRRT, ompl::geometric::VFRRT, ompl::geometric::XXL, ompl::multilevel::BundleSpace, ompl::multilevel::BundleSpaceGraph, ompl::multilevel::BundleSpaceSequence< T >, ompl::multilevel::BundleSpaceSequence< QMPImpl >, ompl::multilevel::BundleSpaceSequence< QMPStarImpl >, ompl::multilevel::BundleSpaceSequence< QRRTImpl >, ompl::multilevel::BundleSpaceSequence< QRRTStarImpl >, ompl::multilevel::PlannerMultiLevel, and ompl::multilevel::QMPImpl.
Definition at line 118 of file Planner.cpp.
◆ clearQuery()
| void ompl::base::Planner::clearQuery |
( |
| ) |
|
|
virtual |
◆ declareParam() [1/2]
template<typename T, typename PlannerType, typename SetterType, typename GetterType>
| void ompl::base::Planner::declareParam |
( |
const std::string & | name, |
|
|
const PlannerType & | planner, |
|
|
const SetterType & | setter, |
|
|
const GetterType & | getter, |
|
|
const std::string & | rangeSuggestion = "" ) |
|
inlineprotected |
This function declares a parameter for this planner instance, and specifies the setter and getter functions.
Definition at line 371 of file Planner.h.
◆ declareParam() [2/2]
template<typename T, typename PlannerType, typename SetterType>
| void ompl::base::Planner::declareParam |
( |
const std::string & | name, |
|
|
const PlannerType & | planner, |
|
|
const SetterType & | setter, |
|
|
const std::string & | rangeSuggestion = "" ) |
|
inlineprotected |
This function declares a parameter for this planner instance, and specifies the setter function.
Definition at line 384 of file Planner.h.
◆ getName()
| const std::string & ompl::base::Planner::getName |
( |
| ) |
const |
Get the name of the planner.
Definition at line 56 of file Planner.cpp.
◆ getPlannerData()
| void ompl::base::Planner::getPlannerData |
( |
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 in ompl::control::EST, ompl::control::HyRRT, ompl::control::HySST, ompl::control::KPIECE1, ompl::control::PDST, ompl::control::RRT, ompl::control::SST, ompl::control::SyclopEST, ompl::control::SyclopRRT, ompl::geometric::AITstar, ompl::geometric::AnytimePathShortening, ompl::geometric::AORRTC, ompl::geometric::ATRRT, ompl::geometric::BFMT, ompl::geometric::BiEST, ompl::geometric::BiRLRT, ompl::geometric::BiTRRT, ompl::geometric::BITstar, ompl::geometric::BKPIECE1, ompl::geometric::BLITstar, ompl::geometric::CForest, ompl::geometric::EITstar, ompl::geometric::EST, ompl::geometric::FMT, ompl::geometric::KPIECE1, ompl::geometric::LazyLBTRRT, ompl::geometric::LazyPRM, ompl::geometric::LazyRRT, ompl::geometric::LBKPIECE1, ompl::geometric::LBTRRT, ompl::geometric::LightningRetrieveRepair, ompl::geometric::PDST, ompl::geometric::PRM, ompl::geometric::ProjEST, ompl::geometric::pRRT, ompl::geometric::pSBL, ompl::geometric::RLRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::RRTstar, ompl::geometric::RRTXstatic, ompl::geometric::SBL, ompl::geometric::SPARS, ompl::geometric::SPARSdb, ompl::geometric::SPARStwo, ompl::geometric::SST, ompl::geometric::STRIDE, ompl::geometric::STRRTstar, ompl::geometric::ThunderRetrieveRepair, ompl::geometric::TRRT, ompl::geometric::TRRTstar, ompl::geometric::TSRRT, ompl::geometric::XXL, ompl::multilevel::BundleSpaceGraph, ompl::multilevel::BundleSpaceSequence< T >, ompl::multilevel::BundleSpaceSequence< QMPImpl >, ompl::multilevel::BundleSpaceSequence< QMPStarImpl >, ompl::multilevel::BundleSpaceSequence< QRRTImpl >, and ompl::multilevel::BundleSpaceSequence< QRRTStarImpl >.
Definition at line 129 of file Planner.cpp.
◆ getPlannerInputStates()
Get the planner input states.
Definition at line 87 of file Planner.cpp.
◆ getPlannerProgressProperties()
Retrieve a planner's planner progress property map.
Definition at line 356 of file Planner.h.
◆ getProblemDefinition() [1/2]
Get the problem definition the planner is trying to solve.
Definition at line 76 of file Planner.cpp.
◆ getProblemDefinition() [2/2]
Get the problem definition the planner is trying to solve.
Definition at line 71 of file Planner.cpp.
◆ getSpaceInformation()
Get the space information this planner is using.
Definition at line 66 of file Planner.cpp.
◆ getSpecs()
Return the specifications (capabilities of this planner).
Definition at line 51 of file Planner.cpp.
◆ isSetup()
| bool ompl::base::Planner::isSetup |
( |
| ) |
const |
◆ params() [1/2]
| ParamSet & ompl::base::Planner::params |
( |
| ) |
|
|
inline |
Get the parameters for this planner.
Definition at line 336 of file Planner.h.
◆ params() [2/2]
| const ParamSet & ompl::base::Planner::params |
( |
| ) |
const |
|
inline |
Get the parameters for this planner.
Definition at line 342 of file Planner.h.
◆ printProperties()
| void ompl::base::Planner::printProperties |
( |
std::ostream & | out | ) |
const |
|
virtual |
Print properties of the motion planner.
Definition at line 147 of file Planner.cpp.
◆ printSettings()
| void ompl::base::Planner::printSettings |
( |
std::ostream & | out | ) |
const |
|
virtual |
◆ setName()
| void ompl::base::Planner::setName |
( |
const std::string & | name | ) |
|
Set the name of the planner.
Definition at line 61 of file Planner.cpp.
◆ setProblemDefinition()
◆ setup()
| void ompl::base::Planner::setup |
( |
| ) |
|
|
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 in ompl::control::EST, ompl::control::HyRRT, ompl::control::HySST, ompl::control::KPIECE1, ompl::control::LTLPlanner, ompl::control::PDST, ompl::control::RRT, ompl::control::SST, ompl::control::Syclop, ompl::control::SyclopEST, ompl::control::SyclopRRT, ompl::geometric::AITstar, ompl::geometric::AnytimePathShortening, ompl::geometric::AORRTC, ompl::geometric::AOXRRTConnect, ompl::geometric::ATRRT, ompl::geometric::BFMT, ompl::geometric::BiEST, ompl::geometric::BiRLRT, ompl::geometric::BiTRRT, ompl::geometric::BITstar, ompl::geometric::BKPIECE1, ompl::geometric::BLITstar, ompl::geometric::CForest, ompl::geometric::EITstar, ompl::geometric::EST, ompl::geometric::FMT, ompl::geometric::KPIECE1, ompl::geometric::LazyLBTRRT, ompl::geometric::LazyPRM, ompl::geometric::LazyRRT, ompl::geometric::LBKPIECE1, ompl::geometric::LBTRRT, ompl::geometric::LightningRetrieveRepair, ompl::geometric::PDST, ompl::geometric::PRM, ompl::geometric::ProjEST, ompl::geometric::pRRT, ompl::geometric::pSBL, ompl::geometric::RLRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::RRTstar, ompl::geometric::RRTXstatic, ompl::geometric::SBL, ompl::geometric::SPARS, ompl::geometric::SPARSdb, ompl::geometric::SPARStwo, ompl::geometric::SST, ompl::geometric::STRIDE, ompl::geometric::STRRTstar, ompl::geometric::ThunderRetrieveRepair, ompl::geometric::TRRT, ompl::geometric::TRRTstar, ompl::geometric::TSRRT, ompl::geometric::VFRRT, ompl::geometric::XXL, ompl::multilevel::BundleSpace, ompl::multilevel::BundleSpaceGraph, ompl::multilevel::BundleSpaceSequence< T >, ompl::multilevel::BundleSpaceSequence< QMPImpl >, ompl::multilevel::BundleSpaceSequence< QMPStarImpl >, ompl::multilevel::BundleSpaceSequence< QRRTImpl >, and ompl::multilevel::BundleSpaceSequence< QRRTStarImpl >.
Definition at line 92 of file Planner.cpp.
◆ solve() [1/3]
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.
Implemented in ompl::control::EST, ompl::control::HyRRT, ompl::control::HySST, ompl::control::KPIECE1, ompl::control::LTLPlanner, ompl::control::PDST, ompl::control::RRT, ompl::control::SST, ompl::control::Syclop, ompl::geometric::AITstar, ompl::geometric::AnytimePathShortening, ompl::geometric::AORRTC, ompl::geometric::AOXRRTConnect, ompl::geometric::ATRRT, ompl::geometric::BFMT, ompl::geometric::BiEST, ompl::geometric::BiRLRT, ompl::geometric::BiTRRT, ompl::geometric::BITstar, ompl::geometric::BKPIECE1, ompl::geometric::BLITstar, ompl::geometric::CForest, ompl::geometric::EITstar, ompl::geometric::EST, ompl::geometric::FMT, ompl::geometric::KPIECE1, ompl::geometric::LazyLBTRRT, ompl::geometric::LazyPRM, ompl::geometric::LazyRRT, ompl::geometric::LBKPIECE1, ompl::geometric::LBTRRT, ompl::geometric::LightningRetrieveRepair, ompl::geometric::PDST, ompl::geometric::PRM, ompl::geometric::ProjEST, ompl::geometric::pRRT, ompl::geometric::pSBL, ompl::geometric::RLRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::RRTstar, ompl::geometric::RRTXstatic, ompl::geometric::SBL, ompl::geometric::SPARS, ompl::geometric::SPARSdb, ompl::geometric::SPARStwo, ompl::geometric::SST, ompl::geometric::STRIDE, ompl::geometric::STRRTstar, ompl::geometric::ThunderRetrieveRepair, ompl::geometric::TRRT, ompl::geometric::TRRTstar, ompl::geometric::TSRRT, ompl::geometric::VFRRT, ompl::geometric::XXL, ompl::multilevel::BundleSpaceSequence< T >, ompl::multilevel::BundleSpaceSequence< QMPImpl >, ompl::multilevel::BundleSpaceSequence< QMPStarImpl >, ompl::multilevel::BundleSpaceSequence< QRRTImpl >, and ompl::multilevel::BundleSpaceSequence< QRRTStarImpl >.
◆ solve() [2/3]
Same as above except the termination condition is only evaluated at a specified interval.
Definition at line 135 of file Planner.cpp.
◆ solve() [3/3]
Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning.
Definition at line 140 of file Planner.cpp.
◆ name_
| std::string ompl::base::Planner::name_ |
|
protected |
The name of this planner.
Definition at line 410 of file Planner.h.
◆ params_
A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function.
Definition at line 417 of file Planner.h.
◆ pdef_
The user set problem definition.
Definition at line 404 of file Planner.h.
◆ pis_
Utility class to extract valid input states.
Definition at line 407 of file Planner.h.
◆ plannerProgressProperties_
A mapping between this planner's progress property names and the functions used for querying those progress properties.
Definition at line 421 of file Planner.h.
◆ setup_
| bool ompl::base::Planner::setup_ |
|
protected |
◆ si_
The space information for which planning is done.
Definition at line 401 of file Planner.h.
◆ specs_
The specifications of the planner (its capabilities).
Definition at line 413 of file Planner.h.
The documentation for this class was generated from the following files: