00001 /* 00002 * TKState.hpp 00003 * 00004 * Created on: Nov 8, 2011 00005 * Author: mriedel 00006 */ 00007 00008 #ifndef TKSTATE_HPP_ 00009 #define TKSTATE_HPP_ 00010 00011 #include <telekyb_defines/telekyb_defines.hpp> 00012 #include <telekyb_base/Spaces/R3.hpp> 00013 #include <telekyb_msgs/TKState.h> 00014 00015 #include <telekyb_base/Time/Time.hpp> 00016 00017 namespace TELEKYB_NAMESPACE { 00018 00019 class TKState { 00020 public: 00021 Time time; 00022 Position3D position; // (x,y,z) 00023 Quaternion orientation; // (w,x,y,z) 00024 Velocity3D linVelocity; // (x,y,z) 00025 Velocity3D angVelocity; // (omega_x, omega_y, omega_z) 00026 00027 TKState(); 00028 TKState(const telekyb_msgs::TKState& tkStateMsg); 00029 virtual ~TKState(); 00030 00031 void toTKStateMsg(telekyb_msgs::TKState& tkStateMsg) const; 00032 void fromTKStateMsg(const telekyb_msgs::TKState& tkStateMsg); 00033 Vector3D getEulerRPY() const; 00034 }; 00035 00036 } 00037 00038 #endif /* TKSTATE_HPP_ */