Public Member Functions | Protected Attributes
dwb_critics::GoalAlignCritic Class Reference

Scores trajectories based on whether the robot ends up pointing toward the eventual goal. More...

#include <goal_align.h>

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

List of all members.

Public Member Functions

 GoalAlignCritic ()
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 geometry_msgs::Pose2D &pose) override
 Retrieve the score for a single pose.

Protected Attributes

double forward_point_distance_

Detailed Description

Scores trajectories based on whether the robot ends up pointing toward the eventual goal.

Similar to GoalDistCritic, this critic finds the pose from the global path farthest from the robot that is still on the costmap and then evaluates how far the front of the robot is from that point. This works as a proxy to calculating which way the robot should be pointing.

Definition at line 52 of file goal_align.h.


Constructor & Destructor Documentation

Definition at line 55 of file goal_align.h.


Member Function Documentation

void dwb_critics::GoalAlignCritic::onInit ( ) [override, virtual]

Reimplemented from dwb_critics::MapGridCritic.

Definition at line 44 of file goal_align.cpp.

bool dwb_critics::GoalAlignCritic::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, virtual]

Reimplemented from dwb_critics::GoalDistCritic.

Definition at line 51 of file goal_align.cpp.

double dwb_critics::GoalAlignCritic::scorePose ( const geometry_msgs::Pose2D &  pose) [override, virtual]

Retrieve the score for a single pose.

Parameters:
poseThe pose to score, assumed to be in the same frame as the costmap
Returns:
The score associated with the cell of the costmap where the pose lies

Reimplemented from dwb_critics::MapGridCritic.

Definition at line 69 of file goal_align.cpp.


Member Data Documentation

Definition at line 61 of file goal_align.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:09:47