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 namespace nav2_collision_monitor
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)
38 CollisionMonitor::~CollisionMonitor()
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_,
this,
true);
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::CallbackReturn::FAILURE;
67 cmd_vel_in_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
70 std::bind(&CollisionMonitor::cmdVelInCallbackUnstamped,
this, std::placeholders::_1),
71 std::bind(&CollisionMonitor::cmdVelInCallbackStamped,
this, std::placeholders::_1));
73 auto node = shared_from_this();
74 cmd_vel_out_pub_ = std::make_unique<nav2_util::TwistPublisher>(node, cmd_vel_out_topic);
76 if (!state_topic.empty()) {
77 state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionMonitorState>(
81 collision_points_marker_pub_ = this->create_publisher<visualization_msgs::msg::MarkerArray>(
82 "~/collision_points_marker");
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) {
90 nav2::setSoftRealTimePriority();
91 }
catch (
const std::runtime_error & e) {
92 RCLCPP_ERROR(get_logger(),
"%s", e.what());
94 return nav2::CallbackReturn::FAILURE;
98 return nav2::CallbackReturn::SUCCESS;
102 CollisionMonitor::on_activate(
const rclcpp_lifecycle::State & )
104 RCLCPP_INFO(get_logger(),
"Activating");
107 cmd_vel_out_pub_->on_activate();
109 state_pub_->on_activate();
111 collision_points_marker_pub_->on_activate();
114 for (std::shared_ptr<Polygon> polygon : polygons_) {
123 process_active_ =
true;
128 return nav2::CallbackReturn::SUCCESS;
132 CollisionMonitor::on_deactivate(
const rclcpp_lifecycle::State & )
134 RCLCPP_INFO(get_logger(),
"Deactivating");
137 process_active_ =
false;
140 robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0},
""};
143 for (std::shared_ptr<Polygon> polygon : polygons_) {
144 polygon->deactivate();
148 cmd_vel_out_pub_->on_deactivate();
150 state_pub_->on_deactivate();
152 collision_points_marker_pub_->on_deactivate();
157 return nav2::CallbackReturn::SUCCESS;
161 CollisionMonitor::on_cleanup(
const rclcpp_lifecycle::State & )
163 RCLCPP_INFO(get_logger(),
"Cleaning up");
165 cmd_vel_in_sub_.reset();
166 cmd_vel_out_pub_.reset();
168 collision_points_marker_pub_.reset();
173 tf_listener_.reset();
176 return nav2::CallbackReturn::SUCCESS;
180 CollisionMonitor::on_shutdown(
const rclcpp_lifecycle::State & )
182 RCLCPP_INFO(get_logger(),
"Shutting down");
184 return nav2::CallbackReturn::SUCCESS;
187 void CollisionMonitor::cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg)
190 if (!nav2_util::validateTwist(msg->twist)) {
191 RCLCPP_ERROR(get_logger(),
"Velocity message contains NaNs or Infs! Ignoring as invalid!");
195 process({msg->twist.linear.x, msg->twist.linear.y, msg->twist.angular.z}, msg->header);
198 void CollisionMonitor::cmdVelInCallbackUnstamped(geometry_msgs::msg::Twist::SharedPtr msg)
200 auto twist_stamped = std::make_shared<geometry_msgs::msg::TwistStamped>();
201 twist_stamped->twist = *msg;
202 cmdVelInCallbackStamped(twist_stamped);
205 void CollisionMonitor::publishVelocity(
206 const Action & robot_action,
const std_msgs::msg::Header & header)
208 if (robot_action.req_vel.isZero()) {
209 if (!robot_action_prev_.req_vel.isZero()) {
211 stop_stamp_ = this->now();
212 }
else if (this->now() - stop_stamp_ > stop_pub_timeout_) {
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;
226 cmd_vel_out_pub_->publish(std::move(cmd_vel_out_msg));
229 bool CollisionMonitor::getParameters(
230 std::string & cmd_vel_in_topic,
231 std::string & cmd_vel_out_topic,
232 std::string & state_topic)
234 std::string base_frame_id, odom_frame_id;
235 tf2::Duration transform_tolerance;
236 rclcpp::Duration source_timeout(2.0, 0.0);
238 auto node = shared_from_this();
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();
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));
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();
269 nav2::declare_parameter_if_not_declared(
270 node,
"stop_pub_timeout", rclcpp::ParameterValue(1.0));
272 rclcpp::Duration::from_seconds(get_parameter(
"stop_pub_timeout").as_double());
276 base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
281 if (!configurePolygons(base_frame_id, transform_tolerance)) {
288 bool CollisionMonitor::configurePolygons(
289 const std::string & base_frame_id,
290 const tf2::Duration & transform_tolerance)
293 auto node = shared_from_this();
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) {
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();
305 if (polygon_type ==
"polygon") {
307 std::make_shared<Polygon>(
308 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
309 }
else if (polygon_type ==
"circle") {
311 std::make_shared<Circle>(
312 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
313 }
else if (polygon_type ==
"velocity_polygon") {
315 std::make_shared<VelocityPolygon>(
316 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
320 "[%s]: Unknown polygon type: %s",
321 polygon_name.c_str(), polygon_type.c_str());
326 if (!polygons_.back()->configure()) {
330 }
catch (
const std::exception & ex) {
331 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
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)
346 auto node = shared_from_this();
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"));
356 const std::string source_type = get_parameter(source_name +
".type").as_string();
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);
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);
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);
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);
388 sources_.push_back(ps);
392 "[%s]: Unknown source type: %s",
393 source_name.c_str(), source_type.c_str());
397 }
catch (
const std::exception & ex) {
398 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
405 void CollisionMonitor::process(
const Velocity & cmd_vel_in,
const std_msgs::msg::Header & header)
408 rclcpp::Time curr_time = this->now();
411 if (!process_active_) {
416 std::unordered_map<std::string, std::vector<Point>> sources_collision_points_map;
419 Action robot_action{DO_NOTHING, cmd_vel_in,
""};
421 std::shared_ptr<Polygon> action_polygon;
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>()});
429 if (source->getEnabled()) {
430 if (!source->getData(curr_time, iter.first->second) &&
431 source->getSourceTimeout().seconds() != 0.0)
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;
443 if (collision_points_marker_pub_->get_subscription_count() > 0) {
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();
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;
459 for (
const auto & point : iter.first->second) {
460 geometry_msgs::msg::Point p;
464 marker.points.push_back(p);
466 marker_array->markers.push_back(marker);
470 if (collision_points_marker_pub_->get_subscription_count() > 0) {
471 collision_points_marker_pub_->publish(std::move(marker_array));
474 for (std::shared_ptr<Polygon> polygon : polygons_) {
475 if (!polygon->getEnabled()) {
478 if (robot_action.action_type == STOP) {
484 polygon->updatePolygon(cmd_vel_in);
486 const ActionType at = polygon->getActionType();
487 if (at == STOP || at == SLOWDOWN || at == LIMIT) {
489 if (processStopSlowdownLimit(
490 polygon, sources_collision_points_map, cmd_vel_in, robot_action))
492 action_polygon = polygon;
494 }
else if (at == APPROACH) {
496 if (processApproach(polygon, sources_collision_points_map, cmd_vel_in, robot_action)) {
497 action_polygon = polygon;
502 if (robot_action.polygon_name != robot_action_prev_.polygon_name) {
504 notifyActionState(robot_action, action_polygon);
508 publishVelocity(robot_action, header);
513 robot_action_prev_ = robot_action;
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,
520 Action & robot_action)
const
522 if (!polygon->isShapeSet()) {
526 if (polygon->getPointsInside(sources_collision_points_map) >= polygon->getMinPoints()) {
527 if (polygon->getActionType() == STOP) {
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;
535 }
else if (polygon->getActionType() == SLOWDOWN) {
536 const Velocity safe_vel = velocity * polygon->getSlowdownRatio();
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;
547 const double linear_vel = std::hypot(velocity.x, velocity.y);
552 if (linear_vel != 0.0) {
553 ratio = std::min(ratio, polygon->getLinearLimit() / linear_vel);
555 if (velocity.tw != 0.0) {
556 ratio = std::min(ratio, polygon->getAngularLimit() / std::abs(velocity.tw));
558 ratio = std::clamp(ratio, 0.0, 1.0);
560 safe_vel = velocity * ratio;
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;
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,
579 Action & robot_action)
const
581 if (!polygon->isShapeSet()) {
586 const double collision_time = polygon->getCollisionTime(sources_collision_points_map, velocity);
587 if (collision_time >= 0.0) {
589 const double change_ratio = collision_time / polygon->getTimeBeforeCollision();
590 const Velocity safe_vel = velocity * change_ratio;
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;
604 void CollisionMonitor::notifyActionState(
605 const Action & robot_action,
const std::shared_ptr<Polygon> action_polygon)
const
607 if (robot_action.action_type == STOP) {
608 if (robot_action.polygon_name ==
"invalid source") {
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");
617 "Robot to stop due to %s polygon",
618 action_polygon->getName().c_str());
620 }
else if (robot_action.action_type == SLOWDOWN) {
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) {
629 "Robot to limit speed due to %s polygon",
630 action_polygon->getName().c_str());
631 }
else if (robot_action.action_type == APPROACH) {
634 "Robot to approach for %f seconds away from collision",
635 action_polygon->getTimeBeforeCollision());
639 "Robot to continue normal operation");
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;
648 state_pub_->publish(std::move(state_msg));
652 void CollisionMonitor::publishPolygons()
const
654 for (std::shared_ptr<Polygon> polygon : polygons_) {
655 if (polygon->getEnabled()) {
663 #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.