Nav2 Navigation Stack - kilted  kilted
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 "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"
26 
27 namespace nav2_route
28 {
29 
36 {
37 public:
41  SemanticScorer() = default;
42 
46  virtual ~SemanticScorer() = default;
47 
51  void configure(
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;
56 
64  bool score(
65  const EdgePtr edge, const RouteRequest & route_request,
66  const EdgeType & edge_type, float & cost) override;
67 
73  void metadataValueScorer(Metadata & mdata, float & score);
74 
80  void metadataKeyScorer(Metadata & mdata, float & score);
81 
86  std::string getName() override;
87 
88 protected:
89  std::string name_, key_;
90  std::unordered_map<std::string, float> semantic_info_;
91  float weight_;
92 };
93 
94 } // namespace nav2_route
95 
96 #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.
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.
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