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"
20 using namespace std::chrono_literals;
21 using rcl_interfaces::msg::ParameterType;
22 using std::placeholders::_1;
24 namespace opennav_docking
27 DockingServer::DockingServer(
const rclcpp::NodeOptions & options)
28 : nav2_util::LifecycleNode(
"docking_server",
"", options)
30 RCLCPP_INFO(get_logger(),
"Creating %s", get_name());
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);
45 nav2_util::CallbackReturn
48 RCLCPP_INFO(get_logger(),
"Configuring %s", get_name());
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_);
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());
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);
75 docking_action_server_ = std::make_unique<DockingActionServer>(
78 nullptr, std::chrono::milliseconds(500),
79 true, server_options);
81 undocking_action_server_ = std::make_unique<UndockingActionServer>(
84 nullptr, std::chrono::milliseconds(500),
85 true, server_options);
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_)) {
94 return nav2_util::CallbackReturn::FAILURE;
97 return nav2_util::CallbackReturn::SUCCESS;
100 nav2_util::CallbackReturn
103 RCLCPP_INFO(get_logger(),
"Activating %s", get_name());
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();
116 dyn_params_handler_ = node->add_on_set_parameters_callback(
122 return nav2_util::CallbackReturn::SUCCESS;
125 nav2_util::CallbackReturn
128 RCLCPP_INFO(get_logger(),
"Deactivating %s", get_name());
130 docking_action_server_->deactivate();
131 undocking_action_server_->deactivate();
132 dock_db_->deactivate();
133 navigator_->deactivate();
134 vel_publisher_->on_deactivate();
136 remove_on_set_parameters_callback(dyn_params_handler_.get());
137 dyn_params_handler_.reset();
138 tf2_listener_.reset();
143 return nav2_util::CallbackReturn::SUCCESS;
146 nav2_util::CallbackReturn
149 RCLCPP_INFO(get_logger(),
"Cleaning up %s", get_name());
151 docking_action_server_.reset();
152 undocking_action_server_.reset();
155 curr_dock_type_.clear();
157 vel_publisher_.reset();
158 return nav2_util::CallbackReturn::SUCCESS;
161 nav2_util::CallbackReturn
164 RCLCPP_INFO(get_logger(),
"Shutting down %s", get_name());
165 return nav2_util::CallbackReturn::SUCCESS;
168 template<
typename ActionT>
170 typename std::shared_ptr<const typename ActionT::Goal> goal,
173 if (action_server->is_preempt_requested()) {
174 goal = action_server->accept_pending_goal();
178 template<
typename ActionT>
181 const std::string & name)
183 if (action_server->is_cancel_requested()) {
184 RCLCPP_WARN(get_logger(),
"Goal was cancelled. Cancelling %s action", name.c_str());
190 template<
typename ActionT>
193 const std::string & name)
195 if (action_server->is_preempt_requested()) {
196 RCLCPP_WARN(get_logger(),
"Goal was preempted. Cancelling %s action", name.c_str());
204 std::lock_guard<std::mutex> lock(*mutex_);
205 action_start_time_ = this->now();
206 rclcpp::Rate loop_rate(controller_frequency_);
208 auto goal = docking_action_server_->get_current_goal();
209 auto result = std::make_shared<DockRobot::Result>();
210 result->success =
false;
212 if (!docking_action_server_ || !docking_action_server_->is_server_active()) {
213 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
218 docking_action_server_->terminate_all();
223 Dock * dock{
nullptr};
228 if (goal->use_dock_id) {
231 "Attempting to dock robot at %s.", goal->dock_id.c_str());
232 dock = dock_db_->findDock(goal->dock_id);
236 "Attempting to dock robot at position (%0.2f, %0.2f).",
237 goal->dock_pose.pose.position.x, goal->dock_pose.pose.position.y);
242 if (dock->plugin->isCharger() && (dock->plugin->isDocked() || dock->plugin->isCharging())) {
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);
252 const auto initial_staging_pose = dock->getStagingPose();
254 if (!goal->navigate_to_staging_pose ||
255 utils::l2Norm(robot_pose.pose, initial_staging_pose.pose) < dock_prestaging_tolerance_)
257 RCLCPP_INFO(get_logger(),
"Robot already within pre-staging pose tolerance for dock");
259 std::function<bool()> isPreempted = [
this]() {
264 navigator_->goToPose(
265 initial_staging_pose,
266 rclcpp::Duration::from_seconds(goal->max_staging_time),
268 RCLCPP_INFO(get_logger(),
"Successful navigation to staging pose");
272 auto dock_pose = utils::getDockPoseStamped(dock, rclcpp::Time(0));
273 tf2_buffer_->transform(dock_pose, dock_pose, fixed_frame_);
277 RCLCPP_INFO(get_logger(),
"Successful initial dock detection");
280 rclcpp::Time dock_contact_time;
281 while (rclcpp::ok()) {
287 get_logger(),
"Made contact with dock, waiting for charge to start (if applicable).");
289 if (dock->plugin->isCharger()) {
290 RCLCPP_INFO(get_logger(),
"Robot is charging!");
292 RCLCPP_INFO(get_logger(),
"Docking was successful!");
294 result->success =
true;
295 result->num_retries = num_retries_;
298 docking_action_server_->succeeded_current(result);
306 docking_action_server_->terminate_all(result);
309 if (++num_retries_ > max_retries_) {
310 RCLCPP_ERROR(get_logger(),
"Failed to dock, all retries have been used");
313 RCLCPP_WARN(get_logger(),
"Docking failed, will retry: %s", e.what());
321 docking_action_server_->terminate_all(result);
324 RCLCPP_INFO(get_logger(),
"Returned to staging pose, attempting docking again");
326 }
catch (
const tf2::TransformException & e) {
327 RCLCPP_ERROR(get_logger(),
"Transform error: %s", e.what());
328 result->error_code = DockRobot::Result::UNKNOWN;
330 RCLCPP_ERROR(get_logger(),
"%s", e.what());
331 result->error_code = DockRobot::Result::DOCK_NOT_IN_DB;
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;
357 result->num_retries = num_retries_;
359 docking_action_server_->terminate_current(result);
364 if (dock && successful) {
365 curr_dock_type_ = dock->type;
368 if (!use_dock_id && dock) {
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);
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) {
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()) {
414 if (dock->plugin->isDocked() || (dock->plugin->isCharger() && dock->plugin->isCharging())) {
426 if (!dock->plugin->getRefinedPose(dock_pose, dock->id)) {
431 geometry_msgs::msg::PoseStamped target_pose = dock_pose;
432 target_pose.header.stamp = rclcpp::Time(0);
436 if (dock_backwards_) {
437 target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
438 tf2::getYaw(target_pose.pose.orientation) + M_PI);
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_);
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,
459 vel_publisher_->publish(std::move(command));
461 if (this->now() - start > timeout) {
463 "Timed out approaching dock; dock nor charging (if applicable) detected");
474 if (!dock->plugin->isCharger()) {
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()) {
484 if (dock->plugin->isCharging()) {
494 if (this->now() - start > timeout) {
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()) {
519 auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
520 command->header.stamp = now();
522 command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_,
false,
527 vel_publisher_->publish(std::move(command));
529 if (this->now() - start > timeout) {
539 geometry_msgs::msg::Twist & cmd,
const geometry_msgs::msg::PoseStamped & pose,
540 double linear_tolerance,
double angular_tolerance,
bool is_docking,
bool backward)
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) {
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_);
563 if (!controller_->computeVelocityCommand(target_pose.pose, cmd, is_docking, backward)) {
573 std::lock_guard<std::mutex> lock(*mutex_);
574 action_start_time_ = this->now();
575 rclcpp::Rate loop_rate(controller_frequency_);
577 auto goal = undocking_action_server_->get_current_goal();
578 auto result = std::make_shared<UndockRobot::Result>();
579 result->success =
false;
581 if (!undocking_action_server_ || !undocking_action_server_->is_server_active()) {
582 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
587 undocking_action_server_->terminate_all(result);
592 auto max_duration = rclcpp::Duration::from_seconds(goal->max_undocking_time);
596 std::string dock_type = curr_dock_type_;
597 if (!goal->dock_type.empty()) {
598 dock_type = goal->dock_type;
601 ChargingDock::Ptr dock = dock_db_->findDockPlugin(dock_type);
607 "Attempting to undock robot of dock type %s.", dock->getName().c_str());
610 if (dock->isCharger() && (!dock->isDocked() && !dock->isCharging())) {
611 RCLCPP_INFO(get_logger(),
"Robot is not in the dock, no need to undock");
619 geometry_msgs::msg::PoseStamped staging_pose =
620 dock->getStagingPose(dock_pose.pose, dock_pose.header.frame_id);
623 rclcpp::Time loop_start = this->now();
624 while (rclcpp::ok()) {
626 auto timeout = rclcpp::Duration::from_seconds(goal->max_undocking_time);
627 if (this->now() - loop_start > timeout) {
636 undocking_action_server_->terminate_all(result);
641 if (dock->isCharger() && !dock->disableCharging()) {
647 auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
648 command->header.stamp = now();
650 command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_,
false,
653 RCLCPP_INFO(get_logger(),
"Robot has 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);
669 vel_publisher_->publish(std::move(command));
672 }
catch (
const tf2::TransformException & e) {
673 RCLCPP_ERROR(get_logger(),
"Transform error: %s", e.what());
674 result->error_code = DockRobot::Result::UNKNOWN;
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;
690 undocking_action_server_->terminate_current(result);
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);
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));
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);
718 rcl_interfaces::msg::SetParametersResult
721 std::lock_guard<std::mutex> lock(*mutex_);
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();
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();
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();
746 }
else if (type == ParameterType::PARAMETER_INTEGER) {
747 if (name ==
"max_retries") {
748 max_retries_ = parameter.as_int();
753 result.successful =
true;
759 #include "rclcpp_components/register_node_macro.hpp"
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.
Abstract docking exception.
Failed to start charging.
Failed to control into or out of the dock.
Failed to detect the charging dock.
Failed to navigate to the staging pose.