17 #ifndef NAV2_UTIL__ROBOT_UTILS_HPP_
18 #define NAV2_UTIL__ROBOT_UTILS_HPP_
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "geometry_msgs/msg/twist.hpp"
26 #include "tf2_ros/buffer.h"
27 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
28 #include "rclcpp/rclcpp.hpp"
42 geometry_msgs::msg::PoseStamped & global_pose,
43 tf2_ros::Buffer & tf_buffer,
const std::string global_frame =
"map",
44 const std::string robot_frame =
"base_link",
const double transform_timeout = 0.1,
45 const rclcpp::Time stamp = rclcpp::Time());
56 bool transformPoseInTargetFrame(
57 const geometry_msgs::msg::PoseStamped & input_pose,
58 geometry_msgs::msg::PoseStamped & transformed_pose,
59 tf2_ros::Buffer & tf_buffer,
const std::string target_frame,
60 const double transform_timeout = 0.1);
84 const std::string & source_frame_id,
85 const std::string & target_frame_id,
86 const tf2::Duration & transform_tolerance,
87 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
88 tf2::Transform & tf2_transform);
104 const std::string & source_frame_id,
105 const rclcpp::Time & source_time,
106 const std::string & target_frame_id,
107 const rclcpp::Time & target_time,
108 const std::string & fixed_frame_id,
109 const tf2::Duration & transform_tolerance,
110 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
111 tf2::Transform & tf2_transform);
118 bool validateTwist(
const geometry_msgs::msg::Twist & msg);