Scores trajectories based on how far from the global path they end up. More...
#include <path_dist.h>

| Public Member Functions | |
| bool | prepare (const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override | 
|  Public Member Functions inherited from dwb_critics::MapGridCritic | |
| 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.  More... | |
| MapGridCritic () | |
| void | onInit () override | 
| virtual double | scorePose (const geometry_msgs::Pose2D &pose) | 
| Retrieve the score for a single pose.  More... | |
| 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.  More... | |
|  Public Member Functions inherited from dwb_local_planner::TrajectoryCritic | |
| virtual void | debrief (const nav_2d_msgs::Twist2D &cmd_vel) | 
| std::string | getName () | 
| void | initialize (const ros::NodeHandle &planner_nh, std::string name, nav_core2::Costmap::Ptr costmap) | 
| void | setScale (const double scale) | 
| virtual | ~TrajectoryCritic () | 
| Additional Inherited Members | |
|  Public Types inherited from dwb_local_planner::TrajectoryCritic | |
| typedef std::shared_ptr< dwb_local_planner::TrajectoryCritic > | Ptr | 
|  Protected Types inherited from dwb_critics::MapGridCritic | |
| enum | ScoreAggregationType { ScoreAggregationType::Last, ScoreAggregationType::Sum, ScoreAggregationType::Product } | 
| Separate modes for aggregating scores across the multiple poses in a trajectory.  More... | |
|  Protected Member Functions inherited from dwb_critics::MapGridCritic | |
| void | propogateManhattanDistances () | 
| Go through the queue and set the cells to the Manhattan distance from their parents.  More... | |
| void | reset () override | 
| Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore.  More... | |
|  Protected Attributes inherited from dwb_critics::MapGridCritic | |
| 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.  More... | |
|  Protected Attributes inherited from dwb_local_planner::TrajectoryCritic | |
| nav_core2::Costmap::Ptr | costmap_ | 
| ros::NodeHandle | critic_nh_ | 
| std::string | name_ | 
| ros::NodeHandle | planner_nh_ | 
| double | scale_ | 
Scores trajectories based on how far from the global path they end up.
Definition at line 45 of file path_dist.h.
| 
 | overridevirtual | 
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 42 of file path_dist.cpp.