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