zoneset_to_marker_conversion.h
Go to the documentation of this file.
1 // Copyright (c) 2021 Pilz GmbH & Co. KG
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU Lesser General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU Lesser General Public License for more details.
12 //
13 // You should have received a copy of the GNU Lesser General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #ifndef PSEN_SCAN_V2_ZONESET_TO_MARKER_CONVERSION_H
17 #define PSEN_SCAN_V2_ZONESET_TO_MARKER_CONVERSION_H
18 
19 #include <string>
20 #include <vector>
21 
22 #include <fmt/format.h>
23 
24 #include <geometry_msgs/Point.h>
25 #include <geometry_msgs/Point32.h>
26 #include <std_msgs/ColorRGBA.h>
27 #include <visualization_msgs/Marker.h>
28 
29 #include "psen_scan_v2/ZoneSet.h"
30 
31 #define TO_MARKER(zoneset_obj, polygon_type, polygon_index) \
32  createMarker(fmt::format("active zoneset {}{} {}", #polygon_type, #polygon_index, getRangeInfo(zoneset_obj)), \
33  createRGBA(strcmp(#polygon_type, "muting") != 0, \
34  strcmp(#polygon_type, "warn") == 0, \
35  strcmp(#polygon_type, "muting") == 0, \
36  1), \
37  zoneset_obj.header.frame_id, \
38  zoneset_obj.polygon_type##polygon_index.points, \
39  0.01 * (strcmp(#polygon_type, "warn") == 0) + 0.02 * (strcmp(#polygon_type, "muting") == 0))
40 
41 namespace psen_scan_v2
42 {
43 geometry_msgs::Point createPoint(const double& x, const double& y, const double& z)
44 {
45  geometry_msgs::Point p;
46  p.x = x;
47  p.y = y;
48  p.z = z;
49  return p;
50 }
51 
52 std_msgs::ColorRGBA createRGBA(const float& r, const float& g, const float& b, const float& a)
53 {
54  std_msgs::ColorRGBA color;
55  color.r = r;
56  color.g = g;
57  color.b = b;
58  color.a = a;
59  return color;
60 }
61 
62 visualization_msgs::Marker createMarker(const std::string& ns,
63  const std_msgs::ColorRGBA& color,
64  const std::string& frame_id,
65  const std::vector<geometry_msgs::Point32>& points,
66  const double& z_offset = 0)
67 {
68  visualization_msgs::Marker marker;
69  marker.header.frame_id = frame_id;
70  marker.ns = ns;
71  marker.id = 0;
72  marker.type = marker.TRIANGLE_LIST;
73  marker.action = marker.ADD;
74 
75  marker.scale.x = 1.0;
76  marker.scale.y = 1.0;
77  marker.scale.z = 1.0;
78 
79  marker.color.r = 0.0;
80  marker.color.g = 0.0;
81  marker.color.b = 0.0;
82  marker.color.a = 0.4;
83 
84  marker.pose.orientation.x = 0.0;
85  marker.pose.orientation.y = 0.0;
86  marker.pose.orientation.z = 0.0;
87  marker.pose.orientation.w = 1.0;
88  marker.pose.position.x = 0.0;
89  marker.pose.position.y = 0.0;
90  marker.pose.position.z = z_offset;
91 
92  marker.points.reserve(3 * (points.size() - 1));
93  marker.colors.reserve(points.size() - 1);
94 
95  for (std::size_t i = 1; i < points.size(); ++i)
96  {
97  marker.points.push_back(createPoint(0.0, 0.0, 0.0));
98  marker.points.push_back(createPoint(points.at(i - 1).x, points.at(i - 1).y, 0.0));
99  marker.points.push_back(createPoint(points.at(i).x, points.at(i).y, 0.0));
100  marker.colors.push_back(color);
101  }
102  return marker;
103 }
104 
105 std::string getRangeInfo(const ZoneSet& zoneset)
106 {
107  std::string range_info = "";
108  if (zoneset.speed_lower != 0 || zoneset.speed_upper != 0)
109  {
110  range_info = fmt::format("min:{:+} max:{:+}", zoneset.speed_lower, zoneset.speed_upper);
111  }
112  return range_info;
113 }
114 
115 std::vector<visualization_msgs::Marker> toMarkers(const ZoneSet& zoneset)
116 {
117  std::vector<visualization_msgs::Marker> return_vec;
118 
119  if (!zoneset.safety1.points.empty())
120  {
121  return_vec.push_back(TO_MARKER(zoneset, safety, 1));
122  }
123  if (!zoneset.safety2.points.empty())
124  {
125  return_vec.push_back(TO_MARKER(zoneset, safety, 2));
126  }
127  if (!zoneset.safety3.points.empty())
128  {
129  return_vec.push_back(TO_MARKER(zoneset, safety, 3));
130  }
131  if (!zoneset.warn1.points.empty())
132  {
133  return_vec.push_back(TO_MARKER(zoneset, warn, 1));
134  }
135  if (!zoneset.warn2.points.empty())
136  {
137  return_vec.push_back(TO_MARKER(zoneset, warn, 2));
138  }
139  if (!zoneset.muting1.points.empty())
140  {
141  return_vec.push_back(TO_MARKER(zoneset, muting, 1));
142  }
143  if (!zoneset.muting2.points.empty())
144  {
145  return_vec.push_back(TO_MARKER(zoneset, muting, 2));
146  }
147 
148  return return_vec;
149 }
150 
151 } // namespace psen_scan_v2
152 
153 #endif // PSEN_SCAN_V2_ZONESET_TO_MARKER_CONVERSION_H
TO_MARKER
#define TO_MARKER(zoneset_obj, polygon_type, polygon_index)
Definition: zoneset_to_marker_conversion.h:31
psen_scan_v2::createPoint
geometry_msgs::Point createPoint(const double &x, const double &y, const double &z)
Definition: zoneset_to_marker_conversion.h:43
psen_scan_v2
Root namespace for the ROS part.
Definition: active_zoneset_node.h:29
psen_scan_v2::toMarkers
std::vector< visualization_msgs::Marker > toMarkers(const ZoneSet &zoneset)
Definition: zoneset_to_marker_conversion.h:115
psen_scan_v2::createRGBA
std_msgs::ColorRGBA createRGBA(const float &r, const float &g, const float &b, const float &a)
Definition: zoneset_to_marker_conversion.h:52
psen_scan_v2::getRangeInfo
std::string getRangeInfo(const ZoneSet &zoneset)
Definition: zoneset_to_marker_conversion.h:105
r
r
psen_scan_v2::createMarker
visualization_msgs::Marker createMarker(const std::string &ns, const std_msgs::ColorRGBA &color, const std::string &frame_id, const std::vector< geometry_msgs::Point32 > &points, const double &z_offset=0)
Definition: zoneset_to_marker_conversion.h:62


psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Nov 25 2023 03:46:26