Nav2 Navigation Stack - humble  humble
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 "nav2_util/lifecycle_node.hpp"
22 #include "nav2_route/interfaces/edge_cost_function.hpp"
23 #include "nav2_util/line_iterator.hpp"
24 #include "nav2_util/node_utils.hpp"
25 #include "nav2_costmap_2d/costmap_subscriber.hpp"
26 
27 namespace nav2_route
28 {
29 
36 {
37 public:
41  CostmapScorer() = default;
42 
46  virtual ~CostmapScorer() = 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 
72  std::string getName() override;
73 
78  void prepare() override;
79 
80 protected:
81  rclcpp::Logger logger_{rclcpp::get_logger("CostmapScorer")};
82  rclcpp::Clock::SharedPtr clock_;
83  std::string name_;
84  bool use_max_, invalid_on_collision_, invalid_off_map_;
85  float weight_, max_cost_;
86  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber_;
87  std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap_{nullptr};
88  unsigned int check_resolution_ {1u};
89 };
90 
91 } // namespace nav2_route
92 
93 #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