15 #ifndef NAV2_MPPI_CONTROLLER__CRITICS__COST_CRITIC_HPP_
16 #define NAV2_MPPI_CONTROLLER__CRITICS__COST_CRITIC_HPP_
21 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
22 #include "nav2_costmap_2d/inflation_layer.hpp"
24 #include "nav2_mppi_controller/critic_function.hpp"
25 #include "nav2_mppi_controller/models/state.hpp"
26 #include "nav2_mppi_controller/tools/utils.hpp"
28 namespace mppi::critics
59 bool inCollision(
float cost,
float x,
float y,
float theta);
80 collision_checker_{
nullptr};
81 float possibly_inscribed_cost_;
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};
90 float near_goal_distance_;
91 std::string inflation_layer_name_;
93 unsigned int power_{0};
Critic objective function for avoiding obstacles using costmap's inflated cost.
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...
void initialize() override
Initialize critic.
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,...