breadth-first scoring of all the cells in the costmap More...
#include <map_grid.h>
Classes | |
class | MapGridQueue |
Subclass of CostmapQueue that avoids Obstacles and Unknown Values. More... | |
Public Member Functions | |
void | addCriticVisualization (sensor_msgs::PointCloud &pc) override |
double | getScale () const override |
double | getScore (unsigned int x, unsigned int y) |
Retrieve the score for a particular cell of the costmap. | |
MapGridCritic () | |
void | onInit () override |
virtual double | scorePose (const geometry_msgs::Pose2D &pose) |
Retrieve the score for a single pose. | |
double | scoreTrajectory (const dwb_msgs::Trajectory2D &traj) override |
void | setAsObstacle (unsigned int x, unsigned int y) |
Sets the score of a particular cell to the obstacle cost. | |
Protected Types | |
enum | ScoreAggregationType { Last, Sum, Product } |
Separate modes for aggregating scores across the multiple poses in a trajectory. More... | |
Protected Member Functions | |
void | propogateManhattanDistances () |
Go through the queue and set the cells to the Manhattan distance from their parents. | |
void | reset () override |
Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore. | |
Protected Attributes | |
ScoreAggregationType | aggregationType_ |
nav_grid::VectorNavGrid< double > | cell_values_ |
double | obstacle_score_ |
std::shared_ptr< MapGridQueue > | queue_ |
bool | stop_on_failure_ |
double | unreachable_score_ |
Special cell_values. |
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.
Definition at line 57 of file map_grid.h.
enum dwb_critics::MapGridCritic::ScoreAggregationType [protected] |
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
Definition at line 99 of file map_grid.h.
dwb_critics::MapGridCritic::MapGridCritic | ( | ) | [inline] |
Definition at line 60 of file map_grid.h.
void dwb_critics::MapGridCritic::addCriticVisualization | ( | sensor_msgs::PointCloud & | pc | ) | [override, virtual] |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 180 of file map_grid.cpp.
double dwb_critics::MapGridCritic::getScale | ( | ) | const [inline, override, virtual] |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Reimplemented in dwb_critics::PathAlignCritic.
Definition at line 66 of file map_grid.h.
double dwb_critics::MapGridCritic::getScore | ( | unsigned int | x, |
unsigned int | y | ||
) | [inline] |
Retrieve the score for a particular cell of the costmap.
x | x-coordinate within the costmap |
y | y-coordinate within the costmap |
Definition at line 82 of file map_grid.h.
void dwb_critics::MapGridCritic::onInit | ( | ) | [override, virtual] |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Reimplemented in dwb_critics::PathAlignCritic, and dwb_critics::GoalAlignCritic.
Definition at line 59 of file map_grid.cpp.
void dwb_critics::MapGridCritic::propogateManhattanDistances | ( | ) | [protected] |
Go through the queue and set the cells to the Manhattan distance from their parents.
Definition at line 109 of file map_grid.cpp.
void dwb_critics::MapGridCritic::reset | ( | ) | [override, protected, virtual] |
Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore.
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 93 of file map_grid.cpp.
double dwb_critics::MapGridCritic::scorePose | ( | const geometry_msgs::Pose2D & | pose | ) | [virtual] |
Retrieve the score for a single pose.
pose | The pose to score, assumed to be in the same frame as the costmap |
Reimplemented in dwb_critics::PathAlignCritic, and dwb_critics::GoalAlignCritic.
Definition at line 169 of file map_grid.cpp.
double dwb_critics::MapGridCritic::scoreTrajectory | ( | const dwb_msgs::Trajectory2D & | traj | ) | [override, virtual] |
Implements dwb_local_planner::TrajectoryCritic.
Definition at line 120 of file map_grid.cpp.
void dwb_critics::MapGridCritic::setAsObstacle | ( | unsigned int | x, |
unsigned int | y | ||
) |
Sets the score of a particular cell to the obstacle cost.
x | X coordinate of cell |
y | Y coordinate of cell |
Definition at line 88 of file map_grid.cpp.
Definition at line 129 of file map_grid.h.
nav_grid::VectorNavGrid<double> dwb_critics::MapGridCritic::cell_values_ [protected] |
Definition at line 126 of file map_grid.h.
double dwb_critics::MapGridCritic::obstacle_score_ [protected] |
Definition at line 127 of file map_grid.h.
std::shared_ptr<MapGridQueue> dwb_critics::MapGridCritic::queue_ [protected] |
Definition at line 125 of file map_grid.h.
bool dwb_critics::MapGridCritic::stop_on_failure_ [protected] |
Definition at line 128 of file map_grid.h.
double dwb_critics::MapGridCritic::unreachable_score_ [protected] |
Special cell_values.
Definition at line 127 of file map_grid.h.