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()));
154 traj_generator_->activate();
160 pub_->on_deactivate();
161 traj_generator_->deactivate();
169 traj_generator_.reset();
175 if (base_name.find(
"Critic") == std::string::npos) {
176 base_name = base_name +
"Critic";
179 if (base_name.find(
"::") == std::string::npos) {
180 for (
unsigned int j = 0; j < default_critic_namespaces_.size(); j++) {
181 std::string full_name = default_critic_namespaces_[j] +
"::" + base_name;
182 if (critic_loader_.isClassAvailable(full_name)) {
193 auto node = node_.lock();
195 throw std::runtime_error{
"Failed to lock node"};
198 node->get_parameter(dwb_plugin_name_ +
".default_critic_namespaces", default_critic_namespaces_);
199 if (default_critic_namespaces_.empty()) {
200 default_critic_namespaces_.emplace_back(
"dwb_critics");
203 std::vector<std::string> critic_names;
204 if (!node->get_parameter(dwb_plugin_name_ +
".critics", critic_names)) {
205 throw std::runtime_error(
"No critics defined for " + dwb_plugin_name_);
208 node->get_parameter(dwb_plugin_name_ +
".critics", critic_names);
209 for (
unsigned int i = 0; i < critic_names.size(); i++) {
210 std::string critic_plugin_name = critic_names[i];
211 std::string plugin_class;
213 declare_parameter_if_not_declared(
214 node, dwb_plugin_name_ +
"." + critic_plugin_name +
".class",
215 rclcpp::ParameterValue(critic_plugin_name));
216 node->get_parameter(dwb_plugin_name_ +
"." + critic_plugin_name +
".class", plugin_class);
220 TrajectoryCritic::Ptr plugin = critic_loader_.createUniqueInstance(plugin_class);
223 "Using critic \"%s\" (%s)", critic_plugin_name.c_str(), plugin_class.c_str());
224 critics_.push_back(plugin);
226 plugin->initialize(node, critic_plugin_name, dwb_plugin_name_, costmap_ros_);
227 }
catch (
const std::exception & e) {
228 RCLCPP_ERROR(logger_,
"Couldn't initialize critic plugin!");
230 "Couldn't initialize critic plugin: " +
231 std::string(e.what()));
233 RCLCPP_INFO(logger_,
"Critic plugin initialized");
240 for (TrajectoryCritic::Ptr & critic : critics_) {
244 traj_generator_->reset();
246 pub_->publishGlobalPlan(path);
250 geometry_msgs::msg::TwistStamped
252 const geometry_msgs::msg::PoseStamped & pose,
253 const geometry_msgs::msg::Twist & velocity,
256 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> results =
nullptr;
257 if (pub_->shouldRecordEvaluation()) {
258 results = std::make_shared<dwb_msgs::msg::LocalPlanEvaluation>();
264 nav_2d_utils::twist3Dto2D(velocity), results);
265 pub_->publishEvaluation(results);
266 geometry_msgs::msg::TwistStamped cmd_vel;
267 cmd_vel.twist = nav_2d_utils::twist2Dto3D(cmd_vel2d.velocity);
270 pub_->publishEvaluation(results);
273 pub_->publishEvaluation(results);
276 pub_->publishEvaluation(results);
279 pub_->publishEvaluation(results);
286 const geometry_msgs::msg::PoseStamped & pose, nav_msgs::msg::Path & transformed_plan,
287 geometry_msgs::msg::PoseStamped & goal_pose,
bool publish_plan)
291 pub_->publishTransformedPlan(transformed_plan);
294 goal_pose.header.frame_id =
global_plan_.header.frame_id;
295 goal_pose.header.stamp = pose.header.stamp;
297 nav2_util::transformPoseInTargetFrame(
298 goal_pose, goal_pose, *tf_,
299 costmap_ros_->getGlobalFrameID(), transform_tolerance_);
302 nav_2d_msgs::msg::Twist2DStamped
304 const geometry_msgs::msg::PoseStamped & pose,
305 const nav_2d_msgs::msg::Twist2D & velocity,
306 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
309 results->header.frame_id = pose.header.frame_id;
310 results->header.stamp = clock_->now();
313 nav_msgs::msg::Path transformed_plan;
314 geometry_msgs::msg::PoseStamped goal_pose;
319 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
321 for (TrajectoryCritic::Ptr & critic : critics_) {
322 if (!critic->prepare(pose.pose, velocity, goal_pose.pose, transformed_plan)) {
323 RCLCPP_WARN(rclcpp::get_logger(
"DWBLocalPlanner"),
"A scoring function failed to prepare");
331 nav_2d_msgs::msg::Twist2DStamped cmd_vel;
332 cmd_vel.header.stamp = clock_->now();
333 cmd_vel.velocity = best.traj.velocity;
336 for (TrajectoryCritic::Ptr & critic : critics_) {
337 critic->debrief(cmd_vel.velocity);
342 pub_->publishLocalPlan(pose.header, best.traj);
343 pub_->publishCostGrid(costmap_ros_, critics_);
347 nav_2d_msgs::msg::Twist2D empty_cmd;
348 dwb_msgs::msg::Trajectory2D empty_traj;
350 for (TrajectoryCritic::Ptr & critic : critics_) {
351 critic->debrief(empty_cmd);
356 pub_->publishLocalPlan(pose.header, empty_traj);
357 pub_->publishCostGrid(costmap_ros_, critics_);
360 "Could not find a legal trajectory: " +
361 std::string(e.what()));
365 dwb_msgs::msg::TrajectoryScore
367 const geometry_msgs::msg::Pose & pose,
368 const nav_2d_msgs::msg::Twist2D velocity,
369 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
371 nav_2d_msgs::msg::Twist2D twist;
372 dwb_msgs::msg::Trajectory2D traj;
373 dwb_msgs::msg::TrajectoryScore best, worst;
378 traj_generator_->startNewIteration(velocity);
379 while (traj_generator_->hasMoreTwists()) {
380 twist = traj_generator_->nextTwist();
381 traj = traj_generator_->generateTrajectory(pose, velocity, twist);
384 dwb_msgs::msg::TrajectoryScore score =
scoreTrajectory(traj, best.total);
385 tracker.addLegalTrajectory();
387 results->twists.push_back(score);
389 if (best.total < 0 || score.total < best.total) {
392 results->best_index = results->twists.size() - 1;
395 if (worst.total < 0 || score.total > worst.total) {
398 results->worst_index = results->twists.size() - 1;
403 dwb_msgs::msg::TrajectoryScore failed_score;
404 failed_score.traj = traj;
406 dwb_msgs::msg::CriticScore cs;
407 cs.name = e.getCriticName();
409 failed_score.scores.push_back(cs);
410 failed_score.total = -1.0;
411 results->twists.push_back(failed_score);
413 tracker.addIllegalTrajectory(e);
417 if (best.total < 0) {
418 if (debug_trajectory_details_) {
419 RCLCPP_ERROR(rclcpp::get_logger(
"DWBLocalPlanner"),
"%s", tracker.getMessage().c_str());
420 for (
auto const & x : tracker.getPercentages()) {
423 "DWBLocalPlanner"),
"%.2f: %10s/%s", x.second,
424 x.first.first.c_str(), x.first.second.c_str());
433 dwb_msgs::msg::TrajectoryScore
435 const dwb_msgs::msg::Trajectory2D & traj,
438 dwb_msgs::msg::TrajectoryScore score;
441 for (TrajectoryCritic::Ptr & critic : critics_) {
442 dwb_msgs::msg::CriticScore cs;
443 cs.name = critic->getName();
444 cs.scale = critic->getScale();
446 if (cs.scale == 0.0) {
447 score.scores.push_back(cs);
451 double critic_score = critic->scoreTrajectory(traj);
452 cs.raw_score = critic_score;
453 score.scores.push_back(cs);
454 score.total += critic_score * cs.scale;
455 if (short_circuit_trajectory_evaluation_ && best_score > 0 && score.total > best_score) {
466 const geometry_msgs::msg::PoseStamped & pose)
473 geometry_msgs::msg::PoseStamped robot_pose;
474 if (!nav2_util::transformPoseInTargetFrame(
475 pose, robot_pose, *tf_,
479 ControllerTFError(
"Unable to transform robot pose into global plan's frame");
489 double prune_dist = prune_distance_;
494 double transform_start_threshold;
496 transform_start_threshold = std::min(dist_threshold, prune_dist);
498 transform_start_threshold = dist_threshold;
504 double transform_end_threshold;
505 double forward_prune_dist = forward_prune_distance_;
506 if (shorten_transformed_plan_) {
507 transform_end_threshold = std::min(dist_threshold, forward_prune_dist);
509 transform_end_threshold = dist_threshold;
514 auto prune_point = nav2_util::geometry_utils::first_after_integrated_distance(
519 auto transformation_begin = std::find_if(
521 [&](
const auto & global_plan_pose) {
522 return euclidean_distance(robot_pose, global_plan_pose) < transform_start_threshold;
527 auto transformation_end = std::find_if(
529 [&](
const auto & global_plan_pose) {
530 return euclidean_distance(global_plan_pose, robot_pose) > transform_end_threshold;
534 nav_msgs::msg::Path transformed_plan;
535 transformed_plan.header.frame_id = costmap_ros_->getGlobalFrameID();
536 transformed_plan.header.stamp = pose.header.stamp;
540 auto transformGlobalPoseToLocal = [&](
const auto & global_plan_pose) {
541 geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
542 stamped_pose.header.frame_id =
global_plan_.header.frame_id;
543 stamped_pose.header.stamp = robot_pose.header.stamp;
544 stamped_pose.pose = global_plan_pose.pose;
545 if (!nav2_util::transformPoseInTargetFrame(
546 stamped_pose, transformed_pose, *tf_,
547 transformed_plan.header.frame_id, transform_tolerance_))
551 transformed_pose.pose.position.z = 0.0;
552 return transformed_pose;
556 transformation_begin, transformation_end,
557 std::back_inserter(transformed_plan.poses),
558 transformGlobalPoseToLocal);
567 if (transformed_plan.poses.empty()) {
570 return transformed_plan;
576 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.