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"
25 #include "geometry_msgs/msg/twist_stamped.hpp"
26 #include "geometry_msgs/msg/transform_stamped.hpp"
28 #include "tf2/transform_datatypes.h"
29 #include "tf2_ros/buffer.h"
30 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
31 #include "rclcpp/rclcpp.hpp"
45 geometry_msgs::msg::PoseStamped & global_pose,
46 tf2_ros::Buffer & tf_buffer,
const std::string global_frame =
"map",
47 const std::string robot_frame =
"base_link",
const double transform_timeout = 0.1,
48 const rclcpp::Time stamp = rclcpp::Time());
59 bool transformPoseInTargetFrame(
60 const geometry_msgs::msg::PoseStamped & input_pose,
61 geometry_msgs::msg::PoseStamped & transformed_pose,
62 tf2_ros::Buffer & tf_buffer,
const std::string target_frame,
63 const double transform_timeout = 0.1);
75 const std::string & source_frame_id,
76 const std::string & target_frame_id,
77 const tf2::Duration & transform_tolerance,
78 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
79 tf2::Transform & tf2_transform);
95 const std::string & source_frame_id,
96 const rclcpp::Time & source_time,
97 const std::string & target_frame_id,
98 const rclcpp::Time & target_time,
99 const std::string & fixed_frame_id,
100 const tf2::Duration & transform_tolerance,
101 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
102 tf2::Transform & tf2_transform);
114 const std::string & source_frame_id,
115 const std::string & target_frame_id,
116 const tf2::Duration & transform_tolerance,
117 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
118 geometry_msgs::msg::TransformStamped & transform_msg);
134 const std::string & source_frame_id,
135 const rclcpp::Time & source_time,
136 const std::string & target_frame_id,
137 const rclcpp::Time & target_time,
138 const std::string & fixed_frame_id,
139 const tf2::Duration & transform_tolerance,
140 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
141 geometry_msgs::msg::TransformStamped & transform_msg);
148 [[nodiscard]]
bool validateTwist(
const geometry_msgs::msg::Twist & msg);
149 [[nodiscard]]
bool validateTwist(
const geometry_msgs::msg::TwistStamped & msg);