Go to the documentation of this file.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 #ifndef NAV_2D_UTILS_TF_HELP_H
00036 #define NAV_2D_UTILS_TF_HELP_H
00037
00038 #include <nav_core2/common.h>
00039 #include <nav_2d_utils/conversions.h>
00040 #include <geometry_msgs/PoseStamped.h>
00041 #include <nav_2d_msgs/Pose2DStamped.h>
00042 #include <string>
00043
00044 namespace nav_2d_utils
00045 {
00057 bool transformPose(const TFListenerPtr tf, const std::string frame,
00058 const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose,
00059 const bool extrapolation_fallback = true)
00060 {
00061 if (in_pose.header.frame_id == frame)
00062 {
00063 out_pose = in_pose;
00064 return true;
00065 }
00066
00067 try
00068 {
00069 tf->transformPose(frame, in_pose, out_pose);
00070 return true;
00071 }
00072 catch (tf::ExtrapolationException& ex)
00073 {
00074 if (!extrapolation_fallback)
00075 throw;
00076 geometry_msgs::PoseStamped latest_in_pose;
00077 latest_in_pose.header.frame_id = in_pose.header.frame_id;
00078 latest_in_pose.pose = in_pose.pose;
00079 tf->transformPose(frame, latest_in_pose, out_pose);
00080 return true;
00081 }
00082 catch (tf::TransformException& ex)
00083 {
00084 ROS_ERROR("Exception in transformPose: %s", ex.what());
00085 return false;
00086 }
00087 return false;
00088 }
00089
00101 bool transformPose(const TFListenerPtr tf, const std::string frame,
00102 const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose,
00103 const bool extrapolation_fallback = true)
00104 {
00105 geometry_msgs::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
00106 geometry_msgs::PoseStamped out_3d_pose;
00107
00108 bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, extrapolation_fallback);
00109 if (ret)
00110 {
00111 out_pose = poseStampedToPose2D(out_3d_pose);
00112 }
00113 return ret;
00114 }
00115
00116 geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped& pose,
00117 const std::string& frame_id)
00118 {
00119 nav_2d_msgs::Pose2DStamped local_pose;
00120 nav_2d_utils::transformPose(tf, frame_id, pose, local_pose);
00121 return local_pose.pose;
00122 }
00123
00124 }
00125
00126 #endif // NAV_2D_UTILS_TF_HELP_H