Class CostCritic

Inheritance Relationships

Base Type

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

inline 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

inline 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 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

inline bool worldToMapFloat(float wx, float wy, unsigned int &mx, unsigned int &my) const

An implementation of worldToMap fully using floats.

Parameters:
  • wx – Float world X coord

  • wy – Float world Y coord

  • mx – unsigned int map X coord

  • my – unsigned into map Y coord

Returns:

if successsful

inline unsigned int getIndex(unsigned int mx, unsigned int my) const

A local implementation of getIndex.

Parameters:
  • mx – unsigned int map X coord

  • my – unsigned into map Y coord

Returns:

Index

Protected Attributes

nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D*> collision_checker_ = {nullptr}
float possible_collision_cost_
bool consider_footprint_ = {true}
bool is_tracking_unknown_ = {true}
float circumscribed_radius_ = {0.0f}
float circumscribed_cost_ = {0.0f}
float collision_cost_ = {0.0f}
float critical_cost_ = {0.0f}
float weight_ = {0}
unsigned int trajectory_point_step_
float origin_x_
float origin_y_
float resolution_
unsigned int size_x_
unsigned int size_y_
float near_goal_distance_
std::string inflation_layer_name_
unsigned int power_ = {0}