Loading...
Searching...
No Matches
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. More...
 
 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) More...
 
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. More...
 
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. More...
 
void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. More...
 
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(). More...
 
const ompl::base::ProblemDefinitionPtrgetProblemDefinition (unsigned int kQuotientSpace) const
 
int getLevels () const
 Number of quotient-spaces. More...
 
std::vector< int > getFeasibleNodes () const
 Number of feasible nodes on each QuotientSpace (for DEBUGGING) More...
 
std::vector< int > getNodes () const
 Number of nodes on each QuotientSpace (for DEBUGGING) More...
 
std::vector< int > getDimensionsPerLevel () const
 Get all dimensions of the quotient-spaces in the sequence. More...
 
void setStopLevel (unsigned int level_)
 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
 
Planneroperator= (const Planner &)=delete
 
 Planner (SpaceInformationPtr si, std::string name)
 Constructor. More...
 
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 SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using. More...
 
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve. More...
 
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve. More...
 
const PlannerInputStatesgetPlannerInputStates () const
 Get the planner input states. More...
 
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(). More...
 
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. More...
 
PlannerStatus solve (const PlannerTerminationConditionFn &ptc, double checkInterval)
 Same as above except the termination condition is only evaluated at a specified interval. More...
 
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. More...
 
virtual void clear ()
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. More...
 
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(). More...
 
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).
More...
 
const std::string & getName () const
 Get the name of the planner. More...
 
void setName (const std::string &name)
 Set the name of the planner. More...
 
const PlannerSpecsgetSpecs () const
 Return the specifications (capabilities of this planner) More...
 
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. More...
 
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. More...
 
bool isSetup () const
 Check if setup() was called for this planner. More...
 
ParamSetparams ()
 Get the parameters for this planner. More...
 
const ParamSetparams () const
 Get the parameters for this planner. More...
 
const PlannerProgressPropertiesgetPlannerProgressProperties () const
 Retrieve a planner's planner progress property map. More...
 
virtual void printProperties (std::ostream &out) const
 Print properties of the motion planner. More...
 
virtual void printSettings (std::ostream &out) const
 Print information about the motion planner's settings. More...
 

Public Attributes

const bool DEBUG {false}
 

Protected Types

typedef std::priority_queue< QuotientSpace *, std::vector< QuotientSpace * >, CmpQuotientSpacePtrsQuotientSpacePriorityQueue
 Priority queue of QuotientSpaces which keeps track of how often every tree on each space has been expanded. More...
 

Protected Attributes

std::vector< ompl::base::PathPtrsolutions_
 Solution paths on each quotient-space. More...
 
std::vector< QuotientSpace * > quotientSpaces_
 Sequence of quotient-spaces. More...
 
bool foundKLevelSolution_ {false}
 Indicator if a solution has been found on the current quotient-spaces. More...
 
unsigned int currentQuotientLevel_ {0}
 Current level on which we have not yet found a path. More...
 
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. More...
 
std::vector< ompl::base::SpaceInformationPtrsiVec_
 Each QuotientSpace has a unique ompl::base::SpaceInformationPtr. More...
 
QuotientSpacePriorityQueue priorityQueue_
 
- Protected Attributes inherited from ompl::base::Planner
SpaceInformationPtr si_
 The space information for which planning is done. More...
 
ProblemDefinitionPtr pdef_
 The user set problem definition. More...
 
PlannerInputStates pis_
 Utility class to extract valid input states
More...
 
std::string name_
 The name of this planner. More...
 
PlannerSpecs specs_
 The specifications of the planner (its capabilities) More...
 
ParamSet params_
 A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function. More...
 
PlannerProgressProperties plannerProgressProperties_
 A mapping between this planner's progress property names and the functions used for querying those progress properties. More...
 
bool setup_
 Flag indicating whether setup() has been called. More...
 

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. More...
 
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. More...
 
- 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. More...
 
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. More...
 
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. More...
 

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.

Member Typedef Documentation

◆ QuotientSpacePriorityQueue

template<class T >
typedef std::priority_queue<QuotientSpace *, std::vector<QuotientSpace *>, CmpQuotientSpacePtrs> ompl::geometric::MultiQuotient< T >::QuotientSpacePriorityQueue
protected

Priority queue of QuotientSpaces which keeps track of how often every tree on each space has been expanded.

Definition at line 129 of file MultiQuotient.h.

Constructor & Destructor Documentation

◆ MultiQuotient()

template<class T >
ompl::geometric::MultiQuotient< T >::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.

Definition at line 47 of file MultiQuotientImpl.h.

◆ ~MultiQuotient()

template<class T >
ompl::geometric::MultiQuotient< T >::~MultiQuotient
overridevirtual

