Nav2 Navigation Stack - humble  humble
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 rclcpp_lifecycle::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_util::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(
41  node->get_logger(),
42  "Using costmap topic: %s instead of server costmap topic: %s for CollisionMonitor.",
43  costmap_topic.c_str(), server_costmap_topic.c_str());
44  costmap_subscriber_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
45  topic_ = costmap_topic;
46  } else {
47  costmap_subscriber_ = costmap_subscriber;
48  topic_ = server_costmap_topic;
49  }
50 
51  nav2_util::declare_parameter_if_not_declared(
52  node, getName() + ".rate", rclcpp::ParameterValue(1.0));
53  double checking_rate = node->get_parameter(getName() + ".rate").as_double();
54  checking_duration_ = rclcpp::Duration::from_seconds(1.0 / checking_rate);
55 
56  nav2_util::declare_parameter_if_not_declared(
57  node, getName() + ".reroute_on_collision", rclcpp::ParameterValue(true));
58  reroute_on_collision_ = node->get_parameter(getName() + ".reroute_on_collision").as_bool();
59 
60  nav2_util::declare_parameter_if_not_declared(
61  node, getName() + ".max_cost", rclcpp::ParameterValue(253.0));
62  max_cost_ = static_cast<float>(node->get_parameter(getName() + ".max_cost").as_double());
63 
64  // Resolution to check the costmap over (1=every cell, 2=every other cell, etc.)
65  nav2_util::declare_parameter_if_not_declared(
66  node, getName() + ".check_resolution", rclcpp::ParameterValue(1));
67  check_resolution_ = static_cast<unsigned int>(
68  node->get_parameter(getName() + ".check_resolution").as_int());
69 
70  nav2_util::declare_parameter_if_not_declared(
71  node, getName() + ".max_collision_dist", rclcpp::ParameterValue(5.0));
72  max_collision_dist_ = static_cast<float>(
73  node->get_parameter(getName() + ".max_collision_dist").as_double());
74  if (max_collision_dist_ <= 0.0) {
75  RCLCPP_INFO(
76  logger_, "Max collision distance to evaluate is zero or negative, checking the full route.");
77  max_collision_dist_ = std::numeric_limits<float>::max();
78  }
79 }
80 
82 {
83  try {
84  costmap_ = costmap_subscriber_->getCostmap();
85  } catch (...) {
87  "Collision Monitor could not obtain a costmap from topic: " + topic_);
88  }
89 }
90 
92  NodePtr /*node*/,
93  EdgePtr curr_edge,
94  EdgePtr /*edge_exited*/,
95  const Route & route,
96  const geometry_msgs::msg::PoseStamped & curr_pose,
97  const Metadata * /*mdata*/)
98 {
99  // Not time yet to check or before getting to first route edge
100  auto now = clock_->now();
101  if (now - last_check_time_ < checking_duration_ || !curr_edge) {
102  return OperationResult();
103  }
104  last_check_time_ = now;
105 
106  OperationResult result;
107  getCostmap();
108 
109  float dist_checked = 0.0;
110  Coordinates end = curr_edge->end->coords;
111  Coordinates start = utils::findClosestPoint(
112  curr_pose, curr_edge->start->coords, end);
113  unsigned int curr_edge_id = curr_edge->edgeid;
114 
115  bool final_edge = false;
116  while (!final_edge) {
117  // Track how far we've checked and should check for collisions
118  const float edge_dist = hypotf(end.x - start.x, end.y - start.y);
119  if (dist_checked + edge_dist >= max_collision_dist_) {
120  float dist_to_eval = max_collision_dist_ - dist_checked;
121  end = backoutValidEndPoint(start, end, dist_to_eval);
122  final_edge = true;
123  }
124  dist_checked += edge_dist;
125 
126  // Find the valid edge grid coords, in case the edge is partially off the grid
127  LineSegment line;
128  if (!lineToMap(start, end, line)) {
129  final_edge = true;
130  if (!backoutValidEndPoint(start, line)) {
131  break;
132  }
133  }
134 
135  // Collision check edge on grid within max distance and
136  // report blocked edges for rerouting or exit task
137  if (isInCollision(line)) {
138  RCLCPP_INFO(
139  logger_, "Collision has been detected within %0.2fm of robot pose!", max_collision_dist_);
140 
141  if (reroute_on_collision_) {
142  result.reroute = true;
143  result.blocked_ids.push_back(curr_edge_id);
144  return result;
145  }
146 
148  "Collision detected, but rerouting is not enabled, canceling tracking task.");
149  }
150 
151  // Restart loop for next edge until complete
152  start = end;
153  if (!final_edge) {
154  auto isCurrEdge = [&](const EdgePtr & edge) {return edge->edgeid == curr_edge_id;};
155  auto iter = std::find_if(route.edges.begin(), route.edges.end(), isCurrEdge);
156  if (iter != route.edges.end() && ++iter != route.edges.end()) {
157  // If we found the edge and the next edge is also valid
158  curr_edge_id = (*iter)->edgeid;
159  end = (*iter)->end->coords;
160  } else {
161  final_edge = true;
162  }
163  }
164  }
165 
166  return result;
167 }
168 
170  const Coordinates & start, const Coordinates & end, const float dist)
171 {
172  Coordinates new_end;
173  const float dx = end.x - start.x;
174  const float dy = end.y - start.y;
175  const float mag = hypotf(dx, dy);
176  if (mag < 1e-6) {
177  return start;
178  }
179  new_end.x = (dx / mag) * dist + start.x;
180  new_end.y = (dy / mag) * dist + start.y;
181  return new_end;
182 }
183 
185  const Coordinates & start, LineSegment & line)
186 {
187  // Check if any part of this edge is potentially valid
188  if (!costmap_->worldToMap(start.x, start.y, line.x0, line.y0)) {
189  return false;
190  }
191 
192  // Since worldToMap will populate the out-of-bounds (x1, y1), we can
193  // iterate through the partially valid line until we hit invalid coords
194  unsigned int last_end_x = line.x0, last_end_y = line.y0;
195  nav2_util::LineIterator iter(line.x0, line.y0, line.x1, line.y1);
196  int size_x = static_cast<int>(costmap_->getSizeInCellsX());
197  int size_y = static_cast<int>(costmap_->getSizeInCellsY());
198  for (; iter.isValid(); iter.advance()) {
199  if (iter.getX() >= size_x || iter.getY() >= size_y) {
200  line.x1 = last_end_x;
201  line.y1 = last_end_y;
202  return true;
203  }
204  last_end_x = iter.getX();
205  last_end_y = iter.getY();
206  }
207 
208  return false;
209 }
210 
212  const Coordinates & start, const Coordinates & end, LineSegment & line)
213 {
214  if (!costmap_->worldToMap(start.x, start.y, line.x0, line.y0) ||
215  !costmap_->worldToMap(end.x, end.y, line.x1, line.y1))
216  {
217  return false;
218  }
219  return true;
220 }
221 
223 {
224  nav2_util::LineIterator iter(line.x0, line.y0, line.x1, line.y1);
225  for (; iter.isValid(); ) {
226  float cost = static_cast<float>(costmap_->getCost(iter.getX(), iter.getY()));
227  if (cost >= max_cost_ && cost != 255.0 /*unknown*/) {
228  return true;
229  }
230 
231  // Advance the iterator by the check resolution on the edge, pruning to a coarse resolution
232  for (unsigned int i = 0; i < check_resolution_; i++) {
233  iter.advance();
234  }
235  }
236  return false;
237 }
238 
239 } // namespace nav2_route
240 
241 #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 rclcpp_lifecycle::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