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;
void addIllegalTrajectory(const nav_core2::IllegalTrajectoryException &e)
void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector< TrajectoryCritic::Ptr > critics)
std::map< std::pair< std::string, std::string >, double > getPercentages() const
#define ROS_INFO_NAMED(name,...)
GoalChecker::Ptr goal_checker_
pluginlib::ClassLoader< TrajectoryCritic > critic_loader_
bool short_circuit_trajectory_evaluation_
#define ROS_WARN_NAMED(name,...)
std::shared_ptr< dwb_local_planner::TrajectoryCritic > Ptr
void publishGlobalPlan(const nav_2d_msgs::Path2D plan)
void publishTransformedPlan(const nav_2d_msgs::Path2D plan)
std::string getBackwardsCompatibleDefaultGenerator(const ros::NodeHandle &nh)
bool transformPose(const TFListenerPtr tf, const std::string frame, const geometry_msgs::PoseStamped &in_pose, geometry_msgs::PoseStamped &out_pose, const bool extrapolation_fallback=true)
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_
double getSquareDistance(const geometry_msgs::Pose2D &pose_a, const geometry_msgs::Pose2D &pose_b)
void publishInputParams(const nav_grid::NavGridInfo &info, const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &velocity, const geometry_msgs::Pose2D &goal_pose)
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.
#define ROS_INFO_THROTTLE_NAMED(rate, name,...)
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 ...
#define ROS_DEBUG_NAMED(name,...)
pluginlib::ClassLoader< GoalChecker > goal_checker_loader_
bool update_costmap_before_planning_
void loadBackwardsCompatibleParameters(const ros::NodeHandle &nh)
Load parameters to emulate dwa_local_planner.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
pluginlib::ClassLoader< TrajectoryGenerator > traj_gen_loader_
void publishEvaluation(std::shared_ptr< dwb_msgs::LocalPlanEvaluation > results)
If the pointer is not null, publish the evaluation and trajectories as needed.
TFSIMD_FORCE_INLINE const tfScalar & x() const
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...
std::string getMessage() const
nav_2d_msgs::Path2D global_plan_
Saved Global Plan.
TFSIMD_FORCE_INLINE const tfScalar & w() const
virtual void loadCritics(const std::string name)
Load the critic parameters from the namespace.
void publishLocalPlan(const std_msgs::Header &header, const dwb_msgs::Trajectory2D &traj)
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" ...
bool getParam(const std::string &key, std::string &s) const
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...
#define ROS_ERROR_NAMED(name,...)
geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped &pose, const std::string &frame_id)
Thrown when all the trajectories explored are illegal.
std::vector< TrajectoryCritic::Ptr > critics_
std::shared_ptr< Costmap > Ptr
std::string getCriticName() const
bool hasParam(const std::string &key) const
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_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
geometry_msgs::Pose2D transformPoseToLocal(const nav_2d_msgs::Pose2DStamped &pose)
Helper method to transform a given pose to the local costmap frame.
bool shouldRecordEvaluation()
Does the publisher require that the LocalPlanEvaluation be saved.
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
void initialize(ros::NodeHandle &nh)
Load the parameters and advertise topics as needed.
void addLegalTrajectory()
DWBLocalPlanner()
Constructor that brings up pluginlib loaders.