Definition at line 108 of file MultiQuotientImpl.h.

Member Function Documentation

◆ clear()

template<class T >
void ompl::geometric::MultiQuotient< T >::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 137 of file MultiQuotientImpl.h.

◆ getDimensionsPerLevel()

template<class T >
std::vector< int > ompl::geometric::MultiQuotient< T >::getDimensionsPerLevel

Get all dimensions of the quotient-spaces in the sequence.

Definition at line 96 of file MultiQuotientImpl.h.

◆ getFeasibleNodes()

template<class T >
std::vector< int > ompl::geometric::MultiQuotient< T >::getFeasibleNodes

Number of feasible nodes on each QuotientSpace (for DEBUGGING)

Definition at line 84 of file MultiQuotientImpl.h.

◆ getLevels()

template<class T >
int ompl::geometric::MultiQuotient< T >::getLevels

Number of quotient-spaces.

Definition at line 66 of file MultiQuotientImpl.h.

◆ getNodes()

template<class T >
std::vector< int > ompl::geometric::MultiQuotient< T >::getNodes

Number of nodes on each QuotientSpace (for DEBUGGING)

Definition at line 72 of file MultiQuotientImpl.h.

◆ getPlannerData()

template<class T >
void ompl::geometric::MultiQuotient< T >::getPlannerData ( ompl::base::PlannerData data) const
overridevirtual

Return annotated vertices (with information about QuotientSpace level)

Reimplemented from ompl::base::Planner.

Definition at line 266 of file MultiQuotientImpl.h.

◆ getProblemDefinition()

template<class T >
const ompl::base::ProblemDefinitionPtr & ompl::geometric::MultiQuotient< T >::getProblemDefinition ( unsigned int  kQuotientSpace) const

Definition at line 218 of file MultiQuotientImpl.h.

◆ setProblemDefinition()

template<class T >
void ompl::geometric::MultiQuotient< T >::setProblemDefinition ( const ompl::base::ProblemDefinitionPtr pdef)
overridevirtual

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().

Reimplemented from ompl::base::Planner.

Definition at line 226 of file MultiQuotientImpl.h.

◆ setStopLevel()

template<class T >
void ompl::geometric::MultiQuotient< T >::setStopLevel ( unsigned int  level_)

Definition at line 124 of file MultiQuotientImpl.h.

◆ setup()

template<class T >
void ompl::geometric::MultiQuotient< T >::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 113 of file MultiQuotientImpl.h.

◆ solve()

template<class T >
ompl::base::PlannerStatus ompl::geometric::MultiQuotient< T >::solve ( const ompl::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 156 of file MultiQuotientImpl.h.

Member Data Documentation

◆ currentQuotientLevel_

template<class T >
unsigned int ompl::geometric::MultiQuotient< T >::currentQuotientLevel_ {0}
protected

Current level on which we have not yet found a path.

Definition at line 106 of file MultiQuotient.h.

◆ DEBUG

template<class T >
const bool ompl::geometric::MultiQuotient< T >::DEBUG {false}

Definition at line 64 of file MultiQuotient.h.

◆ foundKLevelSolution_

template<class T >
bool ompl::geometric::MultiQuotient< T >::foundKLevelSolution_ {false}
protected

Indicator if a solution has been found on the current quotient-spaces.

Definition at line 103 of file MultiQuotient.h.

◆ priorityQueue_

template<class T >
QuotientSpacePriorityQueue ompl::geometric::MultiQuotient< T >::priorityQueue_
protected

Definition at line 130 of file MultiQuotient.h.

◆ quotientSpaces_

template<class T >
std::vector<QuotientSpace *> ompl::geometric::MultiQuotient< T >::quotientSpaces_
protected

Sequence of quotient-spaces.

Definition at line 100 of file MultiQuotient.h.

◆ siVec_

template<class T >
std::vector<ompl::base::SpaceInformationPtr> ompl::geometric::MultiQuotient< T >::siVec_
protected

Each QuotientSpace has a unique ompl::base::SpaceInformationPtr.

Definition at line 114 of file MultiQuotient.h.

◆ solutions_

template<class T >
std::vector<ompl::base::PathPtr> ompl::geometric::MultiQuotient< T >::solutions_
protected

Solution paths on each quotient-space.

Definition at line 97 of file MultiQuotient.h.

◆ stopAtLevel_

template<class T >
unsigned int ompl::geometric::MultiQuotient< T >::stopAtLevel_
protected

Sometimes we only want to plan until a certain quotient-space level (for debugging for example). This variable sets the stopping level.

Definition at line 111 of file MultiQuotient.h.


The documentation for this class was generated from the following files: