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