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