Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
collision_monitor.hpp
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 #ifndef NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__COLLISION_MONITOR_HPP_
16 #define NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__COLLISION_MONITOR_HPP_
17 
18 #include <math.h>
19 #include <memory>
20 #include <string>
21 
22 #include "rclcpp/rclcpp.hpp"
23 #include "rclcpp_lifecycle/lifecycle_node.hpp"
24 #include "nav2_route/interfaces/route_operation.hpp"
25 #include "nav2_route/utils.hpp"
26 #include "nav2_costmap_2d/costmap_subscriber.hpp"
27 #include "nav2_util/line_iterator.hpp"
28 #include "nav2_ros_common/node_utils.hpp"
29 #include "nav2_core/route_exceptions.hpp"
30 
31 namespace nav2_route
32 {
33 
44 {
45 public:
46  struct LineSegment
47  {
48  unsigned int x0, y0, x1, y1;
49  };
50 
54  CollisionMonitor() = default;
55 
59  virtual ~CollisionMonitor() = default;
60 
64  void configure(
65  const nav2::LifecycleNode::SharedPtr node,
66  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
67  const std::string & name) override;
68 
73  std::string getName() override {return name_;}
74 
80  RouteOperationType processType() override {return RouteOperationType::ON_QUERY;}
81 
94  NodePtr /*node*/,
95  EdgePtr curr_edge,
96  EdgePtr /*edge_exited*/,
97  const Route & route,
98  const geometry_msgs::msg::PoseStamped & curr_pose,
99  const Metadata * /*mdata*/) override;
100 
101 protected:
110  const Coordinates & start, const Coordinates & end, const float dist);
111 
119  bool backoutValidEndPoint(const Coordinates & start, LineSegment & line);
120 
128  bool lineToMap(const Coordinates & start, const Coordinates & end, LineSegment & line);
129 
135  bool isInCollision(const LineSegment & line);
136 
140  void getCostmap();
141 
142  std::string name_, topic_;
143  std::atomic_bool reroute_;
144  rclcpp::Logger logger_{rclcpp::get_logger("CollisionMonitor")};
145  rclcpp::Clock::SharedPtr clock_;
146  rclcpp::Time last_check_time_;
147  rclcpp::Duration checking_duration_{0, 0};
148  float max_collision_dist_, max_cost_;
149  bool reroute_on_collision_;
150  unsigned int check_resolution_{1u};
151  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber_;
152  std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap_{nullptr};
153 };
154 
155 } // namespace nav2_route
156 
157 #endif // NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__COLLISION_MONITOR_HPP_
A route operation to process a costmap to determine if a route is blocked requiring immediate rerouti...
RouteOperationType processType() override
Indication that the adjust speed limit route operation is performed on all state changes.
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.
virtual ~CollisionMonitor()=default
destructor
CollisionMonitor()=default
Constructor.
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 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