Loading...
Searching...
No Matches

A single quotient-space. More...

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

Inheritance diagram for ompl::geometric::QuotientSpace:

Public Member Functions

 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 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.
 
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 double getImportance () const
 
const ompl::base::SpaceInformationPtrgetX1 () const
 Get SpaceInformationPtr for X1 (Note: X1 is the second component of Q1 = Q0 x X1)
 
const ompl::base::SpaceInformationPtrgetQ1 () const
 Get SpaceInformationPtr for Q1 (Note: Q1 is the product space Q1 = Q0 x X1)
 
const ompl::base::SpaceInformationPtrgetQ0 () 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::StateSamplerPtrgetX1SamplerPtr () const
 
const ompl::base::StateSamplerPtrgetQ1SamplerPtr () const
 
QuotientSpacegetParent () const
 Parent is a more simplified quotient-space (higher in abstraction hierarchy)
 
QuotientSpacegetChild () 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
 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
 
Planneroperator= (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 SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using.
 
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
 
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
 
const PlannerInputStatesgetPlannerInputStates () 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().
 
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 PlannerSpecsgetSpecs () 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.
 
ParamSetparams ()
 Get the parameters for this planner.
 
const ParamSetparams () const
 Get the parameters for this planner.
 
const PlannerProgressPropertiesgetPlannerProgressProperties () 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.
 

Static Public Member Functions

static void resetCounter ()
 reset counter for number of levels
 

Protected Member Functions

virtual void print (std::ostream &out) const
 Internal function implementing actual printing to stream.
 
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.
 
- 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.
 
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

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.
 
ompl::base::States_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}
 
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.
 
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.
 

Static Protected Attributes

static unsigned int counter_ = 0
 

Friends

std::ostream & operator<< (std::ostream &out, const QuotientSpace &qtnt)
 Write class to stream (use as std::cout << *this << std::endl) Actual implementation is in void print(std::ostream& out), which can be inherited.
 

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

Detailed Description

A single quotient-space.

Definition at line 48 of file QuotientSpace.h.

Constructor & Destructor Documentation

◆ QuotientSpace()

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.

Q1 = Q0 x X1 is a product space of Q0 and X1 and is the main quotient-space of this class Q0 is a pointer to the next lower-dimensional quotient-space and X1 is the quotient-space Q1 / Q0

We assume that Q1 and Q0 have been given (as ompl::base::SpaceInformationPtr), and we compute the inverse of the quotient map, i.e. X1 = Q1/Q0.

Definition at line 50 of file QuotientSpace.cpp.

◆ ~QuotientSpace()

ompl::geometric::QuotientSpace::~QuotientSpace ( )

Definition at line 121 of file QuotientSpace.cpp.

Member Function Documentation

◆ checkSpaceHasFiniteMeasure()

void ompl::geometric::QuotientSpace::checkSpaceHasFiniteMeasure ( const ompl::base::StateSpacePtr space) const

Check if quotient-space is unbounded.

Definition at line 153 of file QuotientSpace.cpp.

◆ clear()

void ompl::geometric::QuotientSpace::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.

Reimplemented in ompl::geometric::QRRTImpl, and ompl::geometric::QuotientSpaceGraph.

Definition at line 139 of file QuotientSpace.cpp.

◆ computeQuotientSpace()

const ompl::base::StateSpacePtr ompl::geometric::QuotientSpace::computeQuotientSpace ( const ompl::base::StateSpacePtr Q1,
const ompl::base::StateSpacePtr Q0 )
protected

Compute the quotient Q1 / Q0 between two given spaces.

Definition at line 195 of file QuotientSpace.cpp.

◆ getChild()

ompl::geometric::QuotientSpace * ompl::geometric::QuotientSpace::getChild ( ) const

Child is a less simplified quotient-space (lower in abstraction hierarchy)

Definition at line 1365 of file QuotientSpace.cpp.

◆ getDimension()

unsigned int ompl::geometric::QuotientSpace::getDimension ( ) const

