A graph on a quotient-space. More...

#include <ompl/geometric/planners/quotientspace/datastructures/QuotientSpaceGraph.h>

Inheritance diagram for ompl::geometric::QuotientSpaceGraph:

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 = boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, Configuration *, EdgeInternalState, GraphBundle >
 A quotient-graph structure using boost::adjacency_list bundles. More...
 
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
 
- 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...
 

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) More...
 
virtual double getImportance () const override
 Importance of quotient-space depending on number of vertices in quotient-graph. More...
 
void init ()
 Initialization methods for the first iteration (adding start configuration and doing sanity checks) More...
 
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. More...
 
virtual void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. More...
 
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(). More...
 
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 Configurationnearest (const Configuration *s) const
 
const GraphgetGraph () const
 
double getGraphLength () const
 
const RoadmapNeighborsPtr & getRoadmapNeighborsPtr () const
 
virtual void print (std::ostream &out) const override
 Internal function implementing actual printing to stream. More...
 
void printConfiguration (const Configuration *) const
 Print configuration to std::cout. More...
 
- Public Member Functions inherited from ompl::geometric::QuotientSpace
 QuotientSpace (const ompl::base::SpaceInformationPtr &si, QuotientSpace *parent_=nullptr)
 Quotient Space contains three OMPL spaces, which we call Q1, Q0 and X1. More...
 
ompl::base::PlannerStatus solve (const ompl::base::PlannerTerminationCondition &ptc) override final
 solve disabled (use MultiQuotient::solve) final prevents subclasses to override 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...
 
virtual void grow ()=0
 
virtual bool getSolution (ompl::base::PathPtr &solution)=0
 
virtual bool sampleQuotient (ompl::base::State *q_random)
 
virtual bool sample (ompl::base::State *q_random)
 
virtual bool hasSolution ()
 
virtual void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. More...
 
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. More...
 
virtual double getImportance () const
 
const ompl::base::SpaceInformationPtrgetX1 () const
 Get SpaceInformationPtr for X1 (Note: X1 is the second component of Q1 = Q0 x X1) More...
 
const ompl::base::SpaceInformationPtrgetQ1 () const
 Get SpaceInformationPtr for Q1 (Note: Q1 is the product space Q1 = Q0 x X1) More...
 
const ompl::base::SpaceInformationPtrgetQ0 () const
 Get SpaceInformationPtr for Q0 (Note: Q0 is the first component of Q1 = Q0 x X1) More...
 
unsigned int getX1Dimension () const
 Dimension of space X1. More...
 
unsigned int getQ1Dimension () const
 Dimension of space Q1. More...
 
unsigned int getQ0Dimension () const
 Dimension of space Q0. More...
 
unsigned int getDimension () const
 Dimension of space Q1. More...
 
const ompl::base::StateSamplerPtrgetX1SamplerPtr () const
 
const ompl::base::StateSamplerPtrgetQ1SamplerPtr () const
 
QuotientSpacegetParent () const
 Parent is a more simplified quotient-space (higher in abstraction hierarchy) More...
 
QuotientSpacegetChild () const
 Child is a less simplified quotient-space (lower in abstraction hierarchy) More...
 
unsigned int getLevel () const
 Level in abstraction hierarchy of quotient-spaces. More...
 
void setLevel (unsigned int)
 Change abstraction level. More...
 
QuotientSpaceType getType () const
 Type of quotient-space. More...
 
void setChild (QuotientSpace *child_)
 Set pointer to less simplified quotient-space. More...
 
void setParent (QuotientSpace *parent_)
 Set pointer to more simplified quotient-space. More...
 
unsigned int getTotalNumberOfSamples () const
 Number of samples drawn on space Q1. More...
 
unsigned int getTotalNumberOfFeasibleSamples () const
 Number of feasible samples drawn on space Q1. More...
 
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. More...
 
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. More...
 
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) More...
 
void checkSpaceHasFiniteMeasure (const ompl::base::StateSpacePtr space) const
 Check if quotient-space is unbounded. More...
 
ompl::base::OptimizationObjectivePtr getOptimizationObjectivePtr () const
 
- 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

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}
 
ConfigurationqStart_ {nullptr}
 
ConfigurationqGoal_ {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. More...
 
- Protected Member Functions inherited from ompl::geometric::QuotientSpace
virtual void print (std::ostream &out) const
 Internal function implementing actual printing to stream. More...
 
const ompl::base::StateSpacePtr computeQuotientSpace (const ompl::base::StateSpacePtr Q1, const ompl::base::StateSpacePtr Q0)
 Compute the quotient Q1 / Q0 between two given spaces. More...
 
QuotientSpaceType identifyQuotientSpaceType (const ompl::base::StateSpacePtr Q1, const ompl::base::StateSpacePtr Q0)
 Identify the type of the quotient Q1 / Q0. 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...
 

Protected Attributes

RoadmapNeighborsPtr nearestDatastructure_
 Nearest neighbor structure for quotient space configurations. More...
 
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. More...
 
- Protected Attributes inherited from ompl::geometric::QuotientSpace
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::States_Q0_tmp_ {nullptr}
 A temporary state on Q0. More...
 
ompl::base::States_X1_tmp_ {nullptr}
 A temporary state on X1. More...
 
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) More...
 
