Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00032 #ifndef TF2_KDL_H
00033 #define TF2_KDL_H
00034
00035 #include <tf2/convert.h>
00036 #include <kdl/frames.hpp>
00037 #include <geometry_msgs/PointStamped.h>
00038 #include <geometry_msgs/TwistStamped.h>
00039 #include <geometry_msgs/WrenchStamped.h>
00040 #include <geometry_msgs/PoseStamped.h>
00041
00042
00043 namespace tf2
00044 {
00049 inline
00050 KDL::Frame transformToKDL(const geometry_msgs::TransformStamped& t)
00051 {
00052 return KDL::Frame(KDL::Rotation::Quaternion(t.transform.rotation.x, t.transform.rotation.y,
00053 t.transform.rotation.z, t.transform.rotation.w),
00054 KDL::Vector(t.transform.translation.x, t.transform.translation.y, t.transform.translation.z));
00055 }
00056
00061 inline
00062 geometry_msgs::TransformStamped kdlToTransform(const KDL::Frame& k)
00063 {
00064 geometry_msgs::TransformStamped t;
00065 t.transform.translation.x = k.p.x();
00066 t.transform.translation.y = k.p.y();
00067 t.transform.translation.z = k.p.z();
00068 k.M.GetQuaternion(t.transform.rotation.x, t.transform.rotation.y, t.transform.rotation.z, t.transform.rotation.w);
00069 return t;
00070 }
00071
00072
00073
00074
00081 template <>
00082 inline
00083 void doTransform(const tf2::Stamped<KDL::Vector>& t_in, tf2::Stamped<KDL::Vector>& t_out, const geometry_msgs::TransformStamped& transform)
00084 {
00085 t_out = tf2::Stamped<KDL::Vector>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00086 }
00087
00093 inline
00094 geometry_msgs::PointStamped toMsg(const tf2::Stamped<KDL::Vector>& in)
00095 {
00096 geometry_msgs::PointStamped msg;
00097 msg.header.stamp = in.stamp_;
00098 msg.header.frame_id = in.frame_id_;
00099 msg.point.x = in[0];
00100 msg.point.y = in[1];
00101 msg.point.z = in[2];
00102 return msg;
00103 }
00104
00110 inline
00111 void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped<KDL::Vector>& out)
00112 {
00113 out.stamp_ = msg.header.stamp;
00114 out.frame_id_ = msg.header.frame_id;
00115 out[0] = msg.point.x;
00116 out[1] = msg.point.y;
00117 out[2] = msg.point.z;
00118 }
00119
00120
00121
00122
00129 template <>
00130 inline
00131 void doTransform(const tf2::Stamped<KDL::Twist>& t_in, tf2::Stamped<KDL::Twist>& t_out, const geometry_msgs::TransformStamped& transform)
00132 {
00133 t_out = tf2::Stamped<KDL::Twist>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00134 }
00135
00141 inline
00142 geometry_msgs::TwistStamped toMsg(const tf2::Stamped<KDL::Twist>& in)
00143 {
00144 geometry_msgs::TwistStamped msg;
00145 msg.header.stamp = in.stamp_;
00146 msg.header.frame_id = in.frame_id_;
00147 msg.twist.linear.x = in.vel[0];
00148 msg.twist.linear.y = in.vel[1];
00149 msg.twist.linear.z = in.vel[2];
00150 msg.twist.angular.x = in.rot[0];
00151 msg.twist.angular.y = in.rot[1];
00152 msg.twist.angular.z = in.rot[2];
00153 return msg;
00154 }
00155
00161 inline
00162 void fromMsg(const geometry_msgs::TwistStamped& msg, tf2::Stamped<KDL::Twist>& out)
00163 {
00164 out.stamp_ = msg.header.stamp;
00165 out.frame_id_ = msg.header.frame_id;
00166 out.vel[0] = msg.twist.linear.x;
00167 out.vel[1] = msg.twist.linear.y;
00168 out.vel[2] = msg.twist.linear.z;
00169 out.rot[0] = msg.twist.angular.x;
00170 out.rot[1] = msg.twist.angular.y;
00171 out.rot[2] = msg.twist.angular.z;
00172 }
00173
00174
00175
00176
00177
00184 template <>
00185 inline
00186 void doTransform(const tf2::Stamped<KDL::Wrench>& t_in, tf2::Stamped<KDL::Wrench>& t_out, const geometry_msgs::TransformStamped& transform)
00187 {
00188 t_out = tf2::Stamped<KDL::Wrench>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00189 }
00190
00196 inline
00197 geometry_msgs::WrenchStamped toMsg(const tf2::Stamped<KDL::Wrench>& in)
00198 {
00199 geometry_msgs::WrenchStamped msg;
00200 msg.header.stamp = in.stamp_;
00201 msg.header.frame_id = in.frame_id_;
00202 msg.wrench.force.x = in.force[0];
00203 msg.wrench.force.y = in.force[1];
00204 msg.wrench.force.z = in.force[2];
00205 msg.wrench.torque.x = in.torque[0];
00206 msg.wrench.torque.y = in.torque[1];
00207 msg.wrench.torque.z = in.torque[2];
00208 return msg;
00209 }
00210
00216 inline
00217 void fromMsg(const geometry_msgs::WrenchStamped& msg, tf2::Stamped<KDL::Wrench>& out)
00218 {
00219 out.stamp_ = msg.header.stamp;
00220 out.frame_id_ = msg.header.frame_id;
00221 out.force[0] = msg.wrench.force.x;
00222 out.force[1] = msg.wrench.force.y;
00223 out.force[2] = msg.wrench.force.z;
00224 out.torque[0] = msg.wrench.torque.x;
00225 out.torque[1] = msg.wrench.torque.y;
00226 out.torque[2] = msg.wrench.torque.z;
00227 }
00228
00229
00230
00231
00232
00233
00234
00241 template <>
00242 inline
00243 void doTransform(const tf2::Stamped<KDL::Frame>& t_in, tf2::Stamped<KDL::Frame>& t_out, const geometry_msgs::TransformStamped& transform)
00244 {
00245 t_out = tf2::Stamped<KDL::Frame>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00246 }
00247
00253 inline
00254 geometry_msgs::PoseStamped toMsg(const tf2::Stamped<KDL::Frame>& in)
00255 {
00256 geometry_msgs::PoseStamped msg;
00257 msg.header.stamp = in.stamp_;
00258 msg.header.frame_id = in.frame_id_;
00259 msg.pose.position.x = in.p[0];
00260 msg.pose.position.y = in.p[1];
00261 msg.pose.position.z = in.p[2];
00262 in.M.GetQuaternion(msg.pose.orientation.x, msg.pose.orientation.y, msg.pose.orientation.z, msg.pose.orientation.w);
00263 return msg;
00264 }
00265
00271 inline
00272 void fromMsg(const geometry_msgs::PoseStamped& msg, tf2::Stamped<KDL::Frame>& out)
00273 {
00274 out.stamp_ = msg.header.stamp;
00275 out.frame_id_ = msg.header.frame_id;
00276 out.p[0] = msg.pose.position.x;
00277 out.p[1] = msg.pose.position.y;
00278 out.p[2] = msg.pose.position.z;
00279 out.M = KDL::Rotation::Quaternion(msg.pose.orientation.x, msg.pose.orientation.y, msg.pose.orientation.z, msg.pose.orientation.w);
00280 }
00281
00282
00283 }
00284
00285 #endif // TF2_KDL_H