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

Scores edges by the average or maximum cost found while iterating over the edge's line segment in the global costmap. More...

#include <nav2_route/include/nav2_route/plugins/edge_cost_functions/costmap_scorer.hpp>

Inheritance diagram for nav2_route::CostmapScorer:
Inheritance graph
[legend]
Collaboration diagram for nav2_route::CostmapScorer:
Collaboration graph
[legend]

Public Member Functions

 CostmapScorer ()=default
 Constructor.
 
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.
 
bool score (const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
 Main scoring plugin API. More...
 
std::string getName () override
 Get name of the plugin for parameter scope mapping. More...
 
void prepare () override
 Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests, or otherwise prepare for scoring.
 
- Public Member Functions inherited from nav2_route::EdgeCostFunction
 EdgeCostFunction ()=default
 Constructor.
 
virtual ~EdgeCostFunction ()=default
 Virtual destructor.
 

Protected Attributes

rclcpp::Logger logger_ {rclcpp::get_logger("CostmapScorer")}
 
rclcpp::Clock::SharedPtr clock_
 
std::string name_
 
bool use_max_
 
bool invalid_on_collision_
 
bool invalid_off_map_
 
float weight_
 
float max_cost_
 
std::shared_ptr< nav2_costmap_2d::CostmapSubscribercostmap_subscriber_
 
std::shared_ptr< nav2_costmap_2d::Costmap2Dcostmap_ {nullptr}
 
unsigned int check_resolution_ {1u}
 

Additional Inherited Members

- Public Types inherited from nav2_route::EdgeCostFunction
using Ptr = std::shared_ptr< nav2_route::EdgeCostFunction >
 

Detailed Description

Scores edges by the average or maximum cost found while iterating over the edge's line segment in the global costmap.

Definition at line 35 of file costmap_scorer.hpp.

Member Function Documentation

◆ getName()

std::string nav2_route::CostmapScorer::getName ( )
overridevirtual

Get name of the plugin for parameter scope mapping.

Returns
Name

Implements nav2_route::EdgeCostFunction.

Definition at line 145 of file costmap_scorer.cpp.

Referenced by configure().

Here is the caller graph for this function:

◆ score()

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

Main scoring plugin API.

Parameters
edgeThe edge pointer to score, which has access to the start/end nodes and their associated metadata and actions
costof the edge scored
Returns
bool if this edge is open valid to traverse

Implements nav2_route::EdgeCostFunction.

Definition at line 95 of file costmap_scorer.cpp.

References nav2_util::LineIterator::isValid().

Here is the call graph for this function:

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