15 #ifndef NAV2_ROUTE__INTERFACES__EDGE_COST_FUNCTION_HPP_
16 #define NAV2_ROUTE__INTERFACES__EDGE_COST_FUNCTION_HPP_
21 #include "tf2_ros/buffer.h"
22 #include "nav2_util/lifecycle_node.hpp"
23 #include "pluginlib/class_loader.hpp"
24 #include "nav2_route/types.hpp"
25 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "nav2_costmap_2d/costmap_subscriber.hpp"
41 using Ptr = std::shared_ptr<nav2_route::EdgeCostFunction>;
58 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
59 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
60 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
61 const std::string & name) = 0;
70 const EdgeType & edge_type,
float & cost) = 0;
A plugin interface to score edges during graph search to modify the lowest cost path (e....
virtual bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost)=0
Main scoring plugin API.
virtual void prepare()
Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests,...
virtual 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)=0
Configure the scorer, but do not store the node.
virtual std::string getName()=0
Get name of the plugin for parameter scope mapping.
virtual ~EdgeCostFunction()=default
Virtual destructor.
EdgeCostFunction()=default
Constructor.
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...