Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
costmap_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__COSTMAP_SCORER_HPP_
16 #define NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__COSTMAP_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/line_iterator.hpp"
25 #include "nav2_util/node_utils.hpp"
26 #include "nav2_costmap_2d/costmap_subscriber.hpp"
27 
28 namespace nav2_route
29 {
30 
37 {
38 public:
42  CostmapScorer() = default;
43 
47  virtual ~CostmapScorer() = default;
48 
52  void configure(
53  const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
54  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
55  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
56  const std::string & name) override;
57 
65  bool score(
66  const EdgePtr edge, const RouteRequest & route_request,
67  const EdgeType & edge_type, float & cost) override;
68 
73  std::string getName() override;
74 
79  void prepare() override;
80 
81 protected:
82  rclcpp::Logger logger_{rclcpp::get_logger("CostmapScorer")};
83  rclcpp::Clock::SharedPtr clock_;
84  std::string name_;
85  bool use_max_, invalid_on_collision_, invalid_off_map_;
86  float weight_, max_cost_;
87  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber_;
88  std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap_{nullptr};
89  unsigned int check_resolution_ {1u};
90 };
91 
92 } // namespace nav2_route
93 
94 #endif // NAV2_ROUTE__PLUGINS__EDGE_COST_FUNCTIONS__COSTMAP_SCORER_HPP_
Scores edges by the average or maximum cost found while iterating over the edge's line segment in the...
std::string getName() override
Get name of the plugin for parameter scope mapping.
void prepare() override
Prepare for a new cycle, by resetting state, grabbing data to use for all immediate requests,...
bool score(const EdgePtr edge, const RouteRequest &route_request, const EdgeType &edge_type, float &cost) override
Main scoring plugin API.
virtual ~CostmapScorer()=default
destructor
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.
CostmapScorer()=default
Constructor.
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