Classes |
Public Member Functions |
Public Attributes |
Protected Types |
Protected Attributes |
List of all members
ompl::geometric::MultiQuotient< T > Class Template Reference
A sequence of multiple quotient-spaces The class MultiQuotient can be used with any planner which inherits the ompl::geometric::QuotientSpace class. More...
#include <ompl/geometric/planners/quotientspace/algorithms/MultiQuotient.h>
Inheritance diagram for ompl::geometric::MultiQuotient< T >:

Classes | |
struct | CmpQuotientSpacePtrs |
Compare function for priority queue. More... | |
Public Member Functions | |
MultiQuotient (std::vector< ompl::base::SpaceInformationPtr > &siVec, std::string type="QuotientPlanner") | |
Constructor taking a sequence of ompl::base::SpaceInformationPtr and computing the quotient-spaces for each pair in the sequence. | |
MultiQuotient (ompl::base::SpaceInformationPtr si)=delete | |
MultiQuotient (ompl::base::SpaceInformationPtr si, std::string type)=delete | |
void | getPlannerData (ompl::base::PlannerData &data) const override |
Return annotated vertices (with information about QuotientSpace level) | |
ompl::base::PlannerStatus | solve (const ompl::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 | 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. | |
void | clear () override |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
virtual void | setProblemDefinition (const ompl::base::ProblemDefinitionPtr &pdef) override |
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(). | |
const ompl::base::ProblemDefinitionPtr & | getProblemDefinition (unsigned int kQuotientSpace) const |
int | getLevels () const |
Number of quotient-spaces. | |
std::vector< int > | getFeasibleNodes () const |
Number of feasible nodes on each QuotientSpace (for DEBUGGING) | |
std::vector< int > | getNodes () const |
Number of nodes on each QuotientSpace (for DEBUGGING) | |
std::vector< int > | getDimensionsPerLevel () const |
Get all dimensions of the quotient-spaces in the sequence. | |
void | setStopLevel (unsigned int level_) |
![]() | |
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. | |
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. | |
Public Attributes | |
const bool | DEBUG {false} |
Protected Types | |
typedef std::priority_queue< QuotientSpace *, std::vector< QuotientSpace * >, CmpQuotientSpacePtrs > | QuotientSpacePriorityQueue |
Priority queue of QuotientSpaces which keeps track of how often every tree on each space has been expanded. | |
Protected Attributes | |
std::vector< ompl::base::PathPtr > | solutions_ |
Solution paths on each quotient-space. | |
std::vector< QuotientSpace * > | quotientSpaces_ |
Sequence of quotient-spaces. | |
bool | foundKLevelSolution_ {false} |
Indicator if a solution has been found on the current quotient-spaces. | |
unsigned int | currentQuotientLevel_ {0} |
Current level on which we have not yet found a path. | |
unsigned int | stopAtLevel_ |
Sometimes we only want to plan until a certain quotient-space level (for debugging for example). This variable sets the stopping level. | |
std::vector< ompl::base::SpaceInformationPtr > | siVec_ |
Each QuotientSpace has a unique ompl::base::SpaceInformationPtr. | |
QuotientSpacePriorityQueue | priorityQueue_ |
![]() | |
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 | |
![]() | |
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. | |
![]() | |
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. | |
Detailed Description
template<class T>
class ompl::geometric::MultiQuotient< T >
A sequence of multiple quotient-spaces The class MultiQuotient can be used with any planner which inherits the ompl::geometric::QuotientSpace class.
Example usage with QRRT (using a sequence si_vec of ompl::base::SpaceInformationPtr) ompl::base::PlannerPtr planner = std::make_shared<MultiQuotient<ompl::geometric::QRRT> >(si_vec);
Definition at line 58 of file MultiQuotient.h.
The documentation for this class was generated from the following files:
- ompl/geometric/planners/quotientspace/algorithms/MultiQuotient.h
- ompl/geometric/planners/quotientspace/algorithms/MultiQuotientImpl.h