15 #ifndef NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__DYNAMIC_EDGES_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__DYNAMIC_EDGES_SCORER_HPP_
20 #include <unordered_map>
23 #include "nav2_ros_common/lifecycle_node.hpp"
24 #include "nav2_route/interfaces/edge_cost_function.hpp"
25 #include "nav2_msgs/srv/dynamic_edges.hpp"
26 #include "nav2_ros_common/node_utils.hpp"
27 #include "nav2_ros_common/service_server.hpp"
54 const nav2::LifecycleNode::SharedPtr node,
55 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
56 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
57 const std::string & name)
override;
68 const EdgeType & edge_type,
float & cost)
override;
82 const std::shared_ptr<rmw_request_id_t> request_header,
83 const std::shared_ptr<nav2_msgs::srv::DynamicEdges::Request> request,
84 std::shared_ptr<nav2_msgs::srv::DynamicEdges::Response> response);
87 rclcpp::Logger logger_{rclcpp::get_logger(
"DynamicEdgesScorer")};
89 std::set<unsigned int> closed_edges_;
90 std::unordered_map<unsigned int, float> dynamic_penalties_;
91 nav2::ServiceServer<nav2_msgs::srv::DynamicEdges>::SharedPtr service_;
Rejects edges that are in the closed set of edges for navigation to prevent routes from containing pa...
virtual ~DynamicEdgesScorer()=default
destructor
void closedEdgesCb(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::DynamicEdges::Request > request, std::shared_ptr< nav2_msgs::srv::DynamicEdges::Response > response)
Service callback to process edge changes.
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
std::string getName() override
Get name of the plugin for parameter scope mapping.
void configure(const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override
Configure.
DynamicEdgesScorer()=default
Constructor.
A plugin interface to score edges during graph search to modify the lowest cost path (e....
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...