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

Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory. More...

#include <obstacle_footprint.h>

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

Public Member Functions

double getScale () const override
 
void onInit () override
 
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
 
double scorePose (const nav_core2::Costmap &costmap, const geometry_msgs::Pose2D &pose) override
 Return the obstacle score for a particular pose. More...
 
virtual double scorePose (const nav_core2::Costmap &costmap, const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Polygon2D &oriented_footprint)
 
- Public Member Functions inherited from dwb_critics::BaseObstacleCritic
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...
 
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 ()
 
void initialize (const ros::NodeHandle &planner_nh, std::string name, nav_core2::Costmap::Ptr costmap)
 
virtual void reset ()
 
void setScale (const double scale)
 
virtual ~TrajectoryCritic ()
 

Protected Attributes

nav_2d_msgs::Polygon2D footprint_spec_
 
- Protected Attributes inherited from dwb_critics::BaseObstacleCritic
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 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory.

Internally, this technically only checks if the border of the footprint collides with anything for computational efficiency. This is valid if the obstacles in the local costmap are inflated.

A more robust class could check every cell within the robot's footprint without inflating the obstacles, at some computational cost. That is left as an excercise to the reader.

Definition at line 55 of file obstacle_footprint.h.

Member Function Documentation

double dwb_critics::ObstacleFootprintCritic::getScale ( ) const
inlineoverridevirtual

Reimplemented from dwb_local_planner::TrajectoryCritic.

Definition at line 64 of file obstacle_footprint.h.

void dwb_critics::ObstacleFootprintCritic::onInit ( )
overridevirtual

Reimplemented from dwb_critics::BaseObstacleCritic.

Definition at line 50 of file obstacle_footprint.cpp.

bool dwb_critics::ObstacleFootprintCritic::prepare ( const geometry_msgs::Pose2D &  pose,
const nav_2d_msgs::Twist2D &  vel,
const geometry_msgs::Pose2D &  goal,
const nav_2d_msgs::Path2D &  global_plan 
)
overridevirtual

Reimplemented from dwb_local_planner::TrajectoryCritic.

Definition at line 56 of file obstacle_footprint.cpp.

double dwb_critics::ObstacleFootprintCritic::scorePose ( const nav_core2::Costmap costmap,
const geometry_msgs::Pose2D &  pose 
)
overridevirtual

Return the obstacle score for a particular pose.

Parameters
costmapDereferenced costmap
posePose to check

Reimplemented from dwb_critics::BaseObstacleCritic.

Definition at line 67 of file obstacle_footprint.cpp.

double dwb_critics::ObstacleFootprintCritic::scorePose ( const nav_core2::Costmap costmap,
const geometry_msgs::Pose2D &  pose,
const nav_2d_msgs::Polygon2D &  oriented_footprint 
)
virtual

Definition at line 75 of file obstacle_footprint.cpp.

Member Data Documentation

nav_2d_msgs::Polygon2D dwb_critics::ObstacleFootprintCritic::footprint_spec_
protected

Definition at line 66 of file obstacle_footprint.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