Uses costmap to assign negative costs if a circular robot would collide at any point of the trajectory. More...
#include <base_obstacle.h>

| Public Member Functions | |
| void | addCriticVisualization (sensor_msgs::PointCloud &pc) override | 
| virtual bool | isValidCost (const unsigned char cost) | 
| Check to see whether a given cell cost is valid for driving through. | |
| void | onInit () override | 
| virtual double | scorePose (const nav_core2::Costmap &costmap, const geometry_msgs::Pose2D &pose) | 
| Return the obstacle score for a particular pose. | |
| double | scoreTrajectory (const dwb_msgs::Trajectory2D &traj) override | 
| Protected Attributes | |
| bool | sum_scores_ | 
Uses costmap to assign negative costs if a circular robot would collide at any point of the trajectory.
This class can only be used to figure out if a circular robot is in collision. If the cell corresponding with any of the poses in the Trajectory is an obstacle, inscribed obstacle or unknown, it will return a negative cost. Otherwise it will return either the final pose's cost, or the sum of all poses, depending on the sum_scores parameter.
Other classes (like ObstacleFootprintCritic) can do more advanced checking for collisions.
Definition at line 53 of file base_obstacle.h.
| void dwb_critics::BaseObstacleCritic::addCriticVisualization | ( | sensor_msgs::PointCloud & | pc | ) |  [override, virtual] | 
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 81 of file base_obstacle.cpp.
| bool dwb_critics::BaseObstacleCritic::isValidCost | ( | const unsigned char | cost | ) |  [virtual] | 
Check to see whether a given cell cost is valid for driving through.
| cost | Cost of the cell | 
Definition at line 74 of file base_obstacle.cpp.
| void dwb_critics::BaseObstacleCritic::onInit | ( | ) |  [override, virtual] | 
Reimplemented from dwb_local_planner::TrajectoryCritic.
Reimplemented in dwb_critics::ObstacleFootprintCritic.
Definition at line 45 of file base_obstacle.cpp.
| double dwb_critics::BaseObstacleCritic::scorePose | ( | const nav_core2::Costmap & | costmap, | 
| const geometry_msgs::Pose2D & | pose | ||
| ) |  [virtual] | 
Return the obstacle score for a particular pose.
| costmap | Dereferenced costmap | 
| pose | Pose to check | 
Reimplemented in dwb_critics::ObstacleFootprintCritic.
Definition at line 63 of file base_obstacle.cpp.
| double dwb_critics::BaseObstacleCritic::scoreTrajectory | ( | const dwb_msgs::Trajectory2D & | traj | ) |  [override, virtual] | 
Implements dwb_local_planner::TrajectoryCritic.
Definition at line 50 of file base_obstacle.cpp.
| bool dwb_critics::BaseObstacleCritic::sum_scores_  [protected] | 
Definition at line 75 of file base_obstacle.h.