8 #include <fields2cover.h>
12 #include <nav_msgs/msg/path.hpp>
13 #include <geometry_msgs/msg/polygon.hpp>
14 #include <geometry_msgs/msg/pose.hpp>
15 #include <geometry_msgs/msg/point32.hpp>
16 #include <geometry_msgs/msg/point.h>
18 #include <nav_msgs/Path.h>
21 #include <geometry_msgs/Polygon.h>
22 #include <geometry_msgs/Pose.h>
23 #include <geometry_msgs/Point32.h>
24 #include <geometry_msgs/Point.h>
31 namespace GeometryMsgs = geometry_msgs::msg;
32 namespace NavMsgs = nav_msgs::msg;
34 namespace GeometryMsgs = geometry_msgs;
35 namespace NavMsgs = nav_msgs;
40 static void to(
const F2CPoint& _point, GeometryMsgs::Point32& _p32);
41 static void to(
const F2CPoint& _point, GeometryMsgs::Point& _p64);
44 static void to(
const T& _curve, GeometryMsgs::Polygon& _poly);
46 static void to(
const F2CCell& _poly,
47 std::vector<GeometryMsgs::Polygon>& _ros_poly);
49 static void to(
const F2CCells& _polys,
50 std::vector<std::vector<GeometryMsgs::Polygon>>& _ros_polys);
52 static void to(
const F2CLineString& _line, NavMsgs::Path& _path);
61 inline void ROS::to(
const T& _curve, GeometryMsgs::Polygon& _poly) {
62 GeometryMsgs::Point32 p32;
63 for (
const auto& p : _curve) {
65 _poly.points.push_back(p32);