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

Scores trajectories based on how far from the global path the front of the robot ends up. More...

#include <path_align.h>

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

List of all members.

Public Member Functions

double getScale () const override
void onInit () override
 PathAlignCritic ()
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_
bool zero_scale_

Detailed Description

Scores trajectories based on how far from the global path the front of the robot ends up.

This uses the costmap grid as a proxy for calculating which way the robot should be facing relative to the global path. Instead of scoring how far the center of the robot is away from the global path, this critic calculates how far a point forward_point_distance in front of the robot is from the global path. This biases the planner toward trajectories that line up with the global plan.

When the robot is near the end of the path, the scale of this critic is set to zero. When the projected point is past the global goal, we no longer want this critic to try to align to a part of the global path that isn't there.

Definition at line 56 of file path_align.h.


Constructor & Destructor Documentation

Definition at line 59 of file path_align.h.


Member Function Documentation

double dwb_critics::PathAlignCritic::getScale ( ) const [override, virtual]

Reimplemented from dwb_critics::MapGridCritic.

Definition at line 72 of file path_align.cpp.

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

Reimplemented from dwb_critics::MapGridCritic.

Definition at line 44 of file path_align.cpp.

bool dwb_critics::PathAlignCritic::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::PathDistCritic.

Definition at line 51 of file path_align.cpp.

double dwb_critics::PathAlignCritic::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 80 of file path_align.cpp.


Member Data Documentation

Definition at line 67 of file path_align.h.

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