Public Member Functions | Protected Attributes
mir_dwb_critics::PathAngleCritic Class Reference

Scores trajectories based on the difference between the path's current angle and the trajectory's angle. More...

#include <path_angle.h>

Inheritance diagram for mir_dwb_critics::PathAngleCritic:
Inheritance graph
[legend]

List of all members.

Public Member Functions

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) override
virtual double scoreTrajectory (const dwb_msgs::Trajectory2D &traj) override

Protected Attributes

double desired_angle_

Detailed Description

Scores trajectories based on the difference between the path's current angle and the trajectory's angle.

This trajectory critic helps to ensure that the robot is roughly aligned with the path (i.e., if the path specifies a forward motion, the robot should point forward along the path and vice versa). This critic is not a replacement for the PathAlignCritic: The PathAlignCritic tries to point the robot towards a point on the path that is in front of the trajectory's end point, so it helps guiding the robot back towards the path. The PathAngleCritic on the other hand uses the path point that is closest to the robot's current position (not the trajectory end point, or even a point in front of that) as a reference, so it always lags behind. Also, it tries to keep the robot parallel to the path, not towards it. For these reasons, the error is squared, so that the PathAngleCritic really only affects the final score if the error is large. The PathAlignCritic doesn't take the path orientation into account though, so that's why the PathAngleCritic is a useful addition.

Definition at line 57 of file path_angle.h.


Member Function Documentation

bool mir_dwb_critics::PathAngleCritic::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_local_planner::TrajectoryCritic.

Definition at line 43 of file path_angle.cpp.

double mir_dwb_critics::PathAngleCritic::scoreTrajectory ( const dwb_msgs::Trajectory2D &  traj) [override, virtual]

Implements dwb_local_planner::TrajectoryCritic.

Definition at line 86 of file path_angle.cpp.


Member Data Documentation

Definition at line 67 of file path_angle.h.


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


mir_dwb_critics
Author(s): Martin Günther
autogenerated on Wed May 8 2019 02:53:29