Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_route::EdgeScorer Class Reference

An class to encapsulate edge scoring logic for plugins and different user specified algorithms to influence graph search. It has access to the edge, which in turn has access to the parent and child node of the connection. It also contains action and arbitrary user-defined metadata to enable edge scoring logic based on arbitrary properties of the graph you select (e.g. some regions have a multiplier, some actions are discouraged with higher costs like having to go through a door, edges with reduced speed limits are proportionally less preferred for optimality relative to the distance the edge represents to optimize time to goal) More...

#include <nav2_route/include/nav2_route/edge_scorer.hpp>

Public Member Functions

 EdgeScorer (rclcpp_lifecycle::LifecycleNode::SharedPtr node, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber)
 Constructor.
 
 ~EdgeScorer ()=default
 Destructor.
 
bool score (const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &score)
 Score the edge with the set of plugins. More...
 
int numPlugins () const
 Provide the number of plugisn in the scorer loaded. More...
 

Protected Attributes

pluginlib::ClassLoader< EdgeCostFunctionplugin_loader_
 
std::vector< EdgeCostFunction::Ptr > plugins_
 

Detailed Description

An class to encapsulate edge scoring logic for plugins and different user specified algorithms to influence graph search. It has access to the edge, which in turn has access to the parent and child node of the connection. It also contains action and arbitrary user-defined metadata to enable edge scoring logic based on arbitrary properties of the graph you select (e.g. some regions have a multiplier, some actions are discouraged with higher costs like having to go through a door, edges with reduced speed limits are proportionally less preferred for optimality relative to the distance the edge represents to optimize time to goal)

Definition at line 45 of file edge_scorer.hpp.

Member Function Documentation

◆ numPlugins()

int nav2_route::EdgeScorer::numPlugins ( ) const

Provide the number of plugisn in the scorer loaded.

Returns
Number of scoring plugins

Definition at line 89 of file edge_scorer.cpp.

◆ score()

bool nav2_route::EdgeScorer::score ( const EdgePtr  edge,
const RouteRequest route_request,
const EdgeType &  edge_type,
float &  score 
)

Score the edge with the set of plugins.

Parameters
edgePtr to edge for scoring
goal_posePose Stamped of desired goal
scoreof edge
final_edgewhether this edge brings us to the goal or not
Returns
If edge is valid

Definition at line 66 of file edge_scorer.cpp.


The documentation for this class was generated from the following files: