Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
penalty_scorer.cpp
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 #include <memory>
16 #include <string>
17 
18 #include "nav2_route/plugins/edge_cost_functions/penalty_scorer.hpp"
19 
20 namespace nav2_route
21 {
22 
24  const nav2::LifecycleNode::SharedPtr node,
25  const std::shared_ptr<tf2_ros::Buffer>/* tf_buffer */,
26  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>/* costmap_subscriber */,
27  const std::string & name)
28 {
29  RCLCPP_INFO(node->get_logger(), "Configuring penalty scorer.");
30  name_ = name;
31 
32  // Find the tag at high the speed limit information is stored
33  nav2::declare_parameter_if_not_declared(
34  node, getName() + ".penalty_tag", rclcpp::ParameterValue("penalty"));
35  penalty_tag_ = node->get_parameter(getName() + ".penalty_tag").as_string();
36 
37  // Find the proportional weight to apply, if multiple cost functions
38  nav2::declare_parameter_if_not_declared(
39  node, getName() + ".weight", rclcpp::ParameterValue(1.0));
40  weight_ = static_cast<float>(node->get_parameter(getName() + ".weight").as_double());
41 }
42 
44  const EdgePtr edge,
45  const RouteRequest & /* route_request */,
46  const EdgeType & /* edge_type */, float & cost)
47 {
48  // Get the speed limit, if set for an edge
49  float penalty_val = 0.0f;
50  penalty_val = edge->metadata.getValue<float>(penalty_tag_, penalty_val);
51  cost = weight_ * penalty_val;
52  return true;
53 }
54 
56 {
57  return name_;
58 }
59 
60 } // namespace nav2_route
61 
62 #include "pluginlib/class_list_macros.hpp"
A plugin interface to score edges during graph search to modify the lowest cost path (e....
Adjusts the score of an edge by an amount set as metadata in the graph.
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.
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.
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