#include <TKState.hpp>
Public Member Functions | |
| void | fromTKStateMsg (const telekyb_msgs::TKState &tkStateMsg) |
| Vector3D | getEulerRPY () const |
| TKState () | |
| TKState (const telekyb_msgs::TKState &tkStateMsg) | |
| void | toTKStateMsg (telekyb_msgs::TKState &tkStateMsg) const |
| virtual | ~TKState () |
Public Attributes | |
| Velocity3D | angVelocity |
| Velocity3D | linVelocity |
| Quaternion | orientation |
| Position3D | position |
| Time | time |
Definition at line 19 of file TKState.hpp.
Definition at line 12 of file TKState.cpp.
| TELEKYB_NAMESPACE::TKState::TKState | ( | const telekyb_msgs::TKState & | tkStateMsg | ) |
Definition at line 19 of file TKState.cpp.
| TELEKYB_NAMESPACE::TKState::~TKState | ( | ) | [virtual] |
Definition at line 24 of file TKState.cpp.
| void TELEKYB_NAMESPACE::TKState::fromTKStateMsg | ( | const telekyb_msgs::TKState & | tkStateMsg | ) |
Definition at line 54 of file TKState.cpp.
| Vector3D TELEKYB_NAMESPACE::TKState::getEulerRPY | ( | ) | const |
Definition at line 79 of file TKState.cpp.
| void TELEKYB_NAMESPACE::TKState::toTKStateMsg | ( | telekyb_msgs::TKState & | tkStateMsg | ) | const |
Definition at line 28 of file TKState.cpp.
| Velocity3D TELEKYB_NAMESPACE::TKState::angVelocity |
Definition at line 25 of file TKState.hpp.
| Velocity3D TELEKYB_NAMESPACE::TKState::linVelocity |
Definition at line 24 of file TKState.hpp.
| Quaternion TELEKYB_NAMESPACE::TKState::orientation |
Definition at line 23 of file TKState.hpp.
| Position3D TELEKYB_NAMESPACE::TKState::position |
Definition at line 22 of file TKState.hpp.
Definition at line 21 of file TKState.hpp.