37 for (
unsigned int i = 0; i < 3; ++i)
39 for (
unsigned int i = 0; i < 9; ++i)
40 k.M.data[i] = t.
getBasis()[i/3][i%3];
45 t.
setOrigin(tf::Vector3(k.p[0], k.p[1], k.p[2]));
47 k.M.data[3], k.M.data[4], k.M.data[5],
48 k.M.data[6], k.M.data[7], k.M.data[8]));
53 k = KDL::Rotation::Quaternion(t[0], t[1], t[2], t[3]);
59 k.GetQuaternion(x, y, z, w);
65 for (
unsigned int i = 0; i < 3; ++i)
67 for (
unsigned int i = 0; i < 9; ++i)
68 k.M.data[i] = t.
getBasis()[i/3][i%3];
73 t.
setOrigin(tf::Vector3(k.p[0], k.p[1], k.p[2]));
75 k.M.data[3], k.M.data[4], k.M.data[5],
76 k.M.data[6], k.M.data[7], k.M.data[8]));
95 geometry_msgs::Pose
addDelta(
const geometry_msgs::Pose &pose,
const geometry_msgs::Twist &twist,
const double &t)
97 geometry_msgs::Pose result;
99 KDL::Frame kdl_pose_id, kdl_pose;