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 inline bool inCollision(
float cost,
float x,
float y,
float theta)
62 float score_cost = cost;
63 if (consider_footprint_ &&
64 (cost >= possible_collision_cost_ || possible_collision_cost_ < 1.0f))
67 static_cast<double>(x),
static_cast<double>(y),
static_cast<double>(theta),
68 costmap_ros_->getRobotFootprint()));
71 switch (
static_cast<unsigned char>(score_cost)) {
72 case (nav2_costmap_2d::LETHAL_OBSTACLE):
74 case (nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE):
75 return consider_footprint_ ? false :
true;
76 case (nav2_costmap_2d::NO_INFORMATION):
77 return is_tracking_unknown_ ? false :
true;
100 inline bool worldToMapFloat(
float wx,
float wy,
unsigned int & mx,
unsigned int & my)
const
102 if (wx < origin_x_ || wy < origin_y_) {
106 mx =
static_cast<unsigned int>((wx - origin_x_) / resolution_);
107 my =
static_cast<unsigned int>((wy - origin_y_) / resolution_);
109 if (mx < size_x_ && my < size_y_) {
121 inline unsigned int getIndex(
unsigned int mx,
unsigned int my)
const
123 return my * size_x_ + mx;
127 collision_checker_{
nullptr};
128 float possible_collision_cost_;
130 bool consider_footprint_{
true};
131 bool is_tracking_unknown_{
true};
132 float circumscribed_radius_{0.0f};
133 float circumscribed_cost_{0.0f};
134 float collision_cost_{0.0f};
135 float critical_cost_{0.0f};
136 unsigned int near_collision_cost_{253};
138 unsigned int trajectory_point_step_;
140 float origin_x_, origin_y_, resolution_;
141 unsigned int size_x_, size_y_;
143 float near_goal_distance_;
144 std::string inflation_layer_name_;
146 unsigned int power_{0};
Critic objective function for avoiding obstacles using costmap's inflated cost.
bool worldToMapFloat(float wx, float wy, unsigned int &mx, unsigned int &my) const
An implementation of worldToMap fully using floats.
unsigned int getIndex(unsigned int mx, unsigned int my) const
A local implementation of getIndex.
bool inCollision(float cost, float x, float y, float theta)
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...
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,...