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 #include <dwb_local_planner/debug_dwb_local_planner.h>
00036 #include <nav_2d_utils/tf_help.h>
00037 #include <nav_core2/exceptions.h>
00038 #include <pluginlib/class_list_macros.h>
00039 #include <string>
00040
00041 namespace dwb_local_planner
00042 {
00043
00044 void DebugDWBLocalPlanner::initialize(const ros::NodeHandle& parent, const std::string& name,
00045 TFListenerPtr tf, nav_core2::Costmap::Ptr costmap)
00046 {
00047 DWBLocalPlanner::initialize(parent, name, tf, costmap);
00048
00049 debug_service_ = planner_nh_.advertiseService("debug_local_plan",
00050 &DebugDWBLocalPlanner::debugLocalPlanService, this);
00051 twist_gen_service_ = planner_nh_.advertiseService("generate_twists",
00052 &DebugDWBLocalPlanner::generateTwistsService, this);
00053 score_service_ = planner_nh_.advertiseService("score_trajectory",
00054 &DebugDWBLocalPlanner::scoreTrajectoryService, this);
00055 critic_service_ = planner_nh_.advertiseService("get_critic_score",
00056 &DebugDWBLocalPlanner::getCriticScoreService, this);
00057 generate_traj_service_ = planner_nh_.advertiseService("generate_traj",
00058 &DebugDWBLocalPlanner::generateTrajectoryService, this);
00059 }
00060
00061 bool DebugDWBLocalPlanner::generateTwistsService(dwb_msgs::GenerateTwists::Request &req,
00062 dwb_msgs::GenerateTwists::Response &res)
00063 {
00064 res.twists = traj_generator_->getTwists(req.current_vel);
00065 return true;
00066 }
00067
00068 bool DebugDWBLocalPlanner::generateTrajectoryService(dwb_msgs::GenerateTrajectory::Request &req,
00069 dwb_msgs::GenerateTrajectory::Response &res)
00070 {
00071 res.traj = traj_generator_->generateTrajectory(req.start_pose, req.start_vel, req.cmd_vel);
00072 return true;
00073 }
00074
00075 bool DebugDWBLocalPlanner::scoreTrajectoryService(dwb_msgs::ScoreTrajectory::Request &req,
00076 dwb_msgs::ScoreTrajectory::Response &res)
00077 {
00078 if (req.goal.header.frame_id != "")
00079 setGoalPose(req.goal);
00080 if (req.global_plan.poses.size() > 0)
00081 setPlan(req.global_plan);
00082
00083 prepare(req.pose, req.velocity);
00084 res.score = scoreTrajectory(req.traj);
00085 return true;
00086 }
00087
00088 TrajectoryCritic::Ptr DebugDWBLocalPlanner::getCritic(std::string name)
00089 {
00090 for (TrajectoryCritic::Ptr critic : critics_)
00091 {
00092 if (critic->getName() == name)
00093 return critic;
00094 }
00095 return nullptr;
00096 }
00097
00098 bool DebugDWBLocalPlanner::getCriticScoreService(dwb_msgs::GetCriticScore::Request &req,
00099 dwb_msgs::GetCriticScore::Response &res)
00100 {
00101 TrajectoryCritic::Ptr critic = getCritic(req.critic_name);
00102 if (critic == nullptr)
00103 {
00104 ROS_WARN_NAMED("DebugDWBLocalPlanner", "Critic %s not found!", req.critic_name.c_str());
00105 return false;
00106 }
00107 if (req.goal.header.frame_id != "")
00108 setGoalPose(req.goal);
00109 if (req.global_plan.poses.size() > 0)
00110 setPlan(req.global_plan);
00111
00112
00113 prepare(req.pose, req.velocity);
00114
00115 res.score.raw_score = critic->scoreTrajectory(req.traj);
00116 res.score.scale = critic->getScale();
00117 res.score.name = req.critic_name;
00118
00119 pub_.publishCostGrid(costmap_, critics_);
00120
00121 return true;
00122 }
00123
00124 bool DebugDWBLocalPlanner::debugLocalPlanService(dwb_msgs::DebugLocalPlan::Request &req,
00125 dwb_msgs::DebugLocalPlan::Response &res)
00126 {
00127 if (req.goal.header.frame_id != "")
00128 setGoalPose(req.goal);
00129 if (req.global_plan.poses.size() > 0)
00130 setPlan(req.global_plan);
00131 std::shared_ptr<dwb_msgs::LocalPlanEvaluation> results = std::make_shared<dwb_msgs::LocalPlanEvaluation>();
00132 try
00133 {
00134 computeVelocityCommands(req.pose, req.velocity, results);
00135 res.results = *results;
00136 return true;
00137 }
00138 catch (const nav_core2::PlannerException& e)
00139 {
00140 ROS_ERROR_NAMED("DebugDWBLocalPlanner", "Exception in computeVelocityCommands: %s", e.what());
00141 return false;
00142 }
00143 }
00144
00145 }
00146
00147
00148
00149 PLUGINLIB_EXPORT_CLASS(dwb_local_planner::DebugDWBLocalPlanner, nav_core2::LocalPlanner)