Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
dynamic_edges_scorer.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 #include <memory>
16 #include <string>
17 
18 #include "nav2_route/plugins/edge_cost_functions/dynamic_edges_scorer.hpp"
19 
20 namespace nav2_route
21 {
22 
24  const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
25  const std::shared_ptr<tf2_ros::Buffer>/* tf_buffer */,
26  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>/* costmap_subscriber */,
27  const std::string & name)
28 {
29  RCLCPP_INFO(node->get_logger(), "Configuring adjust edges scorer.");
30  name_ = name;
31  logger_ = node->get_logger();
32  service_ =
33  node->create_service<nav2_msgs::srv::DynamicEdges>(
34  std::string(node->get_name()) + "/" + getName() + "/adjust_edges", std::bind(
36  std::placeholders::_1, std::placeholders::_2));
37 
38  dynamic_penalties_.clear();
39  closed_edges_.clear();
40 }
41 
43  const std::shared_ptr<nav2_msgs::srv::DynamicEdges::Request> request,
44  std::shared_ptr<nav2_msgs::srv::DynamicEdges::Response> response)
45 {
46  RCLCPP_INFO(logger_, "Edge closure and cost adjustment in progress!");
47 
48  // Add new closed edges
49  for (unsigned int edge : request->closed_edges) {
50  closed_edges_.insert(edge);
51  }
52 
53  // Removed now opened edges, if stored
54  for (unsigned int edge : request->opened_edges) {
55  if (closed_edges_.find(edge) != closed_edges_.end()) {
56  closed_edges_.erase(edge);
57  }
58  }
59 
60  // Add dynamic costs from application system for edges
61  for (auto & edge : request->adjust_edges) {
62  dynamic_penalties_[edge.edgeid] = edge.cost;
63  }
64 
65  response->success = true;
66 }
67 
69  const EdgePtr edge,
70  const RouteRequest & /* route_request */,
71  const EdgeType & /* edge_type */, float & cost)
72 {
73  // Find if this edge is in the closed set of edges
74  if (closed_edges_.find(edge->edgeid) != closed_edges_.end()) {
75  return false;
76  }
77 
78  const auto & dyn_pen = dynamic_penalties_.find(edge->edgeid);
79  if (dyn_pen != dynamic_penalties_.end()) {
80  cost = dyn_pen->second;
81  }
82 
83  return true;
84 }
85 
87 {
88  return name_;
89 }
90 
91 } // namespace nav2_route
92 
93 #include "pluginlib/class_list_macros.hpp"
Rejects edges that are in the closed set of edges for navigation to prevent routes from containing pa...
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.
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