35 #ifndef NAV_2D_UTILS__CONVERSIONS_HPP_
36 #define NAV_2D_UTILS__CONVERSIONS_HPP_
40 #include "geometry_msgs/msg/pose.hpp"
41 #include "geometry_msgs/msg/twist.hpp"
42 #include "nav_2d_msgs/msg/twist2_d.hpp"
43 #include "geometry_msgs/msg/pose_stamped.hpp"
44 #include "nav_msgs/msg/path.hpp"
45 #include "rclcpp/rclcpp.hpp"
46 #include "tf2/convert.hpp"
48 namespace nav_2d_utils
50 geometry_msgs::msg::Twist twist2Dto3D(
const nav_2d_msgs::msg::Twist2D & cmd_vel_2d);
51 nav_2d_msgs::msg::Twist2D twist3Dto2D(
const geometry_msgs::msg::Twist & cmd_vel);
52 nav_msgs::msg::Path posesToPath(
53 const std::vector<geometry_msgs::msg::Pose> & poses,
54 const std::string & frame,
const rclcpp::Time & stamp);