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 "nav_2d_msgs/msg/path2_d.hpp"
44 #include "nav_2d_msgs/msg/pose2_d_stamped.hpp"
45 #include "nav_msgs/msg/path.hpp"
46 #include "rclcpp/rclcpp.hpp"
47 #include "tf2/convert.hpp"
49 namespace nav_2d_utils
51 geometry_msgs::msg::Twist twist2Dto3D(
const nav_2d_msgs::msg::Twist2D & cmd_vel_2d);
52 nav_2d_msgs::msg::Twist2D twist3Dto2D(
const geometry_msgs::msg::Twist & cmd_vel);
54 nav_2d_msgs::msg::Pose2DStamped poseStampedToPose2D(
const geometry_msgs::msg::PoseStamped & pose);
55 geometry_msgs::msg::Pose2D poseToPose2D(
const geometry_msgs::msg::Pose & pose);
56 geometry_msgs::msg::Pose pose2DToPose(
const geometry_msgs::msg::Pose2D & pose2d);
57 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
58 const nav_2d_msgs::msg::Pose2DStamped & pose2d);
59 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
60 const geometry_msgs::msg::Pose2D & pose2d,
61 const std::string & frame,
const rclcpp::Time & stamp);
62 nav_msgs::msg::Path posesToPath(
const std::vector<geometry_msgs::msg::PoseStamped> & poses);
63 nav_2d_msgs::msg::Path2D pathToPath2D(
const nav_msgs::msg::Path & path);
64 nav_msgs::msg::Path poses2DToPath(
65 const std::vector<geometry_msgs::msg::Pose2D> & poses,
66 const std::string & frame,
const rclcpp::Time & stamp);
67 nav_msgs::msg::Path pathToPath(
const nav_2d_msgs::msg::Path2D & path2d);