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 nav2::declare_parameter_if_not_declared(
92 node,
"use_realtime_priority", rclcpp::ParameterValue(
false));
93 bool use_realtime_priority =
false;
94 node->get_parameter(
"use_realtime_priority", use_realtime_priority);
95 if (use_realtime_priority) {
97 nav2::setSoftRealTimePriority();
98 }
catch (
const std::runtime_error & e) {
99 RCLCPP_ERROR(get_logger(),
"%s", e.what());
101 return nav2::CallbackReturn::FAILURE;
105 return nav2::CallbackReturn::SUCCESS;
109 CollisionMonitor::on_activate(
const rclcpp_lifecycle::State & )
111 RCLCPP_INFO(get_logger(),
"Activating");
114 cmd_vel_out_pub_->on_activate();
116 state_pub_->on_activate();
118 collision_points_marker_pub_->on_activate();
121 for (std::shared_ptr<Polygon> polygon : polygons_) {
130 process_active_ =
true;
135 return nav2::CallbackReturn::SUCCESS;
139 CollisionMonitor::on_deactivate(
const rclcpp_lifecycle::State & )
141 RCLCPP_INFO(get_logger(),
"Deactivating");
144 process_active_ =
false;
147 robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0},
""};
150 for (std::shared_ptr<Polygon> polygon : polygons_) {
151 polygon->deactivate();
155 cmd_vel_out_pub_->on_deactivate();
157 state_pub_->on_deactivate();
159 collision_points_marker_pub_->on_deactivate();
164 return nav2::CallbackReturn::SUCCESS;
168 CollisionMonitor::on_cleanup(
const rclcpp_lifecycle::State & )
170 RCLCPP_INFO(get_logger(),
"Cleaning up");
172 cmd_vel_in_sub_.reset();
173 cmd_vel_out_pub_.reset();
175 collision_points_marker_pub_.reset();
180 tf_listener_.reset();
183 return nav2::CallbackReturn::SUCCESS;
187 CollisionMonitor::on_shutdown(
const rclcpp_lifecycle::State & )
189 RCLCPP_INFO(get_logger(),
"Shutting down");
191 return nav2::CallbackReturn::SUCCESS;
194 void CollisionMonitor::cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg)
197 if (!nav2_util::validateTwist(msg->twist)) {
198 RCLCPP_ERROR(get_logger(),
"Velocity message contains NaNs or Infs! Ignoring as invalid!");
202 process({msg->twist.linear.x, msg->twist.linear.y, msg->twist.angular.z}, msg->header);
205 void CollisionMonitor::cmdVelInCallbackUnstamped(geometry_msgs::msg::Twist::SharedPtr msg)
207 auto twist_stamped = std::make_shared<geometry_msgs::msg::TwistStamped>();
208 twist_stamped->twist = *msg;
209 cmdVelInCallbackStamped(twist_stamped);
212 void CollisionMonitor::publishVelocity(
213 const Action & robot_action,
const std_msgs::msg::Header & header)
215 if (robot_action.req_vel.isZero()) {
216 if (!robot_action_prev_.req_vel.isZero()) {
218 stop_stamp_ = this->now();
219 }
else if (this->now() - stop_stamp_ > stop_pub_timeout_) {
226 auto cmd_vel_out_msg = std::make_unique<geometry_msgs::msg::TwistStamped>();
227 cmd_vel_out_msg->header = header;
228 cmd_vel_out_msg->twist.linear.x = robot_action.req_vel.x;
229 cmd_vel_out_msg->twist.linear.y = robot_action.req_vel.y;
230 cmd_vel_out_msg->twist.angular.z = robot_action.req_vel.tw;
233 cmd_vel_out_pub_->publish(std::move(cmd_vel_out_msg));
236 bool CollisionMonitor::getParameters(
237 std::string & cmd_vel_in_topic,
238 std::string & cmd_vel_out_topic,
239 std::string & state_topic)
241 std::string base_frame_id, odom_frame_id;
242 tf2::Duration transform_tolerance;
243 rclcpp::Duration source_timeout(2.0, 0.0);
245 auto node = shared_from_this();
247 nav2::declare_parameter_if_not_declared(
248 node,
"cmd_vel_in_topic", rclcpp::ParameterValue(
"cmd_vel_smoothed"));
249 cmd_vel_in_topic = get_parameter(
"cmd_vel_in_topic").as_string();
250 nav2::declare_parameter_if_not_declared(
251 node,
"cmd_vel_out_topic", rclcpp::ParameterValue(
"cmd_vel"));
252 cmd_vel_out_topic = get_parameter(
"cmd_vel_out_topic").as_string();
253 nav2::declare_parameter_if_not_declared(
254 node,
"state_topic", rclcpp::ParameterValue(
""));
255 state_topic = get_parameter(
"state_topic").as_string();
257 nav2::declare_parameter_if_not_declared(
258 node,
"base_frame_id", rclcpp::ParameterValue(
"base_footprint"));
259 base_frame_id = get_parameter(
"base_frame_id").as_string();
260 nav2::declare_parameter_if_not_declared(
261 node,
"odom_frame_id", rclcpp::ParameterValue(
"odom"));
262 odom_frame_id = get_parameter(
"odom_frame_id").as_string();
263 nav2::declare_parameter_if_not_declared(
264 node,
"transform_tolerance", rclcpp::ParameterValue(0.1));
265 transform_tolerance =
266 tf2::durationFromSec(get_parameter(
"transform_tolerance").as_double());
267 nav2::declare_parameter_if_not_declared(
268 node,
"source_timeout", rclcpp::ParameterValue(2.0));
270 rclcpp::Duration::from_seconds(get_parameter(
"source_timeout").as_double());
271 nav2::declare_parameter_if_not_declared(
272 node,
"base_shift_correction", rclcpp::ParameterValue(
true));
273 const bool base_shift_correction =
274 get_parameter(
"base_shift_correction").as_bool();
276 nav2::declare_parameter_if_not_declared(
277 node,
"stop_pub_timeout", rclcpp::ParameterValue(1.0));
279 rclcpp::Duration::from_seconds(get_parameter(
"stop_pub_timeout").as_double());
283 base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
288 if (!configurePolygons(base_frame_id, transform_tolerance)) {
295 bool CollisionMonitor::configurePolygons(
296 const std::string & base_frame_id,
297 const tf2::Duration & transform_tolerance)
300 auto node = shared_from_this();
303 nav2::declare_parameter_if_not_declared(
304 node,
"polygons", rclcpp::PARAMETER_STRING_ARRAY);
305 std::vector<std::string> polygon_names = get_parameter(
"polygons").as_string_array();
306 for (std::string polygon_name : polygon_names) {
308 nav2::declare_parameter_if_not_declared(
309 node, polygon_name +
".type", rclcpp::PARAMETER_STRING);
310 const std::string polygon_type = get_parameter(polygon_name +
".type").as_string();
312 if (polygon_type ==
"polygon") {
314 std::make_shared<Polygon>(
315 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
316 }
else if (polygon_type ==
"circle") {
318 std::make_shared<Circle>(
319 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
320 }
else if (polygon_type ==
"velocity_polygon") {
322 std::make_shared<VelocityPolygon>(
323 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
327 "[%s]: Unknown polygon type: %s",
328 polygon_name.c_str(), polygon_type.c_str());
333 if (!polygons_.back()->configure()) {
337 }
catch (
const std::exception & ex) {
338 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
345 bool CollisionMonitor::configureSources(
346 const std::string & base_frame_id,
347 const std::string & odom_frame_id,
348 const tf2::Duration & transform_tolerance,
349 const rclcpp::Duration & source_timeout,
350 const bool base_shift_correction)
353 auto node = shared_from_this();
356 nav2::declare_parameter_if_not_declared(
357 node,
"observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
358 std::vector<std::string> source_names = get_parameter(
"observation_sources").as_string_array();
359 for (std::string source_name : source_names) {
360 nav2::declare_parameter_if_not_declared(
361 node, source_name +
".type",
362 rclcpp::ParameterValue(
"scan"));
363 const std::string source_type = get_parameter(source_name +
".type").as_string();
365 if (source_type ==
"scan") {
366 std::shared_ptr<Scan> s = std::make_shared<Scan>(
367 node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
368 transform_tolerance, source_timeout, base_shift_correction);
372 sources_.push_back(s);
373 }
else if (source_type ==
"pointcloud") {
374 std::shared_ptr<PointCloud> p = std::make_shared<PointCloud>(
375 node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
376 transform_tolerance, source_timeout, base_shift_correction);
380 sources_.push_back(p);
381 }
else if (source_type ==
"range") {
382 std::shared_ptr<Range> r = std::make_shared<Range>(
383 node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
384 transform_tolerance, source_timeout, base_shift_correction);
388 sources_.push_back(r);
389 }
else if (source_type ==
"polygon") {
390 std::shared_ptr<PolygonSource> ps = std::make_shared<PolygonSource>(
391 node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
392 transform_tolerance, source_timeout, base_shift_correction);
395 sources_.push_back(ps);
399 "[%s]: Unknown source type: %s",
400 source_name.c_str(), source_type.c_str());
404 }
catch (
const std::exception & ex) {
405 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
412 void CollisionMonitor::process(
const Velocity & cmd_vel_in,
const std_msgs::msg::Header & header)
415 rclcpp::Time curr_time = this->now();
418 if (!process_active_) {
423 std::unordered_map<std::string, std::vector<Point>> sources_collision_points_map;
426 Action robot_action{DO_NOTHING, cmd_vel_in,
""};
428 std::shared_ptr<Polygon> action_polygon;
431 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
432 for (std::shared_ptr<Source> source : sources_) {
433 auto iter = sources_collision_points_map.insert(
434 {source->getSourceName(), std::vector<Point>()});
436 if (source->getEnabled()) {
437 if (!source->getData(curr_time, iter.first->second) &&
438 source->getSourceTimeout().seconds() != 0.0)
440 action_polygon =
nullptr;
441 robot_action.polygon_name =
"invalid source";
442 robot_action.action_type = STOP;
443 robot_action.req_vel.x = 0.0;
444 robot_action.req_vel.y = 0.0;
445 robot_action.req_vel.tw = 0.0;
450 if (collision_points_marker_pub_->get_subscription_count() > 0) {
452 visualization_msgs::msg::Marker marker;
453 marker.header.frame_id = get_parameter(
"base_frame_id").as_string();
454 marker.header.stamp = rclcpp::Time(0, 0);
455 marker.ns =
"collision_points_" + source->getSourceName();
457 marker.type = visualization_msgs::msg::Marker::POINTS;
458 marker.action = visualization_msgs::msg::Marker::ADD;
459 marker.scale.x = 0.02;
460 marker.scale.y = 0.02;
461 marker.color.r = 1.0;
462 marker.color.a = 1.0;
463 marker.lifetime = rclcpp::Duration(0, 0);
464 marker.frame_locked =
true;
466 for (
const auto & point : iter.first->second) {
467 geometry_msgs::msg::Point p;
471 marker.points.push_back(p);
473 marker_array->markers.push_back(marker);
477 if (collision_points_marker_pub_->get_subscription_count() > 0) {
478 collision_points_marker_pub_->publish(std::move(marker_array));
481 for (std::shared_ptr<Polygon> polygon : polygons_) {
482 if (!polygon->getEnabled() || !enabled_) {
485 if (robot_action.action_type == STOP) {
491 polygon->updatePolygon(cmd_vel_in);
493 const ActionType at = polygon->getActionType();
494 if (at == STOP || at == SLOWDOWN || at == LIMIT) {
496 if (processStopSlowdownLimit(
497 polygon, sources_collision_points_map, cmd_vel_in, robot_action))
499 action_polygon = polygon;
501 }
else if (at == APPROACH) {
503 if (processApproach(polygon, sources_collision_points_map, cmd_vel_in, robot_action)) {
504 action_polygon = polygon;
509 if ((robot_action.polygon_name != robot_action_prev_.polygon_name) && enabled_) {
511 notifyActionState(robot_action, action_polygon);
515 publishVelocity(robot_action, header);
520 robot_action_prev_ = robot_action;
523 bool CollisionMonitor::processStopSlowdownLimit(
524 const std::shared_ptr<Polygon> polygon,
525 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
527 Action & robot_action)
const
529 if (!polygon->isShapeSet()) {
533 if (polygon->getPointsInside(sources_collision_points_map) >= polygon->getMinPoints()) {
534 if (polygon->getActionType() == STOP) {
536 robot_action.polygon_name = polygon->getName();
537 robot_action.action_type = STOP;
538 robot_action.req_vel.x = 0.0;
539 robot_action.req_vel.y = 0.0;
540 robot_action.req_vel.tw = 0.0;
542 }
else if (polygon->getActionType() == SLOWDOWN) {
543 const Velocity safe_vel = velocity * polygon->getSlowdownRatio();
546 if (safe_vel < robot_action.req_vel) {
547 robot_action.polygon_name = polygon->getName();
548 robot_action.action_type = SLOWDOWN;
549 robot_action.req_vel = safe_vel;
554 const double linear_vel = std::hypot(velocity.x, velocity.y);
559 if (linear_vel != 0.0) {
560 ratio = std::min(ratio, polygon->getLinearLimit() / linear_vel);
562 if (velocity.tw != 0.0) {
563 ratio = std::min(ratio, polygon->getAngularLimit() / std::abs(velocity.tw));
565 ratio = std::clamp(ratio, 0.0, 1.0);
567 safe_vel = velocity * ratio;
570 if (safe_vel < robot_action.req_vel) {
571 robot_action.polygon_name = polygon->getName();
572 robot_action.action_type = LIMIT;
573 robot_action.req_vel = safe_vel;
582 bool CollisionMonitor::processApproach(
583 const std::shared_ptr<Polygon> polygon,
584 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
586 Action & robot_action)
const
588 if (!polygon->isShapeSet()) {
593 const double collision_time = polygon->getCollisionTime(sources_collision_points_map, velocity);
594 if (collision_time >= 0.0) {
596 const double change_ratio = collision_time / polygon->getTimeBeforeCollision();
597 const Velocity safe_vel = velocity * change_ratio;
600 if (safe_vel < robot_action.req_vel) {
601 robot_action.polygon_name = polygon->getName();
602 robot_action.action_type = APPROACH;
603 robot_action.req_vel = safe_vel;
611 void CollisionMonitor::notifyActionState(
612 const Action & robot_action,
const std::shared_ptr<Polygon> action_polygon)
const
614 if (robot_action.action_type == STOP) {
615 if (robot_action.polygon_name ==
"invalid source") {
618 "Robot to stop due to invalid source."
619 " Either due to data not published yet, or to lack of new data received within the"
620 " sensor timeout, or if impossible to transform data to base frame");
624 "Robot to stop due to %s polygon",
625 action_polygon->getName().c_str());
627 }
else if (robot_action.action_type == SLOWDOWN) {
630 "Robot to slowdown for %f percents due to %s polygon",
631 action_polygon->getSlowdownRatio() * 100,
632 action_polygon->getName().c_str());
633 }
else if (robot_action.action_type == LIMIT) {
636 "Robot to limit speed due to %s polygon",
637 action_polygon->getName().c_str());
638 }
else if (robot_action.action_type == APPROACH) {
641 "Robot to approach for %f seconds away from collision",
642 action_polygon->getTimeBeforeCollision());
646 "Robot to continue normal operation");
650 std::unique_ptr<nav2_msgs::msg::CollisionMonitorState> state_msg =
651 std::make_unique<nav2_msgs::msg::CollisionMonitorState>();
652 state_msg->polygon_name = robot_action.polygon_name;
653 state_msg->action_type = robot_action.action_type;
655 state_pub_->publish(std::move(state_msg));
659 void CollisionMonitor::publishPolygons()
const
661 for (std::shared_ptr<Polygon> polygon : polygons_) {
662 if (polygon->getEnabled() || !enabled_) {
668 void CollisionMonitor::toggleCMServiceCallback(
669 const std::shared_ptr<rmw_request_id_t>,
670 const std::shared_ptr<nav2_msgs::srv::Toggle::Request> request,
671 std::shared_ptr<nav2_msgs::srv::Toggle::Response> response)
673 enabled_ = request->enable;
675 std::stringstream message;
676 message <<
"Collision monitor toggled " << (enabled_ ?
"on" :
"off") <<
" successfully";
678 response->success =
true;
679 response->message = message.str();
684 #include "rclcpp_components/register_node_macro.hpp"
Collision Monitor ROS2 node.
Velocity for 2D model of motion.