41 #include <nav_2d_msgs/Twist2D.h>
42 #include <dwb_msgs/CriticScore.h>
54 traj_gen_loader_(
"dwb_local_planner",
"dwb_local_planner::TrajectoryGenerator"),
55 goal_checker_loader_(
"dwb_local_planner",
"dwb_local_planner::GoalChecker"),
56 critic_loader_(
"dwb_local_planner",
"dwb_local_planner::TrajectoryCritic")
77 std::string traj_generator_name;
80 ROS_INFO_NAMED(
"DWBLocalPlanner",
"Using Trajectory Generator \"%s\"", traj_generator_name.c_str());
84 std::string goal_checker_name;
85 planner_nh_.
param(
"goal_checker_name", goal_checker_name, std::string(
"dwb_plugins::SimpleGoalChecker"));
86 ROS_INFO_NAMED(
"DWBLocalPlanner",
"Using Goal Checker \"%s\"", goal_checker_name.c_str());
95 if (base_name.find(
"Critic") == std::string::npos)
97 base_name = base_name +
"Critic";
100 if (base_name.find(
"::") == std::string::npos)
127 std::vector<std::string> critic_names;
129 for (
unsigned int i = 0; i < critic_names.size(); i++)
131 std::string plugin_name = critic_names[i];
132 std::string plugin_class;
137 ROS_INFO_NAMED(
"DWBLocalPlanner",
"Using critic \"%s\" (%s)", plugin_name.c_str(), plugin_class.c_str());
147 ROS_WARN_NAMED(
"DWBLocalPlanner",
"Cannot check if the goal is reached without the goal being set!");
181 const nav_2d_msgs::Twist2D& velocity)
183 std::shared_ptr<dwb_msgs::LocalPlanEvaluation> results =
nullptr;
186 results = std::make_shared<dwb_msgs::LocalPlanEvaluation>();
222 if (!critic->prepare(local_start_pose, velocity, local_goal_pose, transformed_plan))
224 ROS_WARN_NAMED(
"DWBLocalPlanner",
"Critic \"%s\" failed to prepare", critic->getName().c_str());
230 const nav_2d_msgs::Twist2D& velocity, std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results)
234 results->header.frame_id = pose.header.frame_id;
245 nav_2d_msgs::Twist2DStamped cmd_vel;
247 cmd_vel.velocity = best.traj.velocity;
252 critic->debrief(cmd_vel.velocity);
262 nav_2d_msgs::Twist2D empty_cmd;
263 dwb_msgs::Trajectory2D empty_traj;
267 critic->debrief(empty_cmd);
277 const nav_2d_msgs::Twist2D velocity,
278 std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results)
280 nav_2d_msgs::Twist2D twist;
281 dwb_msgs::Trajectory2D traj;
282 dwb_msgs::TrajectoryScore best, worst;
299 results->twists.push_back(score);
301 if (best.total < 0 || score.total < best.total)
306 results->best_index = results->twists.size() - 1;
309 if (worst.total < 0 || score.total > worst.total)
314 results->worst_index = results->twists.size() - 1;
322 dwb_msgs::TrajectoryScore failed_score;
323 failed_score.traj = traj;
325 dwb_msgs::CriticScore cs;
328 failed_score.scores.push_back(cs);
329 failed_score.total = -1.0;
330 results->twists.push_back(failed_score);
343 ROS_ERROR_NAMED(
"DWBLocalPlanner",
"%.2f: %10s/%s", x.second, x.first.first.c_str(), x.first.second.c_str());
355 dwb_msgs::TrajectoryScore score;
360 dwb_msgs::CriticScore cs;
361 cs.name = critic->getName();
362 cs.scale = critic->getScale();
366 score.scores.push_back(cs);
370 double critic_score = critic->scoreTrajectory(traj);
371 cs.raw_score = critic_score;
372 score.scores.push_back(cs);
373 score.total += critic_score * cs.scale;
384 double getSquareDistance(
const geometry_msgs::Pose2D& pose_a,
const geometry_msgs::Pose2D& pose_b)
386 double x_diff = pose_a.x - pose_b.x;
387 double y_diff = pose_a.y - pose_b.y;
388 return x_diff * x_diff + y_diff * y_diff;
393 nav_2d_msgs::Path2D transformed_plan;
400 nav_2d_msgs::Pose2DStamped robot_pose;
406 transformed_plan.header.frame_id =
costmap_->getFrameId();
407 transformed_plan.header.stamp = pose.header.stamp;
411 double sq_dist_threshold = dist_threshold * dist_threshold;
412 nav_2d_msgs::Pose2DStamped stamped_pose;
413 stamped_pose.header.frame_id =
global_plan_.header.frame_id;
415 for (
unsigned int i = 0; i <
global_plan_.poses.size(); i++)
417 bool should_break =
false;
420 if (transformed_plan.poses.size() == 0)
435 if (should_break)
break;
444 nav_2d_msgs::Pose2DStamped costmap_pose;
451 std::vector<geometry_msgs::Pose2D>::iterator it = transformed_plan.poses.begin();
452 std::vector<geometry_msgs::Pose2D>::iterator global_it =
global_plan_.poses.begin();
454 while (it != transformed_plan.poses.end())
456 const geometry_msgs::Pose2D& w = *it;
460 ROS_DEBUG_NAMED(
"DWBLocalPlanner",
"Nearest waypoint to <%f, %f> is <%f, %f>\n",
461 costmap_pose.pose.x, costmap_pose.pose.y, w.x, w.y);
464 it = transformed_plan.poses.erase(it);
470 if (transformed_plan.poses.size() == 0)
474 return transformed_plan;