Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H
00036 #define DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H
00037
00038 #include <dwb_local_planner/dwb_local_planner.h>
00039 #include <dwb_msgs/DebugLocalPlan.h>
00040 #include <dwb_msgs/GenerateTwists.h>
00041 #include <dwb_msgs/GenerateTrajectory.h>
00042 #include <dwb_msgs/ScoreTrajectory.h>
00043 #include <dwb_msgs/GetCriticScore.h>
00044 #include <string>
00045
00046 namespace dwb_local_planner
00047 {
00048
00054 class DebugDWBLocalPlanner: public DWBLocalPlanner
00055 {
00056 public:
00060 void initialize(const ros::NodeHandle& parent, const std::string& name,
00061 TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override;
00062 protected:
00063 bool generateTwistsService(dwb_msgs::GenerateTwists::Request &req,
00064 dwb_msgs::GenerateTwists::Response &res);
00065 bool generateTrajectoryService(dwb_msgs::GenerateTrajectory::Request &req,
00066 dwb_msgs::GenerateTrajectory::Response &res);
00067 bool scoreTrajectoryService(dwb_msgs::ScoreTrajectory::Request &req,
00068 dwb_msgs::ScoreTrajectory::Response &res);
00069 bool getCriticScoreService(dwb_msgs::GetCriticScore::Request &req,
00070 dwb_msgs::GetCriticScore::Response &res);
00071 bool debugLocalPlanService(dwb_msgs::DebugLocalPlan::Request &req,
00072 dwb_msgs::DebugLocalPlan::Response &res);
00073
00074 TrajectoryCritic::Ptr getCritic(std::string name);
00075
00076 ros::ServiceServer twist_gen_service_, generate_traj_service_, score_service_, critic_service_, debug_service_;
00077 };
00078
00079 }
00080
00081 #endif // DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H