15 #ifndef NAV2_ROUTE__EDGE_SCORER_HPP_
16 #define NAV2_ROUTE__EDGE_SCORER_HPP_
22 #include "tf2_ros/buffer.h"
23 #include "pluginlib/class_loader.hpp"
24 #include "pluginlib/class_list_macros.hpp"
25 #include "nav2_util/node_utils.hpp"
26 #include "nav2_util/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"
52 rclcpp_lifecycle::LifecycleNode::SharedPtr node,
53 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
54 const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber);
71 const EdgeType & edge_type,
81 pluginlib::ClassLoader<EdgeCostFunction> plugin_loader_;
82 std::vector<EdgeCostFunction::Ptr> plugins_;
An class to encapsulate edge scoring logic for plugins and different user specified algorithms to inf...
int numPlugins() const
Provide the number of plugisn in the scorer loaded.
EdgeScorer(rclcpp_lifecycle::LifecycleNode::SharedPtr node, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber)
Constructor.
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &score)
Score the edge with the set of plugins.
~EdgeScorer()=default
Destructor.
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...