Dimension of space Q1.

Definition at line 1320 of file QuotientSpace.cpp.

◆ getImportance()

double ompl::geometric::QuotientSpace::getImportance ( ) const
virtual

Reimplemented in ompl::geometric::QRRTImpl, and ompl::geometric::QuotientSpaceGraph.

Definition at line 1439 of file QuotientSpace.cpp.

◆ getLevel()

unsigned int ompl::geometric::QuotientSpace::getLevel ( ) const

Level in abstraction hierarchy of quotient-spaces.

Definition at line 1380 of file QuotientSpace.cpp.

◆ getOptimizationObjectivePtr()

ompl::base::OptimizationObjectivePtr ompl::geometric::QuotientSpace::getOptimizationObjectivePtr ( ) const

Definition at line 1395 of file QuotientSpace.cpp.

◆ getParent()

ompl::geometric::QuotientSpace * ompl::geometric::QuotientSpace::getParent ( ) const

Parent is a more simplified quotient-space (higher in abstraction hierarchy)

Definition at line 1360 of file QuotientSpace.cpp.

◆ getQ0()

const ompl::base::SpaceInformationPtr & ompl::geometric::QuotientSpace::getQ0 ( ) const

Get SpaceInformationPtr for Q0 (Note: Q0 is the first component of Q1 = Q0 x X1)

Definition at line 1305 of file QuotientSpace.cpp.

◆ getQ0Dimension()

unsigned int ompl::geometric::QuotientSpace::getQ0Dimension ( ) const

Dimension of space Q0.

Definition at line 1325 of file QuotientSpace.cpp.

◆ getQ1()

const ompl::base::SpaceInformationPtr & ompl::geometric::QuotientSpace::getQ1 ( ) const

Get SpaceInformationPtr for Q1 (Note: Q1 is the product space Q1 = Q0 x X1)

Definition at line 1300 of file QuotientSpace.cpp.

◆ getQ1Dimension()

unsigned int ompl::geometric::QuotientSpace::getQ1Dimension ( ) const

Dimension of space Q1.

Definition at line 1315 of file QuotientSpace.cpp.

◆ getQ1SamplerPtr()

const ompl::base::StateSamplerPtr & ompl::geometric::QuotientSpace::getQ1SamplerPtr ( ) const

Definition at line 1335 of file QuotientSpace.cpp.

◆ getTotalNumberOfFeasibleSamples()

unsigned int ompl::geometric::QuotientSpace::getTotalNumberOfFeasibleSamples ( ) const

Number of feasible samples drawn on space Q1.

Definition at line 1355 of file QuotientSpace.cpp.

◆ getTotalNumberOfSamples()

unsigned int ompl::geometric::QuotientSpace::getTotalNumberOfSamples ( ) const

Number of samples drawn on space Q1.

Definition at line 1350 of file QuotientSpace.cpp.

◆ getType()

ompl::geometric::QuotientSpace::QuotientSpaceType ompl::geometric::QuotientSpace::getType ( ) const

Type of quotient-space.

Definition at line 1390 of file QuotientSpace.cpp.

◆ getX1()

const ompl::base::SpaceInformationPtr & ompl::geometric::QuotientSpace::getX1 ( ) const

Get SpaceInformationPtr for X1 (Note: X1 is the second component of Q1 = Q0 x X1)

Definition at line 1295 of file QuotientSpace.cpp.

◆ getX1Dimension()

unsigned int ompl::geometric::QuotientSpace::getX1Dimension ( ) const

Dimension of space X1.

Definition at line 1310 of file QuotientSpace.cpp.

◆ getX1SamplerPtr()

const ompl::base::StateSamplerPtr & ompl::geometric::QuotientSpace::getX1SamplerPtr ( ) const

Definition at line 1330 of file QuotientSpace.cpp.

◆ grow()

virtual void ompl::geometric::QuotientSpace::grow ( )
pure virtual

Implemented in ompl::geometric::QRRTImpl.

