Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
tf_help.cpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include <memory>
36 #include <string>
37 #include "nav_2d_utils/tf_help.hpp"
38 
39 namespace nav_2d_utils
40 {
41 
42 bool transformPose(
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
48 )
49 {
50  if (in_pose.header.frame_id == frame) {
51  out_pose = in_pose;
52  return true;
53  }
54 
55  try {
56  tf->transform(in_pose, out_pose, frame);
57  return true;
58  } catch (tf2::ExtrapolationException & ex) {
59  auto transform = tf->lookupTransform(
60  frame,
61  in_pose.header.frame_id,
62  tf2::TimePointZero
63  );
64  if (
65  (rclcpp::Time(in_pose.header.stamp) - rclcpp::Time(transform.header.stamp)) >
66  transform_tolerance)
67  {
68  RCLCPP_ERROR(
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(),
72  frame.c_str()
73  );
74  RCLCPP_ERROR(
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
81  );
82  return false;
83  } else {
84  tf2::doTransform(in_pose, out_pose, transform);
85  return true;
86  }
87  } catch (tf2::TransformException & ex) {
88  RCLCPP_ERROR(
89  rclcpp::get_logger("tf_help"),
90  "Exception in transformPose: %s",
91  ex.what()
92  );
93  return false;
94  }
95  return false;
96 }
97 
98 bool transformPose(
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
104 )
105 {
106  geometry_msgs::msg::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
107  geometry_msgs::msg::PoseStamped out_3d_pose;
108 
109  bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, transform_tolerance);
110  if (ret) {
111  out_pose = poseStampedToPose2D(out_3d_pose);
112  }
113  return ret;
114 }
115 } // namespace nav_2d_utils