Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
dynamic_edges_scorer.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__EDGE_COST_FUNCTIONS__DYNAMIC_EDGES_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__DYNAMIC_EDGES_SCORER_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <unordered_map>
21 #include <set>
22 
23 #include "rclcpp/rclcpp.hpp"
24 #include "rclcpp_lifecycle/lifecycle_node.hpp"
25 #include "nav2_route/interfaces/edge_cost_function.hpp"
26 #include "nav2_msgs/srv/dynamic_edges.hpp"
27 #include "nav2_util/node_utils.hpp"
28 
29 namespace nav2_route
30 {
31 
38 {
39 public:
43  DynamicEdgesScorer() = default;
44 
48  virtual ~DynamicEdgesScorer() = default;
49 
53  void configure(
54  const rclcpp_lifecycle::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;
58 
66  bool score(
67  const EdgePtr edge, const RouteRequest & route_request,
68  const EdgeType & edge_type, float & cost) override;
69 
74  std::string getName() override;
75 
81  void closedEdgesCb(
82  const std::shared_ptr<nav2_msgs::srv::DynamicEdges::Request> request,
83  std::shared_ptr<nav2_msgs::srv::DynamicEdges::Response> response);
84 
85 protected:
86  rclcpp::Logger logger_{rclcpp::get_logger("DynamicEdgesScorer")};
87  std::string name_;
88  std::set<unsigned int> closed_edges_;
89  std::unordered_map<unsigned int, float> dynamic_penalties_;
90  rclcpp::Service<nav2_msgs::srv::DynamicEdges>::SharedPtr service_;
91 };
92 
93 } // namespace nav2_route
94 
95 #endif // NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__DYNAMIC_EDGES_SCORER_HPP_
Rejects edges that are in the closed set of edges for navigation to prevent routes from containing pa...
virtual ~DynamicEdgesScorer()=default
destructor
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 closedEdgesCb(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.
void configure(const rclcpp_lifecycle::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.
Definition: types.hpp:134
An object to store salient features of the route request including its start and goal node ids,...
Definition: types.hpp:224