58 const std::string& to_frame)
60 ROS_DEBUG_STREAM_NAMED(
"tf_visual_tools",
"Publishing transform from " << from_frame <<
" to " << to_frame);
70 quat_norm = 1 / sqrt(tf2_msg.transform.rotation.x * tf2_msg.transform.rotation.x +
71 tf2_msg.transform.rotation.y * tf2_msg.transform.rotation.y +
72 tf2_msg.transform.rotation.z * tf2_msg.transform.rotation.z +
73 tf2_msg.transform.rotation.w * tf2_msg.transform.rotation.w);
74 tf2_msg.transform.rotation.x *= quat_norm;
75 tf2_msg.transform.rotation.y *= quat_norm;
76 tf2_msg.transform.rotation.z *= quat_norm;
77 tf2_msg.transform.rotation.w *= quat_norm;
79 tf2_msg.header.frame_id = from_frame;
80 tf2_msg.child_frame_id = to_frame;
85 if (transform.child_frame_id == to_frame && transform.header.frame_id == from_frame)
88 transform.transform = tf2_msg.transform;