Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
edge_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 
16 #include <string>
17 #include <memory>
18 #include <vector>
19 
20 #include "nav2_route/edge_scorer.hpp"
21 
22 namespace nav2_route
23 {
24 
26  nav2::LifecycleNode::SharedPtr node,
27  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
28  const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber)
29 : plugin_loader_("nav2_route", "nav2_route::EdgeCostFunction")
30 {
31  // load plugins with a default of the DistanceScorer
32  const std::vector<std::string> default_plugin_ids({"DistanceScorer", "DynamicEdgesScorer"});
33  const std::vector<std::string> default_plugin_types(
34  {"nav2_route::DistanceScorer", "nav2_route::DynamicEdgesScorer"});
35 
36  nav2::declare_parameter_if_not_declared(
37  node, "edge_cost_functions", rclcpp::ParameterValue(default_plugin_ids));
38  auto edge_cost_function_ids = node->get_parameter("edge_cost_functions").as_string_array();
39 
40  if (edge_cost_function_ids == default_plugin_ids) {
41  for (unsigned int i = 0; i != edge_cost_function_ids.size(); i++) {
42  nav2::declare_parameter_if_not_declared(
43  node, default_plugin_ids[i] + ".plugin", rclcpp::ParameterValue(default_plugin_types[i]));
44  }
45  }
46 
47  for (size_t i = 0; i != edge_cost_function_ids.size(); i++) {
48  try {
49  std::string type = nav2::get_plugin_type_param(
50  node, edge_cost_function_ids[i]);
51  EdgeCostFunction::Ptr scorer = plugin_loader_.createUniqueInstance(type);
52  RCLCPP_INFO(
53  node->get_logger(), "Created edge cost function plugin %s of type %s",
54  edge_cost_function_ids[i].c_str(), type.c_str());
55  scorer->configure(node, tf_buffer, costmap_subscriber, edge_cost_function_ids[i]);
56  plugins_.push_back(std::move(scorer));
57  } catch (const pluginlib::PluginlibException & ex) {
58  RCLCPP_FATAL(
59  node->get_logger(),
60  "Failed to create edge cost function. Exception: %s", ex.what());
61  throw ex;
62  }
63  }
64 }
65 
67  const EdgePtr edge, const RouteRequest & route_request,
68  const EdgeType & edge_type, float & total_score)
69 {
70  total_score = 0.0;
71  float curr_score = 0.0;
72 
73  for (auto & plugin : plugins_) {
74  plugin->prepare();
75  }
76 
77  for (auto & plugin : plugins_) {
78  curr_score = 0.0;
79  if (plugin->score(edge, route_request, edge_type, curr_score)) {
80  total_score += curr_score;
81  } else {
82  return false;
83  }
84  }
85 
86  return true;
87 }
88 
90 {
91  return plugins_.size();
92 }
93 
94 } // namespace nav2_route
int numPlugins() const
Provide the number of plugisn in the scorer loaded.
Definition: edge_scorer.cpp:89
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &score)
Score the edge with the set of plugins.
Definition: edge_scorer.cpp:66
EdgeScorer(nav2::LifecycleNode::SharedPtr node, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber)
Constructor.
Definition: edge_scorer.cpp:25
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