41 #include "dwb_core/dwb_local_planner.hpp"
42 #include "dwb_core/exceptions.hpp"
43 #include "dwb_core/illegal_trajectory_tracker.hpp"
44 #include "dwb_msgs/msg/critic_score.hpp"
45 #include "nav_2d_msgs/msg/twist2_d.hpp"
46 #include "nav_2d_utils/conversions.hpp"
47 #include "nav2_util/geometry_utils.hpp"
48 #include "nav2_ros_common/lifecycle_node.hpp"
49 #include "nav2_ros_common/node_utils.hpp"
50 #include "nav2_core/controller_exceptions.hpp"
51 #include "pluginlib/class_list_macros.hpp"
52 #include "nav_msgs/msg/path.hpp"
53 #include "geometry_msgs/msg/twist_stamped.hpp"
55 using nav2::declare_parameter_if_not_declared;
56 using nav2_util::geometry_utils::euclidean_distance;
62 : traj_gen_loader_(
"dwb_core",
"dwb_core::TrajectoryGenerator"),
63 critic_loader_(
"dwb_core",
"dwb_core::TrajectoryCritic")
68 const nav2::LifecycleNode::WeakPtr & parent,
69 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
70 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
73 auto node = node_.lock();
75 logger_ = node->get_logger();
76 clock_ = node->get_clock();
77 costmap_ros_ = costmap_ros;
79 dwb_plugin_name_ = name;
80 declare_parameter_if_not_declared(
81 node, dwb_plugin_name_ +
".critics",
82 rclcpp::PARAMETER_STRING_ARRAY);
83 declare_parameter_if_not_declared(
84 node, dwb_plugin_name_ +
".default_critic_namespaces",
85 rclcpp::ParameterValue(std::vector<std::string>()));
86 declare_parameter_if_not_declared(
87 node, dwb_plugin_name_ +
".prune_plan",
88 rclcpp::ParameterValue(
true));
89 declare_parameter_if_not_declared(
90 node, dwb_plugin_name_ +
".prune_distance",
91 rclcpp::ParameterValue(2.0));
92 declare_parameter_if_not_declared(
93 node, dwb_plugin_name_ +
".forward_prune_distance",
94 rclcpp::ParameterValue(2.0));
95 declare_parameter_if_not_declared(
96 node, dwb_plugin_name_ +
".debug_trajectory_details",
97 rclcpp::ParameterValue(
false));
98 declare_parameter_if_not_declared(
99 node, dwb_plugin_name_ +
".trajectory_generator_name",
100 rclcpp::ParameterValue(std::string(
"dwb_plugins::StandardTrajectoryGenerator")));
101 declare_parameter_if_not_declared(
102 node, dwb_plugin_name_ +
".transform_tolerance",
103 rclcpp::ParameterValue(0.1));
104 declare_parameter_if_not_declared(
105 node, dwb_plugin_name_ +
".shorten_transformed_plan",
106 rclcpp::ParameterValue(
true));
107 declare_parameter_if_not_declared(
108 node, dwb_plugin_name_ +
".short_circuit_trajectory_evaluation",
109 rclcpp::ParameterValue(
true));
111 std::string traj_generator_name;
113 double transform_tolerance;
114 node->get_parameter(dwb_plugin_name_ +
".transform_tolerance", transform_tolerance_);
115 RCLCPP_INFO(logger_,
"Setting transform_tolerance to %f", transform_tolerance);
117 node->get_parameter(dwb_plugin_name_ +
".prune_plan", prune_plan_);
118 node->get_parameter(dwb_plugin_name_ +
".prune_distance", prune_distance_);
119 node->get_parameter(dwb_plugin_name_ +
".forward_prune_distance", forward_prune_distance_);
120 if (forward_prune_distance_ < 0.0) {
122 logger_,
"Forward prune distance is negative, setting to max to search"
123 " every point on path for the closest value.");
124 forward_prune_distance_ = std::numeric_limits<double>::max();
126 node->get_parameter(dwb_plugin_name_ +
".debug_trajectory_details", debug_trajectory_details_);
127 node->get_parameter(dwb_plugin_name_ +
".trajectory_generator_name", traj_generator_name);
129 dwb_plugin_name_ +
".short_circuit_trajectory_evaluation",
130 short_circuit_trajectory_evaluation_);
131 node->get_parameter(dwb_plugin_name_ +
".shorten_transformed_plan", shorten_transformed_plan_);
133 pub_ = std::make_unique<DWBPublisher>(node, dwb_plugin_name_);
134 pub_->on_configure();
136 traj_generator_ = traj_gen_loader_.createUniqueInstance(traj_generator_name);
138 traj_generator_->initialize(node, dwb_plugin_name_);
142 }
catch (
const std::exception & e) {
143 RCLCPP_ERROR(logger_,
"Couldn't load critics! Caught exception: %s", e.what());
145 "Couldn't load critics! Caught exception: " +
146 std::string(e.what()));
159 pub_->on_deactivate();
167 traj_generator_.reset();
173 if (base_name.find(
"Critic") == std::string::npos) {
174 base_name = base_name +
"Critic";
177 if (base_name.find(
"::") == std::string::npos) {
178 for (
unsigned int j = 0; j < default_critic_namespaces_.size(); j++) {
179 std::string full_name = default_critic_namespaces_[j] +
"::" + base_name;
180 if (critic_loader_.isClassAvailable(full_name)) {
191 auto node = node_.lock();
193 throw std::runtime_error{
"Failed to lock node"};
196 node->get_parameter(dwb_plugin_name_ +
".default_critic_namespaces", default_critic_namespaces_);
197 if (default_critic_namespaces_.empty()) {
198 default_critic_namespaces_.emplace_back(
"dwb_critics");
201 std::vector<std::string> critic_names;
202 if (!node->get_parameter(dwb_plugin_name_ +
".critics", critic_names)) {
203 throw std::runtime_error(
"No critics defined for " + dwb_plugin_name_);
206 node->get_parameter(dwb_plugin_name_ +
".critics", critic_names);
207 for (
unsigned int i = 0; i < critic_names.size(); i++) {
208 std::string critic_plugin_name = critic_names[i];
209 std::string plugin_class;
211 declare_parameter_if_not_declared(
212 node, dwb_plugin_name_ +
"." + critic_plugin_name +
".class",
213 rclcpp::ParameterValue(critic_plugin_name));
214 node->get_parameter(dwb_plugin_name_ +
"." + critic_plugin_name +
".class", plugin_class);
218 TrajectoryCritic::Ptr plugin = critic_loader_.createUniqueInstance(plugin_class);
221 "Using critic \"%s\" (%s)", critic_plugin_name.c_str(), plugin_class.c_str());
222 critics_.push_back(plugin);
224 plugin->initialize(node, critic_plugin_name, dwb_plugin_name_, costmap_ros_);
225 }
catch (
const std::exception & e) {
226 RCLCPP_ERROR(logger_,
"Couldn't initialize critic plugin!");
228 "Couldn't initialize critic plugin: " +
229 std::string(e.what()));
231 RCLCPP_INFO(logger_,
"Critic plugin initialized");
238 for (TrajectoryCritic::Ptr & critic : critics_) {
242 traj_generator_->reset();
244 pub_->publishGlobalPlan(path);
248 geometry_msgs::msg::TwistStamped
250 const geometry_msgs::msg::PoseStamped & pose,
251 const geometry_msgs::msg::Twist & velocity,
254 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> results =
nullptr;
255 if (pub_->shouldRecordEvaluation()) {
256 results = std::make_shared<dwb_msgs::msg::LocalPlanEvaluation>();
262 nav_2d_utils::twist3Dto2D(velocity), results);
263 pub_->publishEvaluation(results);
264 geometry_msgs::msg::TwistStamped cmd_vel;
265 cmd_vel.twist = nav_2d_utils::twist2Dto3D(cmd_vel2d.velocity);
268 pub_->publishEvaluation(results);
271 pub_->publishEvaluation(results);
274 pub_->publishEvaluation(results);
277 pub_->publishEvaluation(results);
284 const geometry_msgs::msg::PoseStamped & pose, nav_msgs::msg::Path & transformed_plan,
285 geometry_msgs::msg::PoseStamped & goal_pose,
bool publish_plan)
289 pub_->publishTransformedPlan(transformed_plan);
292 goal_pose.header.frame_id =
global_plan_.header.frame_id;
293 goal_pose.header.stamp = pose.header.stamp;
295 nav2_util::transformPoseInTargetFrame(
296 goal_pose, goal_pose, *tf_,
297 costmap_ros_->getGlobalFrameID(), transform_tolerance_);
300 nav_2d_msgs::msg::Twist2DStamped
302 const geometry_msgs::msg::PoseStamped & pose,
303 const nav_2d_msgs::msg::Twist2D & velocity,
304 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
307 results->header.frame_id = pose.header.frame_id;
308 results->header.stamp = clock_->now();
311 nav_msgs::msg::Path transformed_plan;
312 geometry_msgs::msg::PoseStamped goal_pose;
317 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
319 for (TrajectoryCritic::Ptr & critic : critics_) {
320 if (!critic->prepare(pose.pose, velocity, goal_pose.pose, transformed_plan)) {
321 RCLCPP_WARN(rclcpp::get_logger(
"DWBLocalPlanner"),
"A scoring function failed to prepare");
329 nav_2d_msgs::msg::Twist2DStamped cmd_vel;
330 cmd_vel.header.stamp = clock_->now();
331 cmd_vel.velocity = best.traj.velocity;
334 for (TrajectoryCritic::Ptr & critic : critics_) {
335 critic->debrief(cmd_vel.velocity);
340 pub_->publishLocalPlan(pose.header, best.traj);
341 pub_->publishCostGrid(costmap_ros_, critics_);
345 nav_2d_msgs::msg::Twist2D empty_cmd;
346 dwb_msgs::msg::Trajectory2D empty_traj;
348 for (TrajectoryCritic::Ptr & critic : critics_) {
349 critic->debrief(empty_cmd);
354 pub_->publishLocalPlan(pose.header, empty_traj);
355 pub_->publishCostGrid(costmap_ros_, critics_);
358 "Could not find a legal trajectory: " +
359 std::string(e.what()));
363 dwb_msgs::msg::TrajectoryScore
365 const geometry_msgs::msg::Pose & pose,
366 const nav_2d_msgs::msg::Twist2D velocity,
367 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
369 nav_2d_msgs::msg::Twist2D twist;
370 dwb_msgs::msg::Trajectory2D traj;
371 dwb_msgs::msg::TrajectoryScore best, worst;
376 traj_generator_->startNewIteration(velocity);
377 while (traj_generator_->hasMoreTwists()) {
378 twist = traj_generator_->nextTwist();
379 traj = traj_generator_->generateTrajectory(pose, velocity, twist);
382 dwb_msgs::msg::TrajectoryScore score =
scoreTrajectory(traj, best.total);
383 tracker.addLegalTrajectory();
385 results->twists.push_back(score);
387 if (best.total < 0 || score.total < best.total) {
390 results->best_index = results->twists.size() - 1;
393 if (worst.total < 0 || score.total > worst.total) {
396 results->worst_index = results->twists.size() - 1;
401 dwb_msgs::msg::TrajectoryScore failed_score;
402 failed_score.traj = traj;
404 dwb_msgs::msg::CriticScore cs;
405 cs.name = e.getCriticName();
407 failed_score.scores.push_back(cs);
408 failed_score.total = -1.0;
409 results->twists.push_back(failed_score);
411 tracker.addIllegalTrajectory(e);
415 if (best.total < 0) {
416 if (debug_trajectory_details_) {
417 RCLCPP_ERROR(rclcpp::get_logger(
"DWBLocalPlanner"),
"%s", tracker.getMessage().c_str());
418 for (
auto const & x : tracker.getPercentages()) {
421 "DWBLocalPlanner"),
"%.2f: %10s/%s", x.second,
422 x.first.first.c_str(), x.first.second.c_str());
431 dwb_msgs::msg::TrajectoryScore
433 const dwb_msgs::msg::Trajectory2D & traj,
436 dwb_msgs::msg::TrajectoryScore score;
439 for (TrajectoryCritic::Ptr & critic : critics_) {
440 dwb_msgs::msg::CriticScore cs;
441 cs.name = critic->getName();
442 cs.scale = critic->getScale();
444 if (cs.scale == 0.0) {
445 score.scores.push_back(cs);
449 double critic_score = critic->scoreTrajectory(traj);
450 cs.raw_score = critic_score;
451 score.scores.push_back(cs);
452 score.total += critic_score * cs.scale;
453 if (short_circuit_trajectory_evaluation_ && best_score > 0 && score.total > best_score) {
464 const geometry_msgs::msg::PoseStamped & pose)
471 geometry_msgs::msg::PoseStamped robot_pose;
472 if (!nav2_util::transformPoseInTargetFrame(
473 pose, robot_pose, *tf_,
477 ControllerTFError(
"Unable to transform robot pose into global plan's frame");
487 double prune_dist = prune_distance_;
492 double transform_start_threshold;
494 transform_start_threshold = std::min(dist_threshold, prune_dist);
496 transform_start_threshold = dist_threshold;
502 double transform_end_threshold;
503 double forward_prune_dist = forward_prune_distance_;
504 if (shorten_transformed_plan_) {
505 transform_end_threshold = std::min(dist_threshold, forward_prune_dist);
507 transform_end_threshold = dist_threshold;
512 auto prune_point = nav2_util::geometry_utils::first_after_integrated_distance(
517 auto transformation_begin = std::find_if(
519 [&](
const auto & global_plan_pose) {
520 return euclidean_distance(robot_pose, global_plan_pose) < transform_start_threshold;
525 auto transformation_end = std::find_if(
527 [&](
const auto & global_plan_pose) {
528 return euclidean_distance(global_plan_pose, robot_pose) > transform_end_threshold;
532 nav_msgs::msg::Path transformed_plan;
533 transformed_plan.header.frame_id = costmap_ros_->getGlobalFrameID();
534 transformed_plan.header.stamp = pose.header.stamp;
538 auto transformGlobalPoseToLocal = [&](
const auto & global_plan_pose) {
539 geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
540 stamped_pose.header.frame_id =
global_plan_.header.frame_id;
541 stamped_pose.header.stamp = robot_pose.header.stamp;
542 stamped_pose.pose = global_plan_pose.pose;
543 if (!nav2_util::transformPoseInTargetFrame(
544 stamped_pose, transformed_pose, *tf_,
545 transformed_plan.header.frame_id, transform_tolerance_))
549 transformed_pose.pose.position.z = 0.0;
550 return transformed_pose;
554 transformation_begin, transformation_end,
555 std::back_inserter(transformed_plan.poses),
556 transformGlobalPoseToLocal);
565 if (transformed_plan.poses.empty()) {
568 return transformed_plan;
574 PLUGINLIB_EXPORT_CLASS(
Plugin-based flexible controller.
virtual nav_msgs::msg::Path transformGlobalPlan(const geometry_msgs::msg::PoseStamped &pose)
Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses...
virtual dwb_msgs::msg::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::msg::Pose &pose, const nav_2d_msgs::msg::Twist2D velocity, std::shared_ptr< dwb_msgs::msg::LocalPlanEvaluation > &results)
Iterate through all the twists and find the best one.
void configure(const nav2::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
void cleanup() override
Cleanup lifecycle node.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
std::string resolveCriticClassName(std::string base_name)
try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic"
void deactivate() override
Deactivate lifecycle node.
DWBLocalPlanner()
Constructor that brings up pluginlib loaders.
nav_msgs::msg::Path global_plan_
Saved Global Plan.
void prepareGlobalPlan(const geometry_msgs::msg::PoseStamped &pose, nav_msgs::msg::Path &transformed_plan, geometry_msgs::msg::PoseStamped &goal_pose, bool publish_plan=true)
Helper method for two common operations for the operating on the global_plan.
virtual dwb_msgs::msg::TrajectoryScore scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj, double best_score=-1)
Score a given command. Can be used for testing.
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *) override
nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity
virtual void loadCritics()
Load the critic parameters from the namespace.
void activate() override
Activate lifecycle node.
Thrown when one of the critics encountered a fatal error.
Thrown when all the trajectories explored are illegal.
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.
A 2D costmap provides a mapping between points in the world and their associated "costs".
double getResolution() const
Accessor for the resolution of the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.