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