unsigned int level_ {0}
 Level in sequence of quotient-spaces. More...
 
bool hasSolution_ {false}
 
bool firstRun_ {true}
 
QuotientSpaceparent_ {nullptr}
 
QuotientSpacechild_ {nullptr}
 
unsigned int totalNumberOfSamples_ {0}
 
unsigned int totalNumberOfFeasibleSamples_ {0}
 
- 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

- Static Public Member Functions inherited from ompl::geometric::QuotientSpace
static void resetCounter ()
 reset counter for number of levels More...
 
- Static Protected Attributes inherited from ompl::geometric::QuotientSpace
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

using ompl::geometric::QuotientSpaceGraph::Graph = boost::adjacency_list<boost::vecS, boost::vecS, boost::undirectedS, Configuration *, EdgeInternalState, GraphBundle >

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.

◆ PDF

◆ PDF_Element

◆ RNGType

using ompl::geometric::QuotientSpaceGraph::RNGType = boost::minstd_rand
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()

ompl::geometric::QuotientSpaceGraph::Vertex ompl::geometric::QuotientSpaceGraph::addConfiguration ( Configuration q)
protectedvirtual

Definition at line 221 of file QuotientSpaceGraph.cpp.

◆ addEdge()

void ompl::geometric::QuotientSpaceGraph::addEdge ( const Vertex  a,
const Vertex  b 
)
protected

Definition at line 276 of file QuotientSpaceGraph.cpp.

◆ clear()

void ompl::geometric::QuotientSpaceGraph::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()

void ompl::geometric::QuotientSpaceGraph::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()

void ompl::geometric::QuotientSpaceGraph::clearVertices ( )
virtual

Definition at line 140 of file QuotientSpaceGraph.cpp.

◆ costHeuristic()

ompl::base::Cost ompl::geometric::QuotientSpaceGraph::costHeuristic ( Vertex  u,
Vertex  v 
) const
protected

Definition at line 253 of file QuotientSpaceGraph.cpp.

◆ deleteConfiguration()

void ompl::geometric::QuotientSpaceGraph::deleteConfiguration ( Configuration q)
virtual

Definition at line 127 of file QuotientSpaceGraph.cpp.

◆ distance()

double ompl::geometric::QuotientSpaceGraph::distance ( const Configuration a,
const Configuration b 
) const
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()

double ompl::geometric::QuotientSpaceGraph::getImportance ( ) const
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()

unsigned int ompl::geometric::QuotientSpaceGraph::getNumberOfEdges ( ) const
virtual

Definition at line 237 of file QuotientSpaceGraph.cpp.

◆ getNumberOfVertices()

unsigned int ompl::geometric::QuotientSpaceGraph::getNumberOfVertices ( ) const
virtual

Definition at line 232 of file QuotientSpaceGraph.cpp.

◆ getPath()

ompl::base::PathPtr ompl::geometric::QuotientSpaceGraph::getPath ( const Vertex &  start,
const Vertex &  goal 
)
protected

Shortest path on quotient-graph.

Definition at line 319 of file QuotientSpaceGraph.cpp.

◆ getPlannerData()

void ompl::geometric::QuotientSpaceGraph::getPlannerData ( ompl::base::PlannerData data) const
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()

bool ompl::geometric::QuotientSpaceGraph::getSolution ( ompl::base::PathPtr solution)
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()

void ompl::geometric::QuotientSpaceGraph::print ( std::ostream &  out) const
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()

bool ompl::geometric::QuotientSpaceGraph::sampleQuotient ( ompl::base::State q_random_graph)
overridevirtual

Reimplemented from ompl::geometric::QuotientSpace.

Reimplemented in ompl::geometric::QRRTImpl.

Definition at line 367 of file QuotientSpaceGraph.cpp.

◆ setNearestNeighbors()

template<template< typename T > class NN>
void ompl::geometric::QuotientSpaceGraph::setNearestNeighbors

Definition at line 259 of file QuotientSpaceGraph.cpp.

◆ setup()

void ompl::geometric::QuotientSpaceGraph::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_

Graph ompl::geometric::QuotientSpaceGraph::graph_
protected

Definition at line 228 of file QuotientSpaceGraph.h.

◆ graphLength_

double ompl::geometric::QuotientSpaceGraph::graphLength_ {0.0}
protected

Length of graph (useful for determing importance of quotient-space.

Definition at line 236 of file QuotientSpaceGraph.h.

◆ nearestDatastructure_

RoadmapNeighborsPtr ompl::geometric::QuotientSpaceGraph::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_

RNG ompl::geometric::QuotientSpaceGraph::rng_
protected

Definition at line 230 of file QuotientSpaceGraph.h.

◆ rng_boost

RNGType ompl::geometric::QuotientSpaceGraph::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_

ompl::base::PathPtr ompl::geometric::QuotientSpaceGraph::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: