Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
vector_object_shapes.cpp
1 // Copyright (c) 2023 Samsung R&D Institute Russia
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_map_server/vector_object_shapes.hpp"
16 
17 #include <uuid/uuid.h>
18 #include <cmath>
19 #include <exception>
20 #include <limits>
21 #include <stdexcept>
22 #include <vector>
23 
24 #include "geometry_msgs/msg/pose_stamped.hpp"
25 
26 #include "nav2_util/occ_grid_utils.hpp"
27 #include "nav2_util/occ_grid_values.hpp"
28 #include "nav2_util/geometry_utils.hpp"
29 #include "nav2_util/raytrace_line_2d.hpp"
30 #include "nav2_util/robot_utils.hpp"
31 
32 namespace nav2_map_server
33 {
34 
35 // ---------- Shape ----------
36 
37 Shape::Shape(const nav2::LifecycleNode::WeakPtr & node)
38 : type_(UNKNOWN), node_(node)
39 {}
40 
42 {}
43 
44 ShapeType Shape::getType()
45 {
46  return type_;
47 }
48 
49 bool Shape::obtainShapeUUID(const std::string & shape_name, unsigned char * out_uuid)
50 {
51  auto node = node_.lock();
52  if (!node) {
53  throw std::runtime_error{"Failed to lock node"};
54  }
55 
56  try {
57  // Try to get shape UUID from ROS-parameters
58  std::string uuid_str = nav2::declare_or_get_parameter<std::string>(
59  node, shape_name + ".uuid", rclcpp::PARAMETER_STRING);
60  if (uuid_parse(uuid_str.c_str(), out_uuid) != 0) {
61  RCLCPP_ERROR(
62  node->get_logger(),
63  "[%s] Can not parse UUID string for shape: %s",
64  shape_name.c_str(), uuid_str.c_str());
65  return false;
66  }
67  } catch (const std::exception &) {
68  // If no UUID was specified, generate a new one
69  uuid_generate(out_uuid);
70 
71  char uuid_str[37];
72  uuid_unparse(out_uuid, uuid_str);
73  RCLCPP_INFO(
74  node->get_logger(),
75  "[%s] No UUID is specified for shape. Generating a new one: %s",
76  shape_name.c_str(), uuid_str);
77  }
78 
79  return true;
80 }
81 
82 // ---------- Polygon ----------
83 
84 Polygon::Polygon(
85  const nav2::LifecycleNode::WeakPtr & node)
86 : Shape::Shape(node)
87 {
88  type_ = POLYGON;
89 }
90 
91 int8_t Polygon::getValue() const
92 {
93  return params_->value;
94 }
95 
96 std::string Polygon::getFrameID() const
97 {
98  return params_->header.frame_id;
99 }
100 
101 std::string Polygon::getUUID() const
102 {
103  return unparseUUID(params_->uuid.uuid.data());
104 }
105 
106 bool Polygon::isUUID(const unsigned char * uuid) const
107 {
108  return uuid_compare(params_->uuid.uuid.data(), uuid) == 0;
109 }
110 
111 bool Polygon::isFill() const
112 {
113  return params_->closed;
114 }
115 
116 bool Polygon::obtainParams(const std::string & shape_name)
117 {
118  auto node = node_.lock();
119  if (!node) {
120  throw std::runtime_error{"Failed to lock node"};
121  }
122 
123  if (!params_) {
124  params_ = std::make_shared<nav2_msgs::msg::PolygonObject>();
125  }
126  if (!polygon_) {
127  polygon_ = std::make_shared<geometry_msgs::msg::Polygon>();
128  }
129 
130  params_->header.frame_id = nav2::declare_or_get_parameter(
131  node, shape_name + ".frame_id", std::string{"map"});
132  params_->value = nav2::declare_or_get_parameter(
133  node, shape_name + ".value", static_cast<int>(nav2_util::OCC_GRID_OCCUPIED));
134  params_->closed = nav2::declare_or_get_parameter(
135  node, shape_name + ".closed", true);
136 
137  std::vector<double> poly_row;
138  try {
139  poly_row = nav2::declare_or_get_parameter<std::vector<double>>(
140  node, shape_name + ".points", rclcpp::PARAMETER_DOUBLE_ARRAY);
141  } catch (const std::exception & ex) {
142  RCLCPP_ERROR(
143  node->get_logger(),
144  "[%s] Error while getting polygon parameters: %s",
145  shape_name.c_str(), ex.what());
146  return false;
147  }
148  // Check for points format correctness
149  if (poly_row.size() < 6 || poly_row.size() % 2 != 0) {
150  RCLCPP_ERROR(
151  node->get_logger(),
152  "[%s] Polygon has incorrect points description",
153  shape_name.c_str());
154  return false;
155  }
156 
157  // Obtain polygon vertices
158  geometry_msgs::msg::Point32 point;
159  bool first = true;
160  for (double val : poly_row) {
161  if (first) {
162  point.x = val;
163  } else {
164  point.y = val;
165  params_->points.push_back(point);
166  }
167  first = !first;
168  }
169 
170  // Filling the polygon_ with obtained points in map's frame
171  polygon_->points = params_->points;
172 
173  // Getting shape UUID
174  return obtainShapeUUID(shape_name, params_->uuid.uuid.data());
175 }
176 
177 nav2_msgs::msg::PolygonObject::SharedPtr Polygon::getParams() const
178 {
179  return params_;
180 }
181 
182 bool Polygon::setParams(const nav2_msgs::msg::PolygonObject::SharedPtr params)
183 {
184  params_ = params;
185 
186  if (!polygon_) {
187  polygon_ = std::make_shared<geometry_msgs::msg::Polygon>();
188  }
189  polygon_->points = params_->points;
190 
191  // If no UUID was specified, generate a new one
192  if (uuid_is_null(params_->uuid.uuid.data())) {
193  uuid_generate(params_->uuid.uuid.data());
194  }
195 
196  return checkConsistency();
197 }
198 
200  const std::string & to_frame,
201  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
202  const double transform_tolerance)
203 {
204  geometry_msgs::msg::PoseStamped from_pose, to_pose;
205  from_pose.header = params_->header;
206  for (unsigned int i = 0; i < params_->points.size(); i++) {
207  from_pose.pose.position.x = params_->points[i].x;
208  from_pose.pose.position.y = params_->points[i].y;
209  from_pose.pose.position.z = params_->points[i].z;
210  if (
211  nav2_util::transformPoseInTargetFrame(
212  from_pose, to_pose, *tf_buffer, to_frame, transform_tolerance))
213  {
214  polygon_->points[i].x = to_pose.pose.position.x;
215  polygon_->points[i].y = to_pose.pose.position.y;
216  polygon_->points[i].z = to_pose.pose.position.z;
217  } else {
218  return false;
219  }
220  }
221 
222  return true;
223 }
224 
225 void Polygon::getBoundaries(double & min_x, double & min_y, double & max_x, double & max_y)
226 {
227  min_x = std::numeric_limits<double>::max();
228  min_y = std::numeric_limits<double>::max();
229  max_x = std::numeric_limits<double>::lowest();
230  max_y = std::numeric_limits<double>::lowest();
231 
232  for (auto point : polygon_->points) {
233  min_x = std::min(min_x, static_cast<double>(point.x));
234  min_y = std::min(min_y, static_cast<double>(point.y));
235  max_x = std::max(max_x, static_cast<double>(point.x));
236  max_y = std::max(max_y, static_cast<double>(point.y));
237  }
238 }
239 
240 bool Polygon::isPointInside(const double px, const double py) const
241 {
242  return nav2_util::geometry_utils::isPointInsidePolygon(px, py, polygon_->points);
243 }
244 
246  nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)
247 {
248  unsigned int mx0, my0, mx1, my1;
249 
250  auto node = node_.lock();
251  if (!node) {
252  throw std::runtime_error{"Failed to lock node"};
253  }
254 
255  if (!nav2_util::worldToMap(map, polygon_->points[0].x, polygon_->points[0].y, mx1, my1)) {
256  RCLCPP_ERROR(
257  node->get_logger(),
258  "[UUID: %s] Can not convert (%f, %f) point to map",
259  getUUID().c_str(), polygon_->points[0].x, polygon_->points[0].y);
260  return;
261  }
262 
263  MapAction ma(map, params_->value, overlay_type);
264  for (unsigned int i = 1; i < polygon_->points.size(); i++) {
265  mx0 = mx1;
266  my0 = my1;
267  if (!nav2_util::worldToMap(map, polygon_->points[i].x, polygon_->points[i].y, mx1, my1)) {
268  RCLCPP_ERROR(
269  node->get_logger(),
270  "[UUID: %s] Can not convert (%f, %f) point to map",
271  getUUID().c_str(), polygon_->points[i].x, polygon_->points[i].y);
272  return;
273  }
274  nav2_util::raytraceLine(ma, mx0, my0, mx1, my1, map->info.width);
275  }
276 }
277 
279 {
280  if (params_->points.size() < 3) {
281  auto node = node_.lock();
282  if (!node) {
283  throw std::runtime_error{"Failed to lock node"};
284  }
285 
286  RCLCPP_ERROR(
287  node->get_logger(),
288  "[UUID: %s] Polygon has incorrect number of vertices: %li",
289  getUUID().c_str(), params_->points.size());
290  return false;
291  }
292 
293  return true;
294 }
295 
296 // ---------- Circle ----------
297 
298 Circle::Circle(
299  const nav2::LifecycleNode::WeakPtr & node)
300 : Shape::Shape(node)
301 {
302  type_ = CIRCLE;
303 }
304 
305 int8_t Circle::getValue() const
306 {
307  return params_->value;
308 }
309 
310 std::string Circle::getFrameID() const
311 {
312  return params_->header.frame_id;
313 }
314 
315 std::string Circle::getUUID() const
316 {
317  return unparseUUID(params_->uuid.uuid.data());
318 }
319 
320 bool Circle::isUUID(const unsigned char * uuid) const
321 {
322  return uuid_compare(params_->uuid.uuid.data(), uuid) == 0;
323 }
324 
325 bool Circle::isFill() const
326 {
327  return params_->fill;
328 }
329 
330 bool Circle::obtainParams(const std::string & shape_name)
331 {
332  auto node = node_.lock();
333  if (!node) {
334  throw std::runtime_error{"Failed to lock node"};
335  }
336 
337  if (!params_) {
338  params_ = std::make_shared<nav2_msgs::msg::CircleObject>();
339  }
340  if (!center_) {
341  center_ = std::make_shared<geometry_msgs::msg::Point32>();
342  }
343 
344  params_->header.frame_id = nav2::declare_or_get_parameter(
345  node, shape_name + ".frame_id", std::string{"map"});
346  params_->value = nav2::declare_or_get_parameter(
347  node, shape_name + ".value", static_cast<int>(nav2_util::OCC_GRID_OCCUPIED));
348  params_->fill = nav2::declare_or_get_parameter(
349  node, shape_name + ".fill", true);
350 
351  std::vector<double> center_row;
352  try {
353  center_row = nav2::declare_or_get_parameter<std::vector<double>>(
354  node, shape_name + ".center", rclcpp::PARAMETER_DOUBLE_ARRAY);
355  params_->radius = nav2::declare_or_get_parameter<double>(
356  node, shape_name + ".radius", rclcpp::PARAMETER_DOUBLE);
357  if (params_->radius < 0) {
358  RCLCPP_ERROR(
359  node->get_logger(),
360  "[%s] Circle has incorrect radius less than zero",
361  shape_name.c_str());
362  return false;
363  }
364  } catch (const std::exception & ex) {
365  RCLCPP_ERROR(
366  node->get_logger(),
367  "[%s] Error while getting circle parameters: %s",
368  shape_name.c_str(), ex.what());
369  return false;
370  }
371  // Check for points format correctness
372  if (center_row.size() != 2) {
373  RCLCPP_ERROR(
374  node->get_logger(),
375  "[%s] Circle has incorrect center description",
376  shape_name.c_str());
377  return false;
378  }
379 
380  // Obtain circle center
381  params_->center.x = center_row[0];
382  params_->center.y = center_row[1];
383  // Setting the center_ with obtained circle center in map's frame
384  *center_ = params_->center;
385 
386  // Getting shape UUID
387  return obtainShapeUUID(shape_name, params_->uuid.uuid.data());
388 }
389 
390 nav2_msgs::msg::CircleObject::SharedPtr Circle::getParams() const
391 {
392  return params_;
393 }
394 
395 bool Circle::setParams(const nav2_msgs::msg::CircleObject::SharedPtr params)
396 {
397  params_ = params;
398 
399  if (!center_) {
400  center_ = std::make_shared<geometry_msgs::msg::Point32>();
401  }
402  *center_ = params_->center;
403 
404  // If no UUID was specified, generate a new one
405  if (uuid_is_null(params_->uuid.uuid.data())) {
406  uuid_generate(params_->uuid.uuid.data());
407  }
408 
409  return checkConsistency();
410 }
411 
413  const std::string & to_frame,
414  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
415  const double transform_tolerance)
416 {
417  geometry_msgs::msg::PoseStamped from_pose, to_pose;
418  from_pose.header = params_->header;
419  from_pose.pose.position.x = params_->center.x;
420  from_pose.pose.position.y = params_->center.y;
421  from_pose.pose.position.z = params_->center.z;
422  if (
423  nav2_util::transformPoseInTargetFrame(
424  from_pose, to_pose, *tf_buffer, to_frame, transform_tolerance))
425  {
426  center_->x = to_pose.pose.position.x;
427  center_->y = to_pose.pose.position.y;
428  center_->z = to_pose.pose.position.z;
429  } else {
430  return false;
431  }
432 
433  return true;
434 }
435 
436 void Circle::getBoundaries(double & min_x, double & min_y, double & max_x, double & max_y)
437 {
438  min_x = center_->x - params_->radius;
439  min_y = center_->y - params_->radius;
440  max_x = center_->x + params_->radius;
441  max_y = center_->y + params_->radius;
442 }
443 
444 bool Circle::isPointInside(const double px, const double py) const
445 {
446  return ( (px - center_->x) * (px - center_->x) + (py - center_->y) * (py - center_->y) ) <=
447  params_->radius * params_->radius;
448 }
449 
451  nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)
452 {
453  unsigned int mcx, mcy;
454  if (!centerToMap(map, mcx, mcy)) {
455  return;
456  }
457 
458  // Implementation of the circle generation algorithm, based on the following work:
459  // Berthold K.P. Horn "Circle generators for display devices"
460  // Computer Graphics and Image Processing 5.2 (1976): 280-288.
461 
462  // Inputs initialization
463  const int r = static_cast<int>(std::round(params_->radius / map->info.resolution));
464  int x = r;
465  int y = 1;
466 
467  // Error initialization
468  int s = -r;
469 
470  // Calculation algorithm
471  while (x > y) { // Calculating only first circle octant
472  // Put 8 points in each octant reflecting symmetrically
473  putPoint(mcx + x, mcy + y, map, overlay_type);
474  putPoint(mcx + y, mcy + x, map, overlay_type);
475  putPoint(mcx - x + 1, mcy + y, map, overlay_type);
476  putPoint(mcx + y, mcy - x + 1, map, overlay_type);
477  putPoint(mcx - x + 1, mcy - y + 1, map, overlay_type);
478  putPoint(mcx - y + 1, mcy - x + 1, map, overlay_type);
479  putPoint(mcx + x, mcy - y + 1, map, overlay_type);
480  putPoint(mcx - y + 1, mcy + x, map, overlay_type);
481 
482  s = s + 2 * y + 1;
483  y++;
484  if (s > 0) {
485  s = s - 2 * x + 2;
486  x--;
487  }
488  }
489 
490  // Corner case for x == y: do not put end points twice
491  if (x == y) {
492  putPoint(mcx + x, mcy + y, map, overlay_type);
493  putPoint(mcx - x + 1, mcy + y, map, overlay_type);
494  putPoint(mcx - x + 1, mcy - y + 1, map, overlay_type);
495  putPoint(mcx + x, mcy - y + 1, map, overlay_type);
496  }
497 }
498 
500 {
501  if (params_->radius < 0.0) {
502  auto node = node_.lock();
503  if (!node) {
504  throw std::runtime_error{"Failed to lock node"};
505  }
506 
507  RCLCPP_ERROR(
508  node->get_logger(),
509  "[UUID: %s] Circle has incorrect radius less than zero",
510  getUUID().c_str());
511  return false;
512  }
513  return true;
514 }
515 
517  nav_msgs::msg::OccupancyGrid::ConstSharedPtr map,
518  unsigned int & mcx, unsigned int & mcy)
519 {
520  auto node = node_.lock();
521  if (!node) {
522  throw std::runtime_error{"Failed to lock node"};
523  }
524 
525  // Get center of circle in map coordinates
526  if (center_->x < map->info.origin.position.x || center_->y < map->info.origin.position.y) {
527  RCLCPP_ERROR(
528  node->get_logger(),
529  "[UUID: %s] Can not convert (%f, %f) circle center to map",
530  getUUID().c_str(), center_->x, center_->y);
531  return false;
532  }
533  // We need the circle center to be always shifted one cell less its logical center
534  // and to avoid any FP-accuracy losing on small values, so we are using another
535  // than nav2_util::worldToMap() approach
536  mcx = static_cast<unsigned int>(
537  std::round((center_->x - map->info.origin.position.x) / map->info.resolution)) - 1;
538  mcy = static_cast<unsigned int>(
539  std::round((center_->y - map->info.origin.position.y) / map->info.resolution)) - 1;
540  if (mcx >= map->info.width || mcy >= map->info.height) {
541  RCLCPP_ERROR(
542  node->get_logger(),
543  "[UUID: %s] Can not convert (%f, %f) point to map",
544  getUUID().c_str(), center_->x, center_->y);
545  return false;
546  }
547 
548  return true;
549 }
550 
551 inline void Circle::putPoint(
552  unsigned int mx, unsigned int my,
553  nav_msgs::msg::OccupancyGrid::SharedPtr map,
554  const OverlayType overlay_type)
555 {
556  processCell(map, my * map->info.width + mx, params_->value, overlay_type);
557 }
558 
559 } // namespace nav2_map_server
bool isUUID(const unsigned char *uuid) const
Checks whether the shape is equal to a given UUID.
bool toFrame(const std::string &to_frame, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const double transform_tolerance)
Transforms shape coordinates to a new frame.
int8_t getValue() const
Gets the value of the shape.
void putPoint(unsigned int mx, unsigned int my, nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)
Put Circle's point on map.
bool isPointInside(const double px, const double py) const
Is the point inside the shape.
std::string getUUID() const
Gets UUID of the shape.
void getBoundaries(double &min_x, double &min_y, double &max_x, double &max_y)
Gets shape box-boundaries.
std::string getFrameID() const
Gets frame ID of the shape.
bool centerToMap(nav_msgs::msg::OccupancyGrid::ConstSharedPtr map, unsigned int &mcx, unsigned int &mcy)
Converts circle center to map coordinates considering FP-accuracy losing on small values when using c...
bool isFill() const
Whether the shape to be filled or only its borders to be put on map.
nav2_msgs::msg::CircleObject::SharedPtr params_
Input circle parameters (could be in any frame)
bool setParams(const nav2_msgs::msg::CircleObject::SharedPtr params)
Tries to update Circle parameters.
void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)
Puts shape borders on map.
nav2_msgs::msg::CircleObject::SharedPtr getParams() const
Gets Circle parameters.
bool checkConsistency()
Checks that shape is consistent for further operation.
geometry_msgs::msg::Point32::SharedPtr center_
Circle center in the map's frame.
bool obtainParams(const std::string &shape_name)
Supporting routine obtaining ROS-parameters for the given vector object.
Functor class used in raytraceLine algorithm.
std::string getUUID() const
Gets UUID of the shape.
void getBoundaries(double &min_x, double &min_y, double &max_x, double &max_y)
Gets shape box-boundaries.
void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)
Puts shape borders on map.
bool isUUID(const unsigned char *uuid) const
Checks whether the shape is equal to a given UUID.
bool toFrame(const std::string &to_frame, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const double transform_tolerance)
Transforms shape coordinates to a new frame.
nav2_msgs::msg::PolygonObject::SharedPtr getParams() const
Gets Polygon parameters.
int8_t getValue() const
Gets the value of the shape.
bool setParams(const nav2_msgs::msg::PolygonObject::SharedPtr params)
Tries to update Polygon parameters.
std::string getFrameID() const
Gets frame ID of the shape.
nav2_msgs::msg::PolygonObject::SharedPtr params_
Input polygon parameters (could be in any frame)
bool checkConsistency()
Checks that shape is consistent for further operation.
bool isPointInside(const double px, const double py) const
Is the point inside the shape.
bool isFill() const
Whether the shape to be filled or only its borders to be put on map.
bool obtainParams(const std::string &shape_name)
Supporting routine obtaining ROS-parameters for the given vector object.
geometry_msgs::msg::Polygon::SharedPtr polygon_
Polygon in the map's frame.
Basic class, other vector objects to be inherited from.
bool obtainShapeUUID(const std::string &shape_name, unsigned char *out_uuid)
Supporting routine obtaining shape UUID from ROS-parameters for the given shape object.
ShapeType type_
Type of shape.
ShapeType getType()
Returns type of the shape.
nav2::LifecycleNode::WeakPtr node_
VectorObjectServer node.
virtual ~Shape()
Shape destructor.
Shape(const nav2::LifecycleNode::WeakPtr &node)
Shape basic class constructor.