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>
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));
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);
99 geometry_msgs::msg::PointStamped msg;
118 out[0] = msg.point.x;
119 out[1] = msg.point.y;
120 out[2] = msg.point.z;
147 geometry_msgs::msg::TwistStamped msg;
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];
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;
202 geometry_msgs::msg::WrenchStamped msg;
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];
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;
257 geometry_msgs::msg::Pose
toMsg(
const KDL::Frame& in)
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);
273 void fromMsg(
const geometry_msgs::msg::Pose& msg, KDL::Frame& out)
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);
289 geometry_msgs::msg::PoseStamped msg;
292 msg.pose =
toMsg(
static_cast<const KDL::Frame&
>(in));
306 fromMsg(msg.pose,
static_cast<KDL::Frame&
>(out));