15 #ifndef NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__TIME_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__TIME_SCORER_HPP_
21 #include "nav2_ros_common/lifecycle_node.hpp"
22 #include "nav2_route/interfaces/edge_cost_function.hpp"
23 #include "nav2_ros_common/node_utils.hpp"
51 const nav2::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_, prev_time_tag_;
76 float weight_, max_vel_;
A plugin interface to score edges during graph search to modify the lowest cost path (e....
Scores edges by the time to traverse an edge. It uses previous times to navigate the edge primarily,...
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
TimeScorer()=default
Constructor.
void configure(const nav2::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 ~TimeScorer()=default
destructor
std::string getName() override
Get name of the plugin for parameter scope mapping.
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...