Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
distance_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__DISTANCE_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__DISTANCE_SCORER_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "rclcpp_lifecycle/lifecycle_node.hpp"
23 #include "nav2_route/interfaces/edge_cost_function.hpp"
24 #include "nav2_util/node_utils.hpp"
25 
26 namespace nav2_route
27 {
28 
35 {
36 public:
40  DistanceScorer() = default;
41 
45  virtual ~DistanceScorer() = default;
46 
50  void configure(
51  const rclcpp_lifecycle::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 
71  std::string getName() override;
72 
73 protected:
74  std::string name_;
75  std::string speed_tag_;
76  float weight_;
77 };
78 
79 } // namespace nav2_route
80 
81 #endif // NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__DISTANCE_SCORER_HPP_
Scores edges by the distance traversed, weighted by speed limit metadata to optimize for time to goal...
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.
virtual ~DistanceScorer()=default
destructor
DistanceScorer()=default
Constructor.
std::string getName() override
Get name of the plugin for parameter scope mapping.
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
A plugin interface to score edges during graph search to modify the lowest cost path (e....
An object representing edges between nodes.
Definition: types.hpp:134
An object to store salient features of the route request including its start and goal node ids,...
Definition: types.hpp:224