Scores trajectories based on the difference between the path's current angle and the trajectory's angle. More...
#include <path_angle.h>
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 |
Public Member Functions inherited from dwb_local_planner::TrajectoryCritic | |
virtual void | addCriticVisualization (sensor_msgs::PointCloud &pc) |
virtual void | debrief (const nav_2d_msgs::Twist2D &cmd_vel) |
std::string | getName () |
virtual double | getScale () const |
void | initialize (const ros::NodeHandle &planner_nh, std::string name, nav_core2::Costmap::Ptr costmap) |
virtual void | onInit () |
virtual void | reset () |
void | setScale (const double scale) |
virtual | ~TrajectoryCritic () |
Protected Attributes | |
double | desired_angle_ |
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 |
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.
|
overridevirtual |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 43 of file path_angle.cpp.
|
overridevirtual |
Implements dwb_local_planner::TrajectoryCritic.
Definition at line 86 of file path_angle.cpp.
|
protected |
Definition at line 67 of file path_angle.h.