ompl::base::SE2StateSpace::StateType Class Reference

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

#include <SE2StateSpace.h>

Inheritance diagram for ompl::base::SE2StateSpace::StateType:
Inheritance graph
[legend]

List of all members.

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 getYaw (void) 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 setXY (double x, double y)
 Set the X and Y components of the state.
void setY (double y)
 Set the Y component 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.
 StateType (void)

Detailed Description

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

Definition at line 47 of file SE2StateSpace.h.


Constructor & Destructor Documentation

ompl::base::SE2StateSpace::StateType::StateType ( void   )  [inline]

Definition at line 45 of file SE2StateSpace.h.


Member Function Documentation

double ompl::base::SE2StateSpace::StateType::getX ( void   )  const [inline]

Get the X component of the state.

Definition at line 50 of file SE2StateSpace.h.

double ompl::base::SE2StateSpace::StateType::getY ( void   )  const [inline]

Get the Y component of the state.

Definition at line 56 of file SE2StateSpace.h.

double ompl::base::SE2StateSpace::StateType::getYaw ( void   )  const [inline]

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

Definition at line 64 of file SE2StateSpace.h.

void ompl::base::SE2StateSpace::StateType::setX ( double  x  )  [inline]

Set the X component of the state.

Definition at line 70 of file SE2StateSpace.h.

void ompl::base::SE2StateSpace::StateType::setXY ( double  x,
double  y 
) [inline]

Set the X and Y components of the state.

Definition at line 82 of file SE2StateSpace.h.

void ompl::base::SE2StateSpace::StateType::setY ( double  y  )  [inline]

Set the Y component of the state.

Definition at line 76 of file SE2StateSpace.h.

void ompl::base::SE2StateSpace::StateType::setYaw ( double  yaw  )  [inline]

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

Definition at line 91 of file SE2StateSpace.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:34:00 2013