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