Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
collision_detector_node.cpp
1 // Copyright (c) 2022 Samsung R&D Institute Russia
2 // Copyright (c) 2023 Pixel Robotics GmbH
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include "nav2_collision_monitor/collision_detector_node.hpp"
17 
18 #include <exception>
19 #include <utility>
20 #include <functional>
21 
22 #include "tf2_ros/create_timer_ros.hpp"
23 
24 #include "nav2_ros_common/node_utils.hpp"
25 
26 using namespace std::chrono_literals;
27 
28 namespace nav2_collision_monitor
29 {
30 
31 CollisionDetector::CollisionDetector(const rclcpp::NodeOptions & options)
32 : nav2::LifecycleNode("collision_detector", options)
33 {
34 }
35 
37 {
38  polygons_.clear();
39  sources_.clear();
40 }
41 
42 nav2::CallbackReturn
43 CollisionDetector::on_configure(const rclcpp_lifecycle::State & state)
44 {
45  RCLCPP_INFO(get_logger(), "Configuring");
46 
47  // Transform buffer and listener initialization
48  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
49  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
50  this->get_node_base_interface(),
51  this->get_node_timers_interface());
52  tf_buffer_->setCreateTimerInterface(timer_interface);
53  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);
54 
55  state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionDetectorState>(
56  "collision_detector_state");
57 
58  collision_points_marker_pub_ = this->create_publisher<visualization_msgs::msg::MarkerArray>(
59  "~/collision_points_marker");
60 
61  // Obtaining ROS parameters
62  if (!getParameters()) {
63  on_cleanup(state);
64  return nav2::CallbackReturn::FAILURE;
65  }
66 
67  return nav2::CallbackReturn::SUCCESS;
68 }
69 
70 nav2::CallbackReturn
71 CollisionDetector::on_activate(const rclcpp_lifecycle::State & /*state*/)
72 {
73  RCLCPP_INFO(get_logger(), "Activating");
74 
75  // Activating lifecycle publisher
76  state_pub_->on_activate();
77  collision_points_marker_pub_->on_activate();
78 
79  // Activating polygons
80  for (std::shared_ptr<Polygon> polygon : polygons_) {
81  polygon->activate();
82  }
83 
84  // Creating timer
85  timer_ = this->create_timer(
86  std::chrono::duration<double>{1.0 / frequency_},
87  std::bind(&CollisionDetector::process, this));
88 
89  // Creating bond connection
90  createBond();
91 
92  return nav2::CallbackReturn::SUCCESS;
93 }
94 
95 nav2::CallbackReturn
96 CollisionDetector::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
97 {
98  RCLCPP_INFO(get_logger(), "Deactivating");
99 
100  // Resetting timer
101  timer_.reset();
102 
103  // Deactivating lifecycle publishers
104  state_pub_->on_deactivate();
105  collision_points_marker_pub_->on_deactivate();
106 
107  // Deactivating polygons
108  for (std::shared_ptr<Polygon> polygon : polygons_) {
109  polygon->deactivate();
110  }
111 
112  // Destroying bond connection
113  destroyBond();
114 
115  return nav2::CallbackReturn::SUCCESS;
116 }
117 
118 nav2::CallbackReturn
119 CollisionDetector::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
120 {
121  RCLCPP_INFO(get_logger(), "Cleaning up");
122 
123  state_pub_.reset();
125 
126  polygons_.clear();
127  sources_.clear();
128 
129  tf_listener_.reset();
130  tf_buffer_.reset();
131 
132  return nav2::CallbackReturn::SUCCESS;
133 }
134 
135 nav2::CallbackReturn
136 CollisionDetector::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
137 {
138  RCLCPP_INFO(get_logger(), "Shutting down");
139  return nav2::CallbackReturn::SUCCESS;
140 }
141 
143 {
144  std::string base_frame_id, odom_frame_id;
145  tf2::Duration transform_tolerance;
146  rclcpp::Duration source_timeout(2.0, 0.0);
147 
148  auto node = shared_from_this();
149 
150  frequency_ = node->declare_or_get_parameter("frequency", 10.0);
151  base_frame_id = node->declare_or_get_parameter("base_frame_id", std::string("base_footprint"));
152  odom_frame_id = node->declare_or_get_parameter("odom_frame_id", std::string("odom"));
153  transform_tolerance = tf2::durationFromSec(
154  node->declare_or_get_parameter("transform_tolerance", 0.1));
155  source_timeout = rclcpp::Duration::from_seconds(
156  node->declare_or_get_parameter("source_timeout", 2.0));
157  const bool base_shift_correction = node->declare_or_get_parameter("base_shift_correction", true);
158 
159  if (!configureSources(
160  base_frame_id, odom_frame_id, transform_tolerance, source_timeout,
161  base_shift_correction))
162  {
163  return false;
164  }
165 
166  if (!configurePolygons(base_frame_id, transform_tolerance)) {
167  return false;
168  }
169 
170  return true;
171 }
172 
174  const std::string & base_frame_id,
175  const tf2::Duration & transform_tolerance)
176 {
177  try {
178  auto node = shared_from_this();
179 
180  // Leave it to be not initialized: to intentionally cause an error if it will not set
181  std::vector<std::string> polygon_names =
182  node->declare_or_get_parameter<std::vector<std::string>>("polygons");
183  for (std::string polygon_name : polygon_names) {
184  // Leave it not initialized: the will cause an error if it will not set
185  const std::string polygon_type =
186  node->declare_or_get_parameter<std::string>(polygon_name + ".type");
187 
188  if (polygon_type == "polygon") {
189  polygons_.push_back(
190  std::make_shared<Polygon>(
191  node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
192  } else if (polygon_type == "circle") {
193  polygons_.push_back(
194  std::make_shared<Circle>(
195  node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
196  } else if (polygon_type == "velocity_polygon") {
197  polygons_.push_back(
198  std::make_shared<VelocityPolygon>(
199  node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
200  } else { // Error if something else
201  RCLCPP_ERROR(
202  get_logger(),
203  "[%s]: Unknown polygon type: %s",
204  polygon_name.c_str(), polygon_type.c_str());
205  return false;
206  }
207 
208  // Configure last added polygon
209  if (!polygons_.back()->configure()) {
210  return false;
211  }
212 
213  // warn if the added polygon's action_type_ is not different than "none"
214  auto action_type = polygons_.back()->getActionType();
215  if (action_type != DO_NOTHING) {
216  RCLCPP_ERROR(
217  get_logger(),
218  "[%s]: The action_type of the polygon is different than \"none\" which is "
219  "not supported in the collision detector.",
220  polygon_name.c_str());
221  return false;
222  }
223  }
224  } catch (const std::exception & ex) {
225  RCLCPP_ERROR(get_logger(), "Error while getting parameters: %s", ex.what());
226  return false;
227  }
228 
229  return true;
230 }
231 
233  const std::string & base_frame_id,
234  const std::string & odom_frame_id,
235  const tf2::Duration & transform_tolerance,
236  const rclcpp::Duration & source_timeout,
237  const bool base_shift_correction)
238 {
239  try {
240  auto node = shared_from_this();
241 
242  // Leave it to be not initialized to intentionally cause an error if it will not set
243  std::vector<std::string> source_names =
244  node->declare_or_get_parameter<std::vector<std::string>>("observation_sources");
245  for (std::string source_name : source_names) {
246  const std::string source_type = node->declare_or_get_parameter(
247  source_name + ".type", std::string("scan")); // Laser scanner by default
248 
249  if (source_type == "scan") {
250  std::shared_ptr<Scan> s = std::make_shared<Scan>(
251  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
252  transform_tolerance, source_timeout, base_shift_correction);
253 
254  s->configure();
255 
256  sources_.push_back(s);
257  } else if (source_type == "pointcloud") {
258  std::shared_ptr<PointCloud> p = std::make_shared<PointCloud>(
259  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
260  transform_tolerance, source_timeout, base_shift_correction);
261 
262  p->configure();
263 
264  sources_.push_back(p);
265  } else if (source_type == "range") {
266  std::shared_ptr<Range> r = std::make_shared<Range>(
267  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
268  transform_tolerance, source_timeout, base_shift_correction);
269 
270  r->configure();
271 
272  sources_.push_back(r);
273  } else if (source_type == "polygon") {
274  std::shared_ptr<PolygonSource> ps = std::make_shared<PolygonSource>(
275  node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
276  transform_tolerance, source_timeout, base_shift_correction);
277  ps->configure();
278 
279  sources_.push_back(ps);
280  } else { // Error if something else
281  RCLCPP_ERROR(
282  get_logger(),
283  "[%s]: Unknown source type: %s",
284  source_name.c_str(), source_type.c_str());
285  return false;
286  }
287  }
288  } catch (const std::exception & ex) {
289  RCLCPP_ERROR(get_logger(), "Error while getting parameters: %s", ex.what());
290  return false;
291  }
292 
293  return true;
294 }
295 
297 {
298  // Current timestamp for all inner routines prolongation
299  rclcpp::Time curr_time = this->now();
300 
301  // Points array collected from different data sources in a robot base frame
302  std::vector<Point> collision_points;
303 
304  std::unique_ptr<nav2_msgs::msg::CollisionDetectorState> state_msg =
305  std::make_unique<nav2_msgs::msg::CollisionDetectorState>();
306 
307  // Fill collision_points array from different data sources
308  for (std::shared_ptr<Source> source : sources_) {
309  if (source->getEnabled()) {
310  if (!source->getData(curr_time, collision_points) &&
311  source->getSourceTimeout().seconds() != 0.0)
312  {
313  RCLCPP_WARN(
314  get_logger(),
315  "Invalid source %s detected."
316  " Either due to data not published yet, or to lack of new data received within the"
317  " sensor timeout, or if impossible to transform data to base frame",
318  source->getSourceName().c_str());
319  }
320  }
321  }
322 
323  if (collision_points_marker_pub_->get_subscription_count() > 0) {
324  // visualize collision points with markers
325  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
326  visualization_msgs::msg::Marker marker;
327  marker.header.frame_id = get_parameter("base_frame_id").as_string();
328  marker.header.stamp = rclcpp::Time(0, 0);
329  marker.ns = "collision_points";
330  marker.id = 0;
331  marker.type = visualization_msgs::msg::Marker::POINTS;
332  marker.action = visualization_msgs::msg::Marker::ADD;
333  marker.scale.x = 0.02;
334  marker.scale.y = 0.02;
335  marker.color.r = 1.0;
336  marker.color.a = 1.0;
337  marker.lifetime = rclcpp::Duration(0, 0);
338  marker.frame_locked = true;
339 
340  for (const auto & point : collision_points) {
341  geometry_msgs::msg::Point p;
342  p.x = point.x;
343  p.y = point.y;
344  p.z = 0.0;
345  marker.points.push_back(p);
346  }
347  marker_array->markers.push_back(marker);
348  collision_points_marker_pub_->publish(std::move(marker_array));
349  }
350 
351  for (std::shared_ptr<Polygon> polygon : polygons_) {
352  if (!polygon->getEnabled()) {
353  continue;
354  }
355  state_msg->polygons.push_back(polygon->getName());
356  state_msg->detections.push_back(
357  polygon->getPointsInside(
358  collision_points) >= polygon->getMinPoints());
359  }
360 
361  state_pub_->publish(std::move(state_msg));
362 
363  // Publish polygons for better visualization
364  publishPolygons();
365 }
366 
368 {
369  for (std::shared_ptr<Polygon> polygon : polygons_) {
370  if (polygon->getEnabled()) {
371  polygon->publish();
372  }
373  }
374 }
375 
376 } // namespace nav2_collision_monitor
377 
378 #include "rclcpp_components/register_node_macro.hpp"
379 
380 // Register the component with class_loader.
381 // This acts as a sort of entry point, allowing the component to be discoverable when its library
382 // is being loaded into a running process.
383 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_collision_monitor::CollisionDetector)
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
: Activates LifecyclePublishers, polygons and main processor, creates bond connection
nav2::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr collision_points_marker_pub_
Collision points marker publisher.
bool getParameters()
Supporting routine obtaining all ROS-parameters.
bool configureSources(const std::string &base_frame_id, const std::string &odom_frame_id, const tf2::Duration &transform_tolerance, const rclcpp::Duration &source_timeout, const bool base_shift_correction)
Supporting routine creating and configuring all data sources.
void publishPolygons() const
Polygons publishing routine. Made for visualization.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called in shutdown state.
nav2::Publisher< nav2_msgs::msg::CollisionDetectorState >::SharedPtr state_pub_
collision monitor state publisher
~CollisionDetector()
Destructor for the nav2_collision_monitor::CollisionDetector.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
: Resets all subscribers/publishers, polygons/data sources arrays
std::vector< std::shared_ptr< Source > > sources_
Data sources array.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
TF listener.
bool configurePolygons(const std::string &base_frame_id, const tf2::Duration &transform_tolerance)
Supporting routine creating and configuring all polygons.
rclcpp::TimerBase::SharedPtr timer_
timer that runs actions
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
: Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
: Initializes and obtains ROS-parameters, creates main subscribers and publishers,...
std::vector< std::shared_ptr< Polygon > > polygons_
Polygons array.