15 #ifndef NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__DISTANCE_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__DISTANCE_SCORER_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "rclcpp_lifecycle/lifecycle_node.hpp"
23 #include "nav2_route/interfaces/edge_cost_function.hpp"
24 #include "nav2_util/node_utils.hpp"
51 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
52 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
53 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
54 const std::string & name)
override;
65 const EdgeType & edge_type,
float & cost)
override;
75 std::string speed_tag_;
Scores edges by the distance traversed, weighted by speed limit metadata to optimize for time to goal...
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.
virtual ~DistanceScorer()=default
destructor
DistanceScorer()=default
Constructor.
std::string getName() override
Get name of the plugin for parameter scope mapping.
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
A plugin interface to score edges during graph search to modify the lowest cost path (e....
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...