Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
robot_utils.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2019 Steven Macenski
3 // Copyright (c) 2019 Samsung Research America
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #include <string>
18 #include <cmath>
19 #include <memory>
20 
21 #include "tf2/convert.hpp"
22 #include "nav2_util/robot_utils.hpp"
23 #include "rclcpp/logger.hpp"
24 
25 namespace nav2_util
26 {
27 
28 bool getCurrentPose(
29  geometry_msgs::msg::PoseStamped & global_pose,
30  tf2_ros::Buffer & tf_buffer, const std::string global_frame,
31  const std::string robot_frame, const double transform_timeout,
32  const rclcpp::Time stamp)
33 {
34  tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose);
35  global_pose.header.frame_id = robot_frame;
36  global_pose.header.stamp = stamp;
37 
38  return transformPoseInTargetFrame(
39  global_pose, global_pose, tf_buffer, global_frame, transform_timeout);
40 }
41 
42 bool transformPoseInTargetFrame(
43  const geometry_msgs::msg::PoseStamped & input_pose,
44  geometry_msgs::msg::PoseStamped & transformed_pose,
45  tf2_ros::Buffer & tf_buffer, const std::string target_frame,
46  const double transform_timeout)
47 {
48  static rclcpp::Logger logger = rclcpp::get_logger("transformPoseInTargetFrame");
49 
50  try {
51  transformed_pose = tf_buffer.transform(
52  input_pose, target_frame,
53  tf2::durationFromSec(transform_timeout));
54  return true;
55  } catch (tf2::LookupException & ex) {
56  RCLCPP_ERROR(
57  logger,
58  "No Transform available Error looking up target frame: %s\n", ex.what());
59  } catch (tf2::ConnectivityException & ex) {
60  RCLCPP_ERROR(
61  logger,
62  "Connectivity Error looking up target frame: %s\n", ex.what());
63  } catch (tf2::ExtrapolationException & ex) {
64  RCLCPP_ERROR(
65  logger,
66  "Extrapolation Error looking up target frame: %s\n", ex.what());
67  } catch (tf2::TimeoutException & ex) {
68  RCLCPP_ERROR(
69  logger,
70  "Transform timeout with tolerance: %.4f", transform_timeout);
71  } catch (tf2::TransformException & ex) {
72  RCLCPP_ERROR(
73  logger, "Failed to transform from %s to %s",
74  input_pose.header.frame_id.c_str(), target_frame.c_str());
75  }
76 
77  return false;
78 }
79 
80 bool getTransform(
81  const std::string & source_frame_id,
82  const std::string & target_frame_id,
83  const tf2::Duration & transform_tolerance,
84  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
85  geometry_msgs::msg::TransformStamped & transform_msg)
86 {
87  if (source_frame_id == target_frame_id) {
88  // We are already in required frame
89  return true;
90  }
91 
92  try {
93  // Obtaining the transform to get data from source to target frame
94  transform_msg = tf_buffer->lookupTransform(
95  target_frame_id, source_frame_id,
96  tf2::TimePointZero, transform_tolerance);
97  } catch (tf2::TransformException & e) {
98  RCLCPP_ERROR(
99  rclcpp::get_logger("getTransform"),
100  "Failed to get \"%s\"->\"%s\" frame transform: %s",
101  source_frame_id.c_str(), target_frame_id.c_str(), e.what());
102  return false;
103  }
104  return true;
105 }
106 
107 bool getTransform(
108  const std::string & source_frame_id,
109  const std::string & target_frame_id,
110  const tf2::Duration & transform_tolerance,
111  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
112  tf2::Transform & tf2_transform)
113 {
114  tf2_transform.setIdentity(); // initialize by identical transform
115  geometry_msgs::msg::TransformStamped transform;
116  if (getTransform(source_frame_id, target_frame_id, transform_tolerance, tf_buffer, transform)) {
117  // Convert TransformStamped to TF2 transform
118  tf2::fromMsg(transform.transform, tf2_transform);
119  return true;
120  }
121  return false;
122 }
123 
124 bool getTransform(
125  const std::string & source_frame_id,
126  const rclcpp::Time & source_time,
127  const std::string & target_frame_id,
128  const rclcpp::Time & target_time,
129  const std::string & fixed_frame_id,
130  const tf2::Duration & transform_tolerance,
131  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
132  geometry_msgs::msg::TransformStamped & transform_msg)
133 {
134  try {
135  // Obtaining the transform to get data from source to target frame.
136  // This also considers the time shift between source and target.
137  transform_msg = tf_buffer->lookupTransform(
138  target_frame_id, target_time,
139  source_frame_id, source_time,
140  fixed_frame_id, transform_tolerance);
141  } catch (tf2::TransformException & ex) {
142  RCLCPP_ERROR(
143  rclcpp::get_logger("getTransform"),
144  "Failed to get \"%s\"->\"%s\" frame transform: %s",
145  source_frame_id.c_str(), target_frame_id.c_str(), ex.what());
146  return false;
147  }
148 
149  return true;
150 }
151 
152 bool getTransform(
153  const std::string & source_frame_id,
154  const rclcpp::Time & source_time,
155  const std::string & target_frame_id,
156  const rclcpp::Time & target_time,
157  const std::string & fixed_frame_id,
158  const tf2::Duration & transform_tolerance,
159  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
160  tf2::Transform & tf2_transform)
161 {
162  geometry_msgs::msg::TransformStamped transform;
163  tf2_transform.setIdentity(); // initialize by identical transform
164  if (getTransform(
165  source_frame_id, source_time, target_frame_id, target_time, fixed_frame_id,
166  transform_tolerance, tf_buffer, transform))
167  {
168  // Convert TransformStamped to TF2 transform
169  tf2::fromMsg(transform.transform, tf2_transform);
170  return true;
171  }
172 
173  return false;
174 }
175 
176 bool validateTwist(const geometry_msgs::msg::Twist & msg)
177 {
178  if (std::isinf(msg.linear.x) || std::isnan(msg.linear.x)) {
179  return false;
180  }
181 
182  if (std::isinf(msg.linear.y) || std::isnan(msg.linear.y)) {
183  return false;
184  }
185 
186  if (std::isinf(msg.linear.z) || std::isnan(msg.linear.z)) {
187  return false;
188  }
189 
190  if (std::isinf(msg.angular.x) || std::isnan(msg.angular.x)) {
191  return false;
192  }
193 
194  if (std::isinf(msg.angular.y) || std::isnan(msg.angular.y)) {
195  return false;
196  }
197 
198  if (std::isinf(msg.angular.z) || std::isnan(msg.angular.z)) {
199  return false;
200  }
201 
202  return true;
203 }
204 
205 } // end namespace nav2_util