15 #include "nav2_collision_monitor/collision_monitor_node.hpp"
21 #include "tf2_ros/create_timer_ros.h"
23 #include "nav2_util/node_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
26 #include "nav2_collision_monitor/kinematics.hpp"
28 namespace nav2_collision_monitor
32 : nav2_util::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)
38 CollisionMonitor::~CollisionMonitor()
44 nav2_util::CallbackReturn
45 CollisionMonitor::on_configure(
const rclcpp_lifecycle::State & state)
47 RCLCPP_INFO(get_logger(),
"Configuring");
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_);
57 std::string cmd_vel_in_topic;
58 std::string cmd_vel_out_topic;
59 std::string state_topic;
62 if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic, state_topic)) {
64 return nav2_util::CallbackReturn::FAILURE;
67 cmd_vel_in_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
71 std::bind(&CollisionMonitor::cmdVelInCallbackUnstamped,
this, std::placeholders::_1),
72 std::bind(&CollisionMonitor::cmdVelInCallbackStamped,
this, std::placeholders::_1));
74 auto node = shared_from_this();
75 cmd_vel_out_pub_ = std::make_unique<nav2_util::TwistPublisher>(node, cmd_vel_out_topic, 1);
77 if (!state_topic.empty()) {
78 state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionMonitorState>(
82 collision_points_marker_pub_ = this->create_publisher<visualization_msgs::msg::MarkerArray>(
83 "~/collision_points_marker", 1);
85 nav2_util::declare_parameter_if_not_declared(
86 node,
"use_realtime_priority", rclcpp::ParameterValue(
false));
87 bool use_realtime_priority =
false;
88 node->get_parameter(
"use_realtime_priority", use_realtime_priority);
89 if (use_realtime_priority) {
91 nav2_util::setSoftRealTimePriority();
92 }
catch (
const std::runtime_error & e) {
93 RCLCPP_ERROR(get_logger(),
"%s", e.what());
95 return nav2_util::CallbackReturn::FAILURE;
99 return nav2_util::CallbackReturn::SUCCESS;
102 nav2_util::CallbackReturn
103 CollisionMonitor::on_activate(
const rclcpp_lifecycle::State & )
105 RCLCPP_INFO(get_logger(),
"Activating");
108 cmd_vel_out_pub_->on_activate();
110 state_pub_->on_activate();
112 collision_points_marker_pub_->on_activate();
115 for (std::shared_ptr<Polygon> polygon : polygons_) {
124 process_active_ =
true;
129 return nav2_util::CallbackReturn::SUCCESS;
132 nav2_util::CallbackReturn
133 CollisionMonitor::on_deactivate(
const rclcpp_lifecycle::State & )
135 RCLCPP_INFO(get_logger(),
"Deactivating");
138 process_active_ =
false;
141 robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0},
""};
144 for (std::shared_ptr<Polygon> polygon : polygons_) {
145 polygon->deactivate();
149 cmd_vel_out_pub_->on_deactivate();
151 state_pub_->on_deactivate();
153 collision_points_marker_pub_->on_deactivate();
158 return nav2_util::CallbackReturn::SUCCESS;
161 nav2_util::CallbackReturn
162 CollisionMonitor::on_cleanup(
const rclcpp_lifecycle::State & )
164 RCLCPP_INFO(get_logger(),
"Cleaning up");
166 cmd_vel_in_sub_.reset();
167 cmd_vel_out_pub_.reset();
169 collision_points_marker_pub_.reset();
174 tf_listener_.reset();
177 return nav2_util::CallbackReturn::SUCCESS;
180 nav2_util::CallbackReturn
181 CollisionMonitor::on_shutdown(
const rclcpp_lifecycle::State & )
183 RCLCPP_INFO(get_logger(),
"Shutting down");
185 return nav2_util::CallbackReturn::SUCCESS;
188 void CollisionMonitor::cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg)
191 if (!nav2_util::validateTwist(msg->twist)) {
192 RCLCPP_ERROR(get_logger(),
"Velocity message contains NaNs or Infs! Ignoring as invalid!");
196 process({msg->twist.linear.x, msg->twist.linear.y, msg->twist.angular.z}, msg->header);
199 void CollisionMonitor::cmdVelInCallbackUnstamped(geometry_msgs::msg::Twist::SharedPtr msg)
201 auto twist_stamped = std::make_shared<geometry_msgs::msg::TwistStamped>();
202 twist_stamped->twist = *msg;
203 cmdVelInCallbackStamped(twist_stamped);
206 void CollisionMonitor::publishVelocity(
207 const Action & robot_action,
const std_msgs::msg::Header & header)
209 if (robot_action.req_vel.isZero()) {
210 if (!robot_action_prev_.req_vel.isZero()) {
212 stop_stamp_ = this->now();
213 }
else if (this->now() - stop_stamp_ > stop_pub_timeout_) {
220 auto cmd_vel_out_msg = std::make_unique<geometry_msgs::msg::TwistStamped>();
221 cmd_vel_out_msg->header = header;
222 cmd_vel_out_msg->twist.linear.x = robot_action.req_vel.x;
223 cmd_vel_out_msg->twist.linear.y = robot_action.req_vel.y;
224 cmd_vel_out_msg->twist.angular.z = robot_action.req_vel.tw;
227 cmd_vel_out_pub_->publish(std::move(cmd_vel_out_msg));
230 bool CollisionMonitor::getParameters(
231 std::string & cmd_vel_in_topic,
232 std::string & cmd_vel_out_topic,
233 std::string & state_topic)
235 std::string base_frame_id, odom_frame_id;
236 tf2::Duration transform_tolerance;
237 rclcpp::Duration source_timeout(2.0, 0.0);
239 auto node = shared_from_this();
241 nav2_util::declare_parameter_if_not_declared(
242 node,
"cmd_vel_in_topic", rclcpp::ParameterValue(
"cmd_vel_smoothed"));
243 cmd_vel_in_topic = get_parameter(
"cmd_vel_in_topic").as_string();
244 nav2_util::declare_parameter_if_not_declared(
245 node,
"cmd_vel_out_topic", rclcpp::ParameterValue(
"cmd_vel"));
246 cmd_vel_out_topic = get_parameter(
"cmd_vel_out_topic").as_string();
247 nav2_util::declare_parameter_if_not_declared(
248 node,
"state_topic", rclcpp::ParameterValue(
""));
249 state_topic = get_parameter(
"state_topic").as_string();
251 nav2_util::declare_parameter_if_not_declared(
252 node,
"base_frame_id", rclcpp::ParameterValue(
"base_footprint"));
253 base_frame_id = get_parameter(
"base_frame_id").as_string();
254 nav2_util::declare_parameter_if_not_declared(
255 node,
"odom_frame_id", rclcpp::ParameterValue(
"odom"));
256 odom_frame_id = get_parameter(
"odom_frame_id").as_string();
257 nav2_util::declare_parameter_if_not_declared(
258 node,
"transform_tolerance", rclcpp::ParameterValue(0.1));
259 transform_tolerance =
260 tf2::durationFromSec(get_parameter(
"transform_tolerance").as_double());
261 nav2_util::declare_parameter_if_not_declared(
262 node,
"source_timeout", rclcpp::ParameterValue(2.0));
264 rclcpp::Duration::from_seconds(get_parameter(
"source_timeout").as_double());
265 nav2_util::declare_parameter_if_not_declared(
266 node,
"base_shift_correction", rclcpp::ParameterValue(
true));
267 const bool base_shift_correction =
268 get_parameter(
"base_shift_correction").as_bool();
270 nav2_util::declare_parameter_if_not_declared(
271 node,
"stop_pub_timeout", rclcpp::ParameterValue(1.0));
273 rclcpp::Duration::from_seconds(get_parameter(
"stop_pub_timeout").as_double());
277 base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
282 if (!configurePolygons(base_frame_id, transform_tolerance)) {
289 bool CollisionMonitor::configurePolygons(
290 const std::string & base_frame_id,
291 const tf2::Duration & transform_tolerance)
294 auto node = shared_from_this();
297 nav2_util::declare_parameter_if_not_declared(
298 node,
"polygons", rclcpp::PARAMETER_STRING_ARRAY);
299 std::vector<std::string> polygon_names = get_parameter(
"polygons").as_string_array();
300 for (std::string polygon_name : polygon_names) {
302 nav2_util::declare_parameter_if_not_declared(
303 node, polygon_name +
".type", rclcpp::PARAMETER_STRING);
304 const std::string polygon_type = get_parameter(polygon_name +
".type").as_string();
306 if (polygon_type ==
"polygon") {
308 std::make_shared<Polygon>(
309 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
310 }
else if (polygon_type ==
"circle") {
312 std::make_shared<Circle>(
313 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
314 }
else if (polygon_type ==
"velocity_polygon") {
316 std::make_shared<VelocityPolygon>(
317 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
321 "[%s]: Unknown polygon type: %s",
322 polygon_name.c_str(), polygon_type.c_str());
327 if (!polygons_.back()->configure()) {
331 }
catch (
const std::exception & ex) {
332 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
339 bool CollisionMonitor::configureSources(
340 const std::string & base_frame_id,
341 const std::string & odom_frame_id,
342 const tf2::Duration & transform_tolerance,
343 const rclcpp::Duration & source_timeout,
344 const bool base_shift_correction)
347 auto node = shared_from_this();
350 nav2_util::declare_parameter_if_not_declared(
351 node,
"observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
352 std::vector<std::string> source_names = get_parameter(
"observation_sources").as_string_array();
353 for (std::string source_name : source_names) {
354 nav2_util::declare_parameter_if_not_declared(
355 node, source_name +
".type",
356 rclcpp::ParameterValue(
"scan"));
357 const std::string source_type = get_parameter(source_name +
".type").as_string();
359 if (source_type ==
"scan") {
360 std::shared_ptr<Scan> s = std::make_shared<Scan>(
361 node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
362 transform_tolerance, source_timeout, base_shift_correction);
366 sources_.push_back(s);
367 }
else if (source_type ==
"pointcloud") {
368 std::shared_ptr<PointCloud> p = std::make_shared<PointCloud>(
369 node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
370 transform_tolerance, source_timeout, base_shift_correction);
374 sources_.push_back(p);
375 }
else if (source_type ==
"range") {
376 std::shared_ptr<Range> r = std::make_shared<Range>(
377 node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
378 transform_tolerance, source_timeout, base_shift_correction);
382 sources_.push_back(r);
383 }
else if (source_type ==
"polygon") {
384 std::shared_ptr<PolygonSource> ps = std::make_shared<PolygonSource>(
385 node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
386 transform_tolerance, source_timeout, base_shift_correction);
389 sources_.push_back(ps);
393 "[%s]: Unknown source type: %s",
394 source_name.c_str(), source_type.c_str());
398 }
catch (
const std::exception & ex) {
399 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
406 void CollisionMonitor::process(
const Velocity & cmd_vel_in,
const std_msgs::msg::Header & header)
409 rclcpp::Time curr_time = this->now();
412 if (!process_active_) {
417 std::unordered_map<std::string, std::vector<Point>> sources_collision_points_map;
420 Action robot_action{DO_NOTHING, cmd_vel_in,
""};
422 std::shared_ptr<Polygon> action_polygon;
425 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
426 for (std::shared_ptr<Source> source : sources_) {
427 auto iter = sources_collision_points_map.insert(
428 {source->getSourceName(), std::vector<Point>()});
430 if (source->getEnabled()) {
431 if (!source->getData(curr_time, iter.first->second) &&
432 source->getSourceTimeout().seconds() != 0.0)
434 action_polygon =
nullptr;
435 robot_action.polygon_name =
"invalid source";
436 robot_action.action_type = STOP;
437 robot_action.req_vel.x = 0.0;
438 robot_action.req_vel.y = 0.0;
439 robot_action.req_vel.tw = 0.0;
444 if (collision_points_marker_pub_->get_subscription_count() > 0) {
446 visualization_msgs::msg::Marker marker;
447 marker.header.frame_id = get_parameter(
"base_frame_id").as_string();
448 marker.header.stamp = rclcpp::Time(0, 0);
449 marker.ns =
"collision_points_" + source->getSourceName();
451 marker.type = visualization_msgs::msg::Marker::POINTS;
452 marker.action = visualization_msgs::msg::Marker::ADD;
453 marker.scale.x = 0.02;
454 marker.scale.y = 0.02;
455 marker.color.r = 1.0;
456 marker.color.a = 1.0;
457 marker.lifetime = rclcpp::Duration(0, 0);
458 marker.frame_locked =
true;
460 for (
const auto & point : iter.first->second) {
461 geometry_msgs::msg::Point p;
465 marker.points.push_back(p);
467 marker_array->markers.push_back(marker);
471 if (collision_points_marker_pub_->get_subscription_count() > 0) {
472 collision_points_marker_pub_->publish(std::move(marker_array));
475 for (std::shared_ptr<Polygon> polygon : polygons_) {
476 if (!polygon->getEnabled()) {
479 if (robot_action.action_type == STOP) {
485 polygon->updatePolygon(cmd_vel_in);
487 const ActionType at = polygon->getActionType();
488 if (at == STOP || at == SLOWDOWN || at == LIMIT) {
490 if (processStopSlowdownLimit(
491 polygon, sources_collision_points_map, cmd_vel_in, robot_action))
493 action_polygon = polygon;
495 }
else if (at == APPROACH) {
497 if (processApproach(polygon, sources_collision_points_map, cmd_vel_in, robot_action)) {
498 action_polygon = polygon;
503 if (robot_action.polygon_name != robot_action_prev_.polygon_name) {
505 notifyActionState(robot_action, action_polygon);
509 publishVelocity(robot_action, header);
514 robot_action_prev_ = robot_action;
517 bool CollisionMonitor::processStopSlowdownLimit(
518 const std::shared_ptr<Polygon> polygon,
519 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
521 Action & robot_action)
const
523 if (!polygon->isShapeSet()) {
527 if (polygon->getPointsInside(sources_collision_points_map) >= polygon->getMinPoints()) {
528 if (polygon->getActionType() == STOP) {
530 robot_action.polygon_name = polygon->getName();
531 robot_action.action_type = STOP;
532 robot_action.req_vel.x = 0.0;
533 robot_action.req_vel.y = 0.0;
534 robot_action.req_vel.tw = 0.0;
536 }
else if (polygon->getActionType() == SLOWDOWN) {
537 const Velocity safe_vel = velocity * polygon->getSlowdownRatio();
540 if (safe_vel < robot_action.req_vel) {
541 robot_action.polygon_name = polygon->getName();
542 robot_action.action_type = SLOWDOWN;
543 robot_action.req_vel = safe_vel;
548 const double linear_vel = std::hypot(velocity.x, velocity.y);
553 if (linear_vel != 0.0) {
554 ratio = std::min(ratio, polygon->getLinearLimit() / linear_vel);
556 if (velocity.tw != 0.0) {
557 ratio = std::min(ratio, polygon->getAngularLimit() / std::abs(velocity.tw));
559 ratio = std::clamp(ratio, 0.0, 1.0);
561 safe_vel = velocity * ratio;
564 if (safe_vel < robot_action.req_vel) {
565 robot_action.polygon_name = polygon->getName();
566 robot_action.action_type = LIMIT;
567 robot_action.req_vel = safe_vel;
576 bool CollisionMonitor::processApproach(
577 const std::shared_ptr<Polygon> polygon,
578 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
580 Action & robot_action)
const
582 if (!polygon->isShapeSet()) {
587 const double collision_time = polygon->getCollisionTime(sources_collision_points_map, velocity);
588 if (collision_time >= 0.0) {
590 const double change_ratio = collision_time / polygon->getTimeBeforeCollision();
591 const Velocity safe_vel = velocity * change_ratio;
594 if (safe_vel < robot_action.req_vel) {
595 robot_action.polygon_name = polygon->getName();
596 robot_action.action_type = APPROACH;
597 robot_action.req_vel = safe_vel;
605 void CollisionMonitor::notifyActionState(
606 const Action & robot_action,
const std::shared_ptr<Polygon> action_polygon)
const
608 if (robot_action.action_type == STOP) {
609 if (robot_action.polygon_name ==
"invalid source") {
612 "Robot to stop due to invalid source."
613 " Either due to data not published yet, or to lack of new data received within the"
614 " sensor timeout, or if impossible to transform data to base frame");
618 "Robot to stop due to %s polygon",
619 action_polygon->getName().c_str());
621 }
else if (robot_action.action_type == SLOWDOWN) {
624 "Robot to slowdown for %f percents due to %s polygon",
625 action_polygon->getSlowdownRatio() * 100,
626 action_polygon->getName().c_str());
627 }
else if (robot_action.action_type == LIMIT) {
630 "Robot to limit speed due to %s polygon",
631 action_polygon->getName().c_str());
632 }
else if (robot_action.action_type == APPROACH) {
635 "Robot to approach for %f seconds away from collision",
636 action_polygon->getTimeBeforeCollision());
640 "Robot to continue normal operation");
644 std::unique_ptr<nav2_msgs::msg::CollisionMonitorState> state_msg =
645 std::make_unique<nav2_msgs::msg::CollisionMonitorState>();
646 state_msg->polygon_name = robot_action.polygon_name;
647 state_msg->action_type = robot_action.action_type;
649 state_pub_->publish(std::move(state_msg));
653 void CollisionMonitor::publishPolygons()
const
655 for (std::shared_ptr<Polygon> polygon : polygons_) {
656 if (polygon->getEnabled()) {
664 #include "rclcpp_components/register_node_macro.hpp"
Collision Monitor ROS2 node.
CollisionMonitor(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_collision_monitor::CollisionMonitor.
Velocity for 2D model of motion.