36 #include <kdl/frames.hpp>
37 #include <geometry_msgs/PointStamped.h>
38 #include <geometry_msgs/TwistStamped.h>
39 #include <geometry_msgs/WrenchStamped.h>
40 #include <geometry_msgs/PoseStamped.h>
41 #include <geometry_msgs/Pose.h>
53 return KDL::Frame(KDL::Rotation::Quaternion(t.transform.rotation.x, t.transform.rotation.y,
54 t.transform.rotation.z, t.transform.rotation.w),
55 KDL::Vector(t.transform.translation.x, t.transform.translation.y, t.transform.translation.z));
65 geometry_msgs::TransformStamped t;
66 t.transform.translation.x = k.p.x();
67 t.transform.translation.y = k.p.y();
68 t.transform.translation.z = k.p.z();
69 k.M.GetQuaternion(t.transform.rotation.x, t.transform.rotation.y, t.transform.rotation.z, t.transform.rotation.w);
97 geometry_msgs::PointStamped msg;
98 msg.header.stamp = in.
stamp_;
114 out.
stamp_ = msg.header.stamp;
116 out[0] = msg.point.x;
117 out[1] = msg.point.y;
118 out[2] = msg.point.z;
145 geometry_msgs::TwistStamped msg;
146 msg.header.stamp = in.
stamp_;
148 msg.twist.linear.x = in.vel[0];
149 msg.twist.linear.y = in.vel[1];
150 msg.twist.linear.z = in.vel[2];
151 msg.twist.angular.x = in.rot[0];
152 msg.twist.angular.y = in.rot[1];
153 msg.twist.angular.z = in.rot[2];
165 out.
stamp_ = msg.header.stamp;
167 out.vel[0] = msg.twist.linear.x;
168 out.vel[1] = msg.twist.linear.y;
169 out.vel[2] = msg.twist.linear.z;
170 out.rot[0] = msg.twist.angular.x;
171 out.rot[1] = msg.twist.angular.y;
172 out.rot[2] = msg.twist.angular.z;
200 geometry_msgs::WrenchStamped msg;
201 msg.header.stamp = in.
stamp_;
203 msg.wrench.force.x = in.force[0];
204 msg.wrench.force.y = in.force[1];
205 msg.wrench.force.z = in.force[2];
206 msg.wrench.torque.x = in.torque[0];
207 msg.wrench.torque.y = in.torque[1];
208 msg.wrench.torque.z = in.torque[2];
220 out.
stamp_ = msg.header.stamp;
222 out.force[0] = msg.wrench.force.x;
223 out.force[1] = msg.wrench.force.y;
224 out.force[2] = msg.wrench.force.z;
225 out.torque[0] = msg.wrench.torque.x;
226 out.torque[1] = msg.wrench.torque.y;
227 out.torque[2] = msg.wrench.torque.z;
255 geometry_msgs::Pose
toMsg(
const KDL::Frame& in)
257 geometry_msgs::Pose msg;
258 msg.position.x = in.p[0];
259 msg.position.y = in.p[1];
260 msg.position.z = in.p[2];
261 in.M.GetQuaternion(msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w);
271 void fromMsg(
const geometry_msgs::Pose& msg, KDL::Frame& out)
273 out.p[0] = msg.position.x;
274 out.p[1] = msg.position.y;
275 out.p[2] = msg.position.z;
276 out.M = KDL::Rotation::Quaternion(msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w);
287 geometry_msgs::PoseStamped msg;
288 msg.header.stamp = in.
stamp_;
290 msg.pose =
toMsg(
static_cast<const KDL::Frame&
>(in));
302 out.
stamp_ = msg.header.stamp;
304 fromMsg(msg.pose,
static_cast<KDL::Frame&
>(out));