Go to the documentation of this file.
32 #ifndef CONVERSIONS_KDL_MSG_H
33 #define CONVERSIONS_KDL_MSG_H
35 #include "kdl/frames.hpp"
36 #include <geometry_msgs/Point.h>
37 #include <geometry_msgs/Pose.h>
38 #include <geometry_msgs/Quaternion.h>
39 #include <geometry_msgs/Transform.h>
40 #include <geometry_msgs/Twist.h>
41 #include <geometry_msgs/Vector3.h>
42 #include <geometry_msgs/Wrench.h>
50 void pointMsgToKDL(
const geometry_msgs::Point &m, KDL::Vector &k);
53 void pointKDLToMsg(
const KDL::Vector &k, geometry_msgs::Point &m);
56 void poseMsgToKDL(
const geometry_msgs::Pose &m, KDL::Frame &k);
59 void poseKDLToMsg(
const KDL::Frame &k, geometry_msgs::Pose &m);
74 void twistMsgToKDL(
const geometry_msgs::Twist &m, KDL::Twist &k);
77 void twistKDLToMsg(
const KDL::Twist &k, geometry_msgs::Twist &m);
80 void vectorMsgToKDL(
const geometry_msgs::Vector3 &m, KDL::Vector &k);
83 void vectorKDLToMsg(
const KDL::Vector &k, geometry_msgs::Vector3 &m);
86 void wrenchMsgToKDL(
const geometry_msgs::Wrench &m, KDL::Wrench &k);
89 void wrenchKDLToMsg(
const KDL::Wrench &k, geometry_msgs::Wrench &m);
void pointKDLToMsg(const KDL::Vector &k, geometry_msgs::Point &m)
Converts a KDL Vector into a geometry_msgs Vector3.
void twistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m)
Converts a KDL Twist into a Twist message.
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
Converts a Pose message into a KDL Frame.
void vectorKDLToMsg(const KDL::Vector &k, geometry_msgs::Vector3 &m)
Converts a KDL Vector into a Vector3 message.
ROS_DEPRECATED void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k)
Converts a Twist message into a KDL Twist.
ROS_DEPRECATED void PoseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
Converts a KDL Frame into a Pose message.
void quaternionMsgToKDL(const geometry_msgs::Quaternion &m, KDL::Rotation &k)
Converts a quaternion message into a KDL Rotation.
void transformMsgToKDL(const geometry_msgs::Transform &m, KDL::Frame &k)
Converts a Transform message into a KDL Frame.
ROS_DEPRECATED void PoseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
Converts a Pose message into a KDL Frame.
void twistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k)
Converts a Twist message into a KDL Twist.
void quaternionKDLToMsg(const KDL::Rotation &k, geometry_msgs::Quaternion &m)
Converts a KDL Rotation into a message quaternion.
void vectorMsgToKDL(const geometry_msgs::Vector3 &m, KDL::Vector &k)
Converts a Vector3 message into a KDL Vector.
ROS_DEPRECATED void TwistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m)
Converts a KDL Twist into a Twist message.
void pointMsgToKDL(const geometry_msgs::Point &m, KDL::Vector &k)
Conversion functions from/to the corresponding KDL and geometry_msgs types.
void wrenchMsgToKDL(const geometry_msgs::Wrench &m, KDL::Wrench &k)
Converts a Wrench message into a KDL Wrench.
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
Converts a KDL Frame into a Pose message.
void transformKDLToMsg(const KDL::Frame &k, geometry_msgs::Transform &m)
Converts a KDL Frame into a Transform message.
void wrenchKDLToMsg(const KDL::Wrench &k, geometry_msgs::Wrench &m)
Converts a KDL Wrench into a Wrench message.
kdl_conversions
Author(s): Adam Leeper
autogenerated on Sat Aug 19 2023 02:38:06