A graph on a quotient-space. More...
#include <ompl/geometric/planners/quotientspace/datastructures/QuotientSpaceGraph.h>

Classes | |
class | Configuration |
A configuration in quotient-space. More... | |
class | EdgeInternalState |
An edge in quotient-space. More... | |
struct | GraphBundle |
Public Types | |
using | normalized_index_type = int |
using | Graph |
A quotient-graph structure using boost::adjacency_list bundles. | |
using | BGT = boost::graph_traits<Graph> |
using | Vertex = BGT::vertex_descriptor |
using | Edge = BGT::edge_descriptor |
using | VertexIndex = BGT::vertices_size_type |
using | IEIterator = BGT::in_edge_iterator |
using | OEIterator = BGT::out_edge_iterator |
using | VertexParent = Vertex |
using | VertexRank = VertexIndex |
using | RoadmapNeighborsPtr = std::shared_ptr<NearestNeighbors<Configuration *>> |
using | PDF = ompl::PDF<Configuration *> |
using | PDF_Element = PDF::Element |
![]() | |
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. | |
Public Member Functions | |
QuotientSpaceGraph (const ompl::base::SpaceInformationPtr &si, QuotientSpace *parent=nullptr) | |
virtual unsigned int | getNumberOfVertices () const |
virtual unsigned int | getNumberOfEdges () const |
virtual bool | sampleQuotient (ompl::base::State *) override |
virtual bool | getSolution (ompl::base::PathPtr &solution) override |
virtual void | getPlannerData (ompl::base::PlannerData &data) const override |
Return plannerdata structure, whereby each vertex is marked depending to which component it belongs (start/goal/non-connected) | |
virtual double | getImportance () const override |
Importance of quotient-space depending on number of vertices in quotient-graph. | |
void | init () |
Initialization methods for the first iteration (adding start configuration and doing sanity checks) | |
virtual 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. | |
virtual void | clear () override |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
void | clearQuery () override |
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 | clearVertices () |
virtual void | deleteConfiguration (Configuration *q) |
template<template< typename T > class NN> | |
void | setNearestNeighbors () |
void | uniteComponents (Vertex m1, Vertex m2) |
bool | sameComponent (Vertex m1, Vertex m2) |
const Configuration * | nearest (const Configuration *s) const |
const Graph & | getGraph () const |
double | getGraphLength () const |
const RoadmapNeighborsPtr & | getRoadmapNeighborsPtr () const |
virtual void | print (std::ostream &out) const override |
Internal function implementing actual printing to stream. | |
void | printConfiguration (const Configuration *) const |
Print configuration to std::cout. | |
![]() | |
QuotientSpace (const ompl::base::SpaceInformationPtr &si, QuotientSpace *parent_=nullptr) | |
Quotient Space contains three OMPL spaces, which we call Q1, Q0 and X1. | |
ompl::base::PlannerStatus | solve (const ompl::base::PlannerTerminationCondition &ptc) override final |
solve disabled (use MultiQuotient::solve) final prevents subclasses to override | |
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(). | |
virtual void | grow ()=0 |
virtual bool | sample (ompl::base::State *q_random) |
virtual bool | hasSolution () |
const ompl::base::SpaceInformationPtr & | getX1 () const |
Get SpaceInformationPtr for X1 (Note: X1 is the second component of Q1 = Q0 x X1) | |
const ompl::base::SpaceInformationPtr & | getQ1 () const |
Get SpaceInformationPtr for Q1 (Note: Q1 is the product space Q1 = Q0 x X1) | |
const ompl::base::SpaceInformationPtr & | getQ0 () const |
Get SpaceInformationPtr for Q0 (Note: Q0 is the first component of Q1 = Q0 x X1) | |
unsigned int | getX1Dimension () const |
Dimension of space X1. | |
unsigned int | getQ1Dimension () const |
Dimension of space Q1. | |
unsigned int | getQ0Dimension () const |
Dimension of space Q0. | |
unsigned int | getDimension () const |
Dimension of space Q1. | |
const ompl::base::StateSamplerPtr & | getX1SamplerPtr () const |
const ompl::base::StateSamplerPtr & | getQ1SamplerPtr () const |
QuotientSpace * | getParent () const |
Parent is a more simplified quotient-space (higher in abstraction hierarchy) | |
QuotientSpace * | getChild () const |
Child is a less simplified quotient-space (lower in abstraction hierarchy) | |
unsigned int | getLevel () const |
Level in abstraction hierarchy of quotient-spaces. | |
void | setLevel (unsigned int) |
Change abstraction level. | |
QuotientSpaceType | getType () const |
Type of quotient-space. | |
void | setChild (QuotientSpace *child_) |
Set pointer to less simplified quotient-space. | |
void | setParent (QuotientSpace *parent_) |
Set pointer to more simplified quotient-space. | |
unsigned int | getTotalNumberOfSamples () const |
Number of samples drawn on space Q1. | |
unsigned int | getTotalNumberOfFeasibleSamples () const |
Number of feasible samples drawn on space Q1. | |
void | projectX1 (const ompl::base::State *q, ompl::base::State *qX1) const |
Quotient Space Projection Operator onto second component ProjectX1: Q0 \times X1 \rightarrow X1. | |
void | projectQ0 (const ompl::base::State *q, ompl::base::State *qQ0) const |
Quotient Space Projection Operator onto first component ProjectQ0: Q0 \times X1 \rightarrow Q0. | |
void | mergeStates (const ompl::base::State *qQ0, const ompl::base::State *qX1, ompl::base::State *qQ1) const |
Merge a state from Q0 and X1 into a state on Q1 (concatenate) | |
void | checkSpaceHasFiniteMeasure (const ompl::base::StateSpacePtr space) const |
Check if quotient-space is unbounded. | |
ompl::base::OptimizationObjectivePtr | getOptimizationObjectivePtr () const |
![]() | |
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. | |
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. | |
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 | |
std::map< Vertex, VertexRank > | vrank |
std::map< Vertex, Vertex > | vparent |
boost::disjoint_sets< boost::associative_property_map< std::map< Vertex, VertexRank > >, boost::associative_property_map< std::map< Vertex, Vertex > > > | disjointSets_ {boost::make_assoc_property_map(vrank), boost::make_assoc_property_map(vparent)} |
ompl::base::Cost | bestCost_ {+ompl::base::dInf} |
Configuration * | qStart_ {nullptr} |
Configuration * | qGoal_ {nullptr} |
Vertex | vStart_ |
Vertex | vGoal_ |
std::vector< Vertex > | shortestVertexPath_ |
std::vector< Vertex > | startGoalVertexPath_ |
Protected Types | |
using | RNGType = boost::minstd_rand |
Protected Member Functions | |
virtual double | distance (const Configuration *a, const Configuration *b) const |
virtual Vertex | addConfiguration (Configuration *q) |
void | addEdge (const Vertex a, const Vertex b) |
ompl::base::Cost | costHeuristic (Vertex u, Vertex v) const |
ompl::base::PathPtr | getPath (const Vertex &start, const Vertex &goal) |
Shortest path on quotient-graph. | |
![]() | |
const ompl::base::StateSpacePtr | computeQuotientSpace (const ompl::base::StateSpacePtr Q1, const ompl::base::StateSpacePtr Q0) |
Compute the quotient Q1 / Q0 between two given spaces. | |
QuotientSpaceType | identifyQuotientSpaceType (const ompl::base::StateSpacePtr Q1, const ompl::base::StateSpacePtr Q0) |
Identify the type of the quotient Q1 / Q0. | |
![]() | |
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 | |
RoadmapNeighborsPtr | nearestDatastructure_ |
Nearest neighbor structure for quotient space configurations. | |
Graph | graph_ |
ompl::base::PathPtr | solutionPath_ |
RNG | rng_ |
RNGType | rng_boost |
double | graphLength_ {0.0} |
Length of graph (useful for determing importance of quotient-space. | |
![]() | |
ompl::base::SpaceInformationPtr | Q1 {nullptr} |
ompl::base::SpaceInformationPtr | Q0 {nullptr} |
ompl::base::SpaceInformationPtr | X1 {nullptr} |
ompl::base::StateSamplerPtr | X1_sampler_ |
ompl::base::StateSamplerPtr | Q1_sampler_ |
ompl::base::ValidStateSamplerPtr | Q1_valid_sampler_ |
ompl::base::OptimizationObjectivePtr | opt_ |
ompl::base::State * | s_Q0_tmp_ {nullptr} |
A temporary state on Q0. | |
ompl::base::State * | s_X1_tmp_ {nullptr} |
A temporary state on X1. | |
QuotientSpaceType | type_ |
unsigned int | Q1_dimension_ {0} |
unsigned int | Q0_dimension_ {0} |
unsigned int | X1_dimension_ {0} |
unsigned int | id_ {0} |
Identity of space (to keep track of number of quotient-spaces created) | |
unsigned int | level_ {0} |
Level in sequence of quotient-spaces. | |
bool | hasSolution_ {false} |
bool | firstRun_ {true} |
QuotientSpace * | parent_ {nullptr} |
QuotientSpace * | child_ {nullptr} |
unsigned int | totalNumberOfSamples_ {0} |
unsigned int | totalNumberOfFeasibleSamples_ {0} |
![]() | |
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 | |
![]() | |
static void | resetCounter () |
reset counter for number of levels | |
![]() | |
static unsigned int | counter_ = 0 |
Detailed Description
A graph on a quotient-space.
Definition at line 67 of file QuotientSpaceGraph.h.
Member Typedef Documentation
◆ BGT
using ompl::geometric::QuotientSpaceGraph::BGT = boost::graph_traits<Graph> |
Definition at line 145 of file QuotientSpaceGraph.h.
◆ Edge
using ompl::geometric::QuotientSpaceGraph::Edge = BGT::edge_descriptor |
Definition at line 147 of file QuotientSpaceGraph.h.
◆ Graph
A quotient-graph structure using boost::adjacency_list bundles.
Definition at line 137 of file QuotientSpaceGraph.h.
◆ IEIterator
using ompl::geometric::QuotientSpaceGraph::IEIterator = BGT::in_edge_iterator |
Definition at line 149 of file QuotientSpaceGraph.h.
◆ normalized_index_type
using ompl::geometric::QuotientSpaceGraph::normalized_index_type = int |
Definition at line 72 of file QuotientSpaceGraph.h.
◆ OEIterator
using ompl::geometric::QuotientSpaceGraph::OEIterator = BGT::out_edge_iterator |
Definition at line 150 of file QuotientSpaceGraph.h.
Definition at line 156 of file QuotientSpaceGraph.h.
◆ PDF_Element
Definition at line 157 of file QuotientSpaceGraph.h.
◆ RNGType
|
protected |
Definition at line 231 of file QuotientSpaceGraph.h.
◆ RoadmapNeighborsPtr
using ompl::geometric::QuotientSpaceGraph::RoadmapNeighborsPtr = std::shared_ptr<NearestNeighbors<Configuration *>> |
Definition at line 155 of file QuotientSpaceGraph.h.
◆ Vertex
using ompl::geometric::QuotientSpaceGraph::Vertex = BGT::vertex_descriptor |
Definition at line 146 of file QuotientSpaceGraph.h.
◆ VertexIndex
using ompl::geometric::QuotientSpaceGraph::VertexIndex = BGT::vertices_size_type |
Definition at line 148 of file QuotientSpaceGraph.h.
◆ VertexParent
using ompl::geometric::QuotientSpaceGraph::VertexParent = Vertex |
Definition at line 153 of file QuotientSpaceGraph.h.
◆ VertexRank
using ompl::geometric::QuotientSpaceGraph::VertexRank = VertexIndex |
Definition at line 154 of file QuotientSpaceGraph.h.
Constructor & Destructor Documentation
◆ QuotientSpaceGraph()
ompl::geometric::QuotientSpaceGraph::QuotientSpaceGraph | ( | const ompl::base::SpaceInformationPtr & | si, |
QuotientSpace * | parent = nullptr ) |
Definition at line 59 of file QuotientSpaceGraph.cpp.
◆ ~QuotientSpaceGraph()
ompl::geometric::QuotientSpaceGraph::~QuotientSpaceGraph | ( | ) |
Definition at line 73 of file QuotientSpaceGraph.cpp.
Member Function Documentation
◆ addConfiguration()
|
protectedvirtual |
Definition at line 221 of file QuotientSpaceGraph.cpp.
◆ addEdge()
|
protected |
Definition at line 276 of file QuotientSpaceGraph.cpp.
◆ clear()
|
overridevirtual |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
Reimplemented from ompl::geometric::QuotientSpace.
Reimplemented in ompl::geometric::QRRTImpl.
Definition at line 106 of file QuotientSpaceGraph.cpp.
◆ clearQuery()
|
overridevirtual |
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().
Reimplemented from ompl::base::Planner.
Definition at line 155 of file QuotientSpaceGraph.cpp.
◆ clearVertices()
|
virtual |
Definition at line 140 of file QuotientSpaceGraph.cpp.
◆ costHeuristic()
|
protected |
Definition at line 253 of file QuotientSpaceGraph.cpp.
◆ deleteConfiguration()
|
virtual |
Definition at line 127 of file QuotientSpaceGraph.cpp.
◆ distance()
|
protectedvirtual |
Definition at line 271 of file QuotientSpaceGraph.cpp.
◆ getGraph()
const ompl::geometric::QuotientSpaceGraph::Graph & ompl::geometric::QuotientSpaceGraph::getGraph | ( | ) | const |
Definition at line 242 of file QuotientSpaceGraph.cpp.
◆ getGraphLength()
double ompl::geometric::QuotientSpaceGraph::getGraphLength | ( | ) | const |
Definition at line 284 of file QuotientSpaceGraph.cpp.
◆ getImportance()
|
overridevirtual |
Importance of quotient-space depending on number of vertices in quotient-graph.
Reimplemented from ompl::geometric::QuotientSpace.
Reimplemented in ompl::geometric::QRRTImpl.
Definition at line 160 of file QuotientSpaceGraph.cpp.
◆ getNumberOfEdges()
|
virtual |
Definition at line 237 of file QuotientSpaceGraph.cpp.
◆ getNumberOfVertices()
|
virtual |
Definition at line 232 of file QuotientSpaceGraph.cpp.
◆ getPath()
|
protected |
Shortest path on quotient-graph.
Definition at line 319 of file QuotientSpaceGraph.cpp.
◆ getPlannerData()
|
overridevirtual |
Return plannerdata structure, whereby each vertex is marked depending to which component it belongs (start/goal/non-connected)
Reimplemented from ompl::base::Planner.
Definition at line 403 of file QuotientSpaceGraph.cpp.
◆ getRoadmapNeighborsPtr()
const ompl::geometric::QuotientSpaceGraph::RoadmapNeighborsPtr & ompl::geometric::QuotientSpaceGraph::getRoadmapNeighborsPtr | ( | ) | const |
Definition at line 248 of file QuotientSpaceGraph.cpp.
◆ getSolution()
|
overridevirtual |
Implements ompl::geometric::QuotientSpace.
Definition at line 289 of file QuotientSpaceGraph.cpp.
◆ init()
void ompl::geometric::QuotientSpaceGraph::init | ( | ) |
Initialization methods for the first iteration (adding start configuration and doing sanity checks)
Definition at line 166 of file QuotientSpaceGraph.cpp.
◆ nearest()
const ompl::geometric::QuotientSpaceGraph::Configuration * ompl::geometric::QuotientSpaceGraph::nearest | ( | const Configuration * | s | ) | const |
Definition at line 216 of file QuotientSpaceGraph.cpp.
◆ print()
|
overridevirtual |
Internal function implementing actual printing to stream.
Reimplemented from ompl::geometric::QuotientSpace.
Definition at line 390 of file QuotientSpaceGraph.cpp.
◆ printConfiguration()
void ompl::geometric::QuotientSpaceGraph::printConfiguration | ( | const Configuration * | q | ) | const |
Print configuration to std::cout.
Definition at line 398 of file QuotientSpaceGraph.cpp.
◆ sameComponent()
bool ompl::geometric::QuotientSpaceGraph::sameComponent | ( | Vertex | m1, |
Vertex | m2 ) |
Definition at line 210 of file QuotientSpaceGraph.cpp.
◆ sampleQuotient()
|
overridevirtual |
Reimplemented from ompl::geometric::QuotientSpace.
Reimplemented in ompl::geometric::QRRTImpl.
Definition at line 367 of file QuotientSpaceGraph.cpp.
◆ setNearestNeighbors()
void ompl::geometric::QuotientSpaceGraph::setNearestNeighbors | ( | ) |
Definition at line 259 of file QuotientSpaceGraph.cpp.
◆ 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::geometric::QuotientSpace.
Reimplemented in ompl::geometric::QRRTImpl.
Definition at line 77 of file QuotientSpaceGraph.cpp.
◆ uniteComponents()
void ompl::geometric::QuotientSpaceGraph::uniteComponents | ( | Vertex | m1, |
Vertex | m2 ) |
Definition at line 205 of file QuotientSpaceGraph.cpp.
Member Data Documentation
◆ bestCost_
ompl::base::Cost ompl::geometric::QuotientSpaceGraph::bestCost_ {+ompl::base::dInf} |
Definition at line 199 of file QuotientSpaceGraph.h.
◆ disjointSets_
boost::disjoint_sets<boost::associative_property_map<std::map<Vertex, VertexRank> >, boost::associative_property_map<std::map<Vertex, Vertex> > > ompl::geometric::QuotientSpaceGraph::disjointSets_ {boost::make_assoc_property_map(vrank), boost::make_assoc_property_map(vparent)} |
Definition at line 195 of file QuotientSpaceGraph.h.
◆ graph_
|
protected |
Definition at line 228 of file QuotientSpaceGraph.h.
◆ graphLength_
|
protected |
Length of graph (useful for determing importance of quotient-space.
Definition at line 236 of file QuotientSpaceGraph.h.
◆ nearestDatastructure_
|
protected |
Nearest neighbor structure for quotient space configurations.
Definition at line 227 of file QuotientSpaceGraph.h.
◆ qGoal_
Configuration* ompl::geometric::QuotientSpaceGraph::qGoal_ {nullptr} |
Definition at line 201 of file QuotientSpaceGraph.h.
◆ qStart_
Configuration* ompl::geometric::QuotientSpaceGraph::qStart_ {nullptr} |
Definition at line 200 of file QuotientSpaceGraph.h.
◆ rng_
|
protected |
Definition at line 230 of file QuotientSpaceGraph.h.
◆ rng_boost
|
protected |
Definition at line 232 of file QuotientSpaceGraph.h.
◆ shortestVertexPath_
std::vector<Vertex> ompl::geometric::QuotientSpaceGraph::shortestVertexPath_ |
Definition at line 204 of file QuotientSpaceGraph.h.
◆ solutionPath_
|
protected |
Definition at line 229 of file QuotientSpaceGraph.h.
◆ startGoalVertexPath_
std::vector<Vertex> ompl::geometric::QuotientSpaceGraph::startGoalVertexPath_ |
Definition at line 205 of file QuotientSpaceGraph.h.
◆ vGoal_
Vertex ompl::geometric::QuotientSpaceGraph::vGoal_ |
Definition at line 203 of file QuotientSpaceGraph.h.
◆ vparent
std::map<Vertex, Vertex> ompl::geometric::QuotientSpaceGraph::vparent |
Definition at line 192 of file QuotientSpaceGraph.h.
◆ vrank
std::map<Vertex, VertexRank> ompl::geometric::QuotientSpaceGraph::vrank |
Definition at line 191 of file QuotientSpaceGraph.h.
◆ vStart_
Vertex ompl::geometric::QuotientSpaceGraph::vStart_ |
Definition at line 202 of file QuotientSpaceGraph.h.
The documentation for this class was generated from the following files:
- ompl/geometric/planners/quotientspace/datastructures/QuotientSpaceGraph.h
- ompl/geometric/planners/quotientspace/datastructures/src/QuotientSpaceGraph.cpp