Class SE2StateSpace

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Derived Types

Class Documentation

class SE2StateSpace : public ompl::base::CompoundStateSpace

A state space representing SE(2)

Subclassed by ompl::base::DubinsStateSpace, ompl::base::ReedsSheppStateSpace, ompl::base::TrochoidStateSpace

Public Functions

inline SE2StateSpace()
~SE2StateSpace() override = default
inline void setBounds(const RealVectorBounds &bounds)

Set the bounds of this state space. This defines the range of the space in which sampling is performed.

inline const RealVectorBounds &getBounds() const

Get the bounds for this state space.

virtual State *allocState() const override

Allocate a state that can store a point in the described space.

virtual void freeState(State *state) const override

Free the memory of the allocated state.

virtual void registerProjections() override

Register the projections for this state space. Usually, this is at least the default projection. These are implicit projections, set by the implementation of the state space. This is called by setup().

class StateType : public ompl::base::CompoundState

A state in SE(2): (x, y, yaw)

Public Functions

StateType() = default
inline double getX() const

Get the X component of the state.

inline double getY() const

Get the Y component of the state.

inline double getYaw() const

Get the yaw component of the state. This is the rotation in plane, with respect to the Z axis.

inline void setX(double x)

Set the X component of the state.

inline void setY(double y)

Set the Y component of the state.

inline void setXY(double x, double y)

Set the X and Y components of the state.

inline void setYaw(double yaw)

Set the yaw component of the state. This is the rotation in plane, with respect to the Z axis.