Class SE3StateSpace
Defined in File SE3StateSpace.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::CompoundStateSpace
(Class CompoundStateSpace)
Class Documentation
-
class SE3StateSpace : public ompl::base::CompoundStateSpace
A state space representing SE(3)
Public Functions
-
inline SE3StateSpace()
-
~SE3StateSpace() 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.
-
class StateType : public ompl::base::CompoundState
A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w)
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 getZ() const
Get the Z component of the state.
-
inline const SO3StateSpace::StateType &rotation() const
Get the rotation component of the state.
-
inline SO3StateSpace::StateType &rotation()
Get the rotation component of the state and allow changing it as well.
-
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 setZ(double z)
Set the Z component of the state.
-
inline void setXYZ(double x, double y, double z)
Set the X, Y and Z components of the state.
-
StateType() = default
-
inline SE3StateSpace()