Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
cost_critic.hpp
1 // Copyright (c) 2023 Robocc Brice Renaudeau
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_MPPI_CONTROLLER__CRITICS__COST_CRITIC_HPP_
16 #define NAV2_MPPI_CONTROLLER__CRITICS__COST_CRITIC_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
22 #include "nav2_costmap_2d/inflation_layer.hpp"
23 
24 #include "nav2_mppi_controller/critic_function.hpp"
25 #include "nav2_mppi_controller/models/state.hpp"
26 #include "nav2_mppi_controller/tools/utils.hpp"
27 
28 namespace mppi::critics
29 {
30 
35 class CostCritic : public CriticFunction
36 {
37 public:
41  void initialize() override;
42 
48  void score(CriticData & data) override;
49 
50 protected:
59  bool inCollision(float cost, float x, float y, float theta);
60 
67  float costAtPose(float x, float y);
68 
76  float findCircumscribedCost(std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap);
77 
78 protected:
80  collision_checker_{nullptr};
81  float possibly_inscribed_cost_;
82 
83  bool consider_footprint_{true};
84  float circumscribed_radius_{0};
85  float circumscribed_cost_{0};
86  float collision_cost_{0};
87  float critical_cost_{0};
88  float weight_{0};
89 
90  float near_goal_distance_;
91  std::string inflation_layer_name_;
92 
93  unsigned int power_{0};
94 };
95 
96 } // namespace mppi::critics
97 
98 #endif // NAV2_MPPI_CONTROLLER__CRITICS__COST_CRITIC_HPP_
Critic objective function for avoiding obstacles using costmap's inflated cost.
Definition: cost_critic.hpp:36
bool inCollision(float cost, float x, float y, float theta)
Checks if cost represents a collision.
float costAtPose(float x, float y)
cost at a robot pose
float findCircumscribedCost(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap)
Find the min cost of the inflation decay function for which the robot MAY be in collision in any orie...
Definition: cost_critic.cpp:76
void initialize() override
Initialize critic.
Definition: cost_critic.cpp:23
void score(CriticData &data) override
Evaluate cost related to obstacle avoidance.
Abstract critic objective function to score trajectories.
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Definition: critic_data.hpp:39