|
Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
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>


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::CostmapSubscriber > | costmap_subscriber_ |
| std::shared_ptr< nav2_costmap_2d::Costmap2D > | costmap_ {nullptr} |
| unsigned int | check_resolution_ {1u} |
Additional Inherited Members | |
Public Types inherited from nav2_route::EdgeCostFunction | |
| using | Ptr = std::shared_ptr< nav2_route::EdgeCostFunction > |
Scores edges by the average or maximum cost found while iterating over the edge's line segment in the global costmap.
Definition at line 36 of file costmap_scorer.hpp.
|
overridevirtual |
Get name of the plugin for parameter scope mapping.
Implements nav2_route::EdgeCostFunction.
Definition at line 144 of file costmap_scorer.cpp.
Referenced by configure().

|
overridevirtual |
Main scoring plugin API.
| edge | The edge pointer to score, which has access to the start/end nodes and their associated metadata and actions |
| cost | of the edge scored |
Implements nav2_route::EdgeCostFunction.
Definition at line 94 of file costmap_scorer.cpp.
References nav2_util::LineIterator::isValid().
