A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w). More...
#include <SE3StateSpace.h>

Public Member Functions | |
| double | getX (void) const |
| Get the X component of the state. | |
| double | getY (void) const |
| Get the Y component of the state. | |
| double | getZ (void) const |
| Get the Z component of the state. | |
| SO3StateSpace::StateType & | rotation (void) |
| Get the rotation component of the state and allow changing it as well. | |
| const SO3StateSpace::StateType & | rotation (void) const |
| Get the rotation component of the state. | |
| void | setX (double x) |
| Set the X component of the state. | |
| void | setXYZ (double x, double y, double z) |
| Set the X, Y and Z components 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. | |
| StateType (void) | |
A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w).
Definition at line 47 of file SE3StateSpace.h.
| ompl::base::SE3StateSpace::StateType::StateType | ( | void | ) | [inline] |
Definition at line 45 of file SE3StateSpace.h.
| double ompl::base::SE3StateSpace::StateType::getX | ( | void | ) | const [inline] |
Get the X component of the state.
Definition at line 50 of file SE3StateSpace.h.
| double ompl::base::SE3StateSpace::StateType::getY | ( | void | ) | const [inline] |
Get the Y component of the state.
Definition at line 56 of file SE3StateSpace.h.
| double ompl::base::SE3StateSpace::StateType::getZ | ( | void | ) | const [inline] |
Get the Z component of the state.
Definition at line 62 of file SE3StateSpace.h.
| SO3StateSpace::StateType& ompl::base::SE3StateSpace::StateType::rotation | ( | void | ) | [inline] |
Get the rotation component of the state and allow changing it as well.
Definition at line 74 of file SE3StateSpace.h.
| const SO3StateSpace::StateType& ompl::base::SE3StateSpace::StateType::rotation | ( | void | ) | const [inline] |
Get the rotation component of the state.
Definition at line 68 of file SE3StateSpace.h.
| void ompl::base::SE3StateSpace::StateType::setX | ( | double | x | ) | [inline] |
Set the X component of the state.
Definition at line 80 of file SE3StateSpace.h.
| void ompl::base::SE3StateSpace::StateType::setXYZ | ( | double | x, | |
| double | y, | |||
| double | z | |||
| ) | [inline] |
Set the X, Y and Z components of the state.
Definition at line 98 of file SE3StateSpace.h.
| void ompl::base::SE3StateSpace::StateType::setY | ( | double | y | ) | [inline] |
Set the Y component of the state.
Definition at line 86 of file SE3StateSpace.h.
| void ompl::base::SE3StateSpace::StateType::setZ | ( | double | z | ) | [inline] |
Set the Z component of the state.
Definition at line 92 of file SE3StateSpace.h.