15 #ifndef NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__SEMANTIC_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__SEMANTIC_SCORER_HPP_
20 #include <unordered_map>
22 #include "rclcpp/rclcpp.hpp"
23 #include "rclcpp_lifecycle/lifecycle_node.hpp"
24 #include "nav2_route/interfaces/edge_cost_function.hpp"
25 #include "nav2_util/node_utils.hpp"
52 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
53 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
54 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
55 const std::string & name)
override;
66 const EdgeType & edge_type,
float & cost)
override;
89 std::string name_, key_;
90 std::unordered_map<std::string, float> semantic_info_;
A plugin interface to score edges during graph search to modify the lowest cost path (e....
Scores an edge based on arbitrary graph semantic data such as set priority/danger levels or regional ...
void metadataValueScorer(Metadata &mdata, float &score)
Scores graph object based on metadata's semantic value at key.
SemanticScorer()=default
Constructor.
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.
std::string getName() override
Get name of the plugin for parameter scope mapping.
virtual ~SemanticScorer()=default
destructor
void metadataKeyScorer(Metadata &mdata, float &score)
Scores graph object based on metadata's key values.
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
An object representing edges between nodes.
An object to store salient features of the route request including its start and goal node ids,...