@@ -339,6 +339,16 @@ namespace am
339339 m.getRPY (roll, pitch, yaw);
340340 }
341341
342+ geometry_msgs::Vector3 Rotate::getRPY (const geometry_msgs::Pose &pose)
343+ {
344+ tf2::Quaternion tf2_q;
345+ tf2::fromMsg (pose.orientation , tf2_q);
346+ geometry_msgs::Vector3 rpy;
347+
348+ tf2::Matrix3x3 (tf2_q).getRPY (rpy.x , rpy.y , rpy.z );
349+ return rpy;
350+ }
351+
342352 void Rotate::rotate (double &x, double &y, double &z, geometry_msgs::Quaternion &q_rot)
343353 {
344354 double old_x = x;
@@ -351,6 +361,18 @@ namespace am
351361
352362 }
353363
364+ void Rotate::rotate (double &x, double &y, double &z, const geometry_msgs::Quaternion &q_rot)
365+ {
366+ double old_x = x;
367+ double old_y = y;
368+ double old_z = z;
369+
370+ x = q_rot.w *q_rot.w *old_x + 2 *q_rot.y *q_rot.w *old_z - 2 *q_rot.z *q_rot.w *old_y + q_rot.x *q_rot.x *old_x + 2 *q_rot.y *q_rot.x *old_y + 2 *q_rot.z *q_rot.x *old_z - q_rot.z *q_rot.z *old_x - q_rot.y *q_rot.y *old_x;
371+ y = 2 *q_rot.x *q_rot.y *old_x + q_rot.y *q_rot.y *old_y + 2 *q_rot.z *q_rot.y *old_z + 2 *q_rot.w *q_rot.z *old_x - q_rot.z *q_rot.z *old_y + q_rot.w *q_rot.w *old_y - 2 *q_rot.x *q_rot.w *old_z - q_rot.x *q_rot.x *old_y;
372+ z = 2 *q_rot.x *q_rot.z *old_x + 2 *q_rot.y *q_rot.z *old_y + q_rot.z *q_rot.z *old_z - 2 *q_rot.w *q_rot.y *old_x - q_rot.y *q_rot.y *old_z + 2 *q_rot.w *q_rot.x *old_y - q_rot.x *q_rot.x *old_z + q_rot.w *q_rot.w *old_z;
373+
374+ }
375+
354376 void Rotate::rotate (geometry_msgs::Point32 &p, const geometry_msgs::Quaternion &q_rot)
355377 {
356378 geometry_msgs::Point32 old_p = p;
@@ -462,6 +484,21 @@ namespace am
462484 return angle;
463485 }
464486
487+ void Rotate::transform (const geometry_msgs::Pose &src, geometry_msgs::Pose &des)
488+ {
489+ des.position .x = des.position .x - src.position .x ;
490+ des.position .y = des.position .y - src.position .y ;
491+ des.position .z = des.position .z - src.position .z ;
492+
493+ geometry_msgs::Vector3 rpy = Rotate::getRPY (src);
494+ rpy.x *= -1 ;
495+ rpy.y *= -1 ;
496+ rpy.z *= -1 ;
497+ // ROS_INFO("Q:[%f,%f,%f,%f]", src.orientation.x, src.orientation.y, src.orientation.z, src.orientation.w);
498+ Rotate::rotate (des.position .x , des.position .y , des.position .z , toQuaternionMsg (rpy.x , rpy.y , rpy.z ));
499+
500+ }
501+
465502}
466503
467504
0 commit comments