Nav2 Navigation Stack - humble  humble
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.h"
22 
23 #include "nav2_util/node_utils.hpp"
24 
25 #include "nav2_collision_monitor/kinematics.hpp"
26 
27 namespace nav2_collision_monitor
28 {
29 
30 CollisionMonitor::CollisionMonitor(const rclcpp::NodeOptions & options)
31 : nav2_util::LifecycleNode("collision_monitor", "", options),
32  process_active_(false), robot_action_prev_{DO_NOTHING, {-1.0, -1.0, -1.0}},
33  stop_stamp_{0, 0, get_clock()->get_clock_type()}, stop_pub_timeout_(1.0, 0.0)
34 {
35 }
36 
37 CollisionMonitor::~CollisionMonitor()
38 {
39  polygons_.clear();
40  sources_.clear();
41 }
42 
43 nav2_util::CallbackReturn
44 CollisionMonitor::on_configure(const rclcpp_lifecycle::State & /*state*/)
45 {
46  RCLCPP_INFO(get_logger(), "Configuring");
47 
48  // Transform buffer and listener initialization
49  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
50  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
51  this->get_node_base_interface(),
52  this->get_node_timers_interface());
53  tf_buffer_->setCreateTimerInterface(timer_interface);
54  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
55 
56  std::string cmd_vel_in_topic;
57  std::string cmd_vel_out_topic;
58 
59  // Obtaining ROS parameters
60  if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic)) {
61  return nav2_util::CallbackReturn::FAILURE;
62  }
63 
64  cmd_vel_in_sub_ = this->create_subscription<geometry_msgs::msg::Twist>(
65  cmd_vel_in_topic, 1,
66  std::bind(&CollisionMonitor::cmdVelInCallback, this, std::placeholders::_1));
67  cmd_vel_out_pub_ = this->create_publisher<geometry_msgs::msg::Twist>(
68  cmd_vel_out_topic, 1);
69 
70  return nav2_util::CallbackReturn::SUCCESS;
71 }
72 
73 nav2_util::CallbackReturn
74 CollisionMonitor::on_activate(const rclcpp_lifecycle::State & /*state*/)
75 {
76  RCLCPP_INFO(get_logger(), "Activating");
77 
78  // Activating lifecycle publisher
79  cmd_vel_out_pub_->on_activate();
80 
81  // Activating polygons
82  for (std::shared_ptr<Polygon> polygon : polygons_) {
83  polygon->activate();
84  }
85 
86  // Since polygons are being published when cmd_vel_in appears,
87  // we need to publish polygons first time to display them at startup
88  publishPolygons();
89 
90  // Activating main worker
91  process_active_ = true;
92 
93  // Creating bond connection
94  createBond();
95 
96  return nav2_util::CallbackReturn::SUCCESS;
97 }
98 
99 nav2_util::CallbackReturn
100 CollisionMonitor::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
101 {
102  RCLCPP_INFO(get_logger(), "Deactivating");
103 
104  // Deactivating main worker
105  process_active_ = false;
106 
107  // Reset action type to default after worker deactivating
108  robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0}};
109 
110  // Deactivating polygons
111  for (std::shared_ptr<Polygon> polygon : polygons_) {
112  polygon->deactivate();
113  }
114 
115  // Deactivating lifecycle publishers
116  cmd_vel_out_pub_->on_deactivate();
117 
118  // Destroying bond connection
119  destroyBond();
120 
121  return nav2_util::CallbackReturn::SUCCESS;
122 }
123 
124 nav2_util::CallbackReturn
125 CollisionMonitor::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
126 {
127  RCLCPP_INFO(get_logger(), "Cleaning up");
128 
129  cmd_vel_in_sub_.reset();
130  cmd_vel_out_pub_.reset();
131 
132  polygons_.clear();
133  sources_.clear();
134 
135  tf_listener_.reset();
136  tf_buffer_.reset();
137 
138  return nav2_util::CallbackReturn::SUCCESS;
139 }
140 
141 nav2_util::CallbackReturn
142 CollisionMonitor::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
143 {
144  RCLCPP_INFO(get_logger(), "Shutting down");
145 
146  return nav2_util::CallbackReturn::SUCCESS;
147 }
148 
149 void CollisionMonitor::cmdVelInCallback(geometry_msgs::msg::Twist::ConstSharedPtr msg)
150 {
151  // If message contains NaN or Inf, ignore
152  if (!nav2_util::validateTwist(*msg)) {
153  RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
154  return;
155  }
156 
157  process({msg->linear.x, msg->linear.y, msg->angular.z});
158 }
159 
160 void CollisionMonitor::publishVelocity(const Action & robot_action)
161 {
162  if (robot_action.req_vel.isZero()) {
163  if (!robot_action_prev_.req_vel.isZero()) {
164  // Robot just stopped: saving stop timestamp and continue
165  stop_stamp_ = this->now();
166  } else if (this->now() - stop_stamp_ > stop_pub_timeout_) {
167  // More than stop_pub_timeout_ passed after robot has been stopped.
168  // Cease publishing output cmd_vel.
169  return;
170  }
171  }
172 
173  std::unique_ptr<geometry_msgs::msg::Twist> cmd_vel_out_msg =
174  std::make_unique<geometry_msgs::msg::Twist>();
175  cmd_vel_out_msg->linear.x = robot_action.req_vel.x;
176  cmd_vel_out_msg->linear.y = robot_action.req_vel.y;
177  cmd_vel_out_msg->angular.z = robot_action.req_vel.tw;
178  // linear.z, angular.x and angular.y will remain 0.0
179 
180  cmd_vel_out_pub_->publish(std::move(cmd_vel_out_msg));
181 }
182 
183 bool CollisionMonitor::getParameters(
184  std::string & cmd_vel_in_topic,
185  std::string & cmd_vel_out_topic)
186 {
187  std::string base_frame_id, odom_frame_id;
188  tf2::Duration transform_tolerance;
189  rclcpp::Duration source_timeout(2.0, 0.0);
190 
191  auto node = shared_from_this();
192 
193  nav2_util::declare_parameter_if_not_declared(
194  node, "cmd_vel_in_topic", rclcpp::ParameterValue("cmd_vel_raw"));
195  cmd_vel_in_topic = get_parameter("cmd_vel_in_topic").as_string();
196  nav2_util::declare_parameter_if_not_declared(
197  node, "cmd_vel_out_topic", rclcpp::ParameterValue("cmd_vel"));
198  cmd_vel_out_topic = get_parameter("cmd_vel_out_topic").as_string();
199 
200  nav2_util::declare_parameter_if_not_declared(
201  node, "base_frame_id", rclcpp::ParameterValue("base_footprint"));
202  base_frame_id = get_parameter("base_frame_id").as_string();
203  nav2_util::declare_parameter_if_not_declared(
204  node, "odom_frame_id", rclcpp::ParameterValue("odom"));
205  odom_frame_id = get_parameter("odom_frame_id").as_string();
206  nav2_util::declare_parameter_if_not_declared(
207  node, "transform_tolerance", rclcpp::ParameterValue(0.1));
208  transform_tolerance =
209  tf2::durationFromSec(get_parameter("transform_tolerance").as_double());
210  nav2_util::declare_parameter_if_not_declared(
211  node, "source_timeout", rclcpp::ParameterValue(2.0));
212  source_timeout =
213  rclcpp::Duration::from_seconds(get_parameter("source_timeout").as_double());
214  nav2_util::declare_parameter_if_not_declared(
215  node, "base_shift_correction", rclcpp::ParameterValue(true));
216  const bool base_shift_correction =
217  get_parameter("base_shift_correction").as_bool();
218 
219  nav2_util::declare_parameter_if_not_declared(
220  node, "stop_pub_timeout", rclcpp::ParameterValue(1.0));
221  stop_pub_timeout_ =
222  rclcpp::Duration::from_seconds(get_parameter("stop_pub_timeout").as_double());
223 
224  if (!configurePolygons(base_frame_id, transform_tolerance)) {
225  return false;
226  }
227 
228  if (
229  !configureSources(
230  base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
231  {
232  return false;
233  }
234 
235  return true;
236 }
237 
238 bool CollisionMonitor::configurePolygons(
239  const std::string & base_frame_id,
240  const tf2::Duration & transform_tolerance)
241 {
242  try {
243  auto node = shared_from_this();
244 
245  nav2_util::declare_parameter_if_not_declared(
246  node, "polygons", rclcpp::ParameterValue(std::vector<std::string>()));
247  std::vector<std::string> polygon_names = get_parameter("polygons").as_string_array();
248  for (std::string polygon_name : polygon_names) {
249  // Leave it not initialized: the will cause an error if it will not set
250  nav2_util::declare_parameter_if_not_declared(
251  node, polygon_name + ".type", rclcpp::PARAMETER_STRING);
252  const std::string polygon_type = get_parameter(polygon_name + ".type").as_string();
253 
254  if (polygon_type == "polygon") {
255  polygons_.push_back(
256  std::make_shared<Polygon>(
257  node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
258  } else if (polygon_type == "circle") {
259  polygons_.push_back(
260  std::make_shared<Circle>(
261  node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
262  } else { // Error if something else
263  RCLCPP_ERROR(
264  get_logger(),
265  "[%s]: Unknown polygon type: %s",
266  polygon_name.c_str(), polygon_type.c_str());
267  return false;
268  }
269 
270  // Configure last added polygon
271  if (!polygons_.back()->configure()) {
272  return false;
273  }
274  }
275  } catch (const std::exception & ex) {
276  RCLCPP_ERROR(get_logger(), "Error while getting parameters: %s", ex.what());
277  return false;
278  }
279 
280  return true;
281 }
282 
283 bool CollisionMonitor::configureSources(
284  const std::string & base_frame_id,
285  const std::string & odom_frame_id,
286  const tf2::Duration & transform_tolerance,
287  const rclcpp::Duration & source_timeout,
288  const bool base_shift_correction)
289 {
290  try {
291  auto node = shared_from_this();
292 
293  // Leave it to be not initialized: to intentionally cause an error if it will not set
294  nav2_util::declare_parameter_if_not_declared(
295  node, "observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
296  std::vector<std::string> source_names = get_parameter("observation_sources").as_string_array();
297  for (std::string source_name : source_names) {
298  nav2_util::declare_parameter_if_not_declared(
299  node, source_name + ".type",
300  rclcpp::ParameterValue("scan")); // Laser scanner by default
301  const std::string source_type = get_parameter(source_name + ".type").as_string();
302 
303  if (source_type == "scan") {
304  std::shared_ptr<Scan> s = std::make_shared<Scan>(
305  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
306  transform_tolerance, source_timeout, base_shift_correction);
307 
308  s->configure();
309 
310  sources_.push_back(s);
311  } else if (source_type == "pointcloud") {
312  std::shared_ptr<PointCloud> p = std::make_shared<PointCloud>(
313  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
314  transform_tolerance, source_timeout, base_shift_correction);
315 
316  p->configure();
317 
318  sources_.push_back(p);
319  } else if (source_type == "range") {
320  std::shared_ptr<Range> r = std::make_shared<Range>(
321  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
322  transform_tolerance, source_timeout, base_shift_correction);
323 
324  r->configure();
325 
326  sources_.push_back(r);
327  } else { // Error if something else
328  RCLCPP_ERROR(
329  get_logger(),
330  "[%s]: Unknown source type: %s",
331  source_name.c_str(), source_type.c_str());
332  return false;
333  }
334  }
335  } catch (const std::exception & ex) {
336  RCLCPP_ERROR(get_logger(), "Error while getting parameters: %s", ex.what());
337  return false;
338  }
339 
340  return true;
341 }
342 
343 void CollisionMonitor::process(const Velocity & cmd_vel_in)
344 {
345  // Current timestamp for all inner routines prolongation
346  rclcpp::Time curr_time = this->now();
347 
348  // Do nothing if main worker in non-active state
349  if (!process_active_) {
350  return;
351  }
352 
353  // Points array collected from different data sources in a robot base frame
354  std::vector<Point> collision_points;
355 
356  // Fill collision_points array from different data sources
357  for (std::shared_ptr<Source> source : sources_) {
358  if (source->getEnabled()) {
359  source->getData(curr_time, collision_points);
360  }
361  }
362 
363  // By default - there is no action
364  Action robot_action{DO_NOTHING, cmd_vel_in};
365  // Polygon causing robot action (if any)
366  std::shared_ptr<Polygon> action_polygon;
367 
368  for (std::shared_ptr<Polygon> polygon : polygons_) {
369  if (!polygon->getEnabled()) {
370  continue;
371  }
372  if (robot_action.action_type == STOP) {
373  // If robot already should stop, do nothing
374  break;
375  }
376 
377  const ActionType at = polygon->getActionType();
378  if (at == STOP || at == SLOWDOWN) {
379  // Process STOP/SLOWDOWN for the selected polygon
380  if (processStopSlowdown(polygon, collision_points, cmd_vel_in, robot_action)) {
381  action_polygon = polygon;
382  }
383  } else if (at == APPROACH) {
384  // Process APPROACH for the selected polygon
385  if (processApproach(polygon, collision_points, cmd_vel_in, robot_action)) {
386  action_polygon = polygon;
387  }
388  }
389  }
390 
391  if (robot_action.action_type != robot_action_prev_.action_type) {
392  // Report changed robot behavior
393  printAction(robot_action, action_polygon);
394  }
395 
396  // Publish required robot velocity
397  publishVelocity(robot_action);
398 
399  // Publish polygons for better visualization
400  publishPolygons();
401 
402  robot_action_prev_ = robot_action;
403 }
404 
405 bool CollisionMonitor::processStopSlowdown(
406  const std::shared_ptr<Polygon> polygon,
407  const std::vector<Point> & collision_points,
408  const Velocity & velocity,
409  Action & robot_action) const
410 {
411  if (polygon->getPointsInside(collision_points) > polygon->getMaxPoints()) {
412  if (polygon->getActionType() == STOP) {
413  // Setting up zero velocity for STOP model
414  robot_action.action_type = STOP;
415  robot_action.req_vel.x = 0.0;
416  robot_action.req_vel.y = 0.0;
417  robot_action.req_vel.tw = 0.0;
418  return true;
419  } else { // SLOWDOWN
420  const Velocity safe_vel = velocity * polygon->getSlowdownRatio();
421  // Check that currently calculated velocity is safer than
422  // chosen for previous shapes one
423  if (safe_vel < robot_action.req_vel) {
424  robot_action.action_type = SLOWDOWN;
425  robot_action.req_vel = safe_vel;
426  return true;
427  }
428  }
429  }
430 
431  return false;
432 }
433 
434 bool CollisionMonitor::processApproach(
435  const std::shared_ptr<Polygon> polygon,
436  const std::vector<Point> & collision_points,
437  const Velocity & velocity,
438  Action & robot_action) const
439 {
440  polygon->updatePolygon();
441 
442  // Obtain time before a collision
443  const double collision_time = polygon->getCollisionTime(collision_points, velocity);
444  if (collision_time >= 0.0) {
445  // If collision will occurr, reduce robot speed
446  const double change_ratio = collision_time / polygon->getTimeBeforeCollision();
447  const Velocity safe_vel = velocity * change_ratio;
448  // Check that currently calculated velocity is safer than
449  // chosen for previous shapes one
450  if (safe_vel < robot_action.req_vel) {
451  robot_action.action_type = APPROACH;
452  robot_action.req_vel = safe_vel;
453  return true;
454  }
455  }
456 
457  return false;
458 }
459 
460 void CollisionMonitor::printAction(
461  const Action & robot_action, const std::shared_ptr<Polygon> action_polygon) const
462 {
463  if (robot_action.action_type == STOP) {
464  RCLCPP_INFO(
465  get_logger(),
466  "Robot to stop due to %s polygon",
467  action_polygon->getName().c_str());
468  } else if (robot_action.action_type == SLOWDOWN) {
469  RCLCPP_INFO(
470  get_logger(),
471  "Robot to slowdown for %f percents due to %s polygon",
472  action_polygon->getSlowdownRatio() * 100,
473  action_polygon->getName().c_str());
474  } else if (robot_action.action_type == APPROACH) {
475  RCLCPP_INFO(
476  get_logger(),
477  "Robot to approach for %f seconds away from collision",
478  action_polygon->getTimeBeforeCollision());
479  } else { // robot_action.action_type == DO_NOTHING
480  RCLCPP_INFO(
481  get_logger(),
482  "Robot to continue normal operation");
483  }
484 }
485 
486 void CollisionMonitor::publishPolygons() const
487 {
488  for (std::shared_ptr<Polygon> polygon : polygons_) {
489  if (polygon->getEnabled()) {
490  polygon->publish();
491  }
492  }
493 }
494 
495 } // namespace nav2_collision_monitor
496 
497 #include "rclcpp_components/register_node_macro.hpp"
498 
499 // Register the component with class_loader.
500 // This acts as a sort of entry point, allowing the component to be discoverable when its library
501 // is being loaded into a running process.
502 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_collision_monitor::CollisionMonitor)
CollisionMonitor(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_collision_safery::CollisionMonitor.
Action for robot.
Definition: types.hpp:73
Velocity for 2D model of motion.
Definition: types.hpp:23