35 #ifndef DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H    36 #define DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H    39 #include <dwb_msgs/DebugLocalPlan.h>    40 #include <dwb_msgs/GenerateTwists.h>    41 #include <dwb_msgs/GenerateTrajectory.h>    42 #include <dwb_msgs/ScoreTrajectory.h>    43 #include <dwb_msgs/GetCriticScore.h>    64                              dwb_msgs::GenerateTwists::Response &res);
    66                                  dwb_msgs::GenerateTrajectory::Response &res);
    68                               dwb_msgs::ScoreTrajectory::Response &res);
    70                              dwb_msgs::GetCriticScore::Response &res);
    72                              dwb_msgs::DebugLocalPlan::Response &res);
    81 #endif  // DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H bool generateTwistsService(dwb_msgs::GenerateTwists::Request &req, dwb_msgs::GenerateTwists::Response &res)
bool generateTrajectoryService(dwb_msgs::GenerateTrajectory::Request &req, dwb_msgs::GenerateTrajectory::Response &res)
TrajectoryCritic::Ptr getCritic(std::string name)
ros::ServiceServer critic_service_
ros::ServiceServer score_service_
std::shared_ptr< dwb_local_planner::TrajectoryCritic > Ptr
ros::ServiceServer generate_traj_service_
bool scoreTrajectoryService(dwb_msgs::ScoreTrajectory::Request &req, dwb_msgs::ScoreTrajectory::Response &res)
ros::ServiceServer debug_service_
Plugin-based flexible local_planner. 
bool debugLocalPlanService(dwb_msgs::DebugLocalPlan::Request &req, dwb_msgs::DebugLocalPlan::Response &res)
bool getCriticScoreService(dwb_msgs::GetCriticScore::Request &req, dwb_msgs::GetCriticScore::Response &res)
ros::ServiceServer twist_gen_service_
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
Override the DWB constructor to also advertise the services. 
A version of DWBLocalPlanner with ROS services for the major components. 
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr