15 #ifndef NAV2_MPPI_CONTROLLER__CRITICS__OBSTACLES_CRITIC_HPP_
16 #define NAV2_MPPI_CONTROLLER__CRITICS__OBSTACLES_CRITIC_HPP_
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"
27 namespace mppi::critics
87 collision_checker_{
nullptr};
89 bool consider_footprint_{
true};
90 float collision_cost_{0};
91 float inflation_scale_factor_{0}, inflation_radius_{0};
93 float possible_collision_cost_;
94 float collision_margin_distance_;
95 float near_goal_distance_;
96 float circumscribed_cost_{0}, circumscribed_radius_{0};
98 unsigned int power_{0};
99 float repulsion_weight_, critical_weight_{0};
100 bool enforce_path_inversion_{
false};
101 std::string inflation_layer_name_;
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,...
Utility for storing cost information.