14 std::string
getName(){
return "KDLConversions";};
#define ORO_TYPEKIT_PLUGIN(TYPEKIT)
void vectorKDLToMsg(const KDL::Vector &k, geometry_msgs::Vector3 &m)
void transformKDLToMsg(const KDL::Frame &k, geometry_msgs::Transform &m)
void twistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k)
void quaternionMsgToKDL(const geometry_msgs::Quaternion &m, KDL::Rotation &k)
void transformMsgToKDL(const geometry_msgs::Transform &m, KDL::Frame &k)
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
KDLConversionTypekitPlugin KDLTypekit
void twistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m)
void wrenchMsgToKDL(const geometry_msgs::Wrench &m, KDL::Wrench &k)
void quaternionKDLToMsg(const KDL::Rotation &k, geometry_msgs::Quaternion &m)
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
void pointKDLToMsg(const KDL::Vector &k, geometry_msgs::Point &m)
void pointMsgToKDL(const geometry_msgs::Point &m, KDL::Vector &k)
void wrenchKDLToMsg(const KDL::Wrench &k, geometry_msgs::Wrench &m)
static RTT_API Service::shared_ptr Instance()
void vectorMsgToKDL(const geometry_msgs::Vector3 &m, KDL::Vector &k)