Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
obstacles_critic.hpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
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__OBSTACLES_CRITIC_HPP_
16 #define NAV2_MPPI_CONTROLLER__CRITICS__OBSTACLES_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 #include "nav2_mppi_controller/critic_function.hpp"
24 #include "nav2_mppi_controller/models/state.hpp"
25 #include "nav2_mppi_controller/tools/utils.hpp"
26 
27 namespace mppi::critics
28 {
29 
38 {
39 public:
43  void initialize() override;
44 
50  void score(CriticData & data) override;
51 
52 protected:
58  inline bool inCollision(float cost) const;
59 
67  inline CollisionCost costAtPose(float x, float y, float theta);
68 
74  inline float distanceToObstacle(const CollisionCost & cost);
75 
83  float findCircumscribedCost(std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap);
84 
85 protected:
87  collision_checker_{nullptr};
88 
89  bool consider_footprint_{true};
90  float collision_cost_{0};
91  float inflation_scale_factor_{0}, inflation_radius_{0};
92 
93  float possible_collision_cost_;
94  float collision_margin_distance_;
95  float near_goal_distance_;
96  float circumscribed_cost_{0}, circumscribed_radius_{0};
97 
98  unsigned int power_{0};
99  float repulsion_weight_, critical_weight_{0};
100  bool enforce_path_inversion_{false};
101  std::string inflation_layer_name_;
102 };
103 
104 } // namespace mppi::critics
105 
106 #endif // NAV2_MPPI_CONTROLLER__CRITICS__OBSTACLES_CRITIC_HPP_
Abstract critic objective function to score trajectories.
bool inCollision(float cost) const
Checks if cost represents a collision.
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...
CollisionCost costAtPose(float x, float y, float theta)
cost at a robot pose
float distanceToObstacle(const CollisionCost &cost)
Distance to obstacle from cost.
void initialize() override
Initialize critic.
void score(CriticData &data) override
Evaluate cost related to obstacle avoidance.
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Definition: critic_data.hpp:40
Utility for storing cost information.