|
Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Scores an edge based on arbitrary graph semantic data such as set priority/danger levels or regional attributes (e.g. living room, bathroom, work cell 2) More...
#include <nav2_route/include/nav2_route/plugins/edge_cost_functions/semantic_scorer.hpp>


Public Member Functions | |
| SemanticScorer ()=default | |
| Constructor. | |
| virtual | ~SemanticScorer ()=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... | |
| void | metadataValueScorer (Metadata &mdata, float &score) |
| Scores graph object based on metadata's semantic value at key. More... | |
| void | metadataKeyScorer (Metadata &mdata, float &score) |
| Scores graph object based on metadata's key values. More... | |
| std::string | getName () override |
| Get name of the plugin for parameter scope mapping. More... | |
Public Member Functions inherited from nav2_route::EdgeCostFunction | |
| EdgeCostFunction ()=default | |
| Constructor. | |
| virtual | ~EdgeCostFunction ()=default |
| Virtual destructor. | |
| virtual void | prepare () |
| Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests, or otherwise prepare for scoring. | |
Protected Attributes | |
| std::string | name_ |
| std::string | key_ |
| std::unordered_map< std::string, float > | semantic_info_ |
| float | weight_ |
Additional Inherited Members | |
Public Types inherited from nav2_route::EdgeCostFunction | |
| using | Ptr = std::shared_ptr< nav2_route::EdgeCostFunction > |
Scores an edge based on arbitrary graph semantic data such as set priority/danger levels or regional attributes (e.g. living room, bathroom, work cell 2)
Definition at line 35 of file semantic_scorer.hpp.
|
overridevirtual |
Get name of the plugin for parameter scope mapping.
Implements nav2_route::EdgeCostFunction.
Definition at line 97 of file semantic_scorer.cpp.
Referenced by configure().

| void nav2_route::SemanticScorer::metadataKeyScorer | ( | Metadata & | mdata, |
| float & | score | ||
| ) |
Scores graph object based on metadata's key values.
| mdata | Metadata |
| score | to add to |
Definition at line 56 of file semantic_scorer.cpp.
References score().
Referenced by score().


| void nav2_route::SemanticScorer::metadataValueScorer | ( | Metadata & | mdata, |
| float & | score | ||
| ) |
Scores graph object based on metadata's semantic value at key.
| mdata | Metadata |
| score | to add to |
Definition at line 65 of file semantic_scorer.cpp.
References score().
Referenced by score().


|
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 74 of file semantic_scorer.cpp.
References metadataKeyScorer(), and metadataValueScorer().
Referenced by metadataKeyScorer(), and metadataValueScorer().

