58                                      const std::string& to_frame)
    60   ROS_DEBUG_STREAM_NAMED(
"tf_visual_tools", 
"Publishing transform from " << from_frame << 
" to " << to_frame);
    63   geometry_msgs::TransformStamped tf2_msg;
    71   quatNorm = 1 / 
sqrt(tf2_msg.transform.rotation.x * tf2_msg.transform.rotation.x +
    72                       tf2_msg.transform.rotation.y * tf2_msg.transform.rotation.y +
    73                       tf2_msg.transform.rotation.z * tf2_msg.transform.rotation.z +
    74                       tf2_msg.transform.rotation.w * tf2_msg.transform.rotation.w);
    75   tf2_msg.transform.rotation.x *= quatNorm;
    76   tf2_msg.transform.rotation.y *= quatNorm;
    77   tf2_msg.transform.rotation.z *= quatNorm;
    78   tf2_msg.transform.rotation.w *= quatNorm;
    80   tf2_msg.header.frame_id = from_frame;
    81   tf2_msg.child_frame_id = to_frame;
    86     if (transform.child_frame_id == to_frame && transform.header.frame_id == from_frame)
    89       transform.transform = tf2_msg.transform;
    94   transforms_.push_back(tf2_msg);
 
#define ROS_DEBUG_STREAM_NAMED(name, args)
void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
#define ROS_INFO_STREAM_NAMED(name, args)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const 
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)