ompl::base::SE3StateSpace::StateType Class Reference
A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w) More...
#include <ompl/base/spaces/SE3StateSpace.h>
Inheritance diagram for ompl::base::SE3StateSpace::StateType:

Public Member Functions | |
| double | getX () const |
| Get the X component of the state. | |
| double | getY () const |
| Get the Y component of the state. | |
| double | getZ () const |
| Get the Z component of the state. | |
| const SO3StateSpace::StateType & | rotation () const |
| Get the rotation component of the state. | |
| SO3StateSpace::StateType & | rotation () |
| Get the rotation component of the state and allow changing it as well. | |
| void | setX (double x) |
| Set the X component of the state. | |
| void | setY (double y) |
| Set the Y component of the state. | |
| void | setZ (double z) |
| Set the Z component of the state. | |
| void | setXYZ (double x, double y, double z) |
| Set the X, Y and Z components of the state. | |
Public Member Functions inherited from ompl::base::CompoundState | |
| template<class T > | |
| const T * | as (unsigned int index) const |
| Cast a component of this instance to a desired type. More... | |
| template<class T > | |
| T * | as (const unsigned int index) |
| Cast a component of this instance to a desired type. More... | |
| const State * | operator[] (unsigned int i) const |
| Access const element ith component. This does not check whether the index is within bounds. | |
| State * | operator[] (unsigned int i) |
| Access element ith component. This does not check whether the index is within bounds. | |
Public Member Functions inherited from ompl::base::State | |
| template<class T > | |
| const T * | as () const |
| Cast this instance to a desired type. More... | |
| template<class T > | |
| T * | as () |
| Cast this instance to a desired type. More... | |
Additional Inherited Members | |
Public Attributes inherited from ompl::base::CompoundState | |
| State ** | components {nullptr} |
| The components that make up a compound state. | |
Detailed Description
A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w)
Definition at line 149 of file SE3StateSpace.h.
The documentation for this class was generated from the following file:
- ompl/base/spaces/SE3StateSpace.h
Public Member Functions inherited from