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.  More... | |
| void | onInit () override | 
| virtual double | scorePose (const nav_core2::Costmap &costmap, const geometry_msgs::Pose2D &pose) | 
| Return the obstacle score for a particular pose.  More... | |
| double | scoreTrajectory (const dwb_msgs::Trajectory2D &traj) override | 
|  Public Member Functions inherited from dwb_local_planner::TrajectoryCritic | |
| virtual void | debrief (const nav_2d_msgs::Twist2D &cmd_vel) | 
| std::string | getName () | 
| virtual double | getScale () const | 
| void | initialize (const ros::NodeHandle &planner_nh, std::string name, nav_core2::Costmap::Ptr costmap) | 
| virtual 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) | 
| virtual void | reset () | 
| void | setScale (const double scale) | 
| virtual | ~TrajectoryCritic () | 
| Protected Attributes | |
| bool | sum_scores_ | 
|  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_ | 
| Additional Inherited Members | |
|  Public Types inherited from dwb_local_planner::TrajectoryCritic | |
| typedef std::shared_ptr< dwb_local_planner::TrajectoryCritic > | Ptr | 
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.
| 
 | overridevirtual | 
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 81 of file base_obstacle.cpp.
| 
 | 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.
| 
 | overridevirtual | 
Reimplemented from dwb_local_planner::TrajectoryCritic.
Reimplemented in dwb_critics::ObstacleFootprintCritic.
Definition at line 45 of file base_obstacle.cpp.
| 
 | 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.
| 
 | overridevirtual | 
Implements dwb_local_planner::TrajectoryCritic.
Definition at line 50 of file base_obstacle.cpp.
| 
 | protected | 
Definition at line 75 of file base_obstacle.h.