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 "nav_2d_utils/parameters.hpp"
48 #include "nav_2d_utils/tf_help.hpp"
49 #include "nav2_util/geometry_utils.hpp"
50 #include "nav2_util/lifecycle_node.hpp"
51 #include "nav2_util/node_utils.hpp"
52 #include "pluginlib/class_list_macros.hpp"
53 #include "nav_msgs/msg/path.hpp"
54 #include "geometry_msgs/msg/twist_stamped.hpp"
56 using nav2_util::declare_parameter_if_not_declared;
57 using nav2_util::geometry_utils::euclidean_distance;
63 : traj_gen_loader_(
"dwb_core",
"dwb_core::TrajectoryGenerator"),
64 critic_loader_(
"dwb_core",
"dwb_core::TrajectoryCritic")
69 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
70 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
71 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
74 auto node = node_.lock();
76 logger_ = node->get_logger();
77 clock_ = node->get_clock();
78 costmap_ros_ = costmap_ros;
80 dwb_plugin_name_ = name;
81 declare_parameter_if_not_declared(
82 node, dwb_plugin_name_ +
".critics",
83 rclcpp::PARAMETER_STRING_ARRAY);
84 declare_parameter_if_not_declared(
85 node, dwb_plugin_name_ +
".default_critic_namespaces",
86 rclcpp::ParameterValue(std::vector<std::string>()));
87 declare_parameter_if_not_declared(
88 node, dwb_plugin_name_ +
".prune_plan",
89 rclcpp::ParameterValue(
true));
90 declare_parameter_if_not_declared(
91 node, dwb_plugin_name_ +
".prune_distance",
92 rclcpp::ParameterValue(2.0));
93 declare_parameter_if_not_declared(
94 node, dwb_plugin_name_ +
".forward_prune_distance",
95 rclcpp::ParameterValue(2.0));
96 declare_parameter_if_not_declared(
97 node, dwb_plugin_name_ +
".debug_trajectory_details",
98 rclcpp::ParameterValue(
false));
99 declare_parameter_if_not_declared(
100 node, dwb_plugin_name_ +
".trajectory_generator_name",
101 rclcpp::ParameterValue(std::string(
"dwb_plugins::StandardTrajectoryGenerator")));
102 declare_parameter_if_not_declared(
103 node, dwb_plugin_name_ +
".transform_tolerance",
104 rclcpp::ParameterValue(0.1));
105 declare_parameter_if_not_declared(
106 node, dwb_plugin_name_ +
".shorten_transformed_plan",
107 rclcpp::ParameterValue(
true));
108 declare_parameter_if_not_declared(
109 node, dwb_plugin_name_ +
".short_circuit_trajectory_evaluation",
110 rclcpp::ParameterValue(
true));
112 std::string traj_generator_name;
114 double transform_tolerance;
115 node->get_parameter(dwb_plugin_name_ +
".transform_tolerance", transform_tolerance);
116 transform_tolerance_ = rclcpp::Duration::from_seconds(transform_tolerance);
117 RCLCPP_INFO(logger_,
"Setting transform_tolerance to %f", transform_tolerance);
119 node->get_parameter(dwb_plugin_name_ +
".prune_plan", prune_plan_);
120 node->get_parameter(dwb_plugin_name_ +
".prune_distance", prune_distance_);
121 node->get_parameter(dwb_plugin_name_ +
".forward_prune_distance", forward_prune_distance_);
122 node->get_parameter(dwb_plugin_name_ +
".debug_trajectory_details", debug_trajectory_details_);
123 node->get_parameter(dwb_plugin_name_ +
".trajectory_generator_name", traj_generator_name);
125 dwb_plugin_name_ +
".short_circuit_trajectory_evaluation",
126 short_circuit_trajectory_evaluation_);
127 node->get_parameter(dwb_plugin_name_ +
".shorten_transformed_plan", shorten_transformed_plan_);
129 pub_ = std::make_unique<DWBPublisher>(node, dwb_plugin_name_);
130 pub_->on_configure();
132 traj_generator_ = traj_gen_loader_.createUniqueInstance(traj_generator_name);
134 traj_generator_->initialize(node, dwb_plugin_name_);
138 }
catch (
const std::exception & e) {
139 RCLCPP_ERROR(logger_,
"Couldn't load critics! Caught exception: %s", e.what());
153 pub_->on_deactivate();
161 traj_generator_.reset();
167 if (base_name.find(
"Critic") == std::string::npos) {
168 base_name = base_name +
"Critic";
171 if (base_name.find(
"::") == std::string::npos) {
172 for (
unsigned int j = 0; j < default_critic_namespaces_.size(); j++) {
173 std::string full_name = default_critic_namespaces_[j] +
"::" + base_name;
174 if (critic_loader_.isClassAvailable(full_name)) {
185 auto node = node_.lock();
187 throw std::runtime_error{
"Failed to lock node"};
190 node->get_parameter(dwb_plugin_name_ +
".default_critic_namespaces", default_critic_namespaces_);
191 if (default_critic_namespaces_.empty()) {
192 default_critic_namespaces_.emplace_back(
"dwb_critics");
195 std::vector<std::string> critic_names;
196 if (!node->get_parameter(dwb_plugin_name_ +
".critics", critic_names)) {
197 throw std::runtime_error(
"No critics defined for " + dwb_plugin_name_);
200 node->get_parameter(dwb_plugin_name_ +
".critics", critic_names);
201 for (
unsigned int i = 0; i < critic_names.size(); i++) {
202 std::string critic_plugin_name = critic_names[i];
203 std::string plugin_class;
205 declare_parameter_if_not_declared(
206 node, dwb_plugin_name_ +
"." + critic_plugin_name +
".class",
207 rclcpp::ParameterValue(critic_plugin_name));
208 node->get_parameter(dwb_plugin_name_ +
"." + critic_plugin_name +
".class", plugin_class);
212 TrajectoryCritic::Ptr plugin = critic_loader_.createUniqueInstance(plugin_class);
215 "Using critic \"%s\" (%s)", critic_plugin_name.c_str(), plugin_class.c_str());
216 critics_.push_back(plugin);
218 plugin->initialize(node, critic_plugin_name, dwb_plugin_name_, costmap_ros_);
219 }
catch (
const std::exception & e) {
220 RCLCPP_ERROR(logger_,
"Couldn't initialize critic plugin!");
223 RCLCPP_INFO(logger_,
"Critic plugin initialized");
230 auto path2d = nav_2d_utils::pathToPath2D(path);
231 for (TrajectoryCritic::Ptr & critic : critics_) {
235 traj_generator_->reset();
237 pub_->publishGlobalPlan(path2d);
241 geometry_msgs::msg::TwistStamped
243 const geometry_msgs::msg::PoseStamped & pose,
244 const geometry_msgs::msg::Twist & velocity,
247 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> results =
nullptr;
248 if (pub_->shouldRecordEvaluation()) {
249 results = std::make_shared<dwb_msgs::msg::LocalPlanEvaluation>();
254 nav_2d_utils::poseStampedToPose2D(pose),
255 nav_2d_utils::twist3Dto2D(velocity), results);
256 pub_->publishEvaluation(results);
257 geometry_msgs::msg::TwistStamped cmd_vel;
258 cmd_vel.twist = nav_2d_utils::twist2Dto3D(cmd_vel2d.velocity);
261 pub_->publishEvaluation(results);
268 const nav_2d_msgs::msg::Pose2DStamped & pose, nav_2d_msgs::msg::Path2D & transformed_plan,
269 nav_2d_msgs::msg::Pose2DStamped & goal_pose,
bool publish_plan)
273 pub_->publishTransformedPlan(transformed_plan);
276 goal_pose.header.frame_id =
global_plan_.header.frame_id;
278 nav_2d_utils::transformPose(
279 tf_, costmap_ros_->getGlobalFrameID(), goal_pose,
280 goal_pose, transform_tolerance_);
283 nav_2d_msgs::msg::Twist2DStamped
285 const nav_2d_msgs::msg::Pose2DStamped & pose,
286 const nav_2d_msgs::msg::Twist2D & velocity,
287 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
290 results->header.frame_id = pose.header.frame_id;
291 results->header.stamp = clock_->now();
294 nav_2d_msgs::msg::Path2D transformed_plan;
295 nav_2d_msgs::msg::Pose2DStamped goal_pose;
300 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
302 for (TrajectoryCritic::Ptr & critic : critics_) {
303 if (!critic->prepare(pose.pose, velocity, goal_pose.pose, transformed_plan)) {
304 RCLCPP_WARN(rclcpp::get_logger(
"DWBLocalPlanner"),
"A scoring function failed to prepare");
312 nav_2d_msgs::msg::Twist2DStamped cmd_vel;
313 cmd_vel.header.stamp = clock_->now();
314 cmd_vel.velocity = best.traj.velocity;
317 for (TrajectoryCritic::Ptr & critic : critics_) {
318 critic->debrief(cmd_vel.velocity);
323 pub_->publishLocalPlan(pose.header, best.traj);
324 pub_->publishCostGrid(costmap_ros_, critics_);
328 nav_2d_msgs::msg::Twist2D empty_cmd;
329 dwb_msgs::msg::Trajectory2D empty_traj;
331 for (TrajectoryCritic::Ptr & critic : critics_) {
332 critic->debrief(empty_cmd);
337 pub_->publishLocalPlan(pose.header, empty_traj);
338 pub_->publishCostGrid(costmap_ros_, critics_);
344 dwb_msgs::msg::TrajectoryScore
346 const geometry_msgs::msg::Pose2D & pose,
347 const nav_2d_msgs::msg::Twist2D velocity,
348 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
350 nav_2d_msgs::msg::Twist2D twist;
351 dwb_msgs::msg::Trajectory2D traj;
352 dwb_msgs::msg::TrajectoryScore best, worst;
357 traj_generator_->startNewIteration(velocity);
358 while (traj_generator_->hasMoreTwists()) {
359 twist = traj_generator_->nextTwist();
360 traj = traj_generator_->generateTrajectory(pose, velocity, twist);
363 dwb_msgs::msg::TrajectoryScore score =
scoreTrajectory(traj, best.total);
364 tracker.addLegalTrajectory();
366 results->twists.push_back(score);
368 if (best.total < 0 || score.total < best.total) {
371 results->best_index = results->twists.size() - 1;
374 if (worst.total < 0 || score.total > worst.total) {
377 results->worst_index = results->twists.size() - 1;
382 dwb_msgs::msg::TrajectoryScore failed_score;
383 failed_score.traj = traj;
385 dwb_msgs::msg::CriticScore cs;
386 cs.name = e.getCriticName();
388 failed_score.scores.push_back(cs);
389 failed_score.total = -1.0;
390 results->twists.push_back(failed_score);
392 tracker.addIllegalTrajectory(e);
396 if (best.total < 0) {
397 if (debug_trajectory_details_) {
398 RCLCPP_ERROR(rclcpp::get_logger(
"DWBLocalPlanner"),
"%s", tracker.getMessage().c_str());
399 for (
auto const & x : tracker.getPercentages()) {
402 "DWBLocalPlanner"),
"%.2f: %10s/%s", x.second,
403 x.first.first.c_str(), x.first.second.c_str());
412 dwb_msgs::msg::TrajectoryScore
414 const dwb_msgs::msg::Trajectory2D & traj,
417 dwb_msgs::msg::TrajectoryScore score;
420 for (TrajectoryCritic::Ptr & critic : critics_) {
421 dwb_msgs::msg::CriticScore cs;
422 cs.name = critic->getName();
423 cs.scale = critic->getScale();
425 if (cs.scale == 0.0) {
426 score.scores.push_back(cs);
430 double critic_score = critic->scoreTrajectory(traj);
431 cs.raw_score = critic_score;
432 score.scores.push_back(cs);
433 score.total += critic_score * cs.scale;
434 if (short_circuit_trajectory_evaluation_ && best_score > 0 && score.total > best_score) {
443 nav_2d_msgs::msg::Path2D
445 const nav_2d_msgs::msg::Pose2DStamped & pose)
452 nav_2d_msgs::msg::Pose2DStamped robot_pose;
453 if (!nav_2d_utils::transformPose(
455 robot_pose, transform_tolerance_))
458 PlannerTFException(
"Unable to transform robot pose into global plan's frame");
468 double prune_dist = prune_distance_;
473 double transform_start_threshold;
475 transform_start_threshold = std::min(dist_threshold, prune_dist);
477 transform_start_threshold = dist_threshold;
483 double transform_end_threshold;
484 double forward_prune_dist = forward_prune_distance_;
485 if (shorten_transformed_plan_) {
486 transform_end_threshold = std::min(dist_threshold, forward_prune_dist);
488 transform_end_threshold = dist_threshold;
493 auto prune_point = nav2_util::geometry_utils::first_after_integrated_distance(
498 auto transformation_begin = std::find_if(
500 [&](
const auto & global_plan_pose) {
501 return euclidean_distance(robot_pose.pose, global_plan_pose) < transform_start_threshold;
506 auto transformation_end = std::find_if(
508 [&](
const auto & pose) {
509 return euclidean_distance(pose, robot_pose.pose) > transform_end_threshold;
513 nav_2d_msgs::msg::Path2D transformed_plan;
514 transformed_plan.header.frame_id = costmap_ros_->getGlobalFrameID();
515 transformed_plan.header.stamp = pose.header.stamp;
519 auto transformGlobalPoseToLocal = [&](
const auto & global_plan_pose) {
520 nav_2d_msgs::msg::Pose2DStamped stamped_pose, transformed_pose;
521 stamped_pose.header.frame_id =
global_plan_.header.frame_id;
522 stamped_pose.pose = global_plan_pose;
523 nav_2d_utils::transformPose(
524 tf_, transformed_plan.header.frame_id,
525 stamped_pose, transformed_pose, transform_tolerance_);
526 return transformed_pose.pose;
530 transformation_begin, transformation_end,
531 std::back_inserter(transformed_plan.poses),
532 transformGlobalPoseToLocal);
541 if (transformed_plan.poses.empty()) {
544 return transformed_plan;
550 PLUGINLIB_EXPORT_CLASS(
Plugin-based flexible controller.
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.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
DWBLocalPlanner()
Constructor that brings up pluginlib loaders.
virtual dwb_msgs::msg::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::msg::Pose2D &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.
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.
void prepareGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped &pose, nav_2d_msgs::msg::Path2D &transformed_plan, nav_2d_msgs::msg::Pose2DStamped &goal_pose, bool publish_plan=true)
Helper method for two common operations for the operating on the global_plan.
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.
nav_2d_msgs::msg::Path2D global_plan_
Saved Global Plan.
virtual nav_2d_msgs::msg::Path2D transformGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped &pose)
Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses...
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.