15 #ifndef NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__COLLISION_MONITOR_HPP_
16 #define NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__COLLISION_MONITOR_HPP_
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_util/node_utils.hpp"
29 #include "nav2_core/route_exceptions.hpp"
48 unsigned int x0, y0, x1, y1;
65 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
66 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
67 const std::string & name)
override;
73 std::string
getName()
override {
return name_;}
80 RouteOperationType
processType()
override {
return RouteOperationType::ON_QUERY;}
98 const geometry_msgs::msg::PoseStamped & curr_pose,
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};
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 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.
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.
An object representing edges between nodes.
An object to store the nodes in the graph file.
a struct to hold return from an operation
An ordered set of nodes and edges corresponding to the planned route.