47                   const std::string &robot_frame,
    48                   const std::string &global_frame,
    50                   geometry_msgs::PoseStamped &robot_pose)
    53   local_pose.setIdentity();
    55   geometry_msgs::PoseStamped local_pose_msg;
    67                    const std::string &target_frame,
    70                    const geometry_msgs::PoseStamped &in,
    71                    const std::string &fixed_frame,
    72                    geometry_msgs::PoseStamped &out)
    74   std::string error_msg;
    97     ROS_WARN_STREAM(
"Failed to look up transform from frame '" << in.header.frame_id << 
"' into frame '" << target_frame
    98                     << 
"': " << error_msg);
   105     tf.
transformPose(target_frame, target_time, in, fixed_frame, out);
   107     tf.transform(in, out, target_frame, target_time, fixed_frame);
   112     ROS_WARN_STREAM(
"Failed to transform pose from frame '" <<  in.header.frame_id << 
" ' into frame '"   113                     << target_frame << 
"' with exception: " << ex.what());
   120                     const std::string &target_frame,
   123                     const geometry_msgs::PointStamped &in,
   124                     const std::string &fixed_frame,
   125                     geometry_msgs::PointStamped &out)
   127   std::string error_msg;
   150     ROS_WARN_STREAM(
"Failed to look up transform from frame '" << in.header.frame_id << 
"' into frame '" << target_frame
   151                                                                << 
"': " << error_msg);
   158     tf.
transformPoint(target_frame, target_time, in, fixed_frame, out);
   160     tf.transform(in, out, target_frame, target_time, fixed_frame);
   165     ROS_WARN_STREAM(
"Failed to transform point from frame '" <<  in.header.frame_id << 
" ' into frame '"   166                                                             << target_frame << 
"' with exception: " << ex.what());
   172 double distance(
const geometry_msgs::PoseStamped &pose1, 
const geometry_msgs::PoseStamped &pose2)
   174   const geometry_msgs::Point &p1 = pose1.pose.position;
   175   const geometry_msgs::Point &p2 = pose2.pose.position;
   176   const double dx = p1.x - p2.x;
   177   const double dy = p1.y - p2.y;
   178   const double dz = p1.z - p2.z;
   179   return sqrt(dx * dx + dy * dy + dz * dz);
   182 double angle(
const geometry_msgs::PoseStamped &pose1, 
const geometry_msgs::PoseStamped &pose2)
   184   const geometry_msgs::Quaternion &q1 = pose1.pose.orientation;
   185   const geometry_msgs::Quaternion &q2 = pose2.pose.orientation;
 double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
computes the smallest angle between two poses. 
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
bool getRobotPose(const TF &tf, const std::string &robot_frame, const std::string &global_frame, const ros::Duration &timeout, geometry_msgs::PoseStamped &robot_pose)
Computes the robot pose. 
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
#define ROS_WARN_STREAM(args)
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
Computes the Euclidean-distance between two poses. 
tfScalar angleShortestPath(const Quaternion &q) const 
bool transformPoint(const TF &tf, const std::string &target_frame, const ros::Time &target_time, const ros::Duration &timeout, const geometry_msgs::PointStamped &in, const std::string &fixed_frame, geometry_msgs::PointStamped &out)
Transforms a point from one frame into another. 
bool transformPose(const TF &tf, const std::string &target_frame, const ros::Time &target_time, const ros::Duration &timeout, const geometry_msgs::PoseStamped &in, const std::string &fixed_frame, geometry_msgs::PoseStamped &out)
Transforms a pose from one frame into another.