Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
edge_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__EDGE_SCORER_HPP_
16 #define NAV2_ROUTE__EDGE_SCORER_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <vector>
21 
22 #include "tf2_ros/buffer.hpp"
23 #include "pluginlib/class_loader.hpp"
24 #include "pluginlib/class_list_macros.hpp"
25 #include "nav2_ros_common/node_utils.hpp"
26 #include "nav2_ros_common/lifecycle_node.hpp"
27 #include "nav2_route/types.hpp"
28 #include "nav2_route/utils.hpp"
29 #include "nav2_route/interfaces/edge_cost_function.hpp"
30 #include "geometry_msgs/msg/pose_stamped.hpp"
31 namespace nav2_route
32 {
33 
46 {
47 public:
51  explicit EdgeScorer(
52  nav2::LifecycleNode::SharedPtr node,
53  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
54  const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber);
55 
59  ~EdgeScorer() = default;
60 
69  bool score(
70  const EdgePtr edge, const RouteRequest & route_request,
71  const EdgeType & edge_type,
72  float & score);
73 
78  int numPlugins() const;
79 
80 protected:
81  pluginlib::ClassLoader<EdgeCostFunction> plugin_loader_;
82  std::vector<EdgeCostFunction::Ptr> plugins_;
83 };
84 
85 } // namespace nav2_route
86 
87 #endif // NAV2_ROUTE__EDGE_SCORER_HPP_
An class to encapsulate edge scoring logic for plugins and different user specified algorithms to inf...
Definition: edge_scorer.hpp:46
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
~EdgeScorer()=default
Destructor.
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