15 #ifndef NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__PENALTY_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__PENALTY_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"
49 const nav2::LifecycleNode::SharedPtr node,
50 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
51 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
52 const std::string & name)
override;
63 const EdgeType & edge_type,
float & cost)
override;
73 std::string penalty_tag_;
A plugin interface to score edges during graph search to modify the lowest cost path (e....
Adjusts the score of an edge by an amount set as metadata in the graph.
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.
PenaltyScorer()=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.
virtual ~PenaltyScorer()=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,...