conversor.h
Go to the documentation of this file.
1 //=============================================================================
2 // Copyright (C) 2021-2022 Wageningen University - All Rights Reserved
3 // Author: Gonzalo Mier
4 // BSD-3 License
5 //=============================================================================
6 
7 
8 #include <fields2cover.h>
9 #include <vector>
10 
11 #ifdef IS_ROS2
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>
17 #else
18  #include <nav_msgs/Path.h>
19  // #include <visualization_msgs/Marker.h>
20  // #include <visualization_msgs/MarkerArray.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>
25 #endif
26 
27 
28 namespace conversor {
29 
30 #ifdef IS_ROS2
31  namespace GeometryMsgs = geometry_msgs::msg;
32  namespace NavMsgs = nav_msgs::msg;
33 #else
34  namespace GeometryMsgs = geometry_msgs;
35  namespace NavMsgs = nav_msgs;
36 #endif
37 
38 class ROS {
39  public:
40  static void to(const F2CPoint& _point, GeometryMsgs::Point32& _p32);
41  static void to(const F2CPoint& _point, GeometryMsgs::Point& _p64);
42 
43  template <class T>
44  static void to(const T& _curve, GeometryMsgs::Polygon& _poly);
45 
46  static void to(const F2CCell& _poly,
47  std::vector<GeometryMsgs::Polygon>& _ros_poly);
48 
49  static void to(const F2CCells& _polys,
50  std::vector<std::vector<GeometryMsgs::Polygon>>& _ros_polys);
51 
52  static void to(const F2CLineString& _line, NavMsgs::Path& _path);
53 
54  // static void to(const F2CLineString& _line,
55  // visualization_msgs::MarkerArray& _markers);
56  // static void to(const OGRMultiLineString& _line,
57  // visualization_msgs::MarkerArray& _markers);
58 };
59 
60 template <class T>
61 inline void ROS::to(const T& _curve, GeometryMsgs::Polygon& _poly) {
62  GeometryMsgs::Point32 p32;
63  for (const auto& p : _curve) {
64  to(p, p32);
65  _poly.points.push_back(p32);
66  }
67 }
68 
69 } // namespace conversor
conversor::ROS
Definition: conversor.h:38
conversor
Definition: conversor.h:28
conversor::ROS::to
static void to(const F2CPoint &_point, GeometryMsgs::Point32 &_p32)
Definition: conversor.cpp:12


fields2cover_ros
Author(s):
autogenerated on Tue Feb 7 2023 03:46:06