kdl_msg.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, 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 
00030 #include "kdl_conversions/kdl_msg.h"
00031 
00032 namespace tf {
00033 
00034   void pointMsgToKDL(const geometry_msgs::Point &m, KDL::Vector &k)
00035   {
00036     k[0] = m.x;
00037     k[1] = m.y;
00038     k[2] = m.z;
00039   }
00040 
00041   void pointKDLToMsg(const KDL::Vector &k, geometry_msgs::Point &m)
00042   {
00043     m.x = k[0];
00044     m.y = k[1];
00045     m.z = k[2];
00046   }
00047 
00048   void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
00049   {
00050     k.p[0] = m.position.x;
00051     k.p[1] = m.position.y;
00052     k.p[2] = m.position.z;
00053     
00054     k.M = KDL::Rotation::Quaternion( m.orientation.x, m.orientation.y, m.orientation.z, m.orientation.w);
00055   }
00056 
00057   void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
00058   {
00059     m.position.x = k.p[0];
00060     m.position.y = k.p[1];
00061     m.position.z = k.p[2];
00062     
00063     k.M.GetQuaternion(m.orientation.x, m.orientation.y, m.orientation.z, m.orientation.w);
00064   }
00065 
00066   void quaternionMsgToKDL(const geometry_msgs::Quaternion &m, KDL::Rotation &k)
00067   {
00068     k = KDL::Rotation::Quaternion(m.x, m.y, m.z, m.w);
00069   }
00070 
00071   void quaternionKDLToMsg(const KDL::Rotation &k, geometry_msgs::Quaternion &m)
00072   {
00073     k.GetQuaternion(m.x, m.y, m.z, m.w);
00074   }
00075 
00076   void transformMsgToKDL(const geometry_msgs::Transform &m, KDL::Frame &k)
00077   {
00078     k.p[0] = m.translation.x;
00079     k.p[1] = m.translation.y;
00080     k.p[2] = m.translation.z;
00081     
00082     k.M = KDL::Rotation::Quaternion( m.rotation.x, m.rotation.y, m.rotation.z, m.rotation.w);
00083   }
00084 
00085   void transformKDLToMsg(const KDL::Frame &k, geometry_msgs::Transform &m)
00086   {
00087     m.translation.x = k.p[0];
00088     m.translation.y = k.p[1];
00089     m.translation.z = k.p[2];
00090     
00091     k.M.GetQuaternion(m.rotation.x, m.rotation.y, m.rotation.z, m.rotation.w);
00092   }
00093 
00094   void twistKDLToMsg(const KDL::Twist &t, geometry_msgs::Twist &m)
00095   {
00096     m.linear.x = t.vel[0];
00097     m.linear.y = t.vel[1];
00098     m.linear.z = t.vel[2];
00099     m.angular.x = t.rot[0];
00100     m.angular.y = t.rot[1];
00101     m.angular.z = t.rot[2];
00102   }
00103 
00104   void twistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &t)
00105   {
00106     t.vel[0] = m.linear.x;
00107     t.vel[1] = m.linear.y;
00108     t.vel[2] = m.linear.z;
00109     t.rot[0] = m.angular.x;
00110     t.rot[1] = m.angular.y;
00111     t.rot[2] = m.angular.z;
00112   }
00113 
00114   void vectorMsgToKDL(const geometry_msgs::Vector3 &m, KDL::Vector &k)
00115   {
00116     k[0] = m.x;
00117     k[1] = m.y;
00118     k[2] = m.z;
00119   }
00120 
00121   void vectorKDLToMsg(const KDL::Vector &k, geometry_msgs::Vector3 &m)
00122   {
00123     m.x = k[0];
00124     m.y = k[1];
00125     m.z = k[2];
00126   }
00127 
00128   void wrenchMsgToKDL(const geometry_msgs::Wrench &m, KDL::Wrench &k)
00129   {
00130     k[0] = m.force.x;
00131     k[1] = m.force.y;
00132     k[2] = m.force.z;
00133     k[3] = m.torque.x;
00134     k[4] = m.torque.y;
00135     k[5] = m.torque.z;
00136   }
00137 
00138   void wrenchKDLToMsg(const KDL::Wrench &k, geometry_msgs::Wrench &m)
00139   {
00140     m.force.x  = k[0];
00141     m.force.y  = k[1];
00142     m.force.z  = k[2];
00143     m.torque.x = k[3];
00144     m.torque.y = k[4];
00145     m.torque.z = k[5];
00146   }
00147 
00148 
00150 
00152 void PoseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k) { poseMsgToKDL(m, k);}
00153 
00155 void PoseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m) { poseKDLToMsg(k, m);}
00156 
00158 void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k) {twistMsgToKDL(m, k);};
00159 
00161 void TwistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m){twistKDLToMsg(k, m);};
00162 
00163 
00164 }  // namespace tf
00165 


kdl_conversions
Author(s): Adam Leeper
autogenerated on Thu Aug 27 2015 13:08:36