37 #include <nav_2d_msgs/Pose2DStamped.h>
45 const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose,
46 const bool extrapolation_fallback)
48 if (in_pose.header.frame_id == frame)
56 tf->transform(in_pose, out_pose, frame);
61 if (!extrapolation_fallback)
63 geometry_msgs::PoseStamped latest_in_pose;
64 latest_in_pose.header.frame_id = in_pose.header.frame_id;
65 latest_in_pose.pose = in_pose.pose;
66 tf->transform(latest_in_pose, out_pose, frame);
71 ROS_ERROR(
"Exception in transformPose: %s", ex.what());
78 const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose,
79 const bool extrapolation_fallback)
82 geometry_msgs::PoseStamped out_3d_pose;
84 bool ret =
transformPose(
tf, frame, in_3d_pose, out_3d_pose, extrapolation_fallback);
93 const std::string& frame_id)
95 nav_2d_msgs::Pose2DStamped local_pose;
97 return local_pose.pose;