Class HybridStateSpace

Inheritance Relationships

Base Type

Class Documentation

class HybridStateSpace : public ompl::base::CompoundStateSpace

A state space consisting of a space and a time component.

Public Functions

explicit HybridStateSpace(const StateSpacePtr &spaceComponent)

Constructor. The maximum velocity and the weight of the time component for distance calculation need to be specified.

virtual double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override

The distance from state1 to state2. May be infinite.

The distance is direction independent for compatibility to some planners (like RRTConnect). Make sure that the motion validator does not allow motions backwards in time or adjust the distance function in the Space Time State Space and the used planner.

double timeToCoverDistance(const ompl::base::State *state1, const ompl::base::State *state2) const

The time to get from state1 to state2.

double distanceSpace(const ompl::base::State *state1, const ompl::base::State *state2) const

The distance of just the space component.

double distanceTime(const ompl::base::State *state1, const ompl::base::State *state2) const

The distance of just the time component.

void setTimeBounds(double lb, double ub)

Set lower and upper time bounds for the time component.

StateSpacePtr getSpaceComponent()

The space component as a StateSpacePtr.

HybridTimeStateSpace *getTimeComponent()

The time component as a TimeStateSpace pointer.

virtual bool isMetricSpace() const override

No metric state space, as the triangle inequality is not satisfied.

virtual double getMaximumExtent() const override

Maximum extent is infinite, as the distance can be infinite even with bounded time.

void updateEpsilon()

Scale epsilon appropriately after time or space bounds were set.

Public Static Functions

static double getStateTime(const ompl::base::State *state)

The time value of the given state.

static int getStateJumps(const ompl::base::State *state)

The jumps value of the given state.

static void setStateJumps(ompl::base::State *state, int jumps)

Set the jumps value of the given state.

static void setStateTime(ompl::base::State *state, double position)

Set the time position value of the given state.

Protected Attributes

double eps_ = std::numeric_limits<float>::epsilon()

The epsilon for time distance calculation.