Class GoalAlignCritic
Defined in File goal_align.hpp
Inheritance Relationships
Base Type
public dwb_critics::GoalDistCritic
(Class GoalDistCritic)
Class Documentation
-
class GoalAlignCritic : public dwb_critics::GoalDistCritic
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.
Public Functions
-
inline GoalAlignCritic()
-
void onInit() override
-
virtual double scorePose(const geometry_msgs::msg::Pose2D &pose) override
Retrieve the score for a single pose.
- Parameters:
pose – The 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
Protected Attributes
-
double forward_point_distance_
-
inline GoalAlignCritic()