Nav2 Navigation Stack - humble  humble
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/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_id_{"progress_checker"},
41  default_progress_checker_type_{"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 {
49  RCLCPP_INFO(get_logger(), "Creating controller server");
50 
51  declare_parameter("controller_frequency", 20.0);
52 
53  declare_parameter("progress_checker_plugin", default_progress_checker_id_);
54  declare_parameter("goal_checker_plugins", default_goal_checker_ids_);
55  declare_parameter("controller_plugins", default_ids_);
56  declare_parameter("min_x_velocity_threshold", rclcpp::ParameterValue(0.0001));
57  declare_parameter("min_y_velocity_threshold", rclcpp::ParameterValue(0.0001));
58  declare_parameter("min_theta_velocity_threshold", rclcpp::ParameterValue(0.0001));
59 
60  declare_parameter("speed_limit_topic", rclcpp::ParameterValue("speed_limit"));
61 
62  declare_parameter("failure_tolerance", rclcpp::ParameterValue(0.0));
63  declare_parameter("publish_zero_velocity", rclcpp::ParameterValue(true));
64 
65  // The costmap node is used in the implementation of the controller
66  costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
67  "local_costmap", std::string{get_namespace()}, "local_costmap");
68 }
69 
71 {
72  progress_checker_.reset();
73  goal_checkers_.clear();
74  controllers_.clear();
75  costmap_thread_.reset();
76 }
77 
78 nav2_util::CallbackReturn
79 ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
80 {
81  auto node = shared_from_this();
82 
83  RCLCPP_INFO(get_logger(), "Configuring controller interface");
84 
85  get_parameter("progress_checker_plugin", progress_checker_id_);
86  if (progress_checker_id_ == default_progress_checker_id_) {
87  nav2_util::declare_parameter_if_not_declared(
88  node, default_progress_checker_id_ + ".plugin",
89  rclcpp::ParameterValue(default_progress_checker_type_));
90  }
91 
92  RCLCPP_INFO(get_logger(), "getting goal checker plugins..");
93  get_parameter("goal_checker_plugins", goal_checker_ids_);
94  if (goal_checker_ids_ == default_goal_checker_ids_) {
95  for (size_t i = 0; i < default_goal_checker_ids_.size(); ++i) {
96  nav2_util::declare_parameter_if_not_declared(
97  node, default_goal_checker_ids_[i] + ".plugin",
98  rclcpp::ParameterValue(default_goal_checker_types_[i]));
99  }
100  }
101 
102  get_parameter("controller_plugins", controller_ids_);
103  if (controller_ids_ == default_ids_) {
104  for (size_t i = 0; i < default_ids_.size(); ++i) {
105  nav2_util::declare_parameter_if_not_declared(
106  node, default_ids_[i] + ".plugin",
107  rclcpp::ParameterValue(default_types_[i]));
108  }
109  }
110 
111  controller_types_.resize(controller_ids_.size());
112  goal_checker_types_.resize(goal_checker_ids_.size());
113 
114  get_parameter("controller_frequency", controller_frequency_);
115  get_parameter("min_x_velocity_threshold", min_x_velocity_threshold_);
116  get_parameter("min_y_velocity_threshold", min_y_velocity_threshold_);
117  get_parameter("min_theta_velocity_threshold", min_theta_velocity_threshold_);
118  RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
119 
120  std::string speed_limit_topic;
121  get_parameter("speed_limit_topic", speed_limit_topic);
122  get_parameter("failure_tolerance", failure_tolerance_);
123  get_parameter("publish_zero_velocity", publish_zero_velocity_);
124 
125  costmap_ros_->configure();
126  // Launch a thread to run the costmap node
127  costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
128 
129  try {
130  progress_checker_type_ = nav2_util::get_plugin_type_param(node, progress_checker_id_);
131  progress_checker_ = progress_checker_loader_.createUniqueInstance(progress_checker_type_);
132  RCLCPP_INFO(
133  get_logger(), "Created progress_checker : %s of type %s",
134  progress_checker_id_.c_str(), progress_checker_type_.c_str());
135  progress_checker_->initialize(node, progress_checker_id_);
136  } catch (const pluginlib::PluginlibException & ex) {
137  RCLCPP_FATAL(
138  get_logger(),
139  "Failed to create progress_checker. Exception: %s", ex.what());
140  return nav2_util::CallbackReturn::FAILURE;
141  }
142 
143  for (size_t i = 0; i != goal_checker_ids_.size(); i++) {
144  try {
145  goal_checker_types_[i] = nav2_util::get_plugin_type_param(node, goal_checker_ids_[i]);
146  nav2_core::GoalChecker::Ptr goal_checker =
147  goal_checker_loader_.createUniqueInstance(goal_checker_types_[i]);
148  RCLCPP_INFO(
149  get_logger(), "Created goal checker : %s of type %s",
150  goal_checker_ids_[i].c_str(), goal_checker_types_[i].c_str());
151  goal_checker->initialize(node, goal_checker_ids_[i], costmap_ros_);
152  goal_checkers_.insert({goal_checker_ids_[i], goal_checker});
153  } catch (const pluginlib::PluginlibException & ex) {
154  RCLCPP_FATAL(
155  get_logger(),
156  "Failed to create goal checker. Exception: %s", ex.what());
157  return nav2_util::CallbackReturn::FAILURE;
158  }
159  }
160 
161  for (size_t i = 0; i != goal_checker_ids_.size(); i++) {
162  goal_checker_ids_concat_ += goal_checker_ids_[i] + std::string(" ");
163  }
164 
165  RCLCPP_INFO(
166  get_logger(),
167  "Controller Server has %s goal checkers available.", goal_checker_ids_concat_.c_str());
168 
169  for (size_t i = 0; i != controller_ids_.size(); i++) {
170  try {
171  controller_types_[i] = nav2_util::get_plugin_type_param(node, controller_ids_[i]);
172  nav2_core::Controller::Ptr controller =
173  lp_loader_.createUniqueInstance(controller_types_[i]);
174  RCLCPP_INFO(
175  get_logger(), "Created controller : %s of type %s",
176  controller_ids_[i].c_str(), controller_types_[i].c_str());
177  controller->configure(
178  node, controller_ids_[i],
179  costmap_ros_->getTfBuffer(), costmap_ros_);
180  controllers_.insert({controller_ids_[i], controller});
181  } catch (const pluginlib::PluginlibException & ex) {
182  RCLCPP_FATAL(
183  get_logger(),
184  "Failed to create controller. Exception: %s", ex.what());
185  return nav2_util::CallbackReturn::FAILURE;
186  }
187  }
188 
189  for (size_t i = 0; i != controller_ids_.size(); i++) {
190  controller_ids_concat_ += controller_ids_[i] + std::string(" ");
191  }
192 
193  RCLCPP_INFO(
194  get_logger(),
195  "Controller Server has %s controllers available.", controller_ids_concat_.c_str());
196 
197  odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
198  vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 1);
199 
200  // Create the action server that we implement with our followPath method
201  action_server_ = std::make_unique<ActionServer>(
203  "follow_path",
204  std::bind(&ControllerServer::computeControl, this),
205  nullptr,
206  std::chrono::milliseconds(500),
207  true);
208 
209  // Set subscribtion to the speed limiting topic
210  speed_limit_sub_ = create_subscription<nav2_msgs::msg::SpeedLimit>(
211  speed_limit_topic, rclcpp::QoS(10),
212  std::bind(&ControllerServer::speedLimitCallback, this, std::placeholders::_1));
213 
214  return nav2_util::CallbackReturn::SUCCESS;
215 }
216 
217 nav2_util::CallbackReturn
218 ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
219 {
220  RCLCPP_INFO(get_logger(), "Activating");
221 
222  costmap_ros_->activate();
223  ControllerMap::iterator it;
224  for (it = controllers_.begin(); it != controllers_.end(); ++it) {
225  it->second->activate();
226  }
227  vel_publisher_->on_activate();
228  action_server_->activate();
229 
230  auto node = shared_from_this();
231  // Add callback for dynamic parameters
232  dyn_params_handler_ = node->add_on_set_parameters_callback(
233  std::bind(&ControllerServer::dynamicParametersCallback, this, _1));
234 
235  // create bond connection
236  createBond();
237 
238  return nav2_util::CallbackReturn::SUCCESS;
239 }
240 
241 nav2_util::CallbackReturn
242 ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
243 {
244  RCLCPP_INFO(get_logger(), "Deactivating");
245 
246  action_server_->deactivate();
247  ControllerMap::iterator it;
248  for (it = controllers_.begin(); it != controllers_.end(); ++it) {
249  it->second->deactivate();
250  }
251 
252  /*
253  * The costmap is also a lifecycle node, so it may have already fired on_deactivate
254  * via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
255  * in the order added, the preshutdown callbacks clearly don't per se, due to using an
256  * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
257  * ordering assumption: https://github.com/ros2/rclcpp/issues/2096
258  */
259  costmap_ros_->deactivate();
260 
262  vel_publisher_->on_deactivate();
263  dyn_params_handler_.reset();
264 
265  // destroy bond connection
266  destroyBond();
267 
268  return nav2_util::CallbackReturn::SUCCESS;
269 }
270 
271 nav2_util::CallbackReturn
272 ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
273 {
274  RCLCPP_INFO(get_logger(), "Cleaning up");
275 
276  // Cleanup the helper classes
277  ControllerMap::iterator it;
278  for (it = controllers_.begin(); it != controllers_.end(); ++it) {
279  it->second->cleanup();
280  }
281  controllers_.clear();
282 
283  goal_checkers_.clear();
284 
285  costmap_ros_->cleanup();
286 
287 
288  // Release any allocated resources
289  action_server_.reset();
290  odom_sub_.reset();
291  costmap_thread_.reset();
292  vel_publisher_.reset();
293  speed_limit_sub_.reset();
294 
295  return nav2_util::CallbackReturn::SUCCESS;
296 }
297 
298 nav2_util::CallbackReturn
299 ControllerServer::on_shutdown(const rclcpp_lifecycle::State &)
300 {
301  RCLCPP_INFO(get_logger(), "Shutting down");
302  return nav2_util::CallbackReturn::SUCCESS;
303 }
304 
306  const std::string & c_name,
307  std::string & current_controller)
308 {
309  if (controllers_.find(c_name) == controllers_.end()) {
310  if (controllers_.size() == 1 && c_name.empty()) {
311  RCLCPP_WARN_ONCE(
312  get_logger(), "No controller was specified in action call."
313  " Server will use only plugin loaded %s. "
314  "This warning will appear once.", controller_ids_concat_.c_str());
315  current_controller = controllers_.begin()->first;
316  } else {
317  RCLCPP_ERROR(
318  get_logger(), "FollowPath called with controller name %s, "
319  "which does not exist. Available controllers are: %s.",
320  c_name.c_str(), controller_ids_concat_.c_str());
321  return false;
322  }
323  } else {
324  RCLCPP_DEBUG(get_logger(), "Selected controller: %s.", c_name.c_str());
325  current_controller = c_name;
326  }
327 
328  return true;
329 }
330 
332  const std::string & c_name,
333  std::string & current_goal_checker)
334 {
335  if (goal_checkers_.find(c_name) == goal_checkers_.end()) {
336  if (goal_checkers_.size() == 1 && c_name.empty()) {
337  RCLCPP_WARN_ONCE(
338  get_logger(), "No goal checker was specified in parameter 'current_goal_checker'."
339  " Server will use only plugin loaded %s. "
340  "This warning will appear once.", goal_checker_ids_concat_.c_str());
341  current_goal_checker = goal_checkers_.begin()->first;
342  } else {
343  RCLCPP_ERROR(
344  get_logger(), "FollowPath called with goal_checker name %s in parameter"
345  " 'current_goal_checker', which does not exist. Available goal checkers are: %s.",
346  c_name.c_str(), goal_checker_ids_concat_.c_str());
347  return false;
348  }
349  } else {
350  RCLCPP_DEBUG(get_logger(), "Selected goal checker: %s.", c_name.c_str());
351  current_goal_checker = c_name;
352  }
353 
354  return true;
355 }
356 
358 {
359  std::lock_guard<std::mutex> lock(dynamic_params_lock_);
360 
361  RCLCPP_INFO(get_logger(), "Received a goal, begin computing control effort.");
362 
363  try {
364  std::string c_name = action_server_->get_current_goal()->controller_id;
365  std::string current_controller;
366  if (findControllerId(c_name, current_controller)) {
367  current_controller_ = current_controller;
368  } else {
369  action_server_->terminate_current();
370  return;
371  }
372 
373  std::string gc_name = action_server_->get_current_goal()->goal_checker_id;
374  std::string current_goal_checker;
375  if (findGoalCheckerId(gc_name, current_goal_checker)) {
376  current_goal_checker_ = current_goal_checker;
377  } else {
378  action_server_->terminate_current();
379  return;
380  }
381 
382  setPlannerPath(action_server_->get_current_goal()->path);
383  progress_checker_->reset();
384 
385  last_valid_cmd_time_ = now();
386  rclcpp::WallRate loop_rate(controller_frequency_);
387  while (rclcpp::ok()) {
388  if (action_server_ == nullptr || !action_server_->is_server_active()) {
389  RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
390  return;
391  }
392 
393  if (action_server_->is_cancel_requested()) {
394  RCLCPP_INFO(get_logger(), "Goal was canceled. Stopping the robot.");
395  action_server_->terminate_all();
397  return;
398  }
399 
400  // Don't compute a trajectory until costmap is valid (after clear costmap)
401  rclcpp::Rate r(100);
402  while (!costmap_ros_->isCurrent()) {
403  r.sleep();
404  }
405 
407 
409 
410  if (isGoalReached()) {
411  RCLCPP_INFO(get_logger(), "Reached the goal!");
412  break;
413  }
414 
415  if (!loop_rate.sleep()) {
416  RCLCPP_WARN(
417  get_logger(), "Control loop missed its desired rate of %.4fHz",
418  controller_frequency_);
419  }
420  }
421  } catch (nav2_core::PlannerException & e) {
422  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
424  action_server_->terminate_current();
425  return;
426  } catch (std::exception & e) {
427  RCLCPP_ERROR(this->get_logger(), "%s", e.what());
429  std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
430  action_server_->terminate_current(result);
431  return;
432  }
433 
434  RCLCPP_DEBUG(get_logger(), "Controller succeeded, setting result");
435 
436  if (publish_zero_velocity_) {
438  }
439 
440  // TODO(orduno) #861 Handle a pending preemption and set controller name
441  action_server_->succeeded_current();
442 }
443 
444 void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)
445 {
446  RCLCPP_DEBUG(
447  get_logger(),
448  "Providing path to the controller %s", current_controller_.c_str());
449  if (path.poses.empty()) {
450  throw nav2_core::PlannerException("Invalid path, Path is empty.");
451  }
452  controllers_[current_controller_]->setPlan(path);
453 
454  end_pose_ = path.poses.back();
455  end_pose_.header.frame_id = path.header.frame_id;
456  goal_checkers_[current_goal_checker_]->reset();
457 
458  RCLCPP_DEBUG(
459  get_logger(), "Path end point is (%.2f, %.2f)",
460  end_pose_.pose.position.x, end_pose_.pose.position.y);
461 
462  current_path_ = path;
463 }
464 
466 {
467  geometry_msgs::msg::PoseStamped pose;
468 
469  if (!getRobotPose(pose)) {
470  throw nav2_core::PlannerException("Failed to obtain robot pose");
471  }
472 
473  if (!progress_checker_->check(pose)) {
474  throw nav2_core::PlannerException("Failed to make progress");
475  }
476 
477  nav_2d_msgs::msg::Twist2D twist = getThresholdedTwist(odom_sub_->getTwist());
478 
479  geometry_msgs::msg::TwistStamped cmd_vel_2d;
480 
481  try {
482  cmd_vel_2d =
483  controllers_[current_controller_]->computeVelocityCommands(
484  pose,
485  nav_2d_utils::twist2Dto3D(twist),
486  goal_checkers_[current_goal_checker_].get());
487  last_valid_cmd_time_ = now();
488  } catch (nav2_core::PlannerException & e) {
489  if (failure_tolerance_ > 0 || failure_tolerance_ == -1.0) {
490  RCLCPP_WARN(this->get_logger(), "%s", e.what());
491  cmd_vel_2d.twist.angular.x = 0;
492  cmd_vel_2d.twist.angular.y = 0;
493  cmd_vel_2d.twist.angular.z = 0;
494  cmd_vel_2d.twist.linear.x = 0;
495  cmd_vel_2d.twist.linear.y = 0;
496  cmd_vel_2d.twist.linear.z = 0;
497  cmd_vel_2d.header.frame_id = costmap_ros_->getBaseFrameID();
498  cmd_vel_2d.header.stamp = now();
499  if ((now() - last_valid_cmd_time_).seconds() > failure_tolerance_ &&
500  failure_tolerance_ != -1.0)
501  {
502  throw nav2_core::PlannerException("Controller patience exceeded");
503  }
504  } else {
505  throw nav2_core::PlannerException(e.what());
506  }
507  }
508 
509  std::shared_ptr<Action::Feedback> feedback = std::make_shared<Action::Feedback>();
510  feedback->speed = std::hypot(cmd_vel_2d.twist.linear.x, cmd_vel_2d.twist.linear.y);
511 
512  // Find the closest pose to current pose on global path
513  nav_msgs::msg::Path & current_path = current_path_;
514  auto find_closest_pose_idx =
515  [&pose, &current_path]() {
516  size_t closest_pose_idx = 0;
517  double curr_min_dist = std::numeric_limits<double>::max();
518  for (size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
519  double curr_dist = nav2_util::geometry_utils::euclidean_distance(
520  pose, current_path.poses[curr_idx]);
521  if (curr_dist < curr_min_dist) {
522  curr_min_dist = curr_dist;
523  closest_pose_idx = curr_idx;
524  }
525  }
526  return closest_pose_idx;
527  };
528 
529  feedback->distance_to_goal =
530  nav2_util::geometry_utils::calculate_path_length(current_path_, find_closest_pose_idx());
531  action_server_->publish_feedback(feedback);
532 
533  RCLCPP_DEBUG(get_logger(), "Publishing velocity at time %.2f", now().seconds());
534  publishVelocity(cmd_vel_2d);
535 }
536 
538 {
539  if (action_server_->is_preempt_requested()) {
540  RCLCPP_INFO(get_logger(), "Passing new path to controller.");
541  auto goal = action_server_->accept_pending_goal();
542  std::string current_controller;
543  if (findControllerId(goal->controller_id, current_controller)) {
544  current_controller_ = current_controller;
545  } else {
546  RCLCPP_INFO(
547  get_logger(), "Terminating action, invalid controller %s requested.",
548  goal->controller_id.c_str());
549  action_server_->terminate_current();
550  return;
551  }
552  std::string current_goal_checker;
553  if (findGoalCheckerId(goal->goal_checker_id, current_goal_checker)) {
554  current_goal_checker_ = current_goal_checker;
555  } else {
556  RCLCPP_INFO(
557  get_logger(), "Terminating action, invalid goal checker %s requested.",
558  goal->goal_checker_id.c_str());
559  action_server_->terminate_current();
560  return;
561  }
562  setPlannerPath(goal->path);
563  }
564 }
565 
566 void ControllerServer::publishVelocity(const geometry_msgs::msg::TwistStamped & velocity)
567 {
568  auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>(velocity.twist);
569  if (vel_publisher_->is_activated() && vel_publisher_->get_subscription_count() > 0) {
570  vel_publisher_->publish(std::move(cmd_vel));
571  }
572 }
573 
575 {
576  geometry_msgs::msg::TwistStamped velocity;
577  velocity.twist.angular.x = 0;
578  velocity.twist.angular.y = 0;
579  velocity.twist.angular.z = 0;
580  velocity.twist.linear.x = 0;
581  velocity.twist.linear.y = 0;
582  velocity.twist.linear.z = 0;
583  velocity.header.frame_id = costmap_ros_->getBaseFrameID();
584  velocity.header.stamp = now();
585  publishVelocity(velocity);
586 }
587 
589 {
590  geometry_msgs::msg::PoseStamped pose;
591 
592  if (!getRobotPose(pose)) {
593  return false;
594  }
595 
596  nav_2d_msgs::msg::Twist2D twist = getThresholdedTwist(odom_sub_->getTwist());
597  geometry_msgs::msg::Twist velocity = nav_2d_utils::twist2Dto3D(twist);
598 
599  geometry_msgs::msg::PoseStamped transformed_end_pose;
600  rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance()));
601  nav_2d_utils::transformPose(
602  costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(),
603  end_pose_, transformed_end_pose, tolerance);
604 
605  return goal_checkers_[current_goal_checker_]->isGoalReached(
606  pose.pose, transformed_end_pose.pose,
607  velocity);
608 }
609 
610 bool ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped & pose)
611 {
612  geometry_msgs::msg::PoseStamped current_pose;
613  if (!costmap_ros_->getRobotPose(current_pose)) {
614  return false;
615  }
616  pose = current_pose;
617  return true;
618 }
619 
620 void ControllerServer::speedLimitCallback(const nav2_msgs::msg::SpeedLimit::SharedPtr msg)
621 {
622  ControllerMap::iterator it;
623  for (it = controllers_.begin(); it != controllers_.end(); ++it) {
624  it->second->setSpeedLimit(msg->speed_limit, msg->percentage);
625  }
626 }
627 
628 rcl_interfaces::msg::SetParametersResult
629 ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
630 {
631  rcl_interfaces::msg::SetParametersResult result;
632 
633  for (auto parameter : parameters) {
634  const auto & type = parameter.get_type();
635  const auto & name = parameter.get_name();
636 
637  // If we are trying to change the parameter of a plugin we can just skip it at this point
638  // as they handle parameter changes themselves and don't need to lock the mutex
639  if (name.find('.') != std::string::npos) {
640  continue;
641  }
642 
643  if (!dynamic_params_lock_.try_lock()) {
644  RCLCPP_WARN(
645  get_logger(),
646  "Unable to dynamically change Parameters while the controller is currently running");
647  result.successful = false;
648  result.reason =
649  "Unable to dynamically change Parameters while the controller is currently running";
650  return result;
651  }
652 
653  if (type == ParameterType::PARAMETER_DOUBLE) {
654  if (name == "controller_frequency") {
655  controller_frequency_ = parameter.as_double();
656  } else if (name == "min_x_velocity_threshold") {
657  min_x_velocity_threshold_ = parameter.as_double();
658  } else if (name == "min_y_velocity_threshold") {
659  min_y_velocity_threshold_ = parameter.as_double();
660  } else if (name == "min_theta_velocity_threshold") {
661  min_theta_velocity_threshold_ = parameter.as_double();
662  } else if (name == "failure_tolerance") {
663  failure_tolerance_ = parameter.as_double();
664  }
665  }
666 
667  dynamic_params_lock_.unlock();
668  }
669 
670  result.successful = true;
671  return result;
672 }
673 
674 } // namespace nav2_controller
675 
676 #include "rclcpp_components/register_node_macro.hpp"
677 
678 // Register the component with class_loader.
679 // This acts as a sort of entry point, allowing the component to be discoverable when its library
680 // is being loaded into a running process.
681 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.
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.