Class CostCritic
Defined in File cost_critic.hpp
Inheritance Relationships
Base Type
public mppi::critics::CriticFunction
(Class CriticFunction)
Class Documentation
-
class CostCritic : public mppi::critics::CriticFunction
Critic objective function for avoiding obstacles using costmap’s inflated cost.
Public Functions
-
virtual void initialize() override
Initialize critic.
-
virtual void score(CriticData &data) override
Evaluate cost related to obstacle avoidance.
- Parameters:
costs – [out] add obstacle cost values to this tensor
Protected Functions
-
bool inCollision(float cost, float x, float y, float theta)
Checks if cost represents a collision.
- Parameters:
cost – Point cost at pose center
x – X of pose
y – Y of pose
theta – theta of pose
- Returns:
bool if in collision
-
float costAtPose(float x, float y)
cost at a robot pose
- Parameters:
x – X of pose
y – Y of pose
- Returns:
Collision information at pose
Find the min cost of the inflation decay function for which the robot MAY be in collision in any orientation.
- Parameters:
costmap – Costmap2DROS to get minimum inscribed cost (e.g. 128 in inflation layer documentation)
- Returns:
double circumscribed cost, any higher than this and need to do full footprint collision checking since some element of the robot could be in collision
Protected Attributes
-
nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D*> collision_checker_ = {nullptr}
-
float possibly_inscribed_cost_
-
bool consider_footprint_ = {true}
-
float circumscribed_radius_ = {0}
-
float circumscribed_cost_ = {0}
-
float collision_cost_ = {0}
-
float critical_cost_ = {0}
-
float weight_ = {0}
-
float near_goal_distance_
-
std::string inflation_layer_name_
-
unsigned int power_ = {0}
-
virtual void initialize() override