Class ObstacleFootprintCritic

Inheritance Relationships

Base Type

Class Documentation

class ObstacleFootprintCritic : public dwb_critics::BaseObstacleCritic

Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory.

Internally, this technically only checks if the border of the footprint collides with anything for computational efficiency. This is valid if the obstacles in the local costmap are inflated.

A more robust class could check every cell within the robot’s footprint without inflating the obstacles, at some computational cost. That is left as an excercise to the reader.

Public Functions

virtual bool prepare(const geometry_msgs::msg::Pose2D &pose, const nav_2d_msgs::msg::Twist2D &vel, const geometry_msgs::msg::Pose2D &goal, const nav_2d_msgs::msg::Path2D &global_plan) override
virtual double scorePose(const geometry_msgs::msg::Pose2D &pose) override

Return the obstacle score for a particular pose.

Parameters:

pose – Pose to check

virtual double scorePose(const geometry_msgs::msg::Pose2D &pose, const Footprint &oriented_footprint)
inline double getScale() const override

Protected Functions

double lineCost(int x0, int x1, int y0, int y1)

Rasterizes a line in the costmap grid and checks for collisions.

Parameters:
  • x0 – The x position of the first cell in grid coordinates

  • y0 – The y position of the first cell in grid coordinates

  • x1 – The x position of the second cell in grid coordinates

  • y1 – The y position of the second cell in grid coordinates

Returns:

A positive cost for a legal line… negative otherwise

double pointCost(int x, int y)

Checks the cost of a point in the costmap.

Parameters:
  • x – The x position of the point in cell coordinates

  • y – The y position of the point in cell coordinates

Returns:

A positive cost for a legal point… negative otherwise

Protected Attributes

Footprint footprint_spec_