15 #include "nav2_collision_monitor/collision_monitor_node.hpp"
21 #include "tf2_ros/create_timer_ros.hpp"
23 #include "nav2_ros_common/node_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
26 #include "nav2_collision_monitor/kinematics.hpp"
28 using namespace std::placeholders;
30 namespace nav2_collision_monitor
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)
40 CollisionMonitor::~CollisionMonitor()
47 CollisionMonitor::on_configure(
const rclcpp_lifecycle::State & state)
49 RCLCPP_INFO(get_logger(),
"Configuring");
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);
59 std::string cmd_vel_in_topic;
60 std::string cmd_vel_out_topic;
61 std::string state_topic;
64 if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic, state_topic)) {
66 return nav2::CallbackReturn::FAILURE;
69 cmd_vel_in_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
72 std::bind(&CollisionMonitor::cmdVelInCallbackUnstamped,
this, std::placeholders::_1),
73 std::bind(&CollisionMonitor::cmdVelInCallbackStamped,
this, std::placeholders::_1));
75 auto node = shared_from_this();
76 cmd_vel_out_pub_ = std::make_unique<nav2_util::TwistPublisher>(node, cmd_vel_out_topic);
78 if (!state_topic.empty()) {
79 state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionMonitorState>(
83 collision_points_marker_pub_ = this->create_publisher<visualization_msgs::msg::MarkerArray>(
84 "~/collision_points_marker");
87 toggle_cm_service_ = create_service<nav2_msgs::srv::Toggle>(
89 std::bind(&CollisionMonitor::toggleCMServiceCallback,
this, _1, _2, _3));
91 bool use_realtime_priority = node->declare_or_get_parameter(
"use_realtime_priority",
false);
92 if (use_realtime_priority) {
94 nav2::setSoftRealTimePriority();
95 }
catch (
const std::runtime_error & e) {
96 RCLCPP_ERROR(get_logger(),
"%s", e.what());
98 return nav2::CallbackReturn::FAILURE;
102 enabled_ = node->declare_or_get_parameter(
"enabled",
true);
105 RCLCPP_WARN(get_logger(),
"Collision monitor is disabled at startup.");
107 RCLCPP_INFO(get_logger(),
"Collision monitor is enabled at startup.");
110 return nav2::CallbackReturn::SUCCESS;
114 CollisionMonitor::on_activate(
const rclcpp_lifecycle::State & )
116 RCLCPP_INFO(get_logger(),
"Activating");
119 cmd_vel_out_pub_->on_activate();
121 state_pub_->on_activate();
123 collision_points_marker_pub_->on_activate();
126 for (std::shared_ptr<Polygon> polygon : polygons_) {
135 process_active_ =
true;
140 return nav2::CallbackReturn::SUCCESS;
144 CollisionMonitor::on_deactivate(
const rclcpp_lifecycle::State & )
146 RCLCPP_INFO(get_logger(),
"Deactivating");
149 process_active_ =
false;
152 robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0},
""};
155 for (std::shared_ptr<Polygon> polygon : polygons_) {
156 polygon->deactivate();
160 cmd_vel_out_pub_->on_deactivate();
162 state_pub_->on_deactivate();
164 collision_points_marker_pub_->on_deactivate();
169 return nav2::CallbackReturn::SUCCESS;
173 CollisionMonitor::on_cleanup(
const rclcpp_lifecycle::State & )
175 RCLCPP_INFO(get_logger(),
"Cleaning up");
177 cmd_vel_in_sub_.reset();
178 cmd_vel_out_pub_.reset();
180 collision_points_marker_pub_.reset();
185 tf_listener_.reset();
188 return nav2::CallbackReturn::SUCCESS;
192 CollisionMonitor::on_shutdown(
const rclcpp_lifecycle::State & )
194 RCLCPP_INFO(get_logger(),
"Shutting down");
196 return nav2::CallbackReturn::SUCCESS;
199 void CollisionMonitor::cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg)
202 if (!nav2_util::validateTwist(msg->twist)) {
203 RCLCPP_ERROR(get_logger(),
"Velocity message contains NaNs or Infs! Ignoring as invalid!");
207 process({msg->twist.linear.x, msg->twist.linear.y, msg->twist.angular.z}, msg->header);
210 void CollisionMonitor::cmdVelInCallbackUnstamped(geometry_msgs::msg::Twist::SharedPtr msg)
212 auto twist_stamped = std::make_shared<geometry_msgs::msg::TwistStamped>();
213 twist_stamped->twist = *msg;
214 cmdVelInCallbackStamped(twist_stamped);
217 void CollisionMonitor::publishVelocity(
218 const Action & robot_action,
const std_msgs::msg::Header & header)
220 if (robot_action.req_vel.isZero()) {
221 if (!robot_action_prev_.req_vel.isZero()) {
223 stop_stamp_ = this->now();
224 }
else if (this->now() - stop_stamp_ > stop_pub_timeout_) {
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;
238 cmd_vel_out_pub_->publish(std::move(cmd_vel_out_msg));
241 bool CollisionMonitor::getParameters(
242 std::string & cmd_vel_in_topic,
243 std::string & cmd_vel_out_topic,
244 std::string & state_topic)
246 std::string base_frame_id, odom_frame_id;
247 tf2::Duration transform_tolerance;
248 rclcpp::Duration source_timeout(2.0, 0.0);
250 auto node = shared_from_this();
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(
""));
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);
267 stop_pub_timeout_ = rclcpp::Duration::from_seconds(
268 node->declare_or_get_parameter(
"stop_pub_timeout", 1.0));
272 base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
277 if (!configurePolygons(base_frame_id, transform_tolerance)) {
284 bool CollisionMonitor::configurePolygons(
285 const std::string & base_frame_id,
286 const tf2::Duration & transform_tolerance)
289 auto node = shared_from_this();
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) {
296 const std::string polygon_type =
297 node->declare_or_get_parameter<std::string>(polygon_name +
".type");
299 if (polygon_type ==
"polygon") {
301 std::make_shared<Polygon>(
302 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
303 }
else if (polygon_type ==
"circle") {
305 std::make_shared<Circle>(
306 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
307 }
else if (polygon_type ==
"velocity_polygon") {
309 std::make_shared<VelocityPolygon>(
310 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
314 "[%s]: Unknown polygon type: %s",
315 polygon_name.c_str(), polygon_type.c_str());
320 if (!polygons_.back()->configure()) {
324 }
catch (
const std::exception & ex) {
325 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
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)
340 auto node = shared_from_this();
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"));
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);
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);
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);
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);
379 sources_.push_back(ps);
383 "[%s]: Unknown source type: %s",
384 source_name.c_str(), source_type.c_str());
388 }
catch (
const std::exception & ex) {
389 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
396 void CollisionMonitor::process(
const Velocity & cmd_vel_in,
const std_msgs::msg::Header & header)
399 rclcpp::Time curr_time = this->now();
402 if (!process_active_) {
407 std::unordered_map<std::string, std::vector<Point>> sources_collision_points_map;
410 Action robot_action{DO_NOTHING, cmd_vel_in,
""};
412 std::shared_ptr<Polygon> action_polygon;
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>()});
420 if (source->getEnabled()) {
421 if (!source->getData(curr_time, iter.first->second) &&
422 source->getSourceTimeout().seconds() != 0.0)
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;
434 if (collision_points_marker_pub_->get_subscription_count() > 0) {
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();
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;
450 for (
const auto & point : iter.first->second) {
451 geometry_msgs::msg::Point p;
455 marker.points.push_back(p);
457 marker_array->markers.push_back(marker);
461 if (collision_points_marker_pub_->get_subscription_count() > 0) {
462 collision_points_marker_pub_->publish(std::move(marker_array));
465 for (std::shared_ptr<Polygon> polygon : polygons_) {
466 if (!polygon->getEnabled() || !enabled_) {
469 if (robot_action.action_type == STOP) {
475 polygon->updatePolygon(cmd_vel_in);
477 const ActionType at = polygon->getActionType();
478 if (at == STOP || at == SLOWDOWN || at == LIMIT) {
480 if (processStopSlowdownLimit(
481 polygon, sources_collision_points_map, cmd_vel_in, robot_action))
483 action_polygon = polygon;
485 }
else if (at == APPROACH) {
487 if (processApproach(polygon, sources_collision_points_map, cmd_vel_in, robot_action)) {
488 action_polygon = polygon;
493 if ((robot_action.polygon_name != robot_action_prev_.polygon_name) && enabled_) {
495 notifyActionState(robot_action, action_polygon);
499 publishVelocity(robot_action, header);
504 robot_action_prev_ = robot_action;
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,
511 Action & robot_action)
const
513 if (!polygon->isShapeSet()) {
517 if (polygon->getPointsInside(sources_collision_points_map) >= polygon->getMinPoints()) {
518 if (polygon->getActionType() == STOP) {
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;
526 }
else if (polygon->getActionType() == SLOWDOWN) {
527 const Velocity safe_vel = velocity * polygon->getSlowdownRatio();
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;
538 const double linear_vel = std::hypot(velocity.x, velocity.y);
543 if (linear_vel != 0.0) {
544 ratio = std::min(ratio, polygon->getLinearLimit() / linear_vel);
546 if (velocity.tw != 0.0) {
547 ratio = std::min(ratio, polygon->getAngularLimit() / std::abs(velocity.tw));
549 ratio = std::clamp(ratio, 0.0, 1.0);
551 safe_vel = velocity * ratio;
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;
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,
570 Action & robot_action)
const
572 if (!polygon->isShapeSet()) {
577 const double collision_time = polygon->getCollisionTime(sources_collision_points_map, velocity);
578 if (collision_time >= 0.0) {
580 const double change_ratio = collision_time / polygon->getTimeBeforeCollision();
581 const Velocity safe_vel = velocity * change_ratio;
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;
595 void CollisionMonitor::notifyActionState(
596 const Action & robot_action,
const std::shared_ptr<Polygon> action_polygon)
const
598 if (robot_action.action_type == STOP) {
599 if (robot_action.polygon_name ==
"invalid source") {
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");
608 "Robot to stop due to %s polygon",
609 action_polygon->getName().c_str());
611 }
else if (robot_action.action_type == SLOWDOWN) {
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) {
620 "Robot to limit speed due to %s polygon",
621 action_polygon->getName().c_str());
622 }
else if (robot_action.action_type == APPROACH) {
625 "Robot to approach for %f seconds away from collision",
626 action_polygon->getTimeBeforeCollision());
630 "Robot to continue normal operation");
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;
639 state_pub_->publish(std::move(state_msg));
643 void CollisionMonitor::publishPolygons()
const
645 for (std::shared_ptr<Polygon> polygon : polygons_) {
646 if (polygon->getEnabled() || !enabled_) {
652 void CollisionMonitor::toggleCMServiceCallback(
653 const std::shared_ptr<rmw_request_id_t>,
654 const std::shared_ptr<nav2_msgs::srv::Toggle::Request> request,
655 std::shared_ptr<nav2_msgs::srv::Toggle::Response> response)
657 enabled_ = request->enable;
659 std::stringstream message;
660 message <<
"Collision monitor toggled " << (enabled_ ?
"on" :
"off") <<
" successfully";
662 response->success =
true;
663 response->message = message.str();
668 #include "rclcpp_components/register_node_macro.hpp"
Collision Monitor ROS2 node.
Velocity for 2D model of motion.