tf2_kdl.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
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 #include <geometry_msgs/Pose.h>
00042 
00043 
00044 namespace tf2
00045 {
00050 inline
00051 KDL::Frame transformToKDL(const geometry_msgs::TransformStamped& t)
00052   {
00053     return KDL::Frame(KDL::Rotation::Quaternion(t.transform.rotation.x, t.transform.rotation.y,
00054                                                 t.transform.rotation.z, t.transform.rotation.w),
00055                       KDL::Vector(t.transform.translation.x, t.transform.translation.y, t.transform.translation.z));
00056   }
00057 
00062 inline
00063 geometry_msgs::TransformStamped kdlToTransform(const KDL::Frame& k)
00064 {
00065   geometry_msgs::TransformStamped t;
00066   t.transform.translation.x = k.p.x();
00067   t.transform.translation.y = k.p.y();
00068   t.transform.translation.z = k.p.z();
00069   k.M.GetQuaternion(t.transform.rotation.x, t.transform.rotation.y, t.transform.rotation.z, t.transform.rotation.w);
00070   return t;
00071 }
00072 
00073 // ---------------------
00074 // Vector
00075 // ---------------------
00082 template <>
00083 inline
00084   void doTransform(const tf2::Stamped<KDL::Vector>& t_in, tf2::Stamped<KDL::Vector>& t_out, const geometry_msgs::TransformStamped& transform)
00085   {
00086     t_out = tf2::Stamped<KDL::Vector>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00087   }
00088 
00094 inline
00095 geometry_msgs::PointStamped toMsg(const tf2::Stamped<KDL::Vector>& in)
00096 {
00097   geometry_msgs::PointStamped msg;
00098   msg.header.stamp = in.stamp_;
00099   msg.header.frame_id = in.frame_id_;
00100   msg.point.x = in[0];
00101   msg.point.y = in[1];
00102   msg.point.z = in[2];
00103   return msg;
00104 }
00105 
00111 inline
00112 void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped<KDL::Vector>& out)
00113 {
00114   out.stamp_ = msg.header.stamp;
00115   out.frame_id_ = msg.header.frame_id;
00116   out[0] = msg.point.x;
00117   out[1] = msg.point.y;
00118   out[2] = msg.point.z;
00119 }
00120 
00121 // ---------------------
00122 // Twist
00123 // ---------------------
00130 template <>
00131 inline
00132   void doTransform(const tf2::Stamped<KDL::Twist>& t_in, tf2::Stamped<KDL::Twist>& t_out, const geometry_msgs::TransformStamped& transform)
00133   {
00134     t_out = tf2::Stamped<KDL::Twist>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00135   }
00136 
00142 inline
00143 geometry_msgs::TwistStamped toMsg(const tf2::Stamped<KDL::Twist>& in)
00144 {
00145   geometry_msgs::TwistStamped msg;
00146   msg.header.stamp = in.stamp_;
00147   msg.header.frame_id = in.frame_id_;
00148   msg.twist.linear.x = in.vel[0];
00149   msg.twist.linear.y = in.vel[1];
00150   msg.twist.linear.z = in.vel[2];
00151   msg.twist.angular.x = in.rot[0];
00152   msg.twist.angular.y = in.rot[1];
00153   msg.twist.angular.z = in.rot[2];
00154   return msg;
00155 }
00156 
00162 inline
00163 void fromMsg(const geometry_msgs::TwistStamped& msg, tf2::Stamped<KDL::Twist>& out)
00164 {
00165   out.stamp_ = msg.header.stamp;
00166   out.frame_id_ = msg.header.frame_id;
00167   out.vel[0] = msg.twist.linear.x;
00168   out.vel[1] = msg.twist.linear.y;
00169   out.vel[2] = msg.twist.linear.z;
00170   out.rot[0] = msg.twist.angular.x;
00171   out.rot[1] = msg.twist.angular.y;
00172   out.rot[2] = msg.twist.angular.z;
00173 }
00174 
00175 
00176 // ---------------------
00177 // Wrench
00178 // ---------------------
00185 template <>
00186 inline
00187   void doTransform(const tf2::Stamped<KDL::Wrench>& t_in, tf2::Stamped<KDL::Wrench>& t_out, const geometry_msgs::TransformStamped& transform)
00188   {
00189     t_out = tf2::Stamped<KDL::Wrench>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00190   }
00191 
00197 inline
00198 geometry_msgs::WrenchStamped toMsg(const tf2::Stamped<KDL::Wrench>& in)
00199 {
00200   geometry_msgs::WrenchStamped msg;
00201   msg.header.stamp = in.stamp_;
00202   msg.header.frame_id = in.frame_id_;
00203   msg.wrench.force.x = in.force[0];
00204   msg.wrench.force.y = in.force[1];
00205   msg.wrench.force.z = in.force[2];
00206   msg.wrench.torque.x = in.torque[0];
00207   msg.wrench.torque.y = in.torque[1];
00208   msg.wrench.torque.z = in.torque[2];
00209   return msg;
00210 }
00211 
00217 inline
00218 void fromMsg(const geometry_msgs::WrenchStamped& msg, tf2::Stamped<KDL::Wrench>& out)
00219 {
00220   out.stamp_ = msg.header.stamp;
00221   out.frame_id_ = msg.header.frame_id;
00222   out.force[0] = msg.wrench.force.x;
00223   out.force[1] = msg.wrench.force.y;
00224   out.force[2] = msg.wrench.force.z;
00225   out.torque[0] = msg.wrench.torque.x;
00226   out.torque[1] = msg.wrench.torque.y;
00227   out.torque[2] = msg.wrench.torque.z;
00228 }
00229 
00230 
00231 
00232 
00233 // ---------------------
00234 // Frame
00235 // ---------------------
00242 template <>
00243 inline
00244   void doTransform(const tf2::Stamped<KDL::Frame>& t_in, tf2::Stamped<KDL::Frame>& t_out, const geometry_msgs::TransformStamped& transform)
00245   {
00246     t_out = tf2::Stamped<KDL::Frame>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00247   }
00248 
00254 inline
00255 geometry_msgs::Pose toMsg(const KDL::Frame& in)
00256 {
00257   geometry_msgs::Pose msg;
00258   msg.position.x = in.p[0];
00259   msg.position.y = in.p[1];
00260   msg.position.z = in.p[2];
00261   in.M.GetQuaternion(msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w);
00262   return msg;
00263 }
00264 
00270 inline
00271 void fromMsg(const geometry_msgs::Pose& msg, KDL::Frame& out)
00272 {
00273   out.p[0] = msg.position.x;
00274   out.p[1] = msg.position.y;
00275   out.p[2] = msg.position.z;
00276   out.M = KDL::Rotation::Quaternion(msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w);
00277 }
00278 
00284 inline
00285 geometry_msgs::PoseStamped toMsg(const tf2::Stamped<KDL::Frame>& in)
00286 {
00287   geometry_msgs::PoseStamped msg;
00288   msg.header.stamp = in.stamp_;
00289   msg.header.frame_id = in.frame_id_;
00290   msg.pose = toMsg(static_cast<const KDL::Frame&>(in));
00291   return msg;
00292 }
00293 
00299 inline
00300 void fromMsg(const geometry_msgs::PoseStamped& msg, tf2::Stamped<KDL::Frame>& out)
00301 {
00302   out.stamp_ = msg.header.stamp;
00303   out.frame_id_ = msg.header.frame_id;
00304   fromMsg(msg.pose, static_cast<KDL::Frame&>(out));
00305 }
00306 
00307 } // namespace
00308 
00309 #endif // TF2_KDL_H


tf2_kdl
Author(s): Wim Meeussen
autogenerated on Thu Jun 6 2019 20:23:10