35 #ifndef DWB_CRITICS_MAP_GRID_H    36 #define DWB_CRITICS_MAP_GRID_H    75   virtual double scorePose(
const geometry_msgs::Pose2D& pose);
   110       : 
costmap_queue::CostmapQueue(costmap, true), parent_(parent) {}
   119   void reset() 
override;
   134 #endif  // DWB_CRITICS_MAP_GRID_H ScoreAggregationType
Separate modes for aggregating scores across the multiple poses in a trajectory. 
void reset() override
Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore. 
Subclass of CostmapQueue that avoids Obstacles and Unknown Values. 
virtual double scorePose(const geometry_msgs::Pose2D &pose)
Retrieve the score for a single pose. 
void propogateManhattanDistances()
Go through the queue and set the cells to the Manhattan distance from their parents. 
MapGridQueue(nav_core2::Costmap &costmap, MapGridCritic &parent)
void setAsObstacle(unsigned int x, unsigned int y)
Sets the score of a particular cell to the obstacle cost. 
TFSIMD_FORCE_INLINE const tfScalar & y() const 
double getScale() const override
ScoreAggregationType aggregationType_
void addCriticVisualization(sensor_msgs::PointCloud &pc) override
nav_core2::Costmap::Ptr costmap_
breadth-first scoring of all the cells in the costmap 
TFSIMD_FORCE_INLINE const tfScalar & x() const 
double getScore(unsigned int x, unsigned int y)
Retrieve the score for a particular cell of the costmap. 
std::shared_ptr< MapGridQueue > queue_
nav_grid::VectorNavGrid< double > cell_values_
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
double unreachable_score_
Special cell_values.