◆ hasSolution()

bool ompl::geometric::QuotientSpace::hasSolution ( )
virtual

Definition at line 1340 of file QuotientSpace.cpp.

◆ identifyQuotientSpaceType()

ompl::geometric::QuotientSpace::QuotientSpaceType ompl::geometric::QuotientSpace::identifyQuotientSpaceType ( const ompl::base::StateSpacePtr Q1,
const ompl::base::StateSpacePtr Q0 )
protected

Identify the type of the quotient Q1 / Q0.

Definition at line 348 of file QuotientSpace.cpp.

◆ mergeStates()

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

Definition at line 698 of file QuotientSpace.cpp.

◆ print()

void ompl::geometric::QuotientSpace::print ( std::ostream & out) const
protectedvirtual

Internal function implementing actual printing to stream.

Reimplemented in ompl::geometric::QuotientSpaceGraph.

Definition at line 1445 of file QuotientSpace.cpp.

◆ projectQ0()

void ompl::geometric::QuotientSpace::projectQ0 ( const ompl::base::State * q,
ompl::base::State * qQ0 ) const

Quotient Space Projection Operator onto first component ProjectQ0: Q0 \times X1 \rightarrow Q0.

Definition at line 1113 of file QuotientSpace.cpp.

◆ projectX1()

void ompl::geometric::QuotientSpace::projectX1 ( const ompl::base::State * q,
ompl::base::State * qX1 ) const

Quotient Space Projection Operator onto second component ProjectX1: Q0 \times X1 \rightarrow X1.

Definition at line 982 of file QuotientSpace.cpp.

◆ resetCounter()

void ompl::geometric::QuotientSpace::resetCounter ( )
static

reset counter for number of levels

Definition at line 190 of file QuotientSpace.cpp.

◆ sample()

bool ompl::geometric::QuotientSpace::sample ( ompl::base::State * q_random)
virtual

Reimplemented in ompl::geometric::QRRTImpl.

Definition at line 1406 of file QuotientSpace.cpp.

◆ sampleQuotient()

bool ompl::geometric::QuotientSpace::sampleQuotient ( ompl::base::State * q_random)
virtual

Reimplemented in ompl::geometric::QRRTImpl.

Definition at line 1400 of file QuotientSpace.cpp.

◆ setChild()

void ompl::geometric::QuotientSpace::setChild ( QuotientSpace * child_)

Set pointer to less simplified quotient-space.

Definition at line 1370 of file QuotientSpace.cpp.

◆ setLevel()

void ompl::geometric::QuotientSpace::setLevel ( unsigned int level)

Change abstraction level.

Definition at line 1385 of file QuotientSpace.cpp.

◆ setParent()

void ompl::geometric::QuotientSpace::setParent ( QuotientSpace * parent_)

Set pointer to more simplified quotient-space.

Definition at line 1375 of file QuotientSpace.cpp.

◆ setProblemDefinition()

void ompl::geometric::QuotientSpace::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 176 of file QuotientSpace.cpp.

◆ setup()

void ompl::geometric::QuotientSpace::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.

Reimplemented in ompl::geometric::QRRTImpl, and ompl::geometric::QuotientSpaceGraph.

Definition at line 132 of file QuotientSpace.cpp.

◆ solve()

ompl::base::PlannerStatus ompl::geometric::QuotientSpace::solve ( const ompl::base::PlannerTerminationCondition & ptc)
finaloverridevirtual

solve disabled (use MultiQuotient::solve) final prevents subclasses to override

Implements ompl::base::Planner.

Definition at line 170 of file QuotientSpace.cpp.

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream & out,
const QuotientSpace & qtnt )
friend

Write class to stream (use as std::cout << *this << std::endl) Actual implementation is in void print(std::ostream& out), which can be inherited.

Definition at line 1571 of file QuotientSpace.cpp.

Member Data Documentation

◆ child_

QuotientSpace* ompl::geometric::QuotientSpace::child_ {nullptr}
protected

