kdl_conversions-types.cpp
Go to the documentation of this file.
4 
5 namespace KDL
6 {
12  {
13  public:
14  std::string getName(){return "KDLConversions";};
15  bool loadTypes(){return true;};
16  bool loadConstructors(){return true;};
18  {
20  gs->provides("KDL")->addOperation("pointMsgToKDL",&tf::pointMsgToKDL);
21  gs->provides("KDL")->addOperation("pointKDLToMsg",&tf::pointKDLToMsg);
22  gs->provides("KDL")->addOperation("poseMsgToKDL",&tf::poseMsgToKDL);
23  gs->provides("KDL")->addOperation("poseKDLToMsg",&tf::poseKDLToMsg);
24  gs->provides("KDL")->addOperation("quaternionMsgToKDL",&tf::quaternionMsgToKDL);
25  gs->provides("KDL")->addOperation("quaternionKDLToMsg",&tf::quaternionKDLToMsg);
26  gs->provides("KDL")->addOperation("transformMsgToKDL",&tf::transformMsgToKDL);
27  gs->provides("KDL")->addOperation("transformKDLToMsg",&tf::transformKDLToMsg);
28  gs->provides("KDL")->addOperation("twistMsgToKDL",&tf::twistMsgToKDL);
29  gs->provides("KDL")->addOperation("twistKDLToMsg",&tf::twistKDLToMsg);
30  gs->provides("KDL")->addOperation("vectorMsgToKDL",&tf::vectorMsgToKDL);
31  gs->provides("KDL")->addOperation("vectorKDLToMsg",&tf::vectorKDLToMsg);
32  gs->provides("KDL")->addOperation("wrenchMsgToKDL",&tf::wrenchMsgToKDL);
33  gs->provides("KDL")->addOperation("wrenchKDLToMsg",&tf::wrenchKDLToMsg);
34  return true;
35  }
36  };
41 }
42 
#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)


rtt_kdl_conversions
Author(s): Ruben Smits
autogenerated on Sat Jun 8 2019 18:04:51