35 #ifndef DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H    36 #define DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H    77   void setGoalPose(
const nav_2d_msgs::Pose2DStamped& goal_pose) 
override;
    83   void setPlan(
const nav_2d_msgs::Path2D& path) 
override;
    98                                                       const nav_2d_msgs::Twist2D& velocity) 
override;
   110   bool isGoalReached(
const nav_2d_msgs::Pose2DStamped& pose, 
const nav_2d_msgs::Twist2D& velocity) 
override;
   123   virtual dwb_msgs::TrajectoryScore 
scoreTrajectory(
const dwb_msgs::Trajectory2D& traj, 
double best_score = -1);
   138                                                               const nav_2d_msgs::Twist2D& velocity,
   139                                                               std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results);
   148   virtual void prepare(
const nav_2d_msgs::Pose2DStamped& pose, 
const nav_2d_msgs::Twist2D& velocity);
   154                                                          const nav_2d_msgs::Twist2D velocity,
   155                                                          std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results);
   215 #endif  // DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H 
GoalChecker::Ptr goal_checker_
pluginlib::ClassLoader< TrajectoryCritic > critic_loader_
bool short_circuit_trajectory_evaluation_
nav_core2::Costmap::Ptr costmap_
TrajectoryGenerator::Ptr traj_generator_
virtual void prepare(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity)
Helper method for preparing for the core scoring algorithm. 
bool debug_trajectory_details_
Consolidation of all the publishing logic for the DWB Local Planner. 
virtual ~DWBLocalPlanner()
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
nav_core2 initialization 
nav_2d_msgs::Pose2DStamped goal_pose_
Saved Goal Pose. 
Plugin-based flexible local_planner. 
nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity ...
std::shared_ptr< dwb_local_planner::TrajectoryGenerator > Ptr
pluginlib::ClassLoader< GoalChecker > goal_checker_loader_
bool update_costmap_before_planning_
std::shared_ptr< dwb_local_planner::GoalChecker > Ptr
pluginlib::ClassLoader< TrajectoryGenerator > traj_gen_loader_
void setPlan(const nav_2d_msgs::Path2D &path) override
nav_core2 setPlan - Sets the global plan 
bool isGoalReached(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
nav_core2 isGoalReached - Check whether the robot has reached its goal, given the current pose & velo...
nav_2d_msgs::Path2D global_plan_
Saved Global Plan. 
virtual void loadCritics(const std::string name)
Load the critic parameters from the namespace. 
std::vector< std::string > default_critic_namespaces_
std::string resolveCriticClassName(std::string base_name)
try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic" ...
virtual nav_2d_msgs::Path2D transformGlobalPlan(const nav_2d_msgs::Pose2DStamped &pose)
Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses...
std::vector< TrajectoryCritic::Ptr > critics_
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr
virtual dwb_msgs::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D velocity, std::shared_ptr< dwb_msgs::LocalPlanEvaluation > &results)
Iterate through all the twists and find the best one. 
ros::NodeHandle planner_nh_
geometry_msgs::Pose2D transformPoseToLocal(const nav_2d_msgs::Pose2DStamped &pose)
Helper method to transform a given pose to the local costmap frame. 
virtual dwb_msgs::TrajectoryScore scoreTrajectory(const dwb_msgs::Trajectory2D &traj, double best_score=-1)
Score a given command. Can be used for testing. 
void setGoalPose(const nav_2d_msgs::Pose2DStamped &goal_pose) override
nav_core2 setGoalPose - Sets the global goal pose 
DWBLocalPlanner()
Constructor that brings up pluginlib loaders.