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  rclcpp::PARAMETER_STRING);
162  } catch (const std::exception & ex) {
163  RCLCPP_ERROR(
164  get_logger(), "Error while getting shape %s type: %s", shape_name.c_str(), ex.what());
165  return false;
166  }
167 
168  if (shape_type == "polygon") {
169  auto polygon = std::make_shared<Polygon>(node);
170  if (!polygon->obtainParams(shape_name)) {
171  return false;
172  }
173  shapes_.push_back(polygon);
174  } else if (shape_type == "circle") {
175  auto circle = std::make_shared<Circle>(node);
176  if (!circle->obtainParams(shape_name)) {
177  return false;
178  }
179  shapes_.push_back(circle);
180  } else {
181  RCLCPP_ERROR(get_logger(),
182  "Please specify the correct type for shape %s. Supported types are 'polygon' and 'circle'",
183  shape_name.c_str());
184  return false;
185  }
186  }
187 
188  return true;
189 }
190 
191 std::vector<std::shared_ptr<Shape>>::iterator
192 VectorObjectServer::findShape(const unsigned char * uuid)
193 {
194  for (auto it = shapes_.begin(); it != shapes_.end(); it++) {
195  if ((*it)->isUUID(uuid)) {
196  return it;
197  }
198  }
199  return shapes_.end();
200 }
201 
203 {
204  for (auto shape : shapes_) {
205  if (shape->getFrameID() != global_frame_id_ && !shape->getFrameID().empty()) {
206  // Shape to be updated dynamically
207  if (!shape->toFrame(global_frame_id_, tf_buffer_, transform_tolerance_)) {
208  RCLCPP_ERROR(
209  get_logger(), "Can not transform vector object from %s to %s frame",
210  shape->getFrameID().c_str(), global_frame_id_.c_str());
211  return false;
212  }
213  }
214  }
215 
216  return true;
217 }
218 
220  double & min_x, double & min_y, double & max_x, double & max_y) const
221 {
222  min_x = std::numeric_limits<double>::max();
223  min_y = std::numeric_limits<double>::max();
224  max_x = std::numeric_limits<double>::lowest();
225  max_y = std::numeric_limits<double>::lowest();
226 
227  double min_p_x, min_p_y, max_p_x, max_p_y;
228  for (auto shape : shapes_) {
229  shape->getBoundaries(min_p_x, min_p_y, max_p_x, max_p_y);
230  min_x = std::min(min_x, min_p_x);
231  min_y = std::min(min_y, min_p_y);
232  max_x = std::max(max_x, max_p_x);
233  max_y = std::max(max_y, max_p_y);
234  }
235 
236  if (
237  min_x == std::numeric_limits<double>::max() ||
238  min_y == std::numeric_limits<double>::max() ||
239  max_x == std::numeric_limits<double>::lowest() ||
240  max_y == std::numeric_limits<double>::lowest())
241  {
242  throw std::runtime_error("Can not obtain map boundaries");
243  }
244 }
245 
247  const double & min_x, const double & min_y, const double & max_x, const double & max_y)
248 {
249  // Calculate size of update map
250  int size_x = static_cast<int>((max_x - min_x) / resolution_) + 1;
251  int size_y = static_cast<int>((max_y - min_y) / resolution_) + 1;
252 
253  if (size_x < 0) {
254  throw std::runtime_error("Incorrect map x-size");
255  }
256 
257  if (size_y < 0) {
258  throw std::runtime_error("Incorrect map y-size");
259  }
260 
261  if (!map_) {
262  map_ = std::make_shared<nav_msgs::msg::OccupancyGrid>();
263  }
264 
265  if (
266  map_->info.width != static_cast<unsigned int>(size_x) ||
267  map_->info.height != static_cast<unsigned int>(size_y))
268  {
269  // Map size was changed
270  map_->data = std::vector<int8_t>(size_x * size_y, default_value_);
271  map_->info.width = size_x;
272  map_->info.height = size_y;
273  } else if (size_x > 0 && size_y > 0) {
274  // Map size was not changed
275  memset(map_->data.data(), default_value_, size_x * size_y * sizeof(int8_t));
276  }
277 
278  map_->header.frame_id = global_frame_id_;
279  map_->info.resolution = resolution_;
280  map_->info.origin.position.x = min_x;
281  map_->info.origin.position.y = min_y;
282 }
283 
285 {
286  // Filling the shapes
287  for (auto shape : shapes_) {
288  if (shape->isFill()) {
289  // Put filled shape on map
290  double wx1 = std::numeric_limits<double>::max();
291  double wy1 = std::numeric_limits<double>::max();
292  double wx2 = std::numeric_limits<double>::lowest();
293  double wy2 = std::numeric_limits<double>::lowest();
294  unsigned int mx1 = 0;
295  unsigned int my1 = 0;
296  unsigned int mx2 = 0;
297  unsigned int my2 = 0;
298 
299  shape->getBoundaries(wx1, wy1, wx2, wy2);
300  if (
301  !nav2_util::worldToMap(map_, wx1, wy1, mx1, my1) ||
302  !nav2_util::worldToMap(map_, wx2, wy2, mx2, my2))
303  {
304  RCLCPP_ERROR(
305  get_logger(),
306  "Error to get shape boundaries on map (UUID: %s)", shape->getUUID().c_str());
307  return;
308  }
309 
310  unsigned int it;
311  for (unsigned int my = my1; my <= my2; my++) {
312  for (unsigned int mx = mx1; mx <= mx2; mx++) {
313  it = my * map_->info.width + mx;
314  double wx, wy;
315  nav2_util::mapToWorld(map_, mx, my, wx, wy);
316  if (shape->isPointInside(wx, wy)) {
317  processVal(map_->data[it], shape->getValue(), overlay_type_);
318  }
319  }
320  }
321  } else {
322  // Put shape borders on map
323  shape->putBorders(map_, overlay_type_);
324  }
325  }
326 }
327 
329 {
330  if (map_) {
331  auto map = std::make_unique<nav_msgs::msg::OccupancyGrid>(*map_);
332  map_pub_->publish(std::move(map));
333  }
334 }
335 
337 {
338  if (!process_map_) {
339  return;
340  }
341 
342  try {
343  if (shapes_.size() > 0) {
344  if (!transformVectorObjects()) {
345  return;
346  }
347  double min_x, min_y, max_x, max_y;
348 
349  getMapBoundaries(min_x, min_y, max_x, max_y);
350  updateMap(min_x, min_y, max_x, max_y);
352  } else {
353  updateMap(0.0, 0.0, 0.0, 0.0);
354  }
355  } catch (const std::exception & ex) {
356  RCLCPP_ERROR(get_logger(), "Can not update map: %s", ex.what());
357  return;
358  }
359 
360  publishMap();
361 }
362 
364 {
365  for (auto shape : shapes_) {
366  if (shape->getFrameID() != global_frame_id_ && !shape->getFrameID().empty()) {
367  if (!map_timer_) {
368  map_timer_ = this->create_timer(
369  std::chrono::duration<double>(1.0 / update_frequency_),
370  std::bind(&VectorObjectServer::processMap, this));
371  }
372  RCLCPP_INFO(get_logger(), "Publishing map dynamically at %f Hz rate", update_frequency_);
373  return;
374  }
375  }
376 
377  if (map_timer_) {
378  map_timer_->cancel();
379  map_timer_.reset();
380  }
381  RCLCPP_INFO(get_logger(), "Publishing map once");
382  processMap();
383 }
384 
386  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
387  const std::shared_ptr<nav2_msgs::srv::AddShapes::Request> request,
388  std::shared_ptr<nav2_msgs::srv::AddShapes::Response> response)
389 {
390  // Initialize result with true. If one of the required vector object was not added properly,
391  // set it to false.
392  response->success = true;
393 
394  auto node = shared_from_this();
395 
396  // Process polygons
397  for (auto req_poly : request->polygons) {
398  nav2_msgs::msg::PolygonObject::SharedPtr new_params =
399  std::make_shared<nav2_msgs::msg::PolygonObject>(req_poly);
400 
401  auto it = findShape(new_params->uuid.uuid.data());
402  if (it != shapes_.end()) {
403  // Vector Object with given UUID was found: updating it
404  // Check that found shape has correct type
405  if ((*it)->getType() != POLYGON) {
406  RCLCPP_ERROR(
407  get_logger(),
408  "Shape (UUID: %s) is not a polygon type for a polygon update. Not adding shape.",
409  (*it)->getUUID().c_str());
410  response->success = false;
411  // Do not add this shape
412  continue;
413  }
414 
415  std::shared_ptr<Polygon> polygon = std::static_pointer_cast<Polygon>(*it);
416 
417  // Preserving old parameters for the case, if new ones to be incorrect
418  nav2_msgs::msg::PolygonObject::SharedPtr old_params = polygon->getParams();
419  if (!polygon->setParams(new_params)) {
420  RCLCPP_ERROR(
421  get_logger(),
422  "Failed to update existing polygon object (UUID: %s) with new params. "
423  "Reverting to old polygon params.",
424  (*it)->getUUID().c_str());
425  // Restore old parameters
426  polygon->setParams(old_params);
427  // ... and set the failure to return
428  response->success = false;
429  }
430  } else {
431  // Vector Object with given UUID was not found: creating a new one
432  std::shared_ptr<Polygon> polygon = std::make_shared<Polygon>(node);
433  if (polygon->setParams(new_params)) {
434  shapes_.push_back(polygon);
435  } else {
436  RCLCPP_ERROR(
437  get_logger(), "Failed to create a new polygon object using the provided params.");
438  response->success = false;
439  }
440  }
441  }
442 
443  // Process circles
444  for (auto req_crcl : request->circles) {
445  nav2_msgs::msg::CircleObject::SharedPtr new_params =
446  std::make_shared<nav2_msgs::msg::CircleObject>(req_crcl);
447 
448  auto it = findShape(new_params->uuid.uuid.data());
449  if (it != shapes_.end()) {
450  // Vector object with given UUID was found: updating it
451  // Check that found shape has correct type
452  if ((*it)->getType() != CIRCLE) {
453  RCLCPP_ERROR(
454  get_logger(),
455  "Shape (UUID: %s) is not a circle type for a circle update. Not adding shape.",
456  (*it)->getUUID().c_str());
457  response->success = false;
458  // Do not add this shape
459  continue;
460  }
461 
462  std::shared_ptr<Circle> circle = std::static_pointer_cast<Circle>(*it);
463 
464  // Preserving old parameters for the case, if new ones to be incorrect
465  nav2_msgs::msg::CircleObject::SharedPtr old_params = circle->getParams();
466  if (!circle->setParams(new_params)) {
467  RCLCPP_ERROR(
468  get_logger(),
469  "Failed to update existing circle object (UUID: %s) with new params. "
470  "Reverting to old circle params.",
471  (*it)->getUUID().c_str());
472  // Restore old parameters
473  circle->setParams(old_params);
474  // ... and set the failure to return
475  response->success = false;
476  }
477  } else {
478  // Vector Object with given UUID was not found: creating a new one
479  std::shared_ptr<Circle> circle = std::make_shared<Circle>(node);
480  if (circle->setParams(new_params)) {
481  shapes_.push_back(circle);
482  } else {
483  RCLCPP_ERROR(
484  get_logger(), "Failed to create a new circle object using the provided params.");
485  response->success = false;
486  }
487  }
488  }
489 
490  switchMapUpdate();
491 }
492 
494  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
495  const std::shared_ptr<nav2_msgs::srv::GetShapes::Request>/*request*/,
496  std::shared_ptr<nav2_msgs::srv::GetShapes::Response> response)
497 {
498  std::shared_ptr<Polygon> polygon;
499  std::shared_ptr<Circle> circle;
500 
501  for (auto shape : shapes_) {
502  switch (shape->getType()) {
503  case POLYGON:
504  polygon = std::static_pointer_cast<Polygon>(shape);
505  response->polygons.push_back(*(polygon->getParams()));
506  break;
507  case CIRCLE:
508  circle = std::static_pointer_cast<Circle>(shape);
509  response->circles.push_back(*(circle->getParams()));
510  break;
511  default:
512  RCLCPP_WARN(get_logger(), "Unknown shape type (UUID: %s)", shape->getUUID().c_str());
513  }
514  }
515 }
516 
518  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
519  const std::shared_ptr<nav2_msgs::srv::RemoveShapes::Request> request,
520  std::shared_ptr<nav2_msgs::srv::RemoveShapes::Response> response)
521 {
522  // Initialize result with true. If one of the required vector object was not found,
523  // set it to false.
524  response->success = true;
525 
526  if (request->all_objects) {
527  // Clear all objects
528  shapes_.clear();
529  } else {
530  // Find objects to remove
531  for (auto req_uuid : request->uuids) {
532  auto it = findShape(req_uuid.uuid.data());
533  if (it != shapes_.end()) {
534  // Shape with given UUID was found: remove it
535  (*it).reset();
536  shapes_.erase(it);
537  } else {
538  // Required vector object was not found
539  RCLCPP_ERROR(
540  get_logger(),
541  "Can not find shape to remove with UUID: %s",
542  unparseUUID(req_uuid.uuid.data()).c_str());
543  response->success = false;
544  }
545  }
546  }
547 
548  switchMapUpdate();
549 }
550 
551 } // namespace nav2_map_server
552 
553 #include "rclcpp_components/register_node_macro.hpp"
554 
555 // Register the component with class_loader.
556 // This acts as a sort of entry point, allowing the component to be discoverable when its library
557 // is being loaded into a running process.
558 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.