21 #include "nav2_util/robot_utils.hpp"
22 #include "rclcpp/logger.hpp"
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)
33 tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose);
34 global_pose.header.frame_id = robot_frame;
35 global_pose.header.stamp = stamp;
37 return transformPoseInTargetFrame(
38 global_pose, global_pose, tf_buffer, global_frame, transform_timeout);
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)
47 static rclcpp::Logger logger = rclcpp::get_logger(
"transformPoseInTargetFrame");
50 transformed_pose = tf_buffer.transform(
51 input_pose, target_frame,
52 tf2::durationFromSec(transform_timeout));
54 }
catch (tf2::LookupException & ex) {
57 "No Transform available Error looking up target frame: %s\n", ex.what());
58 }
catch (tf2::ConnectivityException & ex) {
61 "Connectivity Error looking up target frame: %s\n", ex.what());
62 }
catch (tf2::ExtrapolationException & ex) {
65 "Extrapolation Error looking up target frame: %s\n", ex.what());
66 }
catch (tf2::TimeoutException & ex) {
69 "Transform timeout with tolerance: %.4f", transform_timeout);
70 }
catch (tf2::TransformException & ex) {
72 logger,
"Failed to transform from %s to %s",
73 input_pose.header.frame_id.c_str(), target_frame.c_str());
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)
86 geometry_msgs::msg::TransformStamped transform;
87 tf2_transform.setIdentity();
89 if (source_frame_id == target_frame_id) {
96 transform = tf_buffer->lookupTransform(
97 target_frame_id, source_frame_id,
98 tf2::TimePointZero, transform_tolerance);
99 }
catch (tf2::TransformException & e) {
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());
108 tf2::fromMsg(transform.transform, tf2_transform);
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)
122 geometry_msgs::msg::TransformStamped transform;
123 tf2_transform.setIdentity();
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) {
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());
141 tf2::fromMsg(transform.transform, tf2_transform);
145 bool validateTwist(
const geometry_msgs::msg::Twist & msg)
147 if (std::isinf(msg.linear.x) || std::isnan(msg.linear.x)) {
151 if (std::isinf(msg.linear.y) || std::isnan(msg.linear.y)) {
155 if (std::isinf(msg.linear.z) || std::isnan(msg.linear.z)) {
159 if (std::isinf(msg.angular.x) || std::isnan(msg.angular.x)) {
163 if (std::isinf(msg.angular.y) || std::isnan(msg.angular.y)) {
167 if (std::isinf(msg.angular.z) || std::isnan(msg.angular.z)) {