Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
collision_monitor.cpp
1 // Copyright (c) 2025, Open Navigation LLC
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 
16 #include <math.h>
17 #include <memory>
18 #include <string>
19 
20 #include "nav2_route/plugins/route_operations/collision_monitor.hpp"
21 
22 namespace nav2_route
23 {
24 
26  const nav2::LifecycleNode::SharedPtr node,
27  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
28  const std::string & name)
29 {
30  name_ = name;
31  clock_ = node->get_clock();
32  logger_ = node->get_logger();
33  last_check_time_ = clock_->now();
34 
35  std::string server_costmap_topic = node->get_parameter("costmap_topic").as_string();
36  nav2::declare_parameter_if_not_declared(
37  node, getName() + ".costmap_topic", rclcpp::ParameterValue("local_costmap/costmap_raw"));
38  std::string costmap_topic = node->get_parameter(getName() + ".costmap_topic").as_string();
39  if (costmap_topic != server_costmap_topic) {
40  RCLCPP_INFO(node->get_logger(),
41  "Using costmap topic: %s instead of server costmap topic: %s for CollisionMonitor.",
42  costmap_topic.c_str(), server_costmap_topic.c_str());
43  costmap_subscriber_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
44  topic_ = costmap_topic;
45  } else {
46  costmap_subscriber_ = costmap_subscriber;
47  topic_ = server_costmap_topic;
48  }
49 
50  nav2::declare_parameter_if_not_declared(
51  node, getName() + ".rate", rclcpp::ParameterValue(1.0));
52  double checking_rate = node->get_parameter(getName() + ".rate").as_double();
53  checking_duration_ = rclcpp::Duration::from_seconds(1.0 / checking_rate);
54 
55  nav2::declare_parameter_if_not_declared(
56  node, getName() + ".reroute_on_collision", rclcpp::ParameterValue(true));
57  reroute_on_collision_ = node->get_parameter(getName() + ".reroute_on_collision").as_bool();
58 
59  nav2::declare_parameter_if_not_declared(
60  node, getName() + ".max_cost", rclcpp::ParameterValue(253.0));
61  max_cost_ = static_cast<float>(node->get_parameter(getName() + ".max_cost").as_double());
62 
63  // Resolution to check the costmap over (1=every cell, 2=every other cell, etc.)
64  nav2::declare_parameter_if_not_declared(
65  node, getName() + ".check_resolution", rclcpp::ParameterValue(1));
66  check_resolution_ = static_cast<unsigned int>(
67  node->get_parameter(getName() + ".check_resolution").as_int());
68 
69  nav2::declare_parameter_if_not_declared(
70  node, getName() + ".max_collision_dist", rclcpp::ParameterValue(5.0));
71  max_collision_dist_ = static_cast<float>(
72  node->get_parameter(getName() + ".max_collision_dist").as_double());
73  if (max_collision_dist_ <= 0.0) {
74  RCLCPP_INFO(
75  logger_, "Max collision distance to evaluate is zero or negative, checking the full route.");
76  max_collision_dist_ = std::numeric_limits<float>::max();
77  }
78 }
79 
81 {
82  try {
83  costmap_ = costmap_subscriber_->getCostmap();
84  } catch (...) {
86  "Collision Monitor could not obtain a costmap from topic: " + topic_);
87  }
88 }
89 
91  NodePtr /*node*/,
92  EdgePtr curr_edge,
93  EdgePtr /*edge_exited*/,
94  const Route & route,
95  const geometry_msgs::msg::PoseStamped & curr_pose,
96  const Metadata * /*mdata*/)
97 {
98  // Not time yet to check or before getting to first route edge
99  auto now = clock_->now();
100  if (now - last_check_time_ < checking_duration_ || !curr_edge) {
101  return OperationResult();
102  }
103  last_check_time_ = now;
104 
105  OperationResult result;
106  getCostmap();
107 
108  float dist_checked = 0.0;
109  Coordinates end = curr_edge->end->coords;
110  Coordinates start = utils::findClosestPoint(
111  curr_pose, curr_edge->start->coords, end);
112  unsigned int curr_edge_id = curr_edge->edgeid;
113 
114  bool final_edge = false;
115  while (!final_edge) {
116  // Track how far we've checked and should check for collisions
117  const float edge_dist = hypotf(end.x - start.x, end.y - start.y);
118  if (dist_checked + edge_dist >= max_collision_dist_) {
119  float dist_to_eval = max_collision_dist_ - dist_checked;
120  end = backoutValidEndPoint(start, end, dist_to_eval);
121  final_edge = true;
122  }
123  dist_checked += edge_dist;
124 
125  // Find the valid edge grid coords, in case the edge is partially off the grid
126  LineSegment line;
127  if (!lineToMap(start, end, line)) {
128  final_edge = true;
129  if (!backoutValidEndPoint(start, line)) {
130  break;
131  }
132  }
133 
134  // Collision check edge on grid within max distance and
135  // report blocked edges for rerouting or exit task
136  if (isInCollision(line)) {
137  RCLCPP_INFO(
138  logger_, "Collision has been detected within %0.2fm of robot pose!", max_collision_dist_);
139 
140  if (reroute_on_collision_) {
141  result.reroute = true;
142  result.blocked_ids.push_back(curr_edge_id);
143  return result;
144  }
145 
147  "Collision detected, but rerouting is not enabled, canceling tracking task.");
148  }
149 
150  // Restart loop for next edge until complete
151  start = end;
152  if (!final_edge) {
153  auto isCurrEdge = [&](const EdgePtr & edge) {return edge->edgeid == curr_edge_id;};
154  auto iter = std::find_if(route.edges.begin(), route.edges.end(), isCurrEdge);
155  if (iter != route.edges.end() && ++iter != route.edges.end()) {
156  // If we found the edge and the next edge is also valid
157  curr_edge_id = (*iter)->edgeid;
158  end = (*iter)->end->coords;
159  } else {
160  final_edge = true;
161  }
162  }
163  }
164 
165  return result;
166 }
167 
169  const Coordinates & start, const Coordinates & end, const float dist)
170 {
171  Coordinates new_end;
172  const float dx = end.x - start.x;
173  const float dy = end.y - start.y;
174  const float mag = hypotf(dx, dy);
175  if (mag < 1e-6) {
176  return start;
177  }
178  new_end.x = (dx / mag) * dist + start.x;
179  new_end.y = (dy / mag) * dist + start.y;
180  return new_end;
181 }
182 
184  const Coordinates & start, LineSegment & line)
185 {
186  // Check if any part of this edge is potentially valid
187  if (!costmap_->worldToMap(start.x, start.y, line.x0, line.y0)) {
188  return false;
189  }
190 
191  // Since worldToMap will populate the out-of-bounds (x1, y1), we can
192  // iterate through the partially valid line until we hit invalid coords
193  unsigned int last_end_x = line.x0, last_end_y = line.y0;
194  nav2_util::LineIterator iter(line.x0, line.y0, line.x1, line.y1);
195  int size_x = static_cast<int>(costmap_->getSizeInCellsX());
196  int size_y = static_cast<int>(costmap_->getSizeInCellsY());
197  for (; iter.isValid(); iter.advance()) {
198  if (iter.getX() >= size_x || iter.getY() >= size_y) {
199  line.x1 = last_end_x;
200  line.y1 = last_end_y;
201  return true;
202  }
203  last_end_x = iter.getX();
204  last_end_y = iter.getY();
205  }
206 
207  return false;
208 }
209 
211  const Coordinates & start, const Coordinates & end, LineSegment & line)
212 {
213  if (!costmap_->worldToMap(start.x, start.y, line.x0, line.y0) ||
214  !costmap_->worldToMap(end.x, end.y, line.x1, line.y1))
215  {
216  return false;
217  }
218  return true;
219 }
220 
222 {
223  nav2_util::LineIterator iter(line.x0, line.y0, line.x1, line.y1);
224  for (; iter.isValid(); ) {
225  float cost = static_cast<float>(costmap_->getCost(iter.getX(), iter.getY()));
226  if (cost >= max_cost_ && cost != 255.0 /*unknown*/) {
227  return true;
228  }
229 
230  // Advance the iterator by the check resolution on the edge, pruning to a coarse resolution
231  for (unsigned int i = 0; i < check_resolution_; i++) {
232  iter.advance();
233  }
234  }
235  return false;
236 }
237 
238 } // namespace nav2_route
239 
240 #include "pluginlib/class_list_macros.hpp"
A route operation to process a costmap to determine if a route is blocked requiring immediate rerouti...
std::string getName() override
Get name of the plugin for parameter scope mapping.
Coordinates backoutValidEndPoint(const Coordinates &start, const Coordinates &end, const float dist)
Backs out the end coordinate along the line segment start-end to length dist.
void configure(const nav2::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override
Configure.
bool lineToMap(const Coordinates &start, const Coordinates &end, LineSegment &line)
Converts a line segment start-end into a LineSegment struct in costmap frame.
bool isInCollision(const LineSegment &line)
Checks a line segment in costmap frame for validity.
void getCostmap()
Gets the latest costmap from the costmap subscriber.
OperationResult perform(NodePtr, EdgePtr curr_edge, EdgePtr, const Route &route, const geometry_msgs::msg::PoseStamped &curr_pose, const Metadata *) override
The main speed limit operation to adjust the maximum speed of the vehicle.
A plugin interface to perform an operation while tracking the route such as triggered from the graph ...
An iterator implementing Bresenham Ray-Tracing.
bool isValid() const
If the iterator is valid.
int getX() const
Get current X value.
void advance()
Advance iteration along the line.
int getY() const
Get current Y value.
An object to store Node coordinates in different frames.
Definition: types.hpp:173
An object representing edges between nodes.
Definition: types.hpp:134
An object to store arbitrary metadata regarding nodes from the graph file.
Definition: types.hpp:35
An object to store the nodes in the graph file.
Definition: types.hpp:183
a struct to hold return from an operation
An ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211