Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
vector_object_server.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_server.hpp"
16 
17 #include <chrono>
18 #include <exception>
19 #include <functional>
20 #include <limits>
21 #include <stdexcept>
22 #include <utility>
23 
24 #include "rclcpp/create_timer.hpp"
25 
26 #include "tf2_ros/create_timer_ros.hpp"
27 
28 #include "nav2_util/occ_grid_utils.hpp"
29 #include "nav2_util/occ_grid_values.hpp"
30 
31 using namespace std::placeholders;
32 
33 namespace nav2_map_server
34 {
35 
36 VectorObjectServer::VectorObjectServer(const rclcpp::NodeOptions & options)
37 : nav2::LifecycleNode("vector_object_server", "", options), process_map_(false)
38 {}
39 
40 nav2::CallbackReturn
41 VectorObjectServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
42 {
43  RCLCPP_INFO(get_logger(), "Configuring");
44 
45  // Transform buffer and listener initialization
46  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
47  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
48  this->get_node_base_interface(),
49  this->get_node_timers_interface());
50  tf_buffer_->setCreateTimerInterface(timer_interface);
51  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
52 
53  // Obtaining ROS parameters
54  if (!obtainParams()) {
55  return nav2::CallbackReturn::FAILURE;
56  }
57 
58  map_pub_ = create_publisher<nav_msgs::msg::OccupancyGrid>(
59  map_topic_,
61 
62  add_shapes_service_ = create_service<nav2_msgs::srv::AddShapes>(
63  "~/add_shapes",
64  std::bind(&VectorObjectServer::addShapesCallback, this, _1, _2, _3));
65 
66  get_shapes_service_ = create_service<nav2_msgs::srv::GetShapes>(
67  "~/get_shapes",
68  std::bind(&VectorObjectServer::getShapesCallback, this, _1, _2, _3));
69 
70  remove_shapes_service_ = create_service<nav2_msgs::srv::RemoveShapes>(
71  "~/remove_shapes",
72  std::bind(&VectorObjectServer::removeShapesCallback, this, _1, _2, _3));
73 
74  return nav2::CallbackReturn::SUCCESS;
75 }
76 
77 nav2::CallbackReturn
78 VectorObjectServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
79 {
80  RCLCPP_INFO(get_logger(), "Activating");
81 
82  map_pub_->on_activate();
83 
84  // Trigger map to be published
85  process_map_ = true;
87 
88  // Creating bond connection
89  createBond();
90 
91  return nav2::CallbackReturn::SUCCESS;
92 }
93 
94 nav2::CallbackReturn
95 VectorObjectServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
96 {
97  RCLCPP_INFO(get_logger(), "Deactivating");
98 
99  if (map_timer_) {
100  map_timer_->cancel();
101  map_timer_.reset();
102  }
103  process_map_ = false;
104 
105  map_pub_->on_deactivate();
106 
107  // Destroying bond connection
108  destroyBond();
109 
110  return nav2::CallbackReturn::SUCCESS;
111 }
112 
113 nav2::CallbackReturn
114 VectorObjectServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
115 {
116  RCLCPP_INFO(get_logger(), "Cleaning up");
117 
118  add_shapes_service_.reset();
119  get_shapes_service_.reset();
120  remove_shapes_service_.reset();
121 
122  map_pub_.reset();
123  map_.reset();
124 
125  shapes_.clear();
126 
127  tf_listener_.reset();
128  tf_buffer_.reset();
129 
130  return nav2::CallbackReturn::SUCCESS;
131 }
132 
133 nav2::CallbackReturn
134 VectorObjectServer::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
135 {
136  RCLCPP_INFO(get_logger(), "Shutting down");
137  return nav2::CallbackReturn::SUCCESS;
138 }
139 
141 {
142  auto node = shared_from_this();
143 
144  // Main ROS-parameters
145  map_topic_ = nav2::declare_or_get_parameter(node, "map_topic", std::string{"vo_map"});
146  global_frame_id_ = nav2::declare_or_get_parameter(node, "global_frame_id", std::string{"map"});
147  resolution_ = nav2::declare_or_get_parameter(node, "resolution", 0.05);
148  default_value_ = nav2::declare_or_get_parameter(node, "default_value",
149  static_cast<int>(nav2_util::OCC_GRID_UNKNOWN));
150  overlay_type_ = static_cast<OverlayType>(nav2::declare_or_get_parameter(node, "overlay_type",
151  static_cast<int>(OverlayType::OVERLAY_SEQ)));
152  update_frequency_ = nav2::declare_or_get_parameter(node, "update_frequency", 1.0);
153  transform_tolerance_ = nav2::declare_or_get_parameter(node, "transform_tolerance", 0.1);
154 
155  // Shapes
156  auto shape_names = nav2::declare_or_get_parameter(node, "shapes", std::vector<std::string>());
157  for (std::string shape_name : shape_names) {
158  std::string shape_type;
159  try {
160  shape_type = nav2::declare_or_get_parameter<std::string>(node, shape_name + ".type");
161  } catch (const std::exception & ex) {
162  RCLCPP_ERROR(
163  get_logger(), "Error while getting shape %s type: %s", shape_name.c_str(), ex.what());
164  return false;
165  }
166 
167  if (shape_type == "polygon") {
168  auto polygon = std::make_shared<Polygon>(node);
169  if (!polygon->obtainParams(shape_name)) {
170  return false;
171  }
172  shapes_.push_back(polygon);
173  } else if (shape_type == "circle") {
174  auto circle = std::make_shared<Circle>(node);
175  if (!circle->obtainParams(shape_name)) {
176  return false;
177  }
178  shapes_.push_back(circle);
179  } else {
180  RCLCPP_ERROR(get_logger(),
181  "Please specify the correct type for shape %s. Supported types are 'polygon' and 'circle'",
182  shape_name.c_str());
183  return false;
184  }
185  }
186 
187  return true;
188 }
189 
190 std::vector<std::shared_ptr<Shape>>::iterator
191 VectorObjectServer::findShape(const unsigned char * uuid)
192 {
193  for (auto it = shapes_.begin(); it != shapes_.end(); it++) {
194  if ((*it)->isUUID(uuid)) {
195  return it;
196  }
197  }
198  return shapes_.end();
199 }
200 
202 {
203  for (auto shape : shapes_) {
204  if (shape->getFrameID() != global_frame_id_ && !shape->getFrameID().empty()) {
205  // Shape to be updated dynamically
206  if (!shape->toFrame(global_frame_id_, tf_buffer_, transform_tolerance_)) {
207  RCLCPP_ERROR(
208  get_logger(), "Can not transform vector object from %s to %s frame",
209  shape->getFrameID().c_str(), global_frame_id_.c_str());
210  return false;
211  }
212  }
213  }
214 
215  return true;
216 }
217 
219  double & min_x, double & min_y, double & max_x, double & max_y) const
220 {
221  min_x = std::numeric_limits<double>::max();
222  min_y = std::numeric_limits<double>::max();
223  max_x = std::numeric_limits<double>::lowest();
224  max_y = std::numeric_limits<double>::lowest();
225 
226  double min_p_x, min_p_y, max_p_x, max_p_y;
227  for (auto shape : shapes_) {
228  shape->getBoundaries(min_p_x, min_p_y, max_p_x, max_p_y);
229  min_x = std::min(min_x, min_p_x);
230  min_y = std::min(min_y, min_p_y);
231  max_x = std::max(max_x, max_p_x);
232  max_y = std::max(max_y, max_p_y);
233  }
234 
235  if (
236  min_x == std::numeric_limits<double>::max() ||
237  min_y == std::numeric_limits<double>::max() ||
238  max_x == std::numeric_limits<double>::lowest() ||
239  max_y == std::numeric_limits<double>::lowest())
240  {
241  throw std::runtime_error("Can not obtain map boundaries");
242  }
243 }
244 
246  const double & min_x, const double & min_y, const double & max_x, const double & max_y)
247 {
248  // Calculate size of update map
249  int size_x = static_cast<int>((max_x - min_x) / resolution_) + 1;
250  int size_y = static_cast<int>((max_y - min_y) / resolution_) + 1;
251 
252  if (size_x < 0) {
253  throw std::runtime_error("Incorrect map x-size");
254  }
255 
256  if (size_y < 0) {
257  throw std::runtime_error("Incorrect map y-size");
258  }
259 
260  if (!map_) {
261  map_ = std::make_shared<nav_msgs::msg::OccupancyGrid>();
262  }
263 
264  if (
265  map_->info.width != static_cast<unsigned int>(size_x) ||
266  map_->info.height != static_cast<unsigned int>(size_y))
267  {
268  // Map size was changed
269  map_->data = std::vector<int8_t>(size_x * size_y, default_value_);
270  map_->info.width = size_x;
271  map_->info.height = size_y;
272  } else if (size_x > 0 && size_y > 0) {
273  // Map size was not changed
274  memset(map_->data.data(), default_value_, size_x * size_y * sizeof(int8_t));
275  }
276 
277  map_->header.frame_id = global_frame_id_;
278  map_->info.resolution = resolution_;
279  map_->info.origin.position.x = min_x;
280  map_->info.origin.position.y = min_y;
281 }
282 
284 {
285  // Filling the shapes
286  for (auto shape : shapes_) {
287  if (shape->isFill()) {
288  // Put filled shape on map
289  double wx1 = std::numeric_limits<double>::max();
290  double wy1 = std::numeric_limits<double>::max();
291  double wx2 = std::numeric_limits<double>::lowest();
292  double wy2 = std::numeric_limits<double>::lowest();
293  unsigned int mx1 = 0;
294  unsigned int my1 = 0;
295  unsigned int mx2 = 0;
296  unsigned int my2 = 0;
297 
298  shape->getBoundaries(wx1, wy1, wx2, wy2);
299  if (
300  !nav2_util::worldToMap(map_, wx1, wy1, mx1, my1) ||
301  !nav2_util::worldToMap(map_, wx2, wy2, mx2, my2))
302  {
303  RCLCPP_ERROR(
304  get_logger(),
305  "Error to get shape boundaries on map (UUID: %s)", shape->getUUID().c_str());
306  return;
307  }
308 
309  unsigned int it;
310  for (unsigned int my = my1; my <= my2; my++) {
311  for (unsigned int mx = mx1; mx <= mx2; mx++) {
312  it = my * map_->info.width + mx;
313  double wx, wy;
314  nav2_util::mapToWorld(map_, mx, my, wx, wy);
315  if (shape->isPointInside(wx, wy)) {
316  processVal(map_->data[it], shape->getValue(), overlay_type_);
317  }
318  }
319  }
320  } else {
321  // Put shape borders on map
322  shape->putBorders(map_, overlay_type_);
323  }
324  }
325 }
326 
328 {
329  if (map_) {
330  auto map = std::make_unique<nav_msgs::msg::OccupancyGrid>(*map_);
331  map_pub_->publish(std::move(map));
332  }
333 }
334 
336 {
337  if (!process_map_) {
338  return;
339  }
340 
341  try {
342  if (shapes_.size() > 0) {
343  if (!transformVectorObjects()) {
344  return;
345  }
346  double min_x, min_y, max_x, max_y;
347 
348  getMapBoundaries(min_x, min_y, max_x, max_y);
349  updateMap(min_x, min_y, max_x, max_y);
351  } else {
352  updateMap(0.0, 0.0, 0.0, 0.0);
353  }
354  } catch (const std::exception & ex) {
355  RCLCPP_ERROR(get_logger(), "Can not update map: %s", ex.what());
356  return;
357  }
358 
359  publishMap();
360 }
361 
363 {
364  for (auto shape : shapes_) {
365  if (shape->getFrameID() != global_frame_id_ && !shape->getFrameID().empty()) {
366  if (!map_timer_) {
367  map_timer_ = this->create_timer(
368  std::chrono::duration<double>(1.0 / update_frequency_),
369  std::bind(&VectorObjectServer::processMap, this));
370  }
371  RCLCPP_INFO(get_logger(), "Publishing map dynamically at %f Hz rate", update_frequency_);
372  return;
373  }
374  }
375 
376  if (map_timer_) {
377  map_timer_->cancel();
378  map_timer_.reset();
379  }
380  RCLCPP_INFO(get_logger(), "Publishing map once");
381  processMap();
382 }
383 
385  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
386  const std::shared_ptr<nav2_msgs::srv::AddShapes::Request> request,
387  std::shared_ptr<nav2_msgs::srv::AddShapes::Response> response)
388 {
389  // Initialize result with true. If one of the required vector object was not added properly,
390  // set it to false.
391  response->success = true;
392 
393  auto node = shared_from_this();
394 
395  // Process polygons
396  for (auto req_poly : request->polygons) {
397  nav2_msgs::msg::PolygonObject::SharedPtr new_params =
398  std::make_shared<nav2_msgs::msg::PolygonObject>(req_poly);
399 
400  auto it = findShape(new_params->uuid.uuid.data());
401  if (it != shapes_.end()) {
402  // Vector Object with given UUID was found: updating it
403  // Check that found shape has correct type
404  if ((*it)->getType() != POLYGON) {
405  RCLCPP_ERROR(
406  get_logger(),
407  "Shape (UUID: %s) is not a polygon type for a polygon update. Not adding shape.",
408  (*it)->getUUID().c_str());
409  response->success = false;
410  // Do not add this shape
411  continue;
412  }
413 
414  std::shared_ptr<Polygon> polygon = std::static_pointer_cast<Polygon>(*it);
415 
416  // Preserving old parameters for the case, if new ones to be incorrect
417  nav2_msgs::msg::PolygonObject::SharedPtr old_params = polygon->getParams();
418  if (!polygon->setParams(new_params)) {
419  RCLCPP_ERROR(
420  get_logger(),
421  "Failed to update existing polygon object (UUID: %s) with new params. "
422  "Reverting to old polygon params.",
423  (*it)->getUUID().c_str());
424  // Restore old parameters
425  polygon->setParams(old_params);
426  // ... and set the failure to return
427  response->success = false;
428  }
429  } else {
430  // Vector Object with given UUID was not found: creating a new one
431  std::shared_ptr<Polygon> polygon = std::make_shared<Polygon>(node);
432  if (polygon->setParams(new_params)) {
433  shapes_.push_back(polygon);
434  } else {
435  RCLCPP_ERROR(
436  get_logger(), "Failed to create a new polygon object using the provided params.");
437  response->success = false;
438  }
439  }
440  }
441 
442  // Process circles
443  for (auto req_crcl : request->circles) {
444  nav2_msgs::msg::CircleObject::SharedPtr new_params =
445  std::make_shared<nav2_msgs::msg::CircleObject>(req_crcl);
446 
447  auto it = findShape(new_params->uuid.uuid.data());
448  if (it != shapes_.end()) {
449  // Vector object with given UUID was found: updating it
450  // Check that found shape has correct type
451  if ((*it)->getType() != CIRCLE) {
452  RCLCPP_ERROR(
453  get_logger(),
454  "Shape (UUID: %s) is not a circle type for a circle update. Not adding shape.",
455  (*it)->getUUID().c_str());
456  response->success = false;
457  // Do not add this shape
458  continue;
459  }
460 
461  std::shared_ptr<Circle> circle = std::static_pointer_cast<Circle>(*it);
462 
463  // Preserving old parameters for the case, if new ones to be incorrect
464  nav2_msgs::msg::CircleObject::SharedPtr old_params = circle->getParams();
465  if (!circle->setParams(new_params)) {
466  RCLCPP_ERROR(
467  get_logger(),
468  "Failed to update existing circle object (UUID: %s) with new params. "
469  "Reverting to old circle params.",
470  (*it)->getUUID().c_str());
471  // Restore old parameters
472  circle->setParams(old_params);
473  // ... and set the failure to return
474  response->success = false;
475  }
476  } else {
477  // Vector Object with given UUID was not found: creating a new one
478  std::shared_ptr<Circle> circle = std::make_shared<Circle>(node);
479  if (circle->setParams(new_params)) {
480  shapes_.push_back(circle);
481  } else {
482  RCLCPP_ERROR(
483  get_logger(), "Failed to create a new circle object using the provided params.");
484  response->success = false;
485  }
486  }
487  }
488 
489  switchMapUpdate();
490 }
491 
493  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
494  const std::shared_ptr<nav2_msgs::srv::GetShapes::Request>/*request*/,
495  std::shared_ptr<nav2_msgs::srv::GetShapes::Response> response)
496 {
497  std::shared_ptr<Polygon> polygon;
498  std::shared_ptr<Circle> circle;
499 
500  for (auto shape : shapes_) {
501  switch (shape->getType()) {
502  case POLYGON:
503  polygon = std::static_pointer_cast<Polygon>(shape);
504  response->polygons.push_back(*(polygon->getParams()));
505  break;
506  case CIRCLE:
507  circle = std::static_pointer_cast<Circle>(shape);
508  response->circles.push_back(*(circle->getParams()));
509  break;
510  default:
511  RCLCPP_WARN(get_logger(), "Unknown shape type (UUID: %s)", shape->getUUID().c_str());
512  }
513  }
514 }
515 
517  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
518  const std::shared_ptr<nav2_msgs::srv::RemoveShapes::Request> request,
519  std::shared_ptr<nav2_msgs::srv::RemoveShapes::Response> response)
520 {
521  // Initialize result with true. If one of the required vector object was not found,
522  // set it to false.
523  response->success = true;
524 
525  if (request->all_objects) {
526  // Clear all objects
527  shapes_.clear();
528  } else {
529  // Find objects to remove
530  for (auto req_uuid : request->uuids) {
531  auto it = findShape(req_uuid.uuid.data());
532  if (it != shapes_.end()) {
533  // Shape with given UUID was found: remove it
534  (*it).reset();
535  shapes_.erase(it);
536  } else {
537  // Required vector object was not found
538  RCLCPP_ERROR(
539  get_logger(),
540  "Can not find shape to remove with UUID: %s",
541  unparseUUID(req_uuid.uuid.data()).c_str());
542  response->success = false;
543  }
544  }
545  }
546 
547  switchMapUpdate();
548 }
549 
550 } // namespace nav2_map_server
551 
552 #include "rclcpp_components/register_node_macro.hpp"
553 
554 // Register the component with class_loader.
555 // This acts as a sort of entry point, allowing the component to be discoverable when its library
556 // is being loaded into a running process.
557 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_map_server::VectorObjectServer)
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
A QoS profile for latched, reliable topics with a history of 1 messages.
void addShapesCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::AddShapes::Request > request, std::shared_ptr< nav2_msgs::srv::AddShapes::Response > response)
Callback for AddShapes service call. Reads all input vector objects from service request,...
void switchMapUpdate()
If map to be update dynamically, creates map processing timer, otherwise process map once.
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
TF listener.
void publishMap()
Publishes output map.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
: Resets all services, publishers, map and TF-s
double process_map_
Whether to process and publish map.
nav2::ServiceServer< nav2_msgs::srv::GetShapes >::SharedPtr get_shapes_service_
GetShapes service.
bool transformVectorObjects()
Transform all vector shapes from their local frame to output map frame.
void processMap()
Calculates new map sizes, updates map, processes all vector objects on it and publishes output map on...
std::vector< std::shared_ptr< Shape > > shapes_
All shapes vector.
double update_frequency_
Frequency to dynamically update/publish the map (if necessary)
int8_t default_value_
Default value the output map to be filled with.
void removeShapesCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::RemoveShapes::Request > request, std::shared_ptr< nav2_msgs::srv::RemoveShapes::Response > response)
Callback for RemoveShapes service call. Try to remove requested vector objects and switches map proce...
std::vector< std::shared_ptr< Shape > >::iterator findShape(const unsigned char *uuid)
Finds the shape with given UUID.
double resolution_
Output map resolution.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
: Activates output map publisher and creates bond connection
nav2::Publisher< nav_msgs::msg::OccupancyGrid >::SharedPtr map_pub_
Output map publisher.
nav_msgs::msg::OccupancyGrid::SharedPtr map_
Output map with vector objects on it.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
void putVectorObjectsOnMap()
Processes all vector objects on raster output map.
double transform_tolerance_
Transform tolerance.
std::string global_frame_id_
Frame of output map.
std::string map_topic_
@beirf Topic name where the output map to be published to
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called in shutdown state.
rclcpp::TimerBase::SharedPtr map_timer_
Map update timer.
void getMapBoundaries(double &min_x, double &min_y, double &max_x, double &max_y) const
Obtains map boundaries to place all vector objects inside.
void getShapesCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::GetShapes::Request > request, std::shared_ptr< nav2_msgs::srv::GetShapes::Response > response)
Callback for GetShapes service call. Gets all shapes and returns them to the service response.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
: Deactivates map publisher and timer (if any), destroys bond connection
nav2::ServiceServer< nav2_msgs::srv::AddShapes >::SharedPtr add_shapes_service_
AddShapes service.
void updateMap(const double &min_x, const double &min_y, const double &max_x, const double &max_y)
Creates or updates existing map with required sizes and fills it with default value.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
: Initializes TF buffer/listener, obtains ROS-parameters, creates incoming services,...
OverlayType overlay_type_
@Overlay Type of overlay of vector objects on the map
bool obtainParams()
Supporting routine obtaining all ROS-parameters.
nav2::ServiceServer< nav2_msgs::srv::RemoveShapes >::SharedPtr remove_shapes_service_
RemoveShapes service.