Nav2 Navigation Stack - humble  humble
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 "nav2_util/robot_utils.hpp"
22 #include "rclcpp/logger.hpp"
23 
24 namespace nav2_util
25 {
26 
27 bool getCurrentPose(
28  geometry_msgs::msg::PoseStamped & global_pose,
29  tf2_ros::Buffer & tf_buffer, const std::string global_frame,
30  const std::string robot_frame, const double transform_timeout,
31  const rclcpp::Time stamp)
32 {
33  tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose);
34  global_pose.header.frame_id = robot_frame;
35  global_pose.header.stamp = stamp;
36 
37  return transformPoseInTargetFrame(
38  global_pose, global_pose, tf_buffer, global_frame, transform_timeout);
39 }
40 
41 bool transformPoseInTargetFrame(
42  const geometry_msgs::msg::PoseStamped & input_pose,
43  geometry_msgs::msg::PoseStamped & transformed_pose,
44  tf2_ros::Buffer & tf_buffer, const std::string target_frame,
45  const double transform_timeout)
46 {
47  static rclcpp::Logger logger = rclcpp::get_logger("transformPoseInTargetFrame");
48 
49  try {
50  transformed_pose = tf_buffer.transform(
51  input_pose, target_frame,
52  tf2::durationFromSec(transform_timeout));
53  return true;
54  } catch (tf2::LookupException & ex) {
55  RCLCPP_ERROR(
56  logger,
57  "No Transform available Error looking up target frame: %s\n", ex.what());
58  } catch (tf2::ConnectivityException & ex) {
59  RCLCPP_ERROR(
60  logger,
61  "Connectivity Error looking up target frame: %s\n", ex.what());
62  } catch (tf2::ExtrapolationException & ex) {
63  RCLCPP_ERROR(
64  logger,
65  "Extrapolation Error looking up target frame: %s\n", ex.what());
66  } catch (tf2::TimeoutException & ex) {
67  RCLCPP_ERROR(
68  logger,
69  "Transform timeout with tolerance: %.4f", transform_timeout);
70  } catch (tf2::TransformException & ex) {
71  RCLCPP_ERROR(
72  logger, "Failed to transform from %s to %s",
73  input_pose.header.frame_id.c_str(), target_frame.c_str());
74  }
75 
76  return false;
77 }
78 
79 bool getTransform(
80  const std::string & source_frame_id,
81  const std::string & target_frame_id,
82  const tf2::Duration & transform_tolerance,
83  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
84  tf2::Transform & tf2_transform)
85 {
86  geometry_msgs::msg::TransformStamped transform;
87  tf2_transform.setIdentity(); // initialize by identical transform
88 
89  if (source_frame_id == target_frame_id) {
90  // We are already in required frame
91  return true;
92  }
93 
94  try {
95  // Obtaining the transform to get data from source to target frame
96  transform = tf_buffer->lookupTransform(
97  target_frame_id, source_frame_id,
98  tf2::TimePointZero, transform_tolerance);
99  } catch (tf2::TransformException & e) {
100  RCLCPP_ERROR(
101  rclcpp::get_logger("getTransform"),
102  "Failed to get \"%s\"->\"%s\" frame transform: %s",
103  source_frame_id.c_str(), target_frame_id.c_str(), e.what());
104  return false;
105  }
106 
107  // Convert TransformStamped to TF2 transform
108  tf2::fromMsg(transform.transform, tf2_transform);
109  return true;
110 }
111 
112 bool getTransform(
113  const std::string & source_frame_id,
114  const rclcpp::Time & source_time,
115  const std::string & target_frame_id,
116  const rclcpp::Time & target_time,
117  const std::string & fixed_frame_id,
118  const tf2::Duration & transform_tolerance,
119  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
120  tf2::Transform & tf2_transform)
121 {
122  geometry_msgs::msg::TransformStamped transform;
123  tf2_transform.setIdentity(); // initialize by identical transform
124 
125  try {
126  // Obtaining the transform to get data from source to target frame.
127  // This also considers the time shift between source and target.
128  transform = tf_buffer->lookupTransform(
129  target_frame_id, target_time,
130  source_frame_id, source_time,
131  fixed_frame_id, transform_tolerance);
132  } catch (tf2::TransformException & ex) {
133  RCLCPP_ERROR(
134  rclcpp::get_logger("getTransform"),
135  "Failed to get \"%s\"->\"%s\" frame transform: %s",
136  source_frame_id.c_str(), target_frame_id.c_str(), ex.what());
137  return false;
138  }
139 
140  // Convert TransformStamped to TF2 transform
141  tf2::fromMsg(transform.transform, tf2_transform);
142  return true;
143 }
144 
145 bool validateTwist(const geometry_msgs::msg::Twist & msg)
146 {
147  if (std::isinf(msg.linear.x) || std::isnan(msg.linear.x)) {
148  return false;
149  }
150 
151  if (std::isinf(msg.linear.y) || std::isnan(msg.linear.y)) {
152  return false;
153  }
154 
155  if (std::isinf(msg.linear.z) || std::isnan(msg.linear.z)) {
156  return false;
157  }
158 
159  if (std::isinf(msg.angular.x) || std::isnan(msg.angular.x)) {
160  return false;
161  }
162 
163  if (std::isinf(msg.angular.y) || std::isnan(msg.angular.y)) {
164  return false;
165  }
166 
167  if (std::isinf(msg.angular.z) || std::isnan(msg.angular.z)) {
168  return false;
169  }
170 
171  return true;
172 }
173 
174 } // end namespace nav2_util