Definition at line 212 of file QuotientSpace.h.

◆ counter_

unsigned int ompl::geometric::QuotientSpace::counter_ = 0
staticprotected

Definition at line 202 of file QuotientSpace.h.

◆ firstRun_

bool ompl::geometric::QuotientSpace::firstRun_ {true}
protected

Definition at line 209 of file QuotientSpace.h.

◆ hasSolution_

bool ompl::geometric::QuotientSpace::hasSolution_ {false}
protected

Definition at line 208 of file QuotientSpace.h.

◆ id_

unsigned int ompl::geometric::QuotientSpace::id_ {0}
protected

Identity of space (to keep track of number of quotient-spaces created)

Definition at line 204 of file QuotientSpace.h.

◆ level_

unsigned int ompl::geometric::QuotientSpace::level_ {0}
protected

Level in sequence of quotient-spaces.

Definition at line 206 of file QuotientSpace.h.

◆ opt_

ompl::base::OptimizationObjectivePtr ompl::geometric::QuotientSpace::opt_
protected

Definition at line 190 of file QuotientSpace.h.

◆ parent_

QuotientSpace* ompl::geometric::QuotientSpace::parent_ {nullptr}
protected

Definition at line 211 of file QuotientSpace.h.

◆ Q0

ompl::base::SpaceInformationPtr ompl::geometric::QuotientSpace::Q0 {nullptr}
protected

Definition at line 183 of file QuotientSpace.h.

◆ Q0_dimension_

unsigned int ompl::geometric::QuotientSpace::Q0_dimension_ {0}
protected

Definition at line 199 of file QuotientSpace.h.

◆ Q1

ompl::base::SpaceInformationPtr ompl::geometric::QuotientSpace::Q1 {nullptr}
protected

Definition at line 182 of file QuotientSpace.h.

◆ Q1_dimension_

unsigned int ompl::geometric::QuotientSpace::Q1_dimension_ {0}
protected

Definition at line 198 of file QuotientSpace.h.

◆ Q1_sampler_

ompl::base::StateSamplerPtr ompl::geometric::QuotientSpace::Q1_sampler_
protected

Definition at line 187 of file QuotientSpace.h.

◆ Q1_valid_sampler_

ompl::base::ValidStateSamplerPtr ompl::geometric::QuotientSpace::Q1_valid_sampler_
protected

Definition at line 188 of file QuotientSpace.h.

◆ s_Q0_tmp_

ompl::base::State* ompl::geometric::QuotientSpace::s_Q0_tmp_ {nullptr}
protected

A temporary state on Q0.

Definition at line 193 of file QuotientSpace.h.

◆ s_X1_tmp_

ompl::base::State* ompl::geometric::QuotientSpace::s_X1_tmp_ {nullptr}
protected

A temporary state on X1.

Definition at line 195 of file QuotientSpace.h.

◆ totalNumberOfFeasibleSamples_

unsigned int ompl::geometric::QuotientSpace::totalNumberOfFeasibleSamples_ {0}
protected

Definition at line 215 of file QuotientSpace.h.

◆ totalNumberOfSamples_

unsigned int ompl::geometric::QuotientSpace::totalNumberOfSamples_ {0}
protected

Definition at line 214 of file QuotientSpace.h.

◆ type_

QuotientSpaceType ompl::geometric::QuotientSpace::type_
protected

Definition at line 197 of file QuotientSpace.h.

◆ X1

ompl::base::SpaceInformationPtr ompl::geometric::QuotientSpace::X1 {nullptr}
protected

Definition at line 184 of file QuotientSpace.h.

◆ X1_dimension_

unsigned int ompl::geometric::QuotientSpace::X1_dimension_ {0}
protected

Definition at line 200 of file QuotientSpace.h.

◆ X1_sampler_

ompl::base::StateSamplerPtr ompl::geometric::QuotientSpace::X1_sampler_
protected

Definition at line 186 of file QuotientSpace.h.


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