Scores trajectories based on how far from the global path they end up, where the global path is pruned to only include waypoints ahead of the robot. More...
#include <path_dist_pruned.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 |
![]() | |
void | addCriticVisualization (sensor_msgs::PointCloud &pc) override |
double | getScale () const override |
double | getScore (unsigned int x, unsigned int y) |
MapGridCritic () | |
void | onInit () override |
virtual double | scorePose (const geometry_msgs::Pose2D &pose) |
double | scoreTrajectory (const dwb_msgs::Trajectory2D &traj) override |
void | setAsObstacle (unsigned int x, unsigned int y) |
![]() | |
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 () |
Additional Inherited Members | |
![]() | |
typedef std::shared_ptr< dwb_local_planner::TrajectoryCritic > | Ptr |
![]() | |
enum | ScoreAggregationType { ScoreAggregationType::Last, ScoreAggregationType::Sum, ScoreAggregationType::Product } |
![]() | |
void | propogateManhattanDistances () |
void | reset () override |
![]() | |
ScoreAggregationType | aggregationType_ |
nav_grid::VectorNavGrid< double > | cell_values_ |
double | obstacle_score_ |
std::shared_ptr< MapGridQueue > | queue_ |
bool | stop_on_failure_ |
double | unreachable_score_ |
![]() | |
nav_core2::Costmap::Ptr | costmap_ |
ros::NodeHandle | critic_nh_ |
std::string | name_ |
ros::NodeHandle | planner_nh_ |
double | scale_ |
Scores trajectories based on how far from the global path they end up, where the global path is pruned to only include waypoints ahead of the robot.
Definition at line 48 of file path_dist_pruned.h.
|
overridevirtual |
Reimplemented from dwb_critics::PathDistCritic.
Definition at line 41 of file path_dist_pruned.cpp.