Calculates an intermediate goal along the global path and scores trajectories on the distance to that goal. More...
#include <path_progress.h>
Public Member Functions | |
void | onInit () override |
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 |
void | reset () override |
double | scoreTrajectory (const dwb_msgs::Trajectory2D &traj) override |
Public Member Functions inherited from dwb_critics::MapGridCritic | |
void | addCriticVisualization (sensor_msgs::PointCloud &pc) override |
double | getScale () const override |
double | getScore (unsigned int x, unsigned int y) |
MapGridCritic () | |
virtual double | scorePose (const geometry_msgs::Pose2D &pose) |
void | setAsObstacle (unsigned int x, unsigned int y) |
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 Member Functions | |
unsigned int | getGoalIndex (const std::vector< geometry_msgs::Pose2D > &plan, unsigned int start_index, unsigned int last_valid_index) const |
bool | getGoalPose (const geometry_msgs::Pose2D &robot_pose, const nav_2d_msgs::Path2D &global_plan, unsigned int &x, unsigned int &y, double &desired_angle) |
Protected Member Functions inherited from dwb_critics::MapGridCritic | |
void | propogateManhattanDistances () |
Protected Attributes | |
double | angle_threshold_ |
double | desired_angle_ |
double | heading_scale_ |
std::vector< geometry_msgs::Pose2D > | reached_intermediate_goals_ |
double | xy_local_goal_tolerance_ |
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_ |
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 } |
Calculates an intermediate goal along the global path and scores trajectories on the distance to that goal.
This trajectory critic helps ensure progress along the global path. It calculates an intermediate goal that is as far as possible along the global path as long as the path continues to move in one direction (+/- angle_threshold).
Definition at line 50 of file path_progress.h.
|
protected |
Definition at line 190 of file path_progress.cpp.
|
protected |
Definition at line 82 of file path_progress.cpp.
|
overridevirtual |
Reimplemented from dwb_critics::MapGridCritic.
Definition at line 60 of file path_progress.cpp.
|
overridevirtual |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 41 of file path_progress.cpp.
|
overridevirtual |
Reimplemented from dwb_critics::MapGridCritic.
Definition at line 70 of file path_progress.cpp.
|
overridevirtual |
Reimplemented from dwb_critics::MapGridCritic.
Definition at line 74 of file path_progress.cpp.
|
protected |
Definition at line 73 of file path_progress.h.
|
protected |
Definition at line 77 of file path_progress.h.
|
protected |
Definition at line 74 of file path_progress.h.
|
protected |
Definition at line 76 of file path_progress.h.
|
protected |
Definition at line 72 of file path_progress.h.