A state in SE(2): (x, y, yaw) More...
#include <ompl/base/spaces/SE2StateSpace.h>

Public Member Functions | |
double | getX () const |
Get the X component of the state. | |
double | getY () const |
Get the Y component of the state. | |
double | getYaw () const |
Get the yaw component of the state. This is the rotation in plane, with respect to the Z axis. | |
void | setX (double x) |
Set the X component of the state. | |
void | setY (double y) |
Set the Y component of the state. | |
void | setXY (double x, double y) |
Set the X and Y components of the state. | |
void | setYaw (double yaw) |
Set the yaw component of the state. This is the rotation in plane, with respect to the Z axis. | |
![]() | |
template<class T > | |
const T * | as (unsigned int index) const |
Cast a component of this instance to a desired type. | |
template<class T > | |
T * | as (const unsigned int index) |
Cast a component of this instance to a desired type. | |
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. | |
![]() | |
template<class T > | |
const T * | as () const |
Cast this instance to a desired type. | |
template<class T > | |
T * | as () |
Cast this instance to a desired type. | |
Additional Inherited Members | |
![]() | |
State ** | components {nullptr} |
The components that make up a compound state. | |
![]() |
Detailed Description
A state in SE(2): (x, y, yaw)
Definition at line 53 of file SE2StateSpace.h.
Member Function Documentation
◆ getX()
|
inline |
Get the X component of the state.
Definition at line 59 of file SE2StateSpace.h.
◆ getY()
|
inline |
Get the Y component of the state.
Definition at line 65 of file SE2StateSpace.h.
◆ getYaw()
|
inline |
Get the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
Definition at line 73 of file SE2StateSpace.h.
◆ setX()
|
inline |
Set the X component of the state.
Definition at line 79 of file SE2StateSpace.h.
◆ setXY()
|
inline |
Set the X and Y components of the state.
Definition at line 91 of file SE2StateSpace.h.
◆ setY()
|
inline |
Set the Y component of the state.
Definition at line 85 of file SE2StateSpace.h.
◆ setYaw()
|
inline |
Set the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
Definition at line 100 of file SE2StateSpace.h.
The documentation for this class was generated from the following file:
- ompl/base/spaces/SE2StateSpace.h