Penalize trajectories with move backwards and/or turn too much. More...
#include <prefer_forward.h>

Public Member Functions | |
| void | onInit () override |
| PreferForwardCritic () | |
| 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 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) |
| virtual void | reset () |
| void | setScale (const double scale) |
| virtual | ~TrajectoryCritic () |
Protected Attributes | |
| double | penalty_ |
| double | strafe_theta_ |
| double | strafe_x_ |
| double | theta_scale_ |
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 |
Penalize trajectories with move backwards and/or turn too much.
Has three different scoring conditions: 1) If the trajectory's x velocity is negative, return the penalty 2) If the trajectory's x is low and the theta is also low, return the penalty. 3) Otherwise, return a scaled version of the trajectory's theta.
Definition at line 53 of file prefer_forward.h.
|
inline |
Definition at line 56 of file prefer_forward.h.
|
overridevirtual |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 44 of file prefer_forward.cpp.
|
overridevirtual |
Implements dwb_local_planner::TrajectoryCritic.
Definition at line 52 of file prefer_forward.cpp.
|
protected |
Definition at line 61 of file prefer_forward.h.
|
protected |
Definition at line 61 of file prefer_forward.h.
|
protected |
Definition at line 61 of file prefer_forward.h.
|
protected |
Definition at line 61 of file prefer_forward.h.