15 #ifndef NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__COSTMAP_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__COSTMAP_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/line_iterator.hpp"
25 #include "nav2_util/node_utils.hpp"
26 #include "nav2_costmap_2d/costmap_subscriber.hpp"
53 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
54 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
55 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
56 const std::string & name)
override;
67 const EdgeType & edge_type,
float & cost)
override;
82 rclcpp::Logger logger_{rclcpp::get_logger(
"CostmapScorer")};
83 rclcpp::Clock::SharedPtr clock_;
85 bool use_max_, invalid_on_collision_, invalid_off_map_;
86 float weight_, max_cost_;
87 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber_;
88 std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap_{
nullptr};
89 unsigned int check_resolution_ {1u};
Scores edges by the average or maximum cost found while iterating over the edge's line segment in the...
std::string getName() override
Get name of the plugin for parameter scope mapping.
void prepare() override
Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests,...
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
virtual ~CostmapScorer()=default
destructor
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.
CostmapScorer()=default
Constructor.
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,...