Class MapGridCritic

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public dwb_core::TrajectoryCritic

Derived Types

Class Documentation

class MapGridCritic : public dwb_core::TrajectoryCritic

breadth-first scoring of all the cells in the costmap

This TrajectoryCritic assigns a score to every cell in the costmap based on the distance to the cell from some set of source points. The cells corresponding with the source points are marked with some initial score, and then every other cell is updated with a score based on its relation to the closest source cell, based on a breadth-first exploration of the cells of the costmap.

This approach was chosen for computational efficiency, such that each trajectory need not be compared to the list of source points.

Subclassed by dwb_critics::GoalDistCritic, dwb_critics::PathDistCritic

Public Functions

void onInit() override
virtual double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
virtual void addCriticVisualization(std::vector<std::pair<std::string, std::vector<float>>> &cost_channels) override
inline double getScale() const override
virtual double scorePose(const geometry_msgs::msg::Pose2D &pose)

Retrieve the score for a single pose.

Parameters:

pose – The pose to score, assumed to be in the same frame as the costmap

Returns:

The score associated with the cell of the costmap where the pose lies

inline double getScore(unsigned int x, unsigned int y)

Retrieve the score for a particular cell of the costmap.

Parameters:
  • x – x-coordinate within the costmap

  • y – y-coordinate within the costmap

Returns:

the score associated with that cell.

void setAsObstacle(unsigned int index)

Sets the score of a particular cell to the obstacle cost.

Parameters:

index – Index of the cell to mark

Protected Types

enum class ScoreAggregationType

Separate modes for aggregating scores across the multiple poses in a trajectory.

Last returns the score associated with the last pose in the trajectory Sum returns the sum of all the scores Product returns the product of all the (non-zero) scores

Values:

enumerator Last
enumerator Sum
enumerator Product

Protected Functions

virtual void reset() override

Clear the queuDWB_CRITICS_MAP_GRID_He and set cell_values_ to the appropriate number of unreachableCellScore.

void propogateManhattanDistances()

Go through the queue and set the cells to the Manhattan distance from their parents.

Protected Attributes

std::shared_ptr<MapGridQueue> queue_
nav2_costmap_2d::Costmap2D *costmap_
std::vector<double> cell_values_
double obstacle_score_
double unreachable_score_

Special cell_values.

bool stop_on_failure_
ScoreAggregationType aggregationType_
class MapGridQueue : public costmap_queue::CostmapQueue

Subclass of CostmapQueue that avoids Obstacles and Unknown Values.

Public Functions

inline MapGridQueue(nav2_costmap_2d::Costmap2D &costmap, MapGridCritic &parent)
virtual ~MapGridQueue() = default
bool validCellToQueue(const costmap_queue::CellData &cell) override

Protected Attributes

MapGridCritic &parent_