Public Member Functions | Protected Attributes | List of all members
dwb_critics::BaseObstacleCritic Class Reference

Uses costmap to assign negative costs if a circular robot would collide at any point of the trajectory. More...

#include <base_obstacle.h>

Inheritance diagram for dwb_critics::BaseObstacleCritic:
Inheritance graph
[legend]

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::TrajectoryCriticPtr
 

Detailed Description

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.

Member Function Documentation

void dwb_critics::BaseObstacleCritic::addCriticVisualization ( sensor_msgs::PointCloud &  pc)
overridevirtual

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.

Parameters
costCost of the cell
Returns
Return true if valid cell

Definition at line 74 of file base_obstacle.cpp.

void dwb_critics::BaseObstacleCritic::onInit ( )
overridevirtual

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.

Parameters
costmapDereferenced costmap
posePose 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)
overridevirtual

Implements dwb_local_planner::TrajectoryCritic.

Definition at line 50 of file base_obstacle.cpp.

Member Data Documentation

bool dwb_critics::BaseObstacleCritic::sum_scores_
protected

Definition at line 75 of file base_obstacle.h.


The documentation for this class was generated from the following files:


dwb_critics
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:06:22