Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
collision_monitor_node.cpp
1 // Copyright (c) 2022 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_collision_monitor/collision_monitor_node.hpp"
16 
17 #include <exception>
18 #include <utility>
19 #include <functional>
20 
21 #include "tf2_ros/create_timer_ros.hpp"
22 
23 #include "nav2_ros_common/node_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
25 
26 #include "nav2_collision_monitor/kinematics.hpp"
27 
28 using namespace std::placeholders;
29 
30 namespace nav2_collision_monitor
31 {
32 
33 CollisionMonitor::CollisionMonitor(const rclcpp::NodeOptions & options)
34 : nav2::LifecycleNode("collision_monitor", options),
35  enabled_{true}, process_active_(false), robot_action_prev_{DO_NOTHING, {-1.0, -1.0, -1.0}, ""},
36  stop_stamp_{0, 0, get_clock()->get_clock_type()}, stop_pub_timeout_(1.0, 0.0)
37 {
38 }
39 
40 CollisionMonitor::~CollisionMonitor()
41 {
42  polygons_.clear();
43  sources_.clear();
44 }
45 
46 nav2::CallbackReturn
47 CollisionMonitor::on_configure(const rclcpp_lifecycle::State & state)
48 {
49  RCLCPP_INFO(get_logger(), "Configuring");
50 
51  // Transform buffer and listener initialization
52  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
53  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
54  this->get_node_base_interface(),
55  this->get_node_timers_interface());
56  tf_buffer_->setCreateTimerInterface(timer_interface);
57  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);
58 
59  std::string cmd_vel_in_topic;
60  std::string cmd_vel_out_topic;
61  std::string state_topic;
62 
63  // Obtaining ROS parameters
64  if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic, state_topic)) {
65  on_cleanup(state);
66  return nav2::CallbackReturn::FAILURE;
67  }
68 
69  cmd_vel_in_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
70  shared_from_this(),
71  cmd_vel_in_topic,
72  std::bind(&CollisionMonitor::cmdVelInCallbackUnstamped, this, std::placeholders::_1),
73  std::bind(&CollisionMonitor::cmdVelInCallbackStamped, this, std::placeholders::_1));
74 
75  auto node = shared_from_this();
76  cmd_vel_out_pub_ = std::make_unique<nav2_util::TwistPublisher>(node, cmd_vel_out_topic);
77 
78  if (!state_topic.empty()) {
79  state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionMonitorState>(
80  state_topic);
81  }
82 
83  collision_points_marker_pub_ = this->create_publisher<visualization_msgs::msg::MarkerArray>(
84  "~/collision_points_marker");
85 
86  // Toggle service initialization
87  toggle_cm_service_ = create_service<nav2_msgs::srv::Toggle>(
88  "~/toggle",
89  std::bind(&CollisionMonitor::toggleCMServiceCallback, this, _1, _2, _3));
90 
91  nav2::declare_parameter_if_not_declared(
92  node, "use_realtime_priority", rclcpp::ParameterValue(false));
93  bool use_realtime_priority = false;
94  node->get_parameter("use_realtime_priority", use_realtime_priority);
95  if (use_realtime_priority) {
96  try {
97  nav2::setSoftRealTimePriority();
98  } catch (const std::runtime_error & e) {
99  RCLCPP_ERROR(get_logger(), "%s", e.what());
100  on_cleanup(state);
101  return nav2::CallbackReturn::FAILURE;
102  }
103  }
104 
105  return nav2::CallbackReturn::SUCCESS;
106 }
107 
108 nav2::CallbackReturn
109 CollisionMonitor::on_activate(const rclcpp_lifecycle::State & /*state*/)
110 {
111  RCLCPP_INFO(get_logger(), "Activating");
112 
113  // Activating lifecycle publisher
114  cmd_vel_out_pub_->on_activate();
115  if (state_pub_) {
116  state_pub_->on_activate();
117  }
118  collision_points_marker_pub_->on_activate();
119 
120  // Activating polygons
121  for (std::shared_ptr<Polygon> polygon : polygons_) {
122  polygon->activate();
123  }
124 
125  // Since polygons are being published when cmd_vel_in appears,
126  // we need to publish polygons first time to display them at startup
127  publishPolygons();
128 
129  // Activating main worker
130  process_active_ = true;
131 
132  // Creating bond connection
133  createBond();
134 
135  return nav2::CallbackReturn::SUCCESS;
136 }
137 
138 nav2::CallbackReturn
139 CollisionMonitor::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
140 {
141  RCLCPP_INFO(get_logger(), "Deactivating");
142 
143  // Deactivating main worker
144  process_active_ = false;
145 
146  // Reset action type to default after worker deactivating
147  robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0}, ""};
148 
149  // Deactivating polygons
150  for (std::shared_ptr<Polygon> polygon : polygons_) {
151  polygon->deactivate();
152  }
153 
154  // Deactivating lifecycle publishers
155  cmd_vel_out_pub_->on_deactivate();
156  if (state_pub_) {
157  state_pub_->on_deactivate();
158  }
159  collision_points_marker_pub_->on_deactivate();
160 
161  // Destroying bond connection
162  destroyBond();
163 
164  return nav2::CallbackReturn::SUCCESS;
165 }
166 
167 nav2::CallbackReturn
168 CollisionMonitor::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
169 {
170  RCLCPP_INFO(get_logger(), "Cleaning up");
171 
172  cmd_vel_in_sub_.reset();
173  cmd_vel_out_pub_.reset();
174  state_pub_.reset();
175  collision_points_marker_pub_.reset();
176 
177  polygons_.clear();
178  sources_.clear();
179 
180  tf_listener_.reset();
181  tf_buffer_.reset();
182 
183  return nav2::CallbackReturn::SUCCESS;
184 }
185 
186 nav2::CallbackReturn
187 CollisionMonitor::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
188 {
189  RCLCPP_INFO(get_logger(), "Shutting down");
190 
191  return nav2::CallbackReturn::SUCCESS;
192 }
193 
194 void CollisionMonitor::cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg)
195 {
196  // If message contains NaN or Inf, ignore
197  if (!nav2_util::validateTwist(msg->twist)) {
198  RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
199  return;
200  }
201 
202  process({msg->twist.linear.x, msg->twist.linear.y, msg->twist.angular.z}, msg->header);
203 }
204 
205 void CollisionMonitor::cmdVelInCallbackUnstamped(geometry_msgs::msg::Twist::SharedPtr msg)
206 {
207  auto twist_stamped = std::make_shared<geometry_msgs::msg::TwistStamped>();
208  twist_stamped->twist = *msg;
209  cmdVelInCallbackStamped(twist_stamped);
210 }
211 
212 void CollisionMonitor::publishVelocity(
213  const Action & robot_action, const std_msgs::msg::Header & header)
214 {
215  if (robot_action.req_vel.isZero()) {
216  if (!robot_action_prev_.req_vel.isZero()) {
217  // Robot just stopped: saving stop timestamp and continue
218  stop_stamp_ = this->now();
219  } else if (this->now() - stop_stamp_ > stop_pub_timeout_) {
220  // More than stop_pub_timeout_ passed after robot has been stopped.
221  // Cease publishing output cmd_vel.
222  return;
223  }
224  }
225 
226  auto cmd_vel_out_msg = std::make_unique<geometry_msgs::msg::TwistStamped>();
227  cmd_vel_out_msg->header = header;
228  cmd_vel_out_msg->twist.linear.x = robot_action.req_vel.x;
229  cmd_vel_out_msg->twist.linear.y = robot_action.req_vel.y;
230  cmd_vel_out_msg->twist.angular.z = robot_action.req_vel.tw;
231  // linear.z, angular.x and angular.y will remain 0.0
232 
233  cmd_vel_out_pub_->publish(std::move(cmd_vel_out_msg));
234 }
235 
236 bool CollisionMonitor::getParameters(
237  std::string & cmd_vel_in_topic,
238  std::string & cmd_vel_out_topic,
239  std::string & state_topic)
240 {
241  std::string base_frame_id, odom_frame_id;
242  tf2::Duration transform_tolerance;
243  rclcpp::Duration source_timeout(2.0, 0.0);
244 
245  auto node = shared_from_this();
246 
247  nav2::declare_parameter_if_not_declared(
248  node, "cmd_vel_in_topic", rclcpp::ParameterValue("cmd_vel_smoothed"));
249  cmd_vel_in_topic = get_parameter("cmd_vel_in_topic").as_string();
250  nav2::declare_parameter_if_not_declared(
251  node, "cmd_vel_out_topic", rclcpp::ParameterValue("cmd_vel"));
252  cmd_vel_out_topic = get_parameter("cmd_vel_out_topic").as_string();
253  nav2::declare_parameter_if_not_declared(
254  node, "state_topic", rclcpp::ParameterValue(""));
255  state_topic = get_parameter("state_topic").as_string();
256 
257  nav2::declare_parameter_if_not_declared(
258  node, "base_frame_id", rclcpp::ParameterValue("base_footprint"));
259  base_frame_id = get_parameter("base_frame_id").as_string();
260  nav2::declare_parameter_if_not_declared(
261  node, "odom_frame_id", rclcpp::ParameterValue("odom"));
262  odom_frame_id = get_parameter("odom_frame_id").as_string();
263  nav2::declare_parameter_if_not_declared(
264  node, "transform_tolerance", rclcpp::ParameterValue(0.1));
265  transform_tolerance =
266  tf2::durationFromSec(get_parameter("transform_tolerance").as_double());
267  nav2::declare_parameter_if_not_declared(
268  node, "source_timeout", rclcpp::ParameterValue(2.0));
269  source_timeout =
270  rclcpp::Duration::from_seconds(get_parameter("source_timeout").as_double());
271  nav2::declare_parameter_if_not_declared(
272  node, "base_shift_correction", rclcpp::ParameterValue(true));
273  const bool base_shift_correction =
274  get_parameter("base_shift_correction").as_bool();
275 
276  nav2::declare_parameter_if_not_declared(
277  node, "stop_pub_timeout", rclcpp::ParameterValue(1.0));
278  stop_pub_timeout_ =
279  rclcpp::Duration::from_seconds(get_parameter("stop_pub_timeout").as_double());
280 
281  if (
282  !configureSources(
283  base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
284  {
285  return false;
286  }
287 
288  if (!configurePolygons(base_frame_id, transform_tolerance)) {
289  return false;
290  }
291 
292  return true;
293 }
294 
295 bool CollisionMonitor::configurePolygons(
296  const std::string & base_frame_id,
297  const tf2::Duration & transform_tolerance)
298 {
299  try {
300  auto node = shared_from_this();
301 
302  // Leave it to be not initialized: to intentionally cause an error if it will not set
303  nav2::declare_parameter_if_not_declared(
304  node, "polygons", rclcpp::PARAMETER_STRING_ARRAY);
305  std::vector<std::string> polygon_names = get_parameter("polygons").as_string_array();
306  for (std::string polygon_name : polygon_names) {
307  // Leave it not initialized: the will cause an error if it will not set
308  nav2::declare_parameter_if_not_declared(
309  node, polygon_name + ".type", rclcpp::PARAMETER_STRING);
310  const std::string polygon_type = get_parameter(polygon_name + ".type").as_string();
311 
312  if (polygon_type == "polygon") {
313  polygons_.push_back(
314  std::make_shared<Polygon>(
315  node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
316  } else if (polygon_type == "circle") {
317  polygons_.push_back(
318  std::make_shared<Circle>(
319  node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
320  } else if (polygon_type == "velocity_polygon") {
321  polygons_.push_back(
322  std::make_shared<VelocityPolygon>(
323  node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
324  } else { // Error if something else
325  RCLCPP_ERROR(
326  get_logger(),
327  "[%s]: Unknown polygon type: %s",
328  polygon_name.c_str(), polygon_type.c_str());
329  return false;
330  }
331 
332  // Configure last added polygon
333  if (!polygons_.back()->configure()) {
334  return false;
335  }
336  }
337  } catch (const std::exception & ex) {
338  RCLCPP_ERROR(get_logger(), "Error while getting parameters: %s", ex.what());
339  return false;
340  }
341 
342  return true;
343 }
344 
345 bool CollisionMonitor::configureSources(
346  const std::string & base_frame_id,
347  const std::string & odom_frame_id,
348  const tf2::Duration & transform_tolerance,
349  const rclcpp::Duration & source_timeout,
350  const bool base_shift_correction)
351 {
352  try {
353  auto node = shared_from_this();
354 
355  // Leave it to be not initialized: to intentionally cause an error if it will not set
356  nav2::declare_parameter_if_not_declared(
357  node, "observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
358  std::vector<std::string> source_names = get_parameter("observation_sources").as_string_array();
359  for (std::string source_name : source_names) {
360  nav2::declare_parameter_if_not_declared(
361  node, source_name + ".type",
362  rclcpp::ParameterValue("scan")); // Laser scanner by default
363  const std::string source_type = get_parameter(source_name + ".type").as_string();
364 
365  if (source_type == "scan") {
366  std::shared_ptr<Scan> s = std::make_shared<Scan>(
367  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
368  transform_tolerance, source_timeout, base_shift_correction);
369 
370  s->configure();
371 
372  sources_.push_back(s);
373  } else if (source_type == "pointcloud") {
374  std::shared_ptr<PointCloud> p = std::make_shared<PointCloud>(
375  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
376  transform_tolerance, source_timeout, base_shift_correction);
377 
378  p->configure();
379 
380  sources_.push_back(p);
381  } else if (source_type == "range") {
382  std::shared_ptr<Range> r = std::make_shared<Range>(
383  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
384  transform_tolerance, source_timeout, base_shift_correction);
385 
386  r->configure();
387 
388  sources_.push_back(r);
389  } else if (source_type == "polygon") {
390  std::shared_ptr<PolygonSource> ps = std::make_shared<PolygonSource>(
391  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
392  transform_tolerance, source_timeout, base_shift_correction);
393  ps->configure();
394 
395  sources_.push_back(ps);
396  } else { // Error if something else
397  RCLCPP_ERROR(
398  get_logger(),
399  "[%s]: Unknown source type: %s",
400  source_name.c_str(), source_type.c_str());
401  return false;
402  }
403  }
404  } catch (const std::exception & ex) {
405  RCLCPP_ERROR(get_logger(), "Error while getting parameters: %s", ex.what());
406  return false;
407  }
408 
409  return true;
410 }
411 
412 void CollisionMonitor::process(const Velocity & cmd_vel_in, const std_msgs::msg::Header & header)
413 {
414  // Current timestamp for all inner routines prolongation
415  rclcpp::Time curr_time = this->now();
416 
417  // Do nothing if main worker in non-active state
418  if (!process_active_) {
419  return;
420  }
421 
422  // Points array collected from different data sources in a robot base frame
423  std::unordered_map<std::string, std::vector<Point>> sources_collision_points_map;
424 
425  // By default - there is no action
426  Action robot_action{DO_NOTHING, cmd_vel_in, ""};
427  // Polygon causing robot action (if any)
428  std::shared_ptr<Polygon> action_polygon;
429 
430  // Fill collision points array from different data sources
431  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
432  for (std::shared_ptr<Source> source : sources_) {
433  auto iter = sources_collision_points_map.insert(
434  {source->getSourceName(), std::vector<Point>()});
435 
436  if (source->getEnabled()) {
437  if (!source->getData(curr_time, iter.first->second) &&
438  source->getSourceTimeout().seconds() != 0.0)
439  {
440  action_polygon = nullptr;
441  robot_action.polygon_name = "invalid source";
442  robot_action.action_type = STOP;
443  robot_action.req_vel.x = 0.0;
444  robot_action.req_vel.y = 0.0;
445  robot_action.req_vel.tw = 0.0;
446  break;
447  }
448  }
449 
450  if (collision_points_marker_pub_->get_subscription_count() > 0) {
451  // visualize collision points with markers
452  visualization_msgs::msg::Marker marker;
453  marker.header.frame_id = get_parameter("base_frame_id").as_string();
454  marker.header.stamp = rclcpp::Time(0, 0);
455  marker.ns = "collision_points_" + source->getSourceName();
456  marker.id = 0;
457  marker.type = visualization_msgs::msg::Marker::POINTS;
458  marker.action = visualization_msgs::msg::Marker::ADD;
459  marker.scale.x = 0.02;
460  marker.scale.y = 0.02;
461  marker.color.r = 1.0;
462  marker.color.a = 1.0;
463  marker.lifetime = rclcpp::Duration(0, 0);
464  marker.frame_locked = true;
465 
466  for (const auto & point : iter.first->second) {
467  geometry_msgs::msg::Point p;
468  p.x = point.x;
469  p.y = point.y;
470  p.z = 0.0;
471  marker.points.push_back(p);
472  }
473  marker_array->markers.push_back(marker);
474  }
475  }
476 
477  if (collision_points_marker_pub_->get_subscription_count() > 0) {
478  collision_points_marker_pub_->publish(std::move(marker_array));
479  }
480 
481  for (std::shared_ptr<Polygon> polygon : polygons_) {
482  if (!polygon->getEnabled() || !enabled_) {
483  continue;
484  }
485  if (robot_action.action_type == STOP) {
486  // If robot already should stop, do nothing
487  break;
488  }
489 
490  // Update polygon coordinates
491  polygon->updatePolygon(cmd_vel_in);
492 
493  const ActionType at = polygon->getActionType();
494  if (at == STOP || at == SLOWDOWN || at == LIMIT) {
495  // Process STOP/SLOWDOWN for the selected polygon
496  if (processStopSlowdownLimit(
497  polygon, sources_collision_points_map, cmd_vel_in, robot_action))
498  {
499  action_polygon = polygon;
500  }
501  } else if (at == APPROACH) {
502  // Process APPROACH for the selected polygon
503  if (processApproach(polygon, sources_collision_points_map, cmd_vel_in, robot_action)) {
504  action_polygon = polygon;
505  }
506  }
507  }
508 
509  if ((robot_action.polygon_name != robot_action_prev_.polygon_name) && enabled_) {
510  // Report changed robot behavior
511  notifyActionState(robot_action, action_polygon);
512  }
513 
514  // Publish required robot velocity
515  publishVelocity(robot_action, header);
516 
517  // Publish polygons for better visualization
518  publishPolygons();
519 
520  robot_action_prev_ = robot_action;
521 }
522 
523 bool CollisionMonitor::processStopSlowdownLimit(
524  const std::shared_ptr<Polygon> polygon,
525  const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
526  const Velocity & velocity,
527  Action & robot_action) const
528 {
529  if (!polygon->isShapeSet()) {
530  return false;
531  }
532 
533  if (polygon->getPointsInside(sources_collision_points_map) >= polygon->getMinPoints()) {
534  if (polygon->getActionType() == STOP) {
535  // Setting up zero velocity for STOP model
536  robot_action.polygon_name = polygon->getName();
537  robot_action.action_type = STOP;
538  robot_action.req_vel.x = 0.0;
539  robot_action.req_vel.y = 0.0;
540  robot_action.req_vel.tw = 0.0;
541  return true;
542  } else if (polygon->getActionType() == SLOWDOWN) {
543  const Velocity safe_vel = velocity * polygon->getSlowdownRatio();
544  // Check that currently calculated velocity is safer than
545  // chosen for previous shapes one
546  if (safe_vel < robot_action.req_vel) {
547  robot_action.polygon_name = polygon->getName();
548  robot_action.action_type = SLOWDOWN;
549  robot_action.req_vel = safe_vel;
550  return true;
551  }
552  } else { // Limit
553  // Compute linear velocity
554  const double linear_vel = std::hypot(velocity.x, velocity.y); // absolute
555  Velocity safe_vel;
556  double ratio = 1.0;
557 
558  // Calculate the most restrictive ratio to preserve curvature
559  if (linear_vel != 0.0) {
560  ratio = std::min(ratio, polygon->getLinearLimit() / linear_vel);
561  }
562  if (velocity.tw != 0.0) {
563  ratio = std::min(ratio, polygon->getAngularLimit() / std::abs(velocity.tw));
564  }
565  ratio = std::clamp(ratio, 0.0, 1.0);
566  // Apply the same ratio to all components to preserve curvature
567  safe_vel = velocity * ratio;
568  // Check that currently calculated velocity is safer than
569  // chosen for previous shapes one
570  if (safe_vel < robot_action.req_vel) {
571  robot_action.polygon_name = polygon->getName();
572  robot_action.action_type = LIMIT;
573  robot_action.req_vel = safe_vel;
574  return true;
575  }
576  }
577  }
578 
579  return false;
580 }
581 
582 bool CollisionMonitor::processApproach(
583  const std::shared_ptr<Polygon> polygon,
584  const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
585  const Velocity & velocity,
586  Action & robot_action) const
587 {
588  if (!polygon->isShapeSet()) {
589  return false;
590  }
591 
592  // Obtain time before a collision
593  const double collision_time = polygon->getCollisionTime(sources_collision_points_map, velocity);
594  if (collision_time >= 0.0) {
595  // If collision will occur, reduce robot speed
596  const double change_ratio = collision_time / polygon->getTimeBeforeCollision();
597  const Velocity safe_vel = velocity * change_ratio;
598  // Check that currently calculated velocity is safer than
599  // chosen for previous shapes one
600  if (safe_vel < robot_action.req_vel) {
601  robot_action.polygon_name = polygon->getName();
602  robot_action.action_type = APPROACH;
603  robot_action.req_vel = safe_vel;
604  return true;
605  }
606  }
607 
608  return false;
609 }
610 
611 void CollisionMonitor::notifyActionState(
612  const Action & robot_action, const std::shared_ptr<Polygon> action_polygon) const
613 {
614  if (robot_action.action_type == STOP) {
615  if (robot_action.polygon_name == "invalid source") {
616  RCLCPP_WARN(
617  get_logger(),
618  "Robot to stop due to invalid source."
619  " Either due to data not published yet, or to lack of new data received within the"
620  " sensor timeout, or if impossible to transform data to base frame");
621  } else {
622  RCLCPP_INFO(
623  get_logger(),
624  "Robot to stop due to %s polygon",
625  action_polygon->getName().c_str());
626  }
627  } else if (robot_action.action_type == SLOWDOWN) {
628  RCLCPP_INFO(
629  get_logger(),
630  "Robot to slowdown for %f percents due to %s polygon",
631  action_polygon->getSlowdownRatio() * 100,
632  action_polygon->getName().c_str());
633  } else if (robot_action.action_type == LIMIT) {
634  RCLCPP_INFO(
635  get_logger(),
636  "Robot to limit speed due to %s polygon",
637  action_polygon->getName().c_str());
638  } else if (robot_action.action_type == APPROACH) {
639  RCLCPP_INFO(
640  get_logger(),
641  "Robot to approach for %f seconds away from collision",
642  action_polygon->getTimeBeforeCollision());
643  } else { // robot_action.action_type == DO_NOTHING
644  RCLCPP_INFO(
645  get_logger(),
646  "Robot to continue normal operation");
647  }
648 
649  if (state_pub_) {
650  std::unique_ptr<nav2_msgs::msg::CollisionMonitorState> state_msg =
651  std::make_unique<nav2_msgs::msg::CollisionMonitorState>();
652  state_msg->polygon_name = robot_action.polygon_name;
653  state_msg->action_type = robot_action.action_type;
654 
655  state_pub_->publish(std::move(state_msg));
656  }
657 }
658 
659 void CollisionMonitor::publishPolygons() const
660 {
661  for (std::shared_ptr<Polygon> polygon : polygons_) {
662  if (polygon->getEnabled() || !enabled_) {
663  polygon->publish();
664  }
665  }
666 }
667 
668 void CollisionMonitor::toggleCMServiceCallback(
669  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
670  const std::shared_ptr<nav2_msgs::srv::Toggle::Request> request,
671  std::shared_ptr<nav2_msgs::srv::Toggle::Response> response)
672 {
673  enabled_ = request->enable;
674 
675  std::stringstream message;
676  message << "Collision monitor toggled " << (enabled_ ? "on" : "off") << " successfully";
677 
678  response->success = true;
679  response->message = message.str();
680 }
681 
682 } // namespace nav2_collision_monitor
683 
684 #include "rclcpp_components/register_node_macro.hpp"
685 
686 // Register the component with class_loader.
687 // This acts as a sort of entry point, allowing the component to be discoverable when its library
688 // is being loaded into a running process.
689 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_collision_monitor::CollisionMonitor)
Action for robot.
Definition: types.hpp:76
Velocity for 2D model of motion.
Definition: types.hpp:25