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