Public Types | Public Member Functions | Protected Attributes | List of all members
dwb_local_planner::TrajectoryCritic Class Referenceabstract

Evaluates a Trajectory2D to produce a score. More...

#include <trajectory_critic.h>

Public Types

using Ptr = std::shared_ptr< dwb_local_planner::TrajectoryCritic >
 

Public Member Functions

virtual void addCriticVisualization (sensor_msgs::PointCloud &pc)
 Add information to the given pointcloud for debugging costmap-grid based scores. More...
 
virtual void debrief (const nav_2d_msgs::Twist2D &cmd_vel)
 debrief informs the critic what the chosen cmd_vel was (if it cares) More...
 
std::string getName ()
 
virtual double getScale () const
 
void initialize (const ros::NodeHandle &planner_nh, std::string name, nav_core2::Costmap::Ptr costmap)
 Initialize the critic with appropriate pointers and parameters. More...
 
virtual void onInit ()
 
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)
 Prior to evaluating any trajectories, look at contextual information constant across all trajectories. More...
 
virtual void reset ()
 Reset the state of the critic. More...
 
virtual double scoreTrajectory (const dwb_msgs::Trajectory2D &traj)=0
 Return a raw score for the given trajectory. More...
 
void setScale (const double scale)
 
virtual ~TrajectoryCritic ()
 

Protected Attributes

nav_core2::Costmap::Ptr costmap_
 
ros::NodeHandle critic_nh_
 
std::string name_
 
ros::NodeHandle planner_nh_
 
double scale_
 

Detailed Description

Evaluates a Trajectory2D to produce a score.

This class defines the plugin interface for the TrajectoryCritic which gives scores to trajectories, where lower numbers are better, but negative scores are considered invalid.

The general lifecycle is 1) initialize is called once at the beginning which in turn calls onInit. Derived classes may override onInit to load parameters as needed. 2) prepare is called once before each set of trajectories. It is presumed that there are multiple trajectories that we want to evaluate, and there may be some shared work that can be done beforehand to optimize the scoring of each individual trajectory. 3) scoreTrajectory is called once per trajectory and returns the score. 4) debrief is called after each set of trajectories with the chosen trajectory. This can be used for stateful critics that monitor the trajectory through time.

Optionally, there is also a debugging mechanism for certain types of critics in the addCriticVisualization method. If the score for a trajectory depends on its relationship to the costmap, addCriticVisualization can provide that information to the dwb_local_planner which will publish the grid scores as a PointCloud2.

Definition at line 76 of file trajectory_critic.h.

Member Typedef Documentation

Definition at line 79 of file trajectory_critic.h.

Constructor & Destructor Documentation

virtual dwb_local_planner::TrajectoryCritic::~TrajectoryCritic ( )
inlinevirtual

Definition at line 81 of file trajectory_critic.h.

Member Function Documentation

virtual void dwb_local_planner::TrajectoryCritic::addCriticVisualization ( sensor_msgs::PointCloud &  pc)
inlinevirtual

Add information to the given pointcloud for debugging costmap-grid based scores.

addCriticVisualization is an optional debugging mechanism for providing rich information about the cost for certain trajectories. Some critics will have scoring mechanisms wherein there will be some score for each cell in the costmap. This could be as straightforward as the cost in the costmap, or it could be the number of cells away from the goal pose.

Prior to calling this, dwb_local_planner will load the PointCloud's header and the points in row-major order. The critic may then add a ChannelFloat to the channels member of the PC with the same number of values as the points array. This information may then be converted and published as a PointCloud2.

Parameters
pcPointCloud to add channels to

Definition at line 159 of file trajectory_critic.h.

virtual void dwb_local_planner::TrajectoryCritic::debrief ( const nav_2d_msgs::Twist2D &  cmd_vel)
inlinevirtual

debrief informs the critic what the chosen cmd_vel was (if it cares)

Definition at line 141 of file trajectory_critic.h.

std::string dwb_local_planner::TrajectoryCritic::getName ( )
inline

Definition at line 161 of file trajectory_critic.h.

virtual double dwb_local_planner::TrajectoryCritic::getScale ( ) const
inlinevirtual

Definition at line 166 of file trajectory_critic.h.

void dwb_local_planner::TrajectoryCritic::initialize ( const ros::NodeHandle planner_nh,
std::string  name,
nav_core2::Costmap::Ptr  costmap 
)
inline

Initialize the critic with appropriate pointers and parameters.

The name and costmap are stored as member variables. A NodeHandle for the critic is created with the namespace of the planner NodeHandle

Parameters
planner_nhPlanner Nodehandle
nameThe name of this critic
costmap_rosPointer to the costmap

Definition at line 93 of file trajectory_critic.h.

virtual void dwb_local_planner::TrajectoryCritic::onInit ( )
inlinevirtual

Definition at line 103 of file trajectory_critic.h.

virtual bool dwb_local_planner::TrajectoryCritic::prepare ( const geometry_msgs::Pose2D &  pose,
const nav_2d_msgs::Twist2D &  vel,
const geometry_msgs::Pose2D &  goal,
const nav_2d_msgs::Path2D &  global_plan 
)
inlinevirtual

Prior to evaluating any trajectories, look at contextual information constant across all trajectories.

Subclasses may overwrite. Return false in case there is any error.

Parameters
poseCurrent pose (costmap frame)
velCurrent velocity
goalThe final goal (costmap frame)
global_planTransformed global plan in costmap frame, possibly cropped to nearby points

Definition at line 123 of file trajectory_critic.h.

virtual void dwb_local_planner::TrajectoryCritic::reset ( )
inlinevirtual

Reset the state of the critic.

Reset is called when the planner receives a new global goal. This can be used to discard information specific to one plan.

Definition at line 111 of file trajectory_critic.h.

virtual double dwb_local_planner::TrajectoryCritic::scoreTrajectory ( const dwb_msgs::Trajectory2D &  traj)
pure virtual

Return a raw score for the given trajectory.

scores < 0 are considered invalid/errors, such as collisions This is the raw score in that the scale should not be applied to it.

void dwb_local_planner::TrajectoryCritic::setScale ( const double  scale)
inline

Definition at line 167 of file trajectory_critic.h.

Member Data Documentation

nav_core2::Costmap::Ptr dwb_local_planner::TrajectoryCritic::costmap_
protected

Definition at line 170 of file trajectory_critic.h.

ros::NodeHandle dwb_local_planner::TrajectoryCritic::critic_nh_
protected

Definition at line 172 of file trajectory_critic.h.

std::string dwb_local_planner::TrajectoryCritic::name_
protected

Definition at line 169 of file trajectory_critic.h.

ros::NodeHandle dwb_local_planner::TrajectoryCritic::planner_nh_
protected

Definition at line 172 of file trajectory_critic.h.

double dwb_local_planner::TrajectoryCritic::scale_
protected

Definition at line 171 of file trajectory_critic.h.


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


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Sun Jan 10 2021 04:08:34