37 #include "nav_2d_utils/tf_help.hpp"
39 namespace nav_2d_utils
43 const std::shared_ptr<tf2_ros::Buffer> tf,
44 const std::string frame,
45 const geometry_msgs::msg::PoseStamped & in_pose,
46 geometry_msgs::msg::PoseStamped & out_pose,
47 rclcpp::Duration & transform_tolerance
50 if (in_pose.header.frame_id == frame) {
56 tf->transform(in_pose, out_pose, frame);
58 }
catch (tf2::ExtrapolationException & ex) {
59 auto transform = tf->lookupTransform(
61 in_pose.header.frame_id,
65 (rclcpp::Time(in_pose.header.stamp) - rclcpp::Time(transform.header.stamp)) >
69 rclcpp::get_logger(
"tf_help"),
70 "Transform data too old when converting from %s to %s",
71 in_pose.header.frame_id.c_str(),
75 rclcpp::get_logger(
"tf_help"),
76 "Data time: %ds %uns, Transform time: %ds %uns",
77 in_pose.header.stamp.sec,
78 in_pose.header.stamp.nanosec,
79 transform.header.stamp.sec,
80 transform.header.stamp.nanosec
84 tf2::doTransform(in_pose, out_pose, transform);
87 }
catch (tf2::TransformException & ex) {
89 rclcpp::get_logger(
"tf_help"),
90 "Exception in transformPose: %s",
99 const std::shared_ptr<tf2_ros::Buffer> tf,
100 const std::string frame,
101 const nav_2d_msgs::msg::Pose2DStamped & in_pose,
102 nav_2d_msgs::msg::Pose2DStamped & out_pose,
103 rclcpp::Duration & transform_tolerance
106 geometry_msgs::msg::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
107 geometry_msgs::msg::PoseStamped out_3d_pose;
109 bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, transform_tolerance);
111 out_pose = poseStampedToPose2D(out_3d_pose);