Class ObstaclesCritic

Inheritance Relationships

Base Type

Class Documentation

class ObstaclesCritic : public mppi::critics::CriticFunction

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) const

Checks if cost represents a collision.

Parameters:

cost – Costmap cost

Returns:

bool if in collision

inline CollisionCost costAtPose(float x, float y, float theta)

cost at a robot pose

Parameters:
  • x – X of pose

  • y – Y of pose

  • theta – theta of pose

Returns:

Collision information at pose

inline float distanceToObstacle(const CollisionCost &cost)

Distance to obstacle from cost.

Parameters:

cost – Costmap cost

Returns:

float Distance to the obstacle represented by cost

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

Protected Attributes

nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D*> collision_checker_ = {nullptr}
bool consider_footprint_ = {true}
float collision_cost_ = {0}
float inflation_scale_factor_ = {0}
float inflation_radius_ = {0}
float possibly_inscribed_cost_
float collision_margin_distance_
float near_goal_distance_
float circumscribed_cost_ = {0}
float circumscribed_radius_ = {0}
unsigned int power_ = {0}
float repulsion_weight_
float critical_weight_ = {0}