Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
docking_server.cpp
1 // Copyright (c) 2024 Open Navigation LLC
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 "angles/angles.h"
16 #include "opennav_docking/docking_server.hpp"
17 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
18 #include "tf2/utils.hpp"
19 
20 using namespace std::chrono_literals;
21 using rcl_interfaces::msg::ParameterType;
22 using std::placeholders::_1;
23 
24 namespace opennav_docking
25 {
26 
27 DockingServer::DockingServer(const rclcpp::NodeOptions & options)
28 : nav2::LifecycleNode("docking_server", "", options)
29 {
30  RCLCPP_INFO(get_logger(), "Creating %s", get_name());
31 
32  declare_parameter("controller_frequency", 50.0);
33  declare_parameter("initial_perception_timeout", 5.0);
34  declare_parameter("wait_charge_timeout", 5.0);
35  declare_parameter("dock_approach_timeout", 30.0);
36  declare_parameter("rotate_to_dock_timeout", 10.0);
37  declare_parameter("undock_linear_tolerance", 0.05);
38  declare_parameter("undock_angular_tolerance", 0.05);
39  declare_parameter("max_retries", 3);
40  declare_parameter("base_frame", "base_link");
41  declare_parameter("fixed_frame", "odom");
42  declare_parameter("dock_backwards", rclcpp::PARAMETER_BOOL);
43  declare_parameter("dock_prestaging_tolerance", 0.5);
44  declare_parameter("odom_topic", "odom");
45  declare_parameter("odom_duration", 0.3);
46  declare_parameter("rotation_angular_tolerance", 0.05);
47 }
48 
49 nav2::CallbackReturn
50 DockingServer::on_configure(const rclcpp_lifecycle::State & state)
51 {
52  RCLCPP_INFO(get_logger(), "Configuring %s", get_name());
53  auto node = shared_from_this();
54 
55  get_parameter("controller_frequency", controller_frequency_);
56  get_parameter("initial_perception_timeout", initial_perception_timeout_);
57  get_parameter("wait_charge_timeout", wait_charge_timeout_);
58  get_parameter("dock_approach_timeout", dock_approach_timeout_);
59  get_parameter("rotate_to_dock_timeout", rotate_to_dock_timeout_);
60  get_parameter("undock_linear_tolerance", undock_linear_tolerance_);
61  get_parameter("undock_angular_tolerance", undock_angular_tolerance_);
62  get_parameter("max_retries", max_retries_);
63  get_parameter("base_frame", base_frame_);
64  get_parameter("fixed_frame", fixed_frame_);
65  get_parameter("dock_prestaging_tolerance", dock_prestaging_tolerance_);
66  get_parameter("rotation_angular_tolerance", rotation_angular_tolerance_);
67 
68  RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
69 
70  // Check the dock_backwards deprecated parameter
71  bool dock_backwards = false;
72  try {
73  if (get_parameter("dock_backwards", dock_backwards)) {
74  dock_backwards_ = dock_backwards;
75  RCLCPP_WARN(get_logger(), "Parameter dock_backwards is deprecated. "
76  "Please use the dock_direction parameter in your dock plugin instead.");
77  }
78  } catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
79  }
80 
81  vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel");
82  tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(node->get_clock());
83 
84  // Create odom subscriber for backward blind docking
85  std::string odom_topic;
86  get_parameter("odom_topic", odom_topic);
87  double odom_duration;
88  get_parameter("odom_duration", odom_duration);
89  odom_sub_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration, odom_topic);
90 
91  // Create the action servers for dock / undock
92  docking_action_server_ = node->create_action_server<DockRobot>(
93  "dock_robot",
94  std::bind(&DockingServer::dockRobot, this),
95  nullptr, std::chrono::milliseconds(500),
96  true);
97 
98  undocking_action_server_ = node->create_action_server<UndockRobot>(
99  "undock_robot",
100  std::bind(&DockingServer::undockRobot, this),
101  nullptr, std::chrono::milliseconds(500),
102  true);
103 
104  // Create composed utilities
105  mutex_ = std::make_shared<std::mutex>();
106  controller_ = std::make_unique<Controller>(node, tf2_buffer_, fixed_frame_, base_frame_);
107  navigator_ = std::make_unique<Navigator>(node);
108  dock_db_ = std::make_unique<DockDatabase>(mutex_);
109  if (!dock_db_->initialize(node, tf2_buffer_)) {
110  on_cleanup(state);
111  return nav2::CallbackReturn::FAILURE;
112  }
113 
114  return nav2::CallbackReturn::SUCCESS;
115 }
116 
117 nav2::CallbackReturn
118 DockingServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
119 {
120  RCLCPP_INFO(get_logger(), "Activating %s", get_name());
121 
122  auto node = shared_from_this();
123 
124  tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_, this, true);
125  dock_db_->activate();
126  navigator_->activate();
127  vel_publisher_->on_activate();
128  docking_action_server_->activate();
129  undocking_action_server_->activate();
130  curr_dock_type_.clear();
131 
132  // Add callback for dynamic parameters
133  dyn_params_handler_ = node->add_on_set_parameters_callback(
134  std::bind(&DockingServer::dynamicParametersCallback, this, _1));
135 
136  // Create bond connection
137  createBond();
138 
139  return nav2::CallbackReturn::SUCCESS;
140 }
141 
142 nav2::CallbackReturn
143 DockingServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
144 {
145  RCLCPP_INFO(get_logger(), "Deactivating %s", get_name());
146 
147  docking_action_server_->deactivate();
148  undocking_action_server_->deactivate();
149  dock_db_->deactivate();
150  navigator_->deactivate();
151  vel_publisher_->on_deactivate();
152 
153  remove_on_set_parameters_callback(dyn_params_handler_.get());
154  dyn_params_handler_.reset();
155  tf2_listener_.reset();
156 
157  // Destroy bond connection
158  destroyBond();
159 
160  return nav2::CallbackReturn::SUCCESS;
161 }
162 
163 nav2::CallbackReturn
164 DockingServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
165 {
166  RCLCPP_INFO(get_logger(), "Cleaning up %s", get_name());
167  tf2_buffer_.reset();
168  docking_action_server_.reset();
169  undocking_action_server_.reset();
170  dock_db_.reset();
171  navigator_.reset();
172  curr_dock_type_.clear();
173  controller_.reset();
174  vel_publisher_.reset();
175  dock_backwards_.reset();
176  odom_sub_.reset();
177  return nav2::CallbackReturn::SUCCESS;
178 }
179 
180 nav2::CallbackReturn
181 DockingServer::on_shutdown(const rclcpp_lifecycle::State &)
182 {
183  RCLCPP_INFO(get_logger(), "Shutting down %s", get_name());
184  return nav2::CallbackReturn::SUCCESS;
185 }
186 
187 template<typename ActionT>
189  typename std::shared_ptr<const typename ActionT::Goal> goal,
190  const typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server)
191 {
192  if (action_server->is_preempt_requested()) {
193  goal = action_server->accept_pending_goal();
194  }
195 }
196 
197 template<typename ActionT>
199  typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server,
200  const std::string & name)
201 {
202  if (action_server->is_cancel_requested()) {
203  RCLCPP_WARN(get_logger(), "Goal was cancelled. Cancelling %s action", name.c_str());
204  return true;
205  }
206  return false;
207 }
208 
209 template<typename ActionT>
211  typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server,
212  const std::string & name)
213 {
214  if (action_server->is_preempt_requested()) {
215  RCLCPP_WARN(get_logger(), "Goal was preempted. Cancelling %s action", name.c_str());
216  return true;
217  }
218  return false;
219 }
220 
222 {
223  std::lock_guard<std::mutex> lock(*mutex_);
224  action_start_time_ = this->now();
225  rclcpp::Rate loop_rate(controller_frequency_);
226 
227  auto goal = docking_action_server_->get_current_goal();
228  auto result = std::make_shared<DockRobot::Result>();
229  result->success = false;
230 
231  if (!docking_action_server_ || !docking_action_server_->is_server_active()) {
232  RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
233  return;
234  }
235 
236  if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_, "dock_robot")) {
237  docking_action_server_->terminate_all();
238  return;
239  }
240 
241  getPreemptedGoalIfRequested<DockRobot>(goal, docking_action_server_);
242  Dock * dock{nullptr};
243  num_retries_ = 0;
244 
245  try {
246  // Get dock (instance and plugin information) from request
247  if (goal->use_dock_id) {
248  RCLCPP_INFO(
249  get_logger(),
250  "Attempting to dock robot at %s.", goal->dock_id.c_str());
251  dock = dock_db_->findDock(goal->dock_id);
252  } else {
253  RCLCPP_INFO(
254  get_logger(),
255  "Attempting to dock robot at position (%0.2f, %0.2f).",
256  goal->dock_pose.pose.position.x, goal->dock_pose.pose.position.y);
257  dock = generateGoalDock(goal);
258  }
259 
260  // Check if robot is docked or charging before proceeding, only applicable to charging docks
261  if (dock->plugin->isCharger() && (dock->plugin->isDocked() || dock->plugin->isCharging())) {
262  RCLCPP_INFO(
263  get_logger(), "Robot is already docked and/or charging (if applicable), no need to dock");
264  result->success = true;
265  docking_action_server_->succeeded_current(result);
266  return;
267  }
268 
269  // Send robot to its staging pose
270  publishDockingFeedback(DockRobot::Feedback::NAV_TO_STAGING_POSE);
271  const auto initial_staging_pose = dock->getStagingPose();
272  const auto robot_pose = getRobotPoseInFrame(initial_staging_pose.header.frame_id);
273  if (!goal->navigate_to_staging_pose ||
274  utils::l2Norm(robot_pose.pose, initial_staging_pose.pose) < dock_prestaging_tolerance_)
275  {
276  RCLCPP_INFO(get_logger(), "Robot already within pre-staging pose tolerance for dock");
277  } else {
278  std::function<bool()> isPreempted = [this]() {
279  return checkAndWarnIfCancelled<DockRobot>(docking_action_server_, "dock_robot") ||
280  checkAndWarnIfPreempted<DockRobot>(docking_action_server_, "dock_robot");
281  };
282 
283  navigator_->goToPose(
284  initial_staging_pose,
285  rclcpp::Duration::from_seconds(goal->max_staging_time),
286  isPreempted);
287  RCLCPP_INFO(get_logger(), "Successful navigation to staging pose");
288  }
289 
290  // Construct initial estimate of where the dock is located in fixed_frame
291  auto dock_pose = utils::getDockPoseStamped(dock, rclcpp::Time(0));
292  tf2_buffer_->transform(dock_pose, dock_pose, fixed_frame_);
293 
294  // Get initial detection of dock before proceeding to move
295  doInitialPerception(dock, dock_pose);
296  RCLCPP_INFO(get_logger(), "Successful initial dock detection");
297 
298  // Get the direction of the movement
299  bool dock_backward = dock_backwards_.has_value() ?
300  dock_backwards_.value() :
301  (dock->plugin->getDockDirection() == opennav_docking_core::DockDirection::BACKWARD);
302 
303  // If we performed a rotation before docking backward, we must rotate the staging pose
304  // to match the robot orientation
305  auto staging_pose = dock->getStagingPose();
306  if (dock->plugin->shouldRotateToDock()) {
307  staging_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
308  tf2::getYaw(staging_pose.pose.orientation) + M_PI);
309  }
310 
311  // Docking control loop: while not docked, run controller
312  rclcpp::Time dock_contact_time;
313  while (rclcpp::ok()) {
314  try {
315  // Perform a 180º to face away from the dock if needed
316  if (dock->plugin->shouldRotateToDock()) {
317  rotateToDock(dock_pose);
318  }
319  // Approach the dock using control law
320  if (approachDock(dock, dock_pose, dock_backward)) {
321  // We are docked, wait for charging to begin
322  RCLCPP_INFO(
323  get_logger(), "Made contact with dock, waiting for charge to start (if applicable).");
324  if (waitForCharge(dock)) {
325  if (dock->plugin->isCharger()) {
326  RCLCPP_INFO(get_logger(), "Robot is charging!");
327  } else {
328  RCLCPP_INFO(get_logger(), "Docking was successful!");
329  }
330  result->success = true;
331  result->num_retries = num_retries_;
332  stashDockData(goal->use_dock_id, dock, true);
334  dock->plugin->stopDetectionProcess();
335  docking_action_server_->succeeded_current(result);
336  return;
337  }
338  }
339 
340  // Cancelled, preempted, or shutting down (recoverable errors throw DockingException)
341  stashDockData(goal->use_dock_id, dock, false);
343  dock->plugin->stopDetectionProcess();
344  docking_action_server_->terminate_all(result);
345  return;
347  if (++num_retries_ > max_retries_) {
348  RCLCPP_ERROR(get_logger(), "Failed to dock, all retries have been used");
349  throw;
350  }
351  RCLCPP_WARN(get_logger(), "Docking failed, will retry: %s", e.what());
352  }
353 
354  // Reset to staging pose to try again
355  if (!resetApproach(staging_pose, dock_backward)) {
356  // Cancelled, preempted, or shutting down
357  stashDockData(goal->use_dock_id, dock, false);
359  dock->plugin->stopDetectionProcess();
360  docking_action_server_->terminate_all(result);
361  return;
362  }
363  RCLCPP_INFO(get_logger(), "Returned to staging pose, attempting docking again");
364  }
365  } catch (const tf2::TransformException & e) {
366  result->error_msg = std::string("Transform error: ") + e.what();
367  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
368  result->error_code = DockRobot::Result::UNKNOWN;
369  } catch (opennav_docking_core::DockNotInDB & e) {
370  result->error_msg = e.what();
371  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
372  result->error_code = DockRobot::Result::DOCK_NOT_IN_DB;
373  } catch (opennav_docking_core::DockNotValid & e) {
374  result->error_msg = e.what();
375  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
376  result->error_code = DockRobot::Result::DOCK_NOT_VALID;
378  result->error_msg = e.what();
379  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
380  result->error_code = DockRobot::Result::FAILED_TO_STAGE;
382  result->error_msg = e.what();
383  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
384  result->error_code = DockRobot::Result::FAILED_TO_DETECT_DOCK;
386  result->error_msg = e.what();
387  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
388  result->error_code = DockRobot::Result::FAILED_TO_CONTROL;
390  result->error_msg = e.what();
391  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
392  result->error_code = DockRobot::Result::FAILED_TO_CHARGE;
394  result->error_msg = e.what();
395  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
396  result->error_code = DockRobot::Result::UNKNOWN;
397  } catch (std::exception & e) {
398  result->error_code = DockRobot::Result::UNKNOWN;
399  result->error_msg = e.what();
400  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
401  }
402 
403  // Store dock state for later undocking and delete temp dock, if applicable
404  stashDockData(goal->use_dock_id, dock, false);
405  result->num_retries = num_retries_;
407  dock->plugin->stopDetectionProcess();
408  docking_action_server_->terminate_current(result);
409 }
410 
411 void DockingServer::stashDockData(bool use_dock_id, Dock * dock, bool successful)
412 {
413  if (dock && successful) {
414  curr_dock_type_ = dock->type;
415  }
416 
417  if (!use_dock_id && dock) {
418  delete dock;
419  dock = nullptr;
420  }
421 }
422 
423 Dock * DockingServer::generateGoalDock(std::shared_ptr<const DockRobot::Goal> goal)
424 {
425  auto dock = new Dock();
426  dock->frame = goal->dock_pose.header.frame_id;
427  dock->pose = goal->dock_pose.pose;
428  dock->type = goal->dock_type;
429  dock->plugin = dock_db_->findDockPlugin(dock->type);
430  return dock;
431 }
432 
433 void DockingServer::doInitialPerception(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose)
434 {
435  publishDockingFeedback(DockRobot::Feedback::INITIAL_PERCEPTION);
436 
437  if (!dock->plugin->startDetectionProcess()) {
438  throw opennav_docking_core::FailedToDetectDock("Failed to start the detection process.");
439  }
440 
441  rclcpp::Rate loop_rate(controller_frequency_);
442  auto start = this->now();
443  auto timeout = rclcpp::Duration::from_seconds(initial_perception_timeout_);
444  while (!dock->plugin->getRefinedPose(dock_pose, dock->id)) {
445  if (this->now() - start > timeout) {
447  "Failed initial dock detection: Timeout exceeded");
448  }
449 
450  if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_, "dock_robot") ||
451  checkAndWarnIfPreempted<DockRobot>(docking_action_server_, "dock_robot"))
452  {
453  return;
454  }
455 
456  loop_rate.sleep();
457  }
458 }
459 
460 void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose)
461 {
462  const double dt = 1.0 / controller_frequency_;
463  auto target_pose = dock_pose;
464  target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
465  tf2::getYaw(target_pose.pose.orientation) + M_PI);
466 
467  rclcpp::Rate loop_rate(controller_frequency_);
468  auto start = this->now();
469  auto timeout = rclcpp::Duration::from_seconds(rotate_to_dock_timeout_);
470 
471  while (rclcpp::ok()) {
472  auto robot_pose = getRobotPoseInFrame(dock_pose.header.frame_id);
473  auto angular_distance_to_heading = angles::shortest_angular_distance(
474  tf2::getYaw(robot_pose.pose.orientation), tf2::getYaw(target_pose.pose.orientation));
475  if (fabs(angular_distance_to_heading) < rotation_angular_tolerance_) {
476  break;
477  }
478 
479  auto current_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
480  current_vel->twist.angular.z = odom_sub_->getRawTwist().angular.z;
481 
482  auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
483  command->header = robot_pose.header;
484  command->twist = controller_->computeRotateToHeadingCommand(
485  angular_distance_to_heading, current_vel->twist, dt);
486 
487  vel_publisher_->publish(std::move(command));
488 
489  if (this->now() - start > timeout) {
490  throw opennav_docking_core::FailedToControl("Timed out rotating to dock");
491  }
492 
493  loop_rate.sleep();
494  }
495 }
496 
498  Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose, bool backward)
499 {
500  rclcpp::Rate loop_rate(controller_frequency_);
501  auto start = this->now();
502  auto timeout = rclcpp::Duration::from_seconds(dock_approach_timeout_);
503 
504  while (rclcpp::ok()) {
505  publishDockingFeedback(DockRobot::Feedback::CONTROLLING);
506 
507  // Stop and report success if connected to dock
508  if (dock->plugin->isDocked() || (dock->plugin->isCharger() && dock->plugin->isCharging())) {
509  return true;
510  }
511 
512  // Stop if cancelled/preempted
513  if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_, "dock_robot") ||
514  checkAndWarnIfPreempted<DockRobot>(docking_action_server_, "dock_robot"))
515  {
516  return false;
517  }
518 
519  // Update perception
520  if (!dock->plugin->getRefinedPose(dock_pose, dock->id) && !dock->plugin->shouldRotateToDock()) {
521  throw opennav_docking_core::FailedToDetectDock("Failed dock detection");
522  }
523 
524  // Transform target_pose into base_link frame
525  geometry_msgs::msg::PoseStamped target_pose = dock_pose;
526  target_pose.header.stamp = rclcpp::Time(0);
527 
528  // The control law can get jittery when close to the end when atan2's can explode.
529  // Thus, we backward project the controller's target pose a little bit after the
530  // dock so that the robot never gets to the end of the spiral before its in contact
531  // with the dock to stop the docking procedure.
532  const double backward_projection = 0.25;
533  const double yaw = tf2::getYaw(target_pose.pose.orientation);
534  target_pose.pose.position.x += cos(yaw) * backward_projection;
535  target_pose.pose.position.y += sin(yaw) * backward_projection;
536  tf2_buffer_->transform(target_pose, target_pose, base_frame_);
537 
538  // Make sure that the target pose is pointing at the robot when moving backwards
539  // This is to ensure that the robot doesn't try to dock from the wrong side
540  if (backward) {
541  target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
542  tf2::getYaw(target_pose.pose.orientation) + M_PI);
543  }
544 
545  // Compute and publish controls
546  auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
547  command->header.stamp = now();
548  if (!controller_->computeVelocityCommand(target_pose.pose, command->twist, true, backward)) {
549  throw opennav_docking_core::FailedToControl("Failed to get control");
550  }
551  vel_publisher_->publish(std::move(command));
552 
553  if (this->now() - start > timeout) {
555  "Timed out approaching dock; dock nor charging (if applicable) detected");
556  }
557 
558  loop_rate.sleep();
559  }
560  return false;
561 }
562 
564 {
565  // This is a non-charger docking request
566  if (!dock->plugin->isCharger()) {
567  return true;
568  }
569 
570  rclcpp::Rate loop_rate(controller_frequency_);
571  auto start = this->now();
572  auto timeout = rclcpp::Duration::from_seconds(wait_charge_timeout_);
573  while (rclcpp::ok()) {
574  publishDockingFeedback(DockRobot::Feedback::WAIT_FOR_CHARGE);
575 
576  if (dock->plugin->isCharging()) {
577  return true;
578  }
579 
580  if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_, "dock_robot") ||
581  checkAndWarnIfPreempted<DockRobot>(docking_action_server_, "dock_robot"))
582  {
583  return false;
584  }
585 
586  if (this->now() - start > timeout) {
587  throw opennav_docking_core::FailedToCharge("Timed out waiting for charge to start");
588  }
589 
590  loop_rate.sleep();
591  }
592  return false;
593 }
594 
596  const geometry_msgs::msg::PoseStamped & staging_pose, bool backward)
597 {
598  rclcpp::Rate loop_rate(controller_frequency_);
599  auto start = this->now();
600  auto timeout = rclcpp::Duration::from_seconds(dock_approach_timeout_);
601  while (rclcpp::ok()) {
602  publishDockingFeedback(DockRobot::Feedback::INITIAL_PERCEPTION);
603 
604  // Stop if cancelled/preempted
605  if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_, "dock_robot") ||
606  checkAndWarnIfPreempted<DockRobot>(docking_action_server_, "dock_robot"))
607  {
608  return false;
609  }
610 
611  // Compute and publish command
612  auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
613  command->header.stamp = now();
614  if (getCommandToPose(
615  command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_, false,
616  !backward))
617  {
618  return true;
619  }
620  vel_publisher_->publish(std::move(command));
621 
622  if (this->now() - start > timeout) {
623  throw opennav_docking_core::FailedToControl("Timed out resetting dock approach");
624  }
625 
626  loop_rate.sleep();
627  }
628  return false;
629 }
630 
632  geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose,
633  double linear_tolerance, double angular_tolerance, bool is_docking, bool backward)
634 {
635  // Reset command to zero velocity
636  cmd.linear.x = 0;
637  cmd.angular.z = 0;
638 
639  // Determine if we have reached pose yet & stop
640  geometry_msgs::msg::PoseStamped robot_pose = getRobotPoseInFrame(pose.header.frame_id);
641  const double dist = std::hypot(
642  robot_pose.pose.position.x - pose.pose.position.x,
643  robot_pose.pose.position.y - pose.pose.position.y);
644  const double yaw = angles::shortest_angular_distance(
645  tf2::getYaw(robot_pose.pose.orientation), tf2::getYaw(pose.pose.orientation));
646  if (dist < linear_tolerance && abs(yaw) < angular_tolerance) {
647  return true;
648  }
649 
650  // Transform target_pose into base_link frame
651  geometry_msgs::msg::PoseStamped target_pose = pose;
652  target_pose.header.stamp = rclcpp::Time(0);
653  tf2_buffer_->transform(target_pose, target_pose, base_frame_);
654 
655  // Compute velocity command
656  if (!controller_->computeVelocityCommand(target_pose.pose, cmd, is_docking, backward)) {
657  throw opennav_docking_core::FailedToControl("Failed to get control");
658  }
659 
660  // Command is valid, but target is not reached
661  return false;
662 }
663 
665 {
666  std::lock_guard<std::mutex> lock(*mutex_);
667  action_start_time_ = this->now();
668  rclcpp::Rate loop_rate(controller_frequency_);
669 
670  auto goal = undocking_action_server_->get_current_goal();
671  auto result = std::make_shared<UndockRobot::Result>();
672  result->success = false;
673 
674  if (!undocking_action_server_ || !undocking_action_server_->is_server_active()) {
675  RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
676  return;
677  }
678 
679  if (checkAndWarnIfCancelled<UndockRobot>(undocking_action_server_, "undock_robot")) {
680  undocking_action_server_->terminate_all(result);
681  return;
682  }
683 
684  getPreemptedGoalIfRequested<UndockRobot>(goal, undocking_action_server_);
685  auto max_duration = rclcpp::Duration::from_seconds(goal->max_undocking_time);
686 
687  try {
688  // Get dock plugin information from request or docked state, reset state.
689  std::string dock_type = curr_dock_type_;
690  if (!goal->dock_type.empty()) {
691  dock_type = goal->dock_type;
692  }
693 
694  ChargingDock::Ptr dock = dock_db_->findDockPlugin(dock_type);
695  if (!dock) {
696  throw opennav_docking_core::DockNotValid("No dock information to undock from!");
697  }
698  RCLCPP_INFO(
699  get_logger(),
700  "Attempting to undock robot of dock type %s.", dock->getName().c_str());
701 
702  // Check if the robot is docked before proceeding
703  if (dock->isCharger() && (!dock->isDocked() && !dock->isCharging())) {
704  RCLCPP_INFO(get_logger(), "Robot is not in the dock, no need to undock");
705  return;
706  }
707 
708  bool dock_backward = dock_backwards_.has_value() ?
709  dock_backwards_.value() :
710  (dock->getDockDirection() == opennav_docking_core::DockDirection::BACKWARD);
711 
712  // Get "dock pose" by finding the robot pose
713  geometry_msgs::msg::PoseStamped dock_pose = getRobotPoseInFrame(fixed_frame_);
714 
715  // Make sure that the staging pose is pointing in the same direction when moving backwards
716  if (dock_backward) {
717  dock_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
718  tf2::getYaw(dock_pose.pose.orientation) + M_PI);
719  }
720 
721  // Get staging pose (in fixed frame)
722  geometry_msgs::msg::PoseStamped staging_pose =
723  dock->getStagingPose(dock_pose.pose, dock_pose.header.frame_id);
724 
725  // If we performed a rotation before docking backward, we must rotate the staging pose
726  // to match the robot orientation
727  if (dock->shouldRotateToDock()) {
728  staging_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
729  tf2::getYaw(staging_pose.pose.orientation) + M_PI);
730  }
731 
732  // Control robot to staging pose
733  rclcpp::Time loop_start = this->now();
734  while (rclcpp::ok()) {
735  // Stop if we exceed max duration
736  auto timeout = rclcpp::Duration::from_seconds(goal->max_undocking_time);
737  if (this->now() - loop_start > timeout) {
738  throw opennav_docking_core::FailedToControl("Undocking timed out");
739  }
740 
741  // Stop if cancelled/preempted
742  if (checkAndWarnIfCancelled<UndockRobot>(undocking_action_server_, "undock_robot") ||
743  checkAndWarnIfPreempted<UndockRobot>(undocking_action_server_, "undock_robot"))
744  {
746  undocking_action_server_->terminate_all(result);
747  return;
748  }
749 
750  // Don't control the robot until charging is disabled
751  if (dock->isCharger() && !dock->disableCharging()) {
752  loop_rate.sleep();
753  continue;
754  }
755 
756  // Get command to approach staging pose
757  auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
758  command->header.stamp = now();
759 
760  if (getCommandToPose(
761  command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_, false,
762  !dock_backward))
763  {
764  // Perform a 180º to the original staging pose
765  if (dock->shouldRotateToDock()) {
766  rotateToDock(staging_pose);
767  }
768 
769  // Have reached staging_pose
770  RCLCPP_INFO(get_logger(), "Robot has reached staging pose");
771  vel_publisher_->publish(std::move(command));
772  if (!dock->isCharger() || dock->hasStoppedCharging()) {
773  RCLCPP_INFO(get_logger(), "Robot has undocked!");
774  result->success = true;
775  curr_dock_type_.clear();
777  undocking_action_server_->succeeded_current(result);
778  return;
779  }
780  // Haven't stopped charging?
781  throw opennav_docking_core::FailedToControl("Failed to control off dock");
782  }
783 
784  // Publish command and sleep
785  vel_publisher_->publish(std::move(command));
786  loop_rate.sleep();
787  }
788  } catch (const tf2::TransformException & e) {
789  result->error_msg = std::string("Transform error: ") + e.what();
790  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
791  result->error_code = DockRobot::Result::UNKNOWN;
792  } catch (opennav_docking_core::DockNotValid & e) {
793  result->error_msg = e.what();
794  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
795  result->error_code = DockRobot::Result::DOCK_NOT_VALID;
797  result->error_msg = e.what();
798  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
799  result->error_code = DockRobot::Result::FAILED_TO_CONTROL;
801  result->error_msg = e.what();
802  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
803  result->error_code = DockRobot::Result::UNKNOWN;
804  } catch (std::exception & e) {
805  result->error_msg = std::string("Internal error: ") + e.what();
806  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
807  result->error_code = DockRobot::Result::UNKNOWN;
808  }
809 
811  undocking_action_server_->terminate_current(result);
812 }
813 
814 geometry_msgs::msg::PoseStamped DockingServer::getRobotPoseInFrame(const std::string & frame)
815 {
816  geometry_msgs::msg::PoseStamped robot_pose;
817  robot_pose.header.frame_id = base_frame_;
818  robot_pose.header.stamp = rclcpp::Time(0);
819  tf2_buffer_->transform(robot_pose, robot_pose, frame);
820  return robot_pose;
821 }
822 
824 {
825  auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
826  cmd_vel->header.stamp = now();
827  vel_publisher_->publish(std::move(cmd_vel));
828 }
829 
831 {
832  auto feedback = std::make_shared<DockRobot::Feedback>();
833  feedback->state = state;
834  feedback->docking_time = this->now() - action_start_time_;
835  feedback->num_retries = num_retries_;
836  docking_action_server_->publish_feedback(feedback);
837 }
838 
839 rcl_interfaces::msg::SetParametersResult
840 DockingServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
841 {
842  std::lock_guard<std::mutex> lock(*mutex_);
843 
844  rcl_interfaces::msg::SetParametersResult result;
845  for (auto parameter : parameters) {
846  const auto & param_type = parameter.get_type();
847  const auto & param_name = parameter.get_name();
848  if (param_name.find('.') != std::string::npos) {
849  continue;
850  }
851 
852  if (param_type == ParameterType::PARAMETER_DOUBLE) {
853  if (param_name == "controller_frequency") {
854  controller_frequency_ = parameter.as_double();
855  } else if (param_name == "initial_perception_timeout") {
856  initial_perception_timeout_ = parameter.as_double();
857  } else if (param_name == "wait_charge_timeout") {
858  wait_charge_timeout_ = parameter.as_double();
859  } else if (param_name == "undock_linear_tolerance") {
860  undock_linear_tolerance_ = parameter.as_double();
861  } else if (param_name == "undock_angular_tolerance") {
862  undock_angular_tolerance_ = parameter.as_double();
863  } else if (param_name == "rotation_angular_tolerance") {
864  rotation_angular_tolerance_ = parameter.as_double();
865  }
866  } else if (param_type == ParameterType::PARAMETER_STRING) {
867  if (param_name == "base_frame") {
868  base_frame_ = parameter.as_string();
869  } else if (param_name == "fixed_frame") {
870  fixed_frame_ = parameter.as_string();
871  }
872  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
873  if (param_name == "max_retries") {
874  max_retries_ = parameter.as_int();
875  }
876  }
877  }
878 
879  result.successful = true;
880  return result;
881 }
882 
883 } // namespace opennav_docking
884 
885 #include "rclcpp_components/register_node_macro.hpp"
886 
887 // Register the component with class_loader.
888 // This acts as a sort of entry point, allowing the component to be discoverable when its library
889 // is being loaded into a running process.
890 RCLCPP_COMPONENTS_REGISTER_NODE(opennav_docking::DockingServer)
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.
bool is_cancel_requested() const
Whether or not a cancel command has come in.
bool is_preempt_requested() const
Whether the action server has been asked to be preempted with a new goal.
const std::shared_ptr< const typename ActionT::Goal > accept_pending_goal()
Accept pending goals.
An action server which implements charger docking node for AMRs.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual geometry_msgs::msg::PoseStamped getRobotPoseInFrame(const std::string &frame)
Get the robot pose (aka base_frame pose) in another frame.
bool resetApproach(const geometry_msgs::msg::PoseStamped &staging_pose, bool backward)
Reset the robot for another approach by controlling back to staging pose.
void dockRobot()
Main action callback method to complete docking request.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
bool approachDock(Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose, bool backward)
Use control law and dock perception to approach the charge dock.
void doInitialPerception(Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose)
Do initial perception, up to a timeout.
void publishDockingFeedback(uint16_t state)
Publish feedback from a docking action.
bool checkAndWarnIfCancelled(typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server, const std::string &name)
Checks and logs warning if action canceled.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
bool checkAndWarnIfPreempted(typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server, const std::string &name)
Checks and logs warning if action preempted.
bool getCommandToPose(geometry_msgs::msg::Twist &cmd, const geometry_msgs::msg::PoseStamped &pose, double linear_tolerance, double angular_tolerance, bool is_docking, bool backward)
Run a single iteration of the control loop to approach a pose.
bool waitForCharge(Dock *dock)
Wait for charging to begin.
Dock * generateGoalDock(std::shared_ptr< const DockRobot::Goal > goal)
Generate a dock from action goal.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
void getPreemptedGoalIfRequested(typename std::shared_ptr< const typename ActionT::Goal > goal, const typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server)
Gets a preempted goal if immediately requested.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables.
void publishZeroVelocity()
Publish zero velocity at terminal condition.
void rotateToDock(const geometry_msgs::msg::PoseStamped &dock_pose)
Perform a pure rotation to dock orientation.
void undockRobot()
Main action callback method to complete undocking request.
void stashDockData(bool use_dock_id, Dock *dock, bool successful)
Called at the conclusion of docking actions. Saves relevant docking data for later undocking action.
Dock was not found in the provided dock database.
Dock plugin provided in the database or action was invalid.
Failed to control into or out of the dock.
Failed to detect the charging dock.
Failed to navigate to the staging pose.
Definition: types.hpp:33