Class BundleSpace

Inheritance Relationships

Base Type

Derived Type

Class Documentation

class BundleSpace : public ompl::base::Planner

A single Bundle-space.

Subclassed by ompl::multilevel::BundleSpaceGraph

Public Functions

BundleSpace(const ompl::base::SpaceInformationPtr &si, BundleSpace *baseSpace_ = nullptr)

Bundle Space contains three primary characters, the bundle space, the base space and the projection.

  • Bundle is (locally) a product space of Base and Fiber

  • Base is a pointer to the next lower-dimensional Bundle-space (if any)

  • Projection is a mapping from Bundle to Base

You can provide Bundle and Base space (as ompl::base::SpaceInformationPtr) and let the class compute the projection automatically or provide an explicit projection

virtual ~BundleSpace()
const ompl::base::SpaceInformationPtr &getBundle() const

Get SpaceInformationPtr for Bundle.

const ompl::base::SpaceInformationPtr &getBase() const

Get SpaceInformationPtr for Base.

ProjectionPtr getProjection() const

Get ProjectionPtr from Bundle to Base.

bool makeProjection()

Given bundle space and base space, try to guess the right.

void setProjection(ProjectionPtr projection)

Set explicit projection (so that we do not need to guess.

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

Perform an iteration of the planner.

virtual bool getSolution(ompl::base::PathPtr &solution) = 0

Return best solution.

virtual void setMetric(const std::string &sMetric) = 0
virtual void setPropagator(const std::string &sPropagator) = 0
virtual void sampleFromDatastructure(ompl::base::State *xBase) = 0
virtual void sampleBundle(ompl::base::State *xRandom)
bool sampleBundleValid(ompl::base::State *xRandom)
virtual bool hasSolution()
virtual bool isInfeasible()

Check if any infeasibility guarantees are fulfilled.

virtual bool hasConverged()

Check if the current space can still be sampled.

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 = 0

Compute importance of bundle space (to decide where to.

ompl::base::State *allocIdentityStateBundle() const

Allocate State, set entries to Identity/Zero.

ompl::base::State *allocIdentityStateBase() const
ompl::base::State *allocIdentityState(ompl::base::StateSpacePtr) const
void allocIdentityState(ompl::base::State*, ompl::base::StateSpacePtr) const
unsigned int getBaseDimension() const

Dimension of Base Space.

unsigned int getBundleDimension() const

Dimension of Bundle Space.

unsigned int getCoDimension() const

Dimension of Bundle Space - Dimension of Base Space.

const ompl::base::StateSamplerPtr &getBundleSamplerPtr() const
const ompl::base::StateSamplerPtr &getBaseSamplerPtr() const
BundleSpace *getChild() const

Return k-1 th bundle space (locally the base space)

void setChild(BundleSpace *child)

Pointer to k-1 th bundle space (locally the base space)

BundleSpace *getParent() const

Return k+1 th bundle space (locally the total space)

void setParent(BundleSpace *parent)

Pointer to k+1 th bundle space (locally the total space)

bool hasParent() const

Return if has parent space pointer.

bool hasBaseSpace() const

Return if has base space pointer.

unsigned int getLevel() const

Level in hierarchy of Bundle-spaces.

void setLevel(unsigned int)

Change level in hierarchy.

void project(const ompl::base::State *xBundle, ompl::base::State *xBase) const

Bundle Space Projection Operator onto first component ProjectBase: Bundle \rightarrow Base.

void lift(const ompl::base::State *xBase, ompl::base::State *xBundle) const

Lift a state from Base to Bundle.

ompl::base::OptimizationObjectivePtr getOptimizationObjectivePtr() const
bool isDynamic() const
base::GoalSampleableRegion *getGoalPtr() const

Public Static Functions

static void resetCounter()

reset counter for number of levels

Protected Functions

void checkBundleSpaceMeasure(std::string name, const ompl::base::StateSpacePtr space) const

Check if Bundle-space is bounded.

void sanityChecks() const

Check if Bundle-space has correct structure.

virtual void print(std::ostream &out) const

Internal function implementing actual printing to stream.

Protected Attributes

ompl::base::State *xBaseTmp_ = {nullptr}

A temporary state on Base.

ompl::base::State *xBundleTmp_ = {nullptr}

A temporary state on Bundle.

unsigned int id_ = {0}

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

bool hasSolution_ = {false}

If there exists a solution.

bool firstRun_ = {true}

Variable to check if this bundle space planner has been run at.

bool isDynamic_ = {false}

If the problem is dynamic or geometric.

BundleSpaceMetricPtr metric_

Metric on bundle space.

BundleSpacePropagatorPtr propagator_

Propagator (steering or interpolation) on bundle space. Note: currently just a stub for base::StatePropagator.

Protected Static Attributes

static unsigned int counter_

Internal counter to track multiple bundle spaces.

Friends

friend std::ostream &operator<<(std::ostream&, const BundleSpace&)

Write class to stream (use as std::cout << *this << std::endl)