15 #include "nav2_collision_monitor/collision_monitor_node.hpp"
21 #include "tf2_ros/create_timer_ros.h"
23 #include "nav2_util/node_utils.hpp"
25 #include "nav2_collision_monitor/kinematics.hpp"
27 namespace nav2_collision_monitor
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)
37 CollisionMonitor::~CollisionMonitor()
43 nav2_util::CallbackReturn
44 CollisionMonitor::on_configure(
const rclcpp_lifecycle::State & )
46 RCLCPP_INFO(get_logger(),
"Configuring");
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_);
56 std::string cmd_vel_in_topic;
57 std::string cmd_vel_out_topic;
60 if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic)) {
61 return nav2_util::CallbackReturn::FAILURE;
64 cmd_vel_in_sub_ = this->create_subscription<geometry_msgs::msg::Twist>(
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);
70 return nav2_util::CallbackReturn::SUCCESS;
73 nav2_util::CallbackReturn
74 CollisionMonitor::on_activate(
const rclcpp_lifecycle::State & )
76 RCLCPP_INFO(get_logger(),
"Activating");
79 cmd_vel_out_pub_->on_activate();
82 for (std::shared_ptr<Polygon> polygon : polygons_) {
91 process_active_ =
true;
96 return nav2_util::CallbackReturn::SUCCESS;
99 nav2_util::CallbackReturn
100 CollisionMonitor::on_deactivate(
const rclcpp_lifecycle::State & )
102 RCLCPP_INFO(get_logger(),
"Deactivating");
105 process_active_ =
false;
108 robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0}};
111 for (std::shared_ptr<Polygon> polygon : polygons_) {
112 polygon->deactivate();
116 cmd_vel_out_pub_->on_deactivate();
121 return nav2_util::CallbackReturn::SUCCESS;
124 nav2_util::CallbackReturn
125 CollisionMonitor::on_cleanup(
const rclcpp_lifecycle::State & )
127 RCLCPP_INFO(get_logger(),
"Cleaning up");
129 cmd_vel_in_sub_.reset();
130 cmd_vel_out_pub_.reset();
135 tf_listener_.reset();
138 return nav2_util::CallbackReturn::SUCCESS;
141 nav2_util::CallbackReturn
142 CollisionMonitor::on_shutdown(
const rclcpp_lifecycle::State & )
144 RCLCPP_INFO(get_logger(),
"Shutting down");
146 return nav2_util::CallbackReturn::SUCCESS;
149 void CollisionMonitor::cmdVelInCallback(geometry_msgs::msg::Twist::ConstSharedPtr msg)
152 if (!nav2_util::validateTwist(*msg)) {
153 RCLCPP_ERROR(get_logger(),
"Velocity message contains NaNs or Infs! Ignoring as invalid!");
157 process({msg->linear.x, msg->linear.y, msg->angular.z});
160 void CollisionMonitor::publishVelocity(
const Action & robot_action)
162 if (robot_action.req_vel.isZero()) {
163 if (!robot_action_prev_.req_vel.isZero()) {
165 stop_stamp_ = this->now();
166 }
else if (this->now() - stop_stamp_ > stop_pub_timeout_) {
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;
180 cmd_vel_out_pub_->publish(std::move(cmd_vel_out_msg));
183 bool CollisionMonitor::getParameters(
184 std::string & cmd_vel_in_topic,
185 std::string & cmd_vel_out_topic)
187 std::string base_frame_id, odom_frame_id;
188 tf2::Duration transform_tolerance;
189 rclcpp::Duration source_timeout(2.0, 0.0);
191 auto node = shared_from_this();
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();
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));
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();
219 nav2_util::declare_parameter_if_not_declared(
220 node,
"stop_pub_timeout", rclcpp::ParameterValue(1.0));
222 rclcpp::Duration::from_seconds(get_parameter(
"stop_pub_timeout").as_double());
224 if (!configurePolygons(base_frame_id, transform_tolerance)) {
230 base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
238 bool CollisionMonitor::configurePolygons(
239 const std::string & base_frame_id,
240 const tf2::Duration & transform_tolerance)
243 auto node = shared_from_this();
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) {
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();
254 if (polygon_type ==
"polygon") {
256 std::make_shared<Polygon>(
257 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
258 }
else if (polygon_type ==
"circle") {
260 std::make_shared<Circle>(
261 node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
265 "[%s]: Unknown polygon type: %s",
266 polygon_name.c_str(), polygon_type.c_str());
271 if (!polygons_.back()->configure()) {
275 }
catch (
const std::exception & ex) {
276 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
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)
291 auto node = shared_from_this();
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"));
301 const std::string source_type = get_parameter(source_name +
".type").as_string();
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);
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);
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);
326 sources_.push_back(r);
330 "[%s]: Unknown source type: %s",
331 source_name.c_str(), source_type.c_str());
335 }
catch (
const std::exception & ex) {
336 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
343 void CollisionMonitor::process(
const Velocity & cmd_vel_in)
346 rclcpp::Time curr_time = this->now();
349 if (!process_active_) {
354 std::vector<Point> collision_points;
357 for (std::shared_ptr<Source> source : sources_) {
358 if (source->getEnabled()) {
359 source->getData(curr_time, collision_points);
364 Action robot_action{DO_NOTHING, cmd_vel_in};
366 std::shared_ptr<Polygon> action_polygon;
368 for (std::shared_ptr<Polygon> polygon : polygons_) {
369 if (!polygon->getEnabled()) {
372 if (robot_action.action_type == STOP) {
377 const ActionType at = polygon->getActionType();
378 if (at == STOP || at == SLOWDOWN) {
380 if (processStopSlowdown(polygon, collision_points, cmd_vel_in, robot_action)) {
381 action_polygon = polygon;
383 }
else if (at == APPROACH) {
385 if (processApproach(polygon, collision_points, cmd_vel_in, robot_action)) {
386 action_polygon = polygon;
391 if (robot_action.action_type != robot_action_prev_.action_type) {
393 printAction(robot_action, action_polygon);
397 publishVelocity(robot_action);
402 robot_action_prev_ = robot_action;
405 bool CollisionMonitor::processStopSlowdown(
406 const std::shared_ptr<Polygon> polygon,
407 const std::vector<Point> & collision_points,
409 Action & robot_action)
const
411 if (polygon->getPointsInside(collision_points) > polygon->getMaxPoints()) {
412 if (polygon->getActionType() == STOP) {
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;
420 const Velocity safe_vel = velocity * polygon->getSlowdownRatio();
423 if (safe_vel < robot_action.req_vel) {
424 robot_action.action_type = SLOWDOWN;
425 robot_action.req_vel = safe_vel;
434 bool CollisionMonitor::processApproach(
435 const std::shared_ptr<Polygon> polygon,
436 const std::vector<Point> & collision_points,
438 Action & robot_action)
const
440 polygon->updatePolygon();
443 const double collision_time = polygon->getCollisionTime(collision_points, velocity);
444 if (collision_time >= 0.0) {
446 const double change_ratio = collision_time / polygon->getTimeBeforeCollision();
447 const Velocity safe_vel = velocity * change_ratio;
450 if (safe_vel < robot_action.req_vel) {
451 robot_action.action_type = APPROACH;
452 robot_action.req_vel = safe_vel;
460 void CollisionMonitor::printAction(
461 const Action & robot_action,
const std::shared_ptr<Polygon> action_polygon)
const
463 if (robot_action.action_type == STOP) {
466 "Robot to stop due to %s polygon",
467 action_polygon->getName().c_str());
468 }
else if (robot_action.action_type == SLOWDOWN) {
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) {
477 "Robot to approach for %f seconds away from collision",
478 action_polygon->getTimeBeforeCollision());
482 "Robot to continue normal operation");
486 void CollisionMonitor::publishPolygons()
const
488 for (std::shared_ptr<Polygon> polygon : polygons_) {
489 if (polygon->getEnabled()) {
497 #include "rclcpp_components/register_node_macro.hpp"
Collision Monitor ROS2 node.
CollisionMonitor(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_collision_safery::CollisionMonitor.
Velocity for 2D model of motion.