tf2_kdl  master
KDL binding for tf2
tf2_kdl.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #ifndef TF2_KDL_H
33 #define TF2_KDL_H
34 
35 #include <tf2/convert.h>
37 #include <kdl/frames.hpp>
38 #include <geometry_msgs/msg/point_stamped.hpp>
39 #include <geometry_msgs/msg/twist_stamped.hpp>
40 #include <geometry_msgs/msg/wrench_stamped.hpp>
41 #include <geometry_msgs/msg/pose.hpp>
42 #include <geometry_msgs/msg/pose_stamped.hpp>
43 #include <builtin_interfaces/msg/time.hpp>
44 #include <geometry_msgs/msg/transform_stamped.hpp>
45 
46 namespace tf2
47 {
52 inline
53 KDL::Frame transformToKDL(const geometry_msgs::msg::TransformStamped& t)
54  {
55  return KDL::Frame(KDL::Rotation::Quaternion(t.transform.rotation.x, t.transform.rotation.y,
56  t.transform.rotation.z, t.transform.rotation.w),
57  KDL::Vector(t.transform.translation.x, t.transform.translation.y, t.transform.translation.z));
58  }
59 
64 inline
65 geometry_msgs::msg::TransformStamped kdlToTransform(const KDL::Frame& k)
66 {
67  geometry_msgs::msg::TransformStamped t;
68  t.transform.translation.x = k.p.x();
69  t.transform.translation.y = k.p.y();
70  t.transform.translation.z = k.p.z();
71  k.M.GetQuaternion(t.transform.rotation.x, t.transform.rotation.y, t.transform.rotation.z, t.transform.rotation.w);
72  return t;
73 }
74 
75 // ---------------------
76 // Vector
77 // ---------------------
84 template <>
85 inline
86  void doTransform(const tf2::Stamped<KDL::Vector>& t_in, tf2::Stamped<KDL::Vector>& t_out, const geometry_msgs::msg::TransformStamped& transform)
87  {
88  t_out = tf2::Stamped<KDL::Vector>(transformToKDL(transform) * t_in, tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
89  }
90 
96 inline
97 geometry_msgs::msg::PointStamped toMsg(const tf2::Stamped<KDL::Vector>& in)
98 {
99  geometry_msgs::msg::PointStamped msg;
100  msg.header.stamp = tf2_ros::toMsg(in.stamp_);
101  msg.header.frame_id = in.frame_id_;
102  msg.point.x = in[0];
103  msg.point.y = in[1];
104  msg.point.z = in[2];
105  return msg;
106 }
107 
113 inline
114 void fromMsg(const geometry_msgs::msg::PointStamped& msg, tf2::Stamped<KDL::Vector>& out)
115 {
116  out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
117  out.frame_id_ = msg.header.frame_id;
118  out[0] = msg.point.x;
119  out[1] = msg.point.y;
120  out[2] = msg.point.z;
121 }
122 
123 // ---------------------
124 // Twist
125 // ---------------------
132 template <>
133 inline
134  void doTransform(const tf2::Stamped<KDL::Twist>& t_in, tf2::Stamped<KDL::Twist>& t_out, const geometry_msgs::msg::TransformStamped& transform)
135  {
136  t_out = tf2::Stamped<KDL::Twist>(transformToKDL(transform) * t_in, tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
137  }
138 
144 inline
145 geometry_msgs::msg::TwistStamped toMsg(const tf2::Stamped<KDL::Twist>& in)
146 {
147  geometry_msgs::msg::TwistStamped msg;
148  msg.header.stamp = tf2_ros::toMsg(in.stamp_);
149  msg.header.frame_id = in.frame_id_;
150  msg.twist.linear.x = in.vel[0];
151  msg.twist.linear.y = in.vel[1];
152  msg.twist.linear.z = in.vel[2];
153  msg.twist.angular.x = in.rot[0];
154  msg.twist.angular.y = in.rot[1];
155  msg.twist.angular.z = in.rot[2];
156  return msg;
157 }
158 
164 inline
165 void fromMsg(const geometry_msgs::msg::TwistStamped& msg, tf2::Stamped<KDL::Twist>& out)
166 {
167  out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
168  out.frame_id_ = msg.header.frame_id;
169  out.vel[0] = msg.twist.linear.x;
170  out.vel[1] = msg.twist.linear.y;
171  out.vel[2] = msg.twist.linear.z;
172  out.rot[0] = msg.twist.angular.x;
173  out.rot[1] = msg.twist.angular.y;
174  out.rot[2] = msg.twist.angular.z;
175 }
176 
177 
178 // ---------------------
179 // Wrench
180 // ---------------------
187 template <>
188 inline
189  void doTransform(const tf2::Stamped<KDL::Wrench>& t_in, tf2::Stamped<KDL::Wrench>& t_out, const geometry_msgs::msg::TransformStamped& transform)
190  {
191  t_out = tf2::Stamped<KDL::Wrench>(transformToKDL(transform) * t_in, tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
192  }
193 
199 inline
200 geometry_msgs::msg::WrenchStamped toMsg(const tf2::Stamped<KDL::Wrench>& in)
201 {
202  geometry_msgs::msg::WrenchStamped msg;
203  msg.header.stamp = tf2_ros::toMsg(in.stamp_);
204  msg.header.frame_id = in.frame_id_;
205  msg.wrench.force.x = in.force[0];
206  msg.wrench.force.y = in.force[1];
207  msg.wrench.force.z = in.force[2];
208  msg.wrench.torque.x = in.torque[0];
209  msg.wrench.torque.y = in.torque[1];
210  msg.wrench.torque.z = in.torque[2];
211  return msg;
212 }
213 
219 inline
220 void fromMsg(const geometry_msgs::msg::WrenchStamped& msg, tf2::Stamped<KDL::Wrench>& out)
221 {
222  out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
223  out.frame_id_ = msg.header.frame_id;
224  out.force[0] = msg.wrench.force.x;
225  out.force[1] = msg.wrench.force.y;
226  out.force[2] = msg.wrench.force.z;
227  out.torque[0] = msg.wrench.torque.x;
228  out.torque[1] = msg.wrench.torque.y;
229  out.torque[2] = msg.wrench.torque.z;
230 }
231 
232 
233 
234 
235 // ---------------------
236 // Frame
237 // ---------------------
244 template <>
245 inline
246  void doTransform(const tf2::Stamped<KDL::Frame>& t_in, tf2::Stamped<KDL::Frame>& t_out, const geometry_msgs::msg::TransformStamped& transform)
247  {
248  t_out = tf2::Stamped<KDL::Frame>(transformToKDL(transform) * t_in, tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
249  }
250 
256 inline
257 geometry_msgs::msg::Pose toMsg(const KDL::Frame& in)
258 {
259  geometry_msgs::msg::Pose msg;
260  msg.position.x = in.p[0];
261  msg.position.y = in.p[1];
262  msg.position.z = in.p[2];
263  in.M.GetQuaternion(msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w);
264  return msg;
265 }
266 
272 inline
273 void fromMsg(const geometry_msgs::msg::Pose& msg, KDL::Frame& out)
274 {
275  out.p[0] = msg.position.x;
276  out.p[1] = msg.position.y;
277  out.p[2] = msg.position.z;
278  out.M = KDL::Rotation::Quaternion(msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w);
279 }
280 
286 inline
287 geometry_msgs::msg::PoseStamped toMsg(const tf2::Stamped<KDL::Frame>& in)
288 {
289  geometry_msgs::msg::PoseStamped msg;
290  msg.header.stamp = tf2_ros::toMsg(in.stamp_);
291  msg.header.frame_id = in.frame_id_;
292  msg.pose = toMsg(static_cast<const KDL::Frame&>(in));
293  return msg;
294 }
295 
301 inline
302 void fromMsg(const geometry_msgs::msg::PoseStamped& msg, tf2::Stamped<KDL::Frame>& out)
303 {
304  out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
305  out.frame_id_ = msg.header.frame_id;
306  fromMsg(msg.pose, static_cast<KDL::Frame&>(out));
307 }
308 
309 } // namespace
310 
311 #endif // TF2_KDL_H
tf2::Stamped::stamp_
TimePoint stamp_
tf2::fromMsg
void fromMsg(const A &, B &b)
tf2::Stamped
tf2::transformToKDL
KDL::Frame transformToKDL(const geometry_msgs::msg::TransformStamped &t)
Convert a timestamped transform to the equivalent KDL data type.
Definition: tf2_kdl.h:53
tf2::Stamped::frame_id_
std::string frame_id_
tf2_ros::fromMsg
tf2::TimePoint fromMsg(const builtin_interfaces::msg::Time &time_msg)
tf2
tf2::toMsg
B toMsg(const A &a)
convert.h
tf2::kdlToTransform
geometry_msgs::msg::TransformStamped kdlToTransform(const KDL::Frame &k)
Convert an KDL Frame to the equivalent geometry_msgs message type.
Definition: tf2_kdl.h:65
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::msg::TransformStamped &transform)
tf2_ros::toMsg
builtin_interfaces::msg::Time toMsg(const tf2::TimePoint &t)
buffer_interface.h