Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
controller_server.cpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <chrono>
16 #include <vector>
17 #include <memory>
18 #include <string>
19 #include <utility>
20 #include <limits>
21 
22 #include "lifecycle_msgs/msg/state.hpp"
23 #include "nav2_core/controller_exceptions.hpp"
24 #include "nav2_ros_common/node_utils.hpp"
25 #include "nav2_util/geometry_utils.hpp"
26 #include "nav2_util/path_utils.hpp"
27 #include "nav2_controller/controller_server.hpp"
28 
29 using namespace std::chrono_literals;
30 using rcl_interfaces::msg::ParameterType;
31 using std::placeholders::_1;
32 
33 namespace nav2_controller
34 {
35 
36 ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
37 : nav2::LifecycleNode("controller_server", "", options),
38  progress_checker_loader_("nav2_core", "nav2_core::ProgressChecker"),
39  default_progress_checker_ids_{"progress_checker"},
40  default_progress_checker_types_{"nav2_controller::SimpleProgressChecker"},
41  goal_checker_loader_("nav2_core", "nav2_core::GoalChecker"),
42  default_goal_checker_ids_{"goal_checker"},
43  default_goal_checker_types_{"nav2_controller::SimpleGoalChecker"},
44  lp_loader_("nav2_core", "nav2_core::Controller"),
45  default_ids_{"FollowPath"},
46  default_types_{"dwb_core::DWBLocalPlanner"},
47  start_index_(0),
48  costmap_update_timeout_(300ms)
49 {
50  RCLCPP_INFO(get_logger(), "Creating controller server");
51 
52  // The costmap node is used in the implementation of the controller
53  costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
54  "local_costmap", std::string{get_namespace()},
55  get_parameter("use_sim_time").as_bool(), options);
56 }
57 
59 {
60  progress_checkers_.clear();
61  goal_checkers_.clear();
62  controllers_.clear();
63  costmap_thread_.reset();
64 }
65 
66 nav2::CallbackReturn
67 ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
68 {
69  auto node = shared_from_this();
70 
71  RCLCPP_INFO(get_logger(), "Configuring controller interface");
72 
73  RCLCPP_INFO(get_logger(), "getting progress checker plugins..");
74  progress_checker_ids_ = declare_or_get_parameter(
75  "progress_checker_plugins", default_progress_checker_ids_);
76  if (progress_checker_ids_ == default_progress_checker_ids_) {
77  for (size_t i = 0; i < default_progress_checker_ids_.size(); ++i) {
78  nav2::declare_parameter_if_not_declared(
79  node, default_progress_checker_ids_[i] + ".plugin",
80  rclcpp::ParameterValue(default_progress_checker_types_[i]));
81  }
82  }
83 
84  RCLCPP_INFO(get_logger(), "getting goal checker plugins..");
85  goal_checker_ids_ = declare_or_get_parameter("goal_checker_plugins", default_goal_checker_ids_);
86  if (goal_checker_ids_ == default_goal_checker_ids_) {
87  for (size_t i = 0; i < default_goal_checker_ids_.size(); ++i) {
88  nav2::declare_parameter_if_not_declared(
89  node, default_goal_checker_ids_[i] + ".plugin",
90  rclcpp::ParameterValue(default_goal_checker_types_[i]));
91  }
92  }
93 
94  controller_ids_ = declare_or_get_parameter("controller_plugins", default_ids_);
95  if (controller_ids_ == default_ids_) {
96  for (size_t i = 0; i < default_ids_.size(); ++i) {
97  nav2::declare_parameter_if_not_declared(
98  node, default_ids_[i] + ".plugin",
99  rclcpp::ParameterValue(default_types_[i]));
100  }
101  }
102 
103  controller_types_.resize(controller_ids_.size());
104  goal_checker_types_.resize(goal_checker_ids_.size());
105  progress_checker_types_.resize(progress_checker_ids_.size());
106 
107  controller_frequency_ = declare_or_get_parameter("controller_frequency", 20.0);
108  min_x_velocity_threshold_ = declare_or_get_parameter("min_x_velocity_threshold", 0.0001);
109  min_y_velocity_threshold_ = declare_or_get_parameter("min_y_velocity_threshold", 0.0001);
110  min_theta_velocity_threshold_ = declare_or_get_parameter("min_theta_velocity_threshold", 0.0001);
111  RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
112 
113  std::string speed_limit_topic = declare_or_get_parameter(
114  "speed_limit_topic", std::string("speed_limit"));
115  std::string odom_topic = declare_or_get_parameter("odom_topic", std::string("odom"));
116  double odom_duration = declare_or_get_parameter("odom_duration", 0.3);
117  failure_tolerance_ = declare_or_get_parameter("failure_tolerance", 0.0);
118  use_realtime_priority_ = declare_or_get_parameter("use_realtime_priority", false);
119  publish_zero_velocity_ = declare_or_get_parameter("publish_zero_velocity", true);
120  search_window_ = declare_or_get_parameter("search_window", 2.0);
121 
122  costmap_ros_->configure();
123  // Launch a thread to run the costmap node
124  costmap_thread_ = std::make_unique<nav2::NodeThread>(costmap_ros_);
125 
126  for (size_t i = 0; i != progress_checker_ids_.size(); i++) {
127  try {
128  progress_checker_types_[i] = nav2::get_plugin_type_param(
129  node, progress_checker_ids_[i]);
130  nav2_core::ProgressChecker::Ptr progress_checker =
131  progress_checker_loader_.createUniqueInstance(progress_checker_types_[i]);
132  RCLCPP_INFO(
133  get_logger(), "Created progress_checker : %s of type %s",
134  progress_checker_ids_[i].c_str(), progress_checker_types_[i].c_str());
135  progress_checker->initialize(node, progress_checker_ids_[i]);
136  progress_checkers_.insert({progress_checker_ids_[i], progress_checker});
137  } catch (const std::exception & ex) {
138  RCLCPP_FATAL(
139  get_logger(),
140  "Failed to create progress_checker. Exception: %s", ex.what());
141  on_cleanup(state);
142  return nav2::CallbackReturn::FAILURE;
143  }
144  }
145 
146  for (size_t i = 0; i != progress_checker_ids_.size(); i++) {
147  progress_checker_ids_concat_ += progress_checker_ids_[i] + std::string(" ");
148  }
149 
150  RCLCPP_INFO(
151  get_logger(),
152  "Controller Server has %s progress checkers available.", progress_checker_ids_concat_.c_str());
153 
154  for (size_t i = 0; i != goal_checker_ids_.size(); i++) {
155  try {
156  goal_checker_types_[i] = nav2::get_plugin_type_param(node, goal_checker_ids_[i]);
157  nav2_core::GoalChecker::Ptr goal_checker =
158  goal_checker_loader_.createUniqueInstance(goal_checker_types_[i]);
159  RCLCPP_INFO(
160  get_logger(), "Created goal checker : %s of type %s",
161  goal_checker_ids_[i].c_str(), goal_checker_types_[i].c_str());
162  goal_checker->initialize(node, goal_checker_ids_[i], costmap_ros_);
163  goal_checkers_.insert({goal_checker_ids_[i], goal_checker});
164  } catch (const pluginlib::PluginlibException & ex) {
165  RCLCPP_FATAL(
166  get_logger(),
167  "Failed to create goal checker. Exception: %s", ex.what());
168  on_cleanup(state);
169  return nav2::CallbackReturn::FAILURE;
170  }
171  }
172 
173  for (size_t i = 0; i != goal_checker_ids_.size(); i++) {
174  goal_checker_ids_concat_ += goal_checker_ids_[i] + std::string(" ");
175  }
176 
177  RCLCPP_INFO(
178  get_logger(),
179  "Controller Server has %s goal checkers available.", goal_checker_ids_concat_.c_str());
180 
181  for (size_t i = 0; i != controller_ids_.size(); i++) {
182  try {
183  controller_types_[i] = nav2::get_plugin_type_param(node, controller_ids_[i]);
184  nav2_core::Controller::Ptr controller =
185  lp_loader_.createUniqueInstance(controller_types_[i]);
186  RCLCPP_INFO(
187  get_logger(), "Created controller : %s of type %s",
188  controller_ids_[i].c_str(), controller_types_[i].c_str());
189  controller->configure(
190  node, controller_ids_[i],
191  costmap_ros_->getTfBuffer(), costmap_ros_);
192  controllers_.insert({controller_ids_[i], controller});
193  } catch (const pluginlib::PluginlibException & ex) {
194  RCLCPP_FATAL(
195  get_logger(),
196  "Failed to create controller. Exception: %s", ex.what());
197  on_cleanup(state);
198  return nav2::CallbackReturn::FAILURE;
199  }
200  }
201 
202  for (size_t i = 0; i != controller_ids_.size(); i++) {
203  controller_ids_concat_ += controller_ids_[i] + std::string(" ");
204  }
205 
206  RCLCPP_INFO(
207  get_logger(),
208  "Controller Server has %s controllers available.", controller_ids_concat_.c_str());
209 
210  odom_sub_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration, odom_topic);
211  vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel");
212  tracking_feedback_pub_ = create_publisher<nav2_msgs::msg::TrackingFeedback>("tracking_feedback");
213 
214  double costmap_update_timeout_dbl = declare_or_get_parameter("costmap_update_timeout", 0.30);
215  costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl);
216 
217  // Create the action server that we implement with our followPath method
218  // This may throw due to real-time prioritization if user doesn't have real-time permissions
219  try {
220  action_server_ = create_action_server<Action>(
221  "follow_path",
222  std::bind(&ControllerServer::computeControl, this),
223  nullptr,
224  std::chrono::milliseconds(500),
225  true /*spin thread*/, use_realtime_priority_ /*soft realtime*/);
226  } catch (const std::runtime_error & e) {
227  RCLCPP_ERROR(get_logger(), "Error creating action server! %s", e.what());
228  on_cleanup(state);
229  return nav2::CallbackReturn::FAILURE;
230  }
231 
232  // Set subscription to the speed limiting topic
233  speed_limit_sub_ = create_subscription<nav2_msgs::msg::SpeedLimit>(
234  speed_limit_topic,
235  std::bind(&ControllerServer::speedLimitCallback, this, std::placeholders::_1));
236 
237  return nav2::CallbackReturn::SUCCESS;
238 }
239 
240 nav2::CallbackReturn
241 ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
242 {
243  RCLCPP_INFO(get_logger(), "Activating");
244 
245  const auto costmap_ros_state = costmap_ros_->activate();
246  if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
247  return nav2::CallbackReturn::FAILURE;
248  }
249  ControllerMap::iterator it;
250  for (it = controllers_.begin(); it != controllers_.end(); ++it) {
251  it->second->activate();
252  }
253  vel_publisher_->on_activate();
254  tracking_feedback_pub_->on_activate();
255  action_server_->activate();
256  auto node = shared_from_this();
257  // Add callback for dynamic parameters
258  dyn_params_handler_ = node->add_on_set_parameters_callback(
259  std::bind(&ControllerServer::dynamicParametersCallback, this, _1));
260 
261  // create bond connection
262  createBond();
263 
264  return nav2::CallbackReturn::SUCCESS;
265 }
266 
267 nav2::CallbackReturn
268 ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
269 {
270  RCLCPP_INFO(get_logger(), "Deactivating");
271 
272  action_server_->deactivate();
273  ControllerMap::iterator it;
274  for (it = controllers_.begin(); it != controllers_.end(); ++it) {
275  it->second->deactivate();
276  }
277 
278  /*
279  * The costmap is also a lifecycle node, so it may have already fired on_deactivate
280  * via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
281  * in the order added, the preshutdown callbacks clearly don't per se, due to using an
282  * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
283  * ordering assumption: https://github.com/ros2/rclcpp/issues/2096
284  */
285  costmap_ros_->deactivate();
286 
288  vel_publisher_->on_deactivate();
289  tracking_feedback_pub_->on_deactivate();
290 
291  remove_on_set_parameters_callback(dyn_params_handler_.get());
292  dyn_params_handler_.reset();
293 
294  // destroy bond connection
295  destroyBond();
296 
297  return nav2::CallbackReturn::SUCCESS;
298 }
299 
300 nav2::CallbackReturn
301 ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
302 {
303  RCLCPP_INFO(get_logger(), "Cleaning up");
304 
305  // Cleanup the helper classes
306  ControllerMap::iterator it;
307  for (it = controllers_.begin(); it != controllers_.end(); ++it) {
308  it->second->cleanup();
309  }
310  controllers_.clear();
311 
312  goal_checkers_.clear();
313  progress_checkers_.clear();
314 
315  costmap_ros_->cleanup();
316 
317 
318  // Release any allocated resources
319  action_server_.reset();
320  odom_sub_.reset();
321  costmap_thread_.reset();
322  vel_publisher_.reset();
323  speed_limit_sub_.reset();
324 
325  return nav2::CallbackReturn::SUCCESS;
326 }
327 
328 nav2::CallbackReturn
329 ControllerServer::on_shutdown(const rclcpp_lifecycle::State &)
330 {
331  RCLCPP_INFO(get_logger(), "Shutting down");
332  return nav2::CallbackReturn::SUCCESS;
333 }
334 
336  const std::string & c_name,
337  std::string & current_controller)
338 {
339  if (controllers_.find(c_name) == controllers_.end()) {
340  if (controllers_.size() == 1 && c_name.empty()) {
341  RCLCPP_WARN_ONCE(
342  get_logger(), "No controller was specified in action call."
343  " Server will use only plugin loaded %s. "
344  "This warning will appear once.", controller_ids_concat_.c_str());
345  current_controller = controllers_.begin()->first;
346  } else {
347  RCLCPP_ERROR(
348  get_logger(), "FollowPath called with controller name %s, "
349  "which does not exist. Available controllers are: %s.",
350  c_name.c_str(), controller_ids_concat_.c_str());
351  return false;
352  }
353  } else {
354  RCLCPP_DEBUG(get_logger(), "Selected controller: %s.", c_name.c_str());
355  current_controller = c_name;
356  }
357 
358  return true;
359 }
360 
362  const std::string & c_name,
363  std::string & current_goal_checker)
364 {
365  if (goal_checkers_.find(c_name) == goal_checkers_.end()) {
366  if (goal_checkers_.size() == 1 && c_name.empty()) {
367  RCLCPP_WARN_ONCE(
368  get_logger(), "No goal checker was specified in parameter 'current_goal_checker'."
369  " Server will use only plugin loaded %s. "
370  "This warning will appear once.", goal_checker_ids_concat_.c_str());
371  current_goal_checker = goal_checkers_.begin()->first;
372  } else {
373  RCLCPP_ERROR(
374  get_logger(), "FollowPath called with goal_checker name %s in parameter"
375  " 'current_goal_checker', which does not exist. Available goal checkers are: %s.",
376  c_name.c_str(), goal_checker_ids_concat_.c_str());
377  return false;
378  }
379  } else {
380  RCLCPP_DEBUG(get_logger(), "Selected goal checker: %s.", c_name.c_str());
381  current_goal_checker = c_name;
382  }
383 
384  return true;
385 }
386 
388  const std::string & c_name,
389  std::string & current_progress_checker)
390 {
391  if (progress_checkers_.find(c_name) == progress_checkers_.end()) {
392  if (progress_checkers_.size() == 1 && c_name.empty()) {
393  RCLCPP_WARN_ONCE(
394  get_logger(), "No progress checker was specified in parameter 'current_progress_checker'."
395  " Server will use only plugin loaded %s. "
396  "This warning will appear once.", progress_checker_ids_concat_.c_str());
397  current_progress_checker = progress_checkers_.begin()->first;
398  } else {
399  RCLCPP_ERROR(
400  get_logger(), "FollowPath called with progress_checker name %s in parameter"
401  " 'current_progress_checker', which does not exist. Available progress checkers are: %s.",
402  c_name.c_str(), progress_checker_ids_concat_.c_str());
403  return false;
404  }
405  } else {
406  RCLCPP_DEBUG(get_logger(), "Selected progress checker: %s.", c_name.c_str());
407  current_progress_checker = c_name;
408  }
409 
410  return true;
411 }
412 
414 {
415  std::lock_guard<std::mutex> lock(dynamic_params_lock_);
416 
417  RCLCPP_INFO(get_logger(), "Received a goal, begin computing control effort.");
418 
419  try {
420  auto goal = action_server_->get_current_goal();
421  if (!goal) {
422  return; // goal would be nullptr if action_server_ is deactivate.
423  }
424 
425  std::string c_name = goal->controller_id;
426  std::string current_controller;
427  if (findControllerId(c_name, current_controller)) {
428  current_controller_ = current_controller;
429  } else {
430  throw nav2_core::InvalidController("Failed to find controller name: " + c_name);
431  }
432 
433  std::string gc_name = goal->goal_checker_id;
434  std::string current_goal_checker;
435  if (findGoalCheckerId(gc_name, current_goal_checker)) {
436  current_goal_checker_ = current_goal_checker;
437  } else {
438  throw nav2_core::ControllerException("Failed to find goal checker name: " + gc_name);
439  }
440 
441  std::string pc_name = goal->progress_checker_id;
442  std::string current_progress_checker;
443  if (findProgressCheckerId(pc_name, current_progress_checker)) {
444  current_progress_checker_ = current_progress_checker;
445  } else {
446  throw nav2_core::ControllerException("Failed to find progress checker name: " + pc_name);
447  }
448 
449  setPlannerPath(goal->path);
450  progress_checkers_[current_progress_checker_]->reset();
451 
452  last_valid_cmd_time_ = now();
453  rclcpp::WallRate loop_rate(controller_frequency_);
454  while (rclcpp::ok()) {
455  auto start_time = this->now();
456 
457  if (action_server_ == nullptr || !action_server_->is_server_active()) {
458  RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
459  return;
460  }
461 
462  if (action_server_->is_cancel_requested()) {
463  if (controllers_[current_controller_]->cancel()) {
464  RCLCPP_INFO(get_logger(), "Cancellation was successful. Stopping the robot.");
465  action_server_->terminate_all();
466  onGoalExit(true);
467  return;
468  } else {
469  RCLCPP_INFO_THROTTLE(
470  get_logger(), *get_clock(), 1000, "Waiting for the controller to finish cancellation");
471  }
472  }
473 
474  // Don't compute a trajectory until costmap is valid (after clear costmap)
475  rclcpp::Rate r(100);
476  auto waiting_start = now();
477  while (!costmap_ros_->isCurrent()) {
478  if (now() - waiting_start > costmap_update_timeout_) {
479  throw nav2_core::ControllerTimedOut("Costmap timed out waiting for update");
480  }
481  r.sleep();
482  }
483 
485 
487 
488  if (isGoalReached()) {
489  RCLCPP_INFO(get_logger(), "Reached the goal!");
490  break;
491  }
492 
493  auto cycle_duration = this->now() - start_time;
494  if (!loop_rate.sleep()) {
495  RCLCPP_WARN(
496  get_logger(),
497  "Control loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz.",
498  controller_frequency_, 1 / cycle_duration.seconds());
499  }
500  }
501  } catch (nav2_core::InvalidController & e) {
502  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
503  onGoalExit(true);
504  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
505  result->error_code = Action::Result::INVALID_CONTROLLER;
506  result->error_msg = e.what();
507  action_server_->terminate_current(result);
508  return;
509  } catch (nav2_core::ControllerTFError & e) {
510  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
511  onGoalExit(true);
512  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
513  result->error_code = Action::Result::TF_ERROR;
514  result->error_msg = e.what();
515  action_server_->terminate_current(result);
516  return;
517  } catch (nav2_core::NoValidControl & e) {
518  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
519  onGoalExit(true);
520  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
521  result->error_code = Action::Result::NO_VALID_CONTROL;
522  result->error_msg = e.what();
523  action_server_->terminate_current(result);
524  return;
525  } catch (nav2_core::FailedToMakeProgress & e) {
526  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
527  onGoalExit(true);
528  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
529  result->error_code = Action::Result::FAILED_TO_MAKE_PROGRESS;
530  result->error_msg = e.what();
531  action_server_->terminate_current(result);
532  return;
533  } catch (nav2_core::PatienceExceeded & e) {
534  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
535  onGoalExit(true);
536  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
537  result->error_code = Action::Result::PATIENCE_EXCEEDED;
538  result->error_msg = e.what();
539  action_server_->terminate_current(result);
540  return;
541  } catch (nav2_core::InvalidPath & e) {
542  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
543  onGoalExit(true);
544  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
545  result->error_code = Action::Result::INVALID_PATH;
546  result->error_msg = e.what();
547  action_server_->terminate_current(result);
548  return;
549  } catch (nav2_core::ControllerTimedOut & e) {
550  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
551  onGoalExit(true);
552  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
553  result->error_code = Action::Result::CONTROLLER_TIMED_OUT;
554  result->error_msg = e.what();
555  action_server_->terminate_current(result);
556  return;
557  } catch (nav2_core::ControllerException & e) {
558  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
559  onGoalExit(true);
560  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
561  result->error_code = Action::Result::UNKNOWN;
562  result->error_msg = e.what();
563  action_server_->terminate_current(result);
564  return;
565  } catch (std::exception & e) {
566  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
567  onGoalExit(true);
568  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
569  result->error_code = Action::Result::UNKNOWN;
570  result->error_msg = e.what();
571  action_server_->terminate_current(result);
572  return;
573  }
574 
575  RCLCPP_DEBUG(get_logger(), "Controller succeeded, setting result");
576 
577  onGoalExit(false);
578 
579  // TODO(orduno) #861 Handle a pending preemption and set controller name
580  action_server_->succeeded_current();
581 }
582 
583 void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)
584 {
585  RCLCPP_DEBUG(
586  get_logger(),
587  "Providing path to the controller %s", current_controller_.c_str());
588  if (path.poses.empty()) {
589  throw nav2_core::InvalidPath("Path is empty.");
590  }
591  controllers_[current_controller_]->setPlan(path);
592 
593  end_pose_ = path.poses.back();
594  end_pose_.header.frame_id = path.header.frame_id;
595  goal_checkers_[current_goal_checker_]->reset();
596 
597  RCLCPP_DEBUG(
598  get_logger(), "Path end point is (%.2f, %.2f)",
599  end_pose_.pose.position.x, end_pose_.pose.position.y);
600 
601  start_index_ = 0;
602  current_path_ = path;
603 }
604 
606 {
607  geometry_msgs::msg::PoseStamped pose;
608 
609  if (!getRobotPose(pose)) {
610  throw nav2_core::ControllerTFError("Failed to obtain robot pose");
611  }
612 
613  if (!progress_checkers_[current_progress_checker_]->check(pose)) {
614  throw nav2_core::FailedToMakeProgress("Failed to make progress");
615  }
616 
617  geometry_msgs::msg::Twist twist = getThresholdedTwist(odom_sub_->getRawTwist());
618 
619  geometry_msgs::msg::TwistStamped cmd_vel_2d;
620 
621  try {
622  cmd_vel_2d =
623  controllers_[current_controller_]->computeVelocityCommands(
624  pose,
625  twist,
626  goal_checkers_[current_goal_checker_].get());
627  last_valid_cmd_time_ = now();
628  cmd_vel_2d.header.frame_id = costmap_ros_->getBaseFrameID();
629  cmd_vel_2d.header.stamp = last_valid_cmd_time_;
630  // Only no valid control exception types are valid to attempt to have control patience, as
631  // other types will not be resolved with more attempts
632  } catch (nav2_core::NoValidControl & e) {
633  if (failure_tolerance_ > 0 || failure_tolerance_ == -1.0) {
634  RCLCPP_WARN(this->get_logger(), "%s", e.what());
635  cmd_vel_2d.twist.angular.x = 0;
636  cmd_vel_2d.twist.angular.y = 0;
637  cmd_vel_2d.twist.angular.z = 0;
638  cmd_vel_2d.twist.linear.x = 0;
639  cmd_vel_2d.twist.linear.y = 0;
640  cmd_vel_2d.twist.linear.z = 0;
641  cmd_vel_2d.header.frame_id = costmap_ros_->getBaseFrameID();
642  cmd_vel_2d.header.stamp = now();
643  if ((now() - last_valid_cmd_time_).seconds() > failure_tolerance_ &&
644  failure_tolerance_ != -1.0)
645  {
646  throw nav2_core::PatienceExceeded("Controller patience exceeded");
647  }
648  } else {
649  throw nav2_core::NoValidControl(e.what());
650  }
651  }
652 
653  RCLCPP_DEBUG(get_logger(), "Publishing velocity at time %.2f", now().seconds());
654  publishVelocity(cmd_vel_2d);
655 
656  nav2_msgs::msg::TrackingFeedback current_tracking_feedback;
657 
658  // Use the current robot pose's timestamp for the transformation
659  end_pose_.header.stamp = pose.header.stamp;
660 
661  if (!nav2_util::transformPoseInTargetFrame(
662  end_pose_, transformed_end_pose_, *costmap_ros_->getTfBuffer(),
663  costmap_ros_->getGlobalFrameID(), costmap_ros_->getTransformTolerance()))
664  {
665  throw nav2_core::ControllerTFError("Failed to transform end pose to global frame");
666  }
667 
668  if (current_path_.poses.size() >= 2) {
669  double current_distance_to_goal = nav2_util::geometry_utils::euclidean_distance(
670  pose, transformed_end_pose_);
671 
672  // Transform robot pose to path frame for path tracking calculations
673  geometry_msgs::msg::PoseStamped robot_pose_in_path_frame;
674  if (!nav2_util::transformPoseInTargetFrame(
675  pose, robot_pose_in_path_frame, *costmap_ros_->getTfBuffer(),
676  current_path_.header.frame_id, costmap_ros_->getTransformTolerance()))
677  {
678  throw nav2_core::ControllerTFError("Failed to transform robot pose to path frame");
679  }
680 
681  const auto path_search_result = nav2_util::distance_from_path(
682  current_path_, robot_pose_in_path_frame.pose, start_index_, search_window_);
683 
684  // Create tracking error message
685  auto tracking_feedback_msg = std::make_unique<nav2_msgs::msg::TrackingFeedback>();
686  tracking_feedback_msg->header = pose.header;
687  tracking_feedback_msg->tracking_error = path_search_result.distance;
688  tracking_feedback_msg->current_path_index = path_search_result.closest_segment_index;
689  tracking_feedback_msg->robot_pose = pose;
690  tracking_feedback_msg->distance_to_goal = current_distance_to_goal;
691  tracking_feedback_msg->speed = std::hypot(twist.linear.x, twist.linear.y);
692  tracking_feedback_msg->remaining_path_length =
693  nav2_util::geometry_utils::calculate_path_length(current_path_, start_index_);
694  start_index_ = path_search_result.closest_segment_index;
695 
696  // Update current tracking error and publish
697  current_tracking_feedback = *tracking_feedback_msg;
698  if (tracking_feedback_pub_->get_subscription_count() > 0) {
699  tracking_feedback_pub_->publish(std::move(tracking_feedback_msg));
700  }
701  }
702 
703  // Publish action feedback
704  std::shared_ptr<Action::Feedback> feedback = std::make_shared<Action::Feedback>();
705  feedback->tracking_feedback = current_tracking_feedback;
706  action_server_->publish_feedback(feedback);
707 }
708 
710 {
711  if (action_server_->is_preempt_requested()) {
712  RCLCPP_INFO(get_logger(), "Passing new path to controller.");
713  auto goal = action_server_->accept_pending_goal();
714  std::string current_controller;
715  if (findControllerId(goal->controller_id, current_controller)) {
716  current_controller_ = current_controller;
717  } else {
718  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
719  result->error_code = Action::Result::INVALID_CONTROLLER;
720  result->error_msg = "Terminating action, invalid controller " +
721  goal->controller_id + " requested.";
722  action_server_->terminate_current(result);
723  return;
724  }
725  std::string current_goal_checker;
726  if (findGoalCheckerId(goal->goal_checker_id, current_goal_checker)) {
727  current_goal_checker_ = current_goal_checker;
728  } else {
729  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
730  result->error_code = Action::Result::INVALID_CONTROLLER;
731  result->error_msg = "Terminating action, invalid goal checker " +
732  goal->goal_checker_id + " requested.";
733  action_server_->terminate_current(result);
734  return;
735  }
736  std::string current_progress_checker;
737  if (findProgressCheckerId(goal->progress_checker_id, current_progress_checker)) {
738  if (current_progress_checker_ != current_progress_checker) {
739  RCLCPP_INFO(
740  get_logger(), "Change of progress checker %s requested, resetting it",
741  goal->progress_checker_id.c_str());
742  current_progress_checker_ = current_progress_checker;
743  progress_checkers_[current_progress_checker_]->reset();
744  }
745  } else {
746  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
747  result->error_code = Action::Result::INVALID_CONTROLLER;
748  result->error_msg = "Terminating action, invalid progress checker " +
749  goal->progress_checker_id + " requested.";
750  action_server_->terminate_current(result);
751  return;
752  }
753  setPlannerPath(goal->path);
754  }
755 }
756 
757 void ControllerServer::publishVelocity(const geometry_msgs::msg::TwistStamped & velocity)
758 {
759  auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>(velocity);
760  if (!nav2_util::validateTwist(cmd_vel->twist)) {
761  RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
762  return;
763  }
764  if (vel_publisher_->is_activated() && vel_publisher_->get_subscription_count() > 0) {
765  vel_publisher_->publish(std::move(cmd_vel));
766  }
767 }
768 
770 {
771  geometry_msgs::msg::TwistStamped velocity;
772  velocity.twist.angular.x = 0;
773  velocity.twist.angular.y = 0;
774  velocity.twist.angular.z = 0;
775  velocity.twist.linear.x = 0;
776  velocity.twist.linear.y = 0;
777  velocity.twist.linear.z = 0;
778  velocity.header.frame_id = costmap_ros_->getBaseFrameID();
779  velocity.header.stamp = now();
780  publishVelocity(velocity);
781 }
782 
783 void ControllerServer::onGoalExit(bool force_stop)
784 {
785  if (publish_zero_velocity_ || force_stop) {
787  }
788 
789  // Reset controller state
790  for (auto & controller : controllers_) {
791  controller.second->reset();
792  }
793 }
794 
796 {
797  geometry_msgs::msg::PoseStamped pose;
798 
799  if (!getRobotPose(pose)) {
800  return false;
801  }
802 
803  geometry_msgs::msg::Twist velocity = getThresholdedTwist(odom_sub_->getRawTwist());
804 
805  return goal_checkers_[current_goal_checker_]->isGoalReached(
806  pose.pose, transformed_end_pose_.pose,
807  velocity);
808 }
809 
810 bool ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped & pose)
811 {
812  geometry_msgs::msg::PoseStamped current_pose;
813  if (!costmap_ros_->getRobotPose(current_pose)) {
814  return false;
815  }
816  pose = current_pose;
817  return true;
818 }
819 
820 void ControllerServer::speedLimitCallback(const nav2_msgs::msg::SpeedLimit::SharedPtr msg)
821 {
822  ControllerMap::iterator it;
823  for (it = controllers_.begin(); it != controllers_.end(); ++it) {
824  it->second->setSpeedLimit(msg->speed_limit, msg->percentage);
825  }
826 }
827 
828 rcl_interfaces::msg::SetParametersResult
829 ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
830 {
831  rcl_interfaces::msg::SetParametersResult result;
832 
833  for (auto parameter : parameters) {
834  const auto & param_type = parameter.get_type();
835  const auto & param_name = parameter.get_name();
836 
837  // If we are trying to change the parameter of a plugin we can just skip it at this point
838  // as they handle parameter changes themselves and don't need to lock the mutex
839  if (param_name.find('.') != std::string::npos) {
840  continue;
841  }
842 
843  if (!dynamic_params_lock_.try_lock()) {
844  RCLCPP_WARN(
845  get_logger(),
846  "Unable to dynamically change Parameters while the controller is currently running");
847  result.successful = false;
848  result.reason =
849  "Unable to dynamically change Parameters while the controller is currently running";
850  return result;
851  }
852 
853  if (param_type == ParameterType::PARAMETER_DOUBLE) {
854  if (param_name == "min_x_velocity_threshold") {
855  min_x_velocity_threshold_ = parameter.as_double();
856  } else if (param_name == "min_y_velocity_threshold") {
857  min_y_velocity_threshold_ = parameter.as_double();
858  } else if (param_name == "min_theta_velocity_threshold") {
859  min_theta_velocity_threshold_ = parameter.as_double();
860  } else if (param_name == "failure_tolerance") {
861  failure_tolerance_ = parameter.as_double();
862  }
863  }
864 
865  dynamic_params_lock_.unlock();
866  }
867 
868  result.successful = true;
869  return result;
870 }
871 
872 } // namespace nav2_controller
873 
874 #include "rclcpp_components/register_node_macro.hpp"
875 
876 // Register the component with class_loader.
877 // This acts as a sort of entry point, allowing the component to be discoverable when its library
878 // is being loaded into a running process.
879 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_controller::ControllerServer)
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
ParameterT declare_or_get_parameter(const std::string &parameter_name, const ParameterDescriptor &parameter_descriptor=ParameterDescriptor())
Declares or gets a parameter with specified type (not value). If the parameter is already declared,...
void createBond()
Create bond connection to lifecycle manager.
This class hosts variety of plugins of different algorithms to complete control tasks from the expose...
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
void publishVelocity(const geometry_msgs::msg::TwistStamped &velocity)
Calls velocity publisher to publish the velocity on "cmd_vel" topic.
bool getRobotPose(geometry_msgs::msg::PoseStamped &pose)
Obtain current pose of the robot in costmap's frame.
void onGoalExit(bool force_stop)
Called on goal exit.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures controller parameters and member variables.
void computeControl()
FollowPath action server callback. Handles action server updates and spins server until goal is reach...
bool isGoalReached()
Checks if goal is reached.
geometry_msgs::msg::Twist getThresholdedTwist(const geometry_msgs::msg::Twist &twist)
get the thresholded Twist
~ControllerServer()
Destructor for nav2_controller::ControllerServer.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
bool findGoalCheckerId(const std::string &c_name, std::string &name)
Find the valid goal checker ID name for the specified parameter.
void updateGlobalPath()
Calls setPlannerPath method with an updated path received from action server.
void setPlannerPath(const nav_msgs::msg::Path &path)
Assigns path to controller.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
void publishZeroVelocity()
Calls velocity publisher to publish zero velocity.
bool findControllerId(const std::string &c_name, std::string &name)
Find the valid controller ID name for the given request.
bool findProgressCheckerId(const std::string &c_name, std::string &name)
Find the valid progress checker ID name for the specified parameter.
void computeAndPublishVelocity()
Calculates velocity and publishes to "cmd_vel" topic.