Class EdgeCostFunction

Inheritance Relationships

Derived Types

Class Documentation

class EdgeCostFunction

A plugin interface to score edges during graph search to modify the lowest cost path (e.g. by distance, maximum speed, regions prefer not to travel blocked by occupancy, or using arbitrarily defined user metadata stored in the edge and nodes of interest.)

Subclassed by nav2_route::CostmapScorer, nav2_route::DistanceScorer, nav2_route::DynamicEdgesScorer, nav2_route::GoalOrientationScorer, nav2_route::PenaltyScorer, nav2_route::SemanticScorer, nav2_route::StartPoseOrientationScorer, nav2_route::TimeScorer

Public Types

using Ptr = std::shared_ptr<nav2_route::EdgeCostFunction>

Public Functions

EdgeCostFunction() = default

Constructor.

virtual ~EdgeCostFunction() = default

Virtual destructor.

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.

Parameters:

parent – pointer to user’s node

virtual bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) = 0

Main scoring plugin API.

Parameters:

edge – The edge pointer to score, which has access to the start/end nodes and their associated metadata and actions

virtual std::string getName() = 0

Get name of the plugin for parameter scope mapping.

Returns:

Name

inline virtual void prepare()

Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests, or otherwise prepare for scoring.