Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
semantic_scorer.hpp
1 // Copyright (c) 2025 Open Navigation LLC
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__SEMANTIC_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__SEMANTIC_SCORER_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <unordered_map>
21 
22 #include "nav2_ros_common/lifecycle_node.hpp"
23 #include "nav2_route/interfaces/edge_cost_function.hpp"
24 #include "nav2_ros_common/node_utils.hpp"
25 
26 namespace nav2_route
27 {
28 
35 {
36 public:
40  SemanticScorer() = default;
41 
45  virtual ~SemanticScorer() = default;
46 
50  void configure(
51  const nav2::LifecycleNode::SharedPtr node,
52  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
53  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
54  const std::string & name) override;
55 
63  bool score(
64  const EdgePtr edge, const RouteRequest & route_request,
65  const EdgeType & edge_type, float & cost) override;
66 
72  void metadataValueScorer(Metadata & mdata, float & score);
73 
79  void metadataKeyScorer(Metadata & mdata, float & score);
80 
85  std::string getName() override;
86 
87 protected:
88  std::string name_, key_;
89  std::unordered_map<std::string, float> semantic_info_;
90  float weight_;
91 };
92 
93 } // namespace nav2_route
94 
95 #endif // NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__SEMANTIC_SCORER_HPP_
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.
void configure(const nav2::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.
SemanticScorer()=default
Constructor.
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.
Definition: types.hpp:134
An object to store arbitrary metadata regarding nodes from the graph file.
Definition: types.hpp:35
An object to store salient features of the route request including its start and goal node ids,...
Definition: types.hpp:224