35 #ifndef NAV_2D_UTILS_TF_HELP_H 36 #define NAV_2D_UTILS_TF_HELP_H 40 #include <geometry_msgs/PoseStamped.h> 41 #include <nav_2d_msgs/Pose2DStamped.h> 59 const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose,
60 const bool extrapolation_fallback =
true)
62 if (in_pose.header.frame_id == frame)
70 tf->transform(in_pose, out_pose, frame);
75 if (!extrapolation_fallback)
77 geometry_msgs::PoseStamped latest_in_pose;
78 latest_in_pose.header.frame_id = in_pose.header.frame_id;
79 latest_in_pose.pose = in_pose.pose;
80 tf->transform(latest_in_pose, out_pose, frame);
85 ROS_ERROR(
"Exception in transformPose: %s", ex.what());
103 const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose,
104 const bool extrapolation_fallback =
true)
107 geometry_msgs::PoseStamped out_3d_pose;
109 bool ret =
transformPose(tf, frame, in_3d_pose, out_3d_pose, extrapolation_fallback);
118 const std::string& frame_id)
120 nav_2d_msgs::Pose2DStamped local_pose;
122 return local_pose.pose;
127 #endif // NAV_2D_UTILS_TF_HELP_H A set of utility functions for Bounds objects interacting with other messages/types.
bool transformPose(const TFListenerPtr tf, const std::string frame, const geometry_msgs::PoseStamped &in_pose, geometry_msgs::PoseStamped &out_pose, const bool extrapolation_fallback=true)
Transform a PoseStamped from one frame to another while catching exceptions.
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped &pose, const std::string &frame_id)