21 #include "tf2/convert.hpp"
22 #include "nav2_util/robot_utils.hpp"
23 #include "rclcpp/logger.hpp"
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)
34 tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose);
35 global_pose.header.frame_id = robot_frame;
36 global_pose.header.stamp = stamp;
38 return transformPoseInTargetFrame(
39 global_pose, global_pose, tf_buffer, global_frame, transform_timeout);
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)
48 static rclcpp::Logger logger = rclcpp::get_logger(
"transformPoseInTargetFrame");
51 transformed_pose = tf_buffer.transform(
52 input_pose, target_frame,
53 tf2::durationFromSec(transform_timeout));
55 }
catch (tf2::LookupException & ex) {
58 "No Transform available Error looking up target frame: %s\n", ex.what());
59 }
catch (tf2::ConnectivityException & ex) {
62 "Connectivity Error looking up target frame: %s\n", ex.what());
63 }
catch (tf2::ExtrapolationException & ex) {
66 "Extrapolation Error looking up target frame: %s\n", ex.what());
67 }
catch (tf2::TimeoutException & ex) {
70 "Transform timeout with tolerance: %.4f", transform_timeout);
71 }
catch (tf2::TransformException & ex) {
73 logger,
"Failed to transform from %s to %s",
74 input_pose.header.frame_id.c_str(), target_frame.c_str());
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)
87 if (source_frame_id == target_frame_id) {
94 transform_msg = tf_buffer->lookupTransform(
95 target_frame_id, source_frame_id,
96 tf2::TimePointZero, transform_tolerance);
97 }
catch (tf2::TransformException & e) {
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());
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)
114 tf2_transform.setIdentity();
115 geometry_msgs::msg::TransformStamped transform;
116 if (getTransform(source_frame_id, target_frame_id, transform_tolerance, tf_buffer, transform)) {
118 tf2::fromMsg(transform.transform, tf2_transform);
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)
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) {
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());
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)
162 geometry_msgs::msg::TransformStamped transform;
163 tf2_transform.setIdentity();
165 source_frame_id, source_time, target_frame_id, target_time, fixed_frame_id,
166 transform_tolerance, tf_buffer, transform))
169 tf2::fromMsg(transform.transform, tf2_transform);
176 bool validateTwist(
const geometry_msgs::msg::Twist & msg)
178 if (std::isinf(msg.linear.x) || std::isnan(msg.linear.x)) {
182 if (std::isinf(msg.linear.y) || std::isnan(msg.linear.y)) {
186 if (std::isinf(msg.linear.z) || std::isnan(msg.linear.z)) {
190 if (std::isinf(msg.angular.x) || std::isnan(msg.angular.x)) {
194 if (std::isinf(msg.angular.y) || std::isnan(msg.angular.y)) {
198 if (std::isinf(msg.angular.z) || std::isnan(msg.angular.z)) {