Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
edge_cost_function.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__INTERFACES__EDGE_COST_FUNCTION_HPP_
16 #define NAV2_ROUTE__INTERFACES__EDGE_COST_FUNCTION_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "tf2_ros/buffer.h"
22 #include "nav2_util/lifecycle_node.hpp"
23 #include "pluginlib/class_loader.hpp"
24 #include "nav2_route/types.hpp"
25 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "nav2_costmap_2d/costmap_subscriber.hpp"
27 
28 namespace nav2_route
29 {
30 
39 {
40 public:
41  using Ptr = std::shared_ptr<nav2_route::EdgeCostFunction>;
42 
46  EdgeCostFunction() = default;
47 
51  virtual ~EdgeCostFunction() = default;
52 
57  virtual void configure(
58  const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
59  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
60  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
61  const std::string & name) = 0;
62 
68  virtual bool score(
69  const EdgePtr edge, const RouteRequest & route_request,
70  const EdgeType & edge_type, float & cost) = 0;
71 
76  virtual std::string getName() = 0;
77 
82  virtual void prepare() {}
83 };
84 
85 } // namespace nav2_route
86 
87 #endif // NAV2_ROUTE__INTERFACES__EDGE_COST_FUNCTION_HPP_
A plugin interface to score edges during graph search to modify the lowest cost path (e....
virtual bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost)=0
Main scoring plugin API.
virtual void prepare()
Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests,...
virtual 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)=0
Configure the scorer, but do not store the node.
virtual std::string getName()=0
Get name of the plugin for parameter scope mapping.
virtual ~EdgeCostFunction()=default
Virtual destructor.
EdgeCostFunction()=default
Constructor.
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