Scores trajectories based on how far from the global path the front of the robot ends up. More...
#include <path_align.h>
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. More... | |
Public Member Functions inherited from dwb_critics::PathDistCritic | |
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 |
Public Member Functions inherited from dwb_critics::MapGridCritic | |
void | addCriticVisualization (sensor_msgs::PointCloud &pc) override |
double | getScore (unsigned int x, unsigned int y) |
Retrieve the score for a particular cell of the costmap. More... | |
MapGridCritic () | |
double | scoreTrajectory (const dwb_msgs::Trajectory2D &traj) override |
void | setAsObstacle (unsigned int x, unsigned int y) |
Sets the score of a particular cell to the obstacle cost. More... | |
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) |
void | setScale (const double scale) |
virtual | ~TrajectoryCritic () |
Protected Attributes | |
double | forward_point_distance_ |
bool | zero_scale_ |
Protected Attributes inherited from dwb_critics::MapGridCritic | |
ScoreAggregationType | aggregationType_ |
nav_grid::VectorNavGrid< double > | cell_values_ |
double | obstacle_score_ |
std::shared_ptr< MapGridQueue > | queue_ |
bool | stop_on_failure_ |
double | unreachable_score_ |
Special cell_values. More... | |
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::TrajectoryCritic > | Ptr |
Protected Types inherited from dwb_critics::MapGridCritic | |
enum | ScoreAggregationType { ScoreAggregationType::Last, ScoreAggregationType::Sum, ScoreAggregationType::Product } |
Separate modes for aggregating scores across the multiple poses in a trajectory. More... | |
Protected Member Functions inherited from dwb_critics::MapGridCritic | |
void | propogateManhattanDistances () |
Go through the queue and set the cells to the Manhattan distance from their parents. More... | |
void | reset () override |
Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore. More... | |
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.
|
inline |
Definition at line 59 of file path_align.h.
|
overridevirtual |
Reimplemented from dwb_critics::MapGridCritic.
Definition at line 72 of file path_align.cpp.
|
overridevirtual |
Reimplemented from dwb_critics::MapGridCritic.
Definition at line 44 of file path_align.cpp.
|
overridevirtual |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 51 of file path_align.cpp.
|
overridevirtual |
Retrieve the score for a single pose.
pose | The pose to score, assumed to be in the same frame as the costmap |
Reimplemented from dwb_critics::MapGridCritic.
Definition at line 80 of file path_align.cpp.
|
protected |
Definition at line 67 of file path_align.h.
|
protected |
Definition at line 66 of file path_align.h.