00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #include "mbf_utility/navigation_utility.h"
00042
00043 namespace mbf_utility
00044 {
00045
00046 bool getRobotPose(const TF &tf,
00047 const std::string &robot_frame,
00048 const std::string &global_frame,
00049 const ros::Duration &timeout,
00050 geometry_msgs::PoseStamped &robot_pose)
00051 {
00052 tf::Stamped<tf::Pose> local_pose;
00053 local_pose.setIdentity();
00054 local_pose.frame_id_ = robot_frame;
00055 geometry_msgs::PoseStamped local_pose_msg;
00056 tf::poseStampedTFToMsg(local_pose, local_pose_msg);
00057 return transformPose(tf,
00058 global_frame,
00059 ros::Time(0),
00060 timeout,
00061 local_pose_msg,
00062 global_frame,
00063 robot_pose);
00064 }
00065
00066 bool transformPose(const TF &tf,
00067 const std::string &target_frame,
00068 const ros::Time &target_time,
00069 const ros::Duration &timeout,
00070 const geometry_msgs::PoseStamped &in,
00071 const std::string &fixed_frame,
00072 geometry_msgs::PoseStamped &out)
00073 {
00074 std::string error_msg;
00075
00076 #ifdef USE_OLD_TF
00077 bool success = tf.waitForTransform(target_frame,
00078 target_time,
00079 in.header.frame_id,
00080 in.header.stamp,
00081 fixed_frame,
00082 timeout,
00083 ros::Duration(0.01),
00084 &error_msg);
00085 #else
00086 bool success = tf.canTransform(target_frame,
00087 target_time,
00088 in.header.frame_id,
00089 in.header.stamp,
00090 fixed_frame,
00091 timeout,
00092 &error_msg);
00093 #endif
00094
00095 if (!success)
00096 {
00097 ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame
00098 << "': " << error_msg);
00099 return false;
00100 }
00101
00102 try
00103 {
00104 #ifdef USE_OLD_TF
00105 tf.transformPose(target_frame, target_time, in, fixed_frame, out);
00106 #else
00107 tf.transform(in, out, target_frame, target_time, fixed_frame);
00108 #endif
00109 }
00110 catch (const TFException &ex)
00111 {
00112 ROS_WARN_STREAM("Failed to transform pose from frame '" << in.header.frame_id << " ' into frame '"
00113 << target_frame << "' with exception: " << ex.what());
00114 return false;
00115 }
00116 return true;
00117 }
00118
00119 bool transformPoint(const TF &tf,
00120 const std::string &target_frame,
00121 const ros::Time &target_time,
00122 const ros::Duration &timeout,
00123 const geometry_msgs::PointStamped &in,
00124 const std::string &fixed_frame,
00125 geometry_msgs::PointStamped &out)
00126 {
00127 std::string error_msg;
00128
00129 #ifdef USE_OLD_TF
00130 bool success = tf.waitForTransform(target_frame,
00131 target_time,
00132 in.header.frame_id,
00133 in.header.stamp,
00134 fixed_frame,
00135 timeout,
00136 ros::Duration(0.01),
00137 &error_msg);
00138 #else
00139 bool success = tf.canTransform(target_frame,
00140 target_time,
00141 in.header.frame_id,
00142 in.header.stamp,
00143 fixed_frame,
00144 timeout,
00145 &error_msg);
00146 #endif
00147
00148 if (!success)
00149 {
00150 ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame
00151 << "': " << error_msg);
00152 return false;
00153 }
00154
00155 try
00156 {
00157 #ifdef USE_OLD_TF
00158 tf.transformPoint(target_frame, target_time, in, fixed_frame, out);
00159 #else
00160 tf.transform(in, out, target_frame, target_time, fixed_frame);
00161 #endif
00162 }
00163 catch (const TFException &ex)
00164 {
00165 ROS_WARN_STREAM("Failed to transform point from frame '" << in.header.frame_id << " ' into frame '"
00166 << target_frame << "' with exception: " << ex.what());
00167 return false;
00168 }
00169 return true;
00170 }
00171
00172 double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
00173 {
00174 const geometry_msgs::Point &p1 = pose1.pose.position;
00175 const geometry_msgs::Point &p2 = pose2.pose.position;
00176 const double dx = p1.x - p2.x;
00177 const double dy = p1.y - p2.y;
00178 const double dz = p1.z - p2.z;
00179 return sqrt(dx * dx + dy * dy + dz * dz);
00180 }
00181
00182 double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
00183 {
00184 const geometry_msgs::Quaternion &q1 = pose1.pose.orientation;
00185 const geometry_msgs::Quaternion &q2 = pose2.pose.orientation;
00186 tf::Quaternion rot1, rot2;
00187 tf::quaternionMsgToTF(q1, rot1);
00188 tf::quaternionMsgToTF(q2, rot2);
00189 return rot1.angleShortestPath(rot2);
00190 }
00191
00192 }