Nav2 Navigation Stack - humble  humble
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 "nav2_costmap_2d/footprint_collision_checker.hpp"
20 #include "nav2_costmap_2d/inflation_layer.hpp"
21 
22 #include "nav2_mppi_controller/critic_function.hpp"
23 #include "nav2_mppi_controller/models/state.hpp"
24 #include "nav2_mppi_controller/tools/utils.hpp"
25 
26 namespace mppi::critics
27 {
28 
37 {
38 public:
42  void initialize() override;
43 
49  void score(CriticData & data) override;
50 
51 protected:
57  inline bool inCollision(float cost) const;
58 
66  inline CollisionCost costAtPose(float x, float y, float theta);
67 
73  inline float distanceToObstacle(const CollisionCost & cost);
74 
82  float findCircumscribedCost(std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap);
83 
84 protected:
86  collision_checker_{nullptr};
87 
88  bool consider_footprint_{true};
89  float collision_cost_{0};
90  float inflation_scale_factor_{0}, inflation_radius_{0};
91 
92  float possibly_inscribed_cost_;
93  float collision_margin_distance_;
94  float near_goal_distance_;
95  float circumscribed_cost_{0}, circumscribed_radius_{0};
96 
97  unsigned int power_{0};
98  float repulsion_weight_, critical_weight_{0};
99 };
100 
101 } // namespace mppi::critics
102 
103 #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:39
Utility for storing cost information.