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"
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(
"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);
48 nav2_util::CallbackReturn
51 RCLCPP_INFO(get_logger(),
"Configuring %s", get_name());
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_);
67 RCLCPP_INFO(get_logger(),
"Controller frequency set to %.4fHz", controller_frequency_);
70 bool dock_backwards =
false;
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.");
77 }
catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
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());
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);
89 docking_action_server_ = std::make_unique<DockingActionServer>(
92 nullptr, std::chrono::milliseconds(500),
95 undocking_action_server_ = std::make_unique<UndockingActionServer>(
98 nullptr, std::chrono::milliseconds(500),
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_)) {
108 return nav2_util::CallbackReturn::FAILURE;
111 return nav2_util::CallbackReturn::SUCCESS;
114 nav2_util::CallbackReturn
117 RCLCPP_INFO(get_logger(),
"Activating %s", get_name());
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();
130 dyn_params_handler_ = node->add_on_set_parameters_callback(
136 return nav2_util::CallbackReturn::SUCCESS;
139 nav2_util::CallbackReturn
142 RCLCPP_INFO(get_logger(),
"Deactivating %s", get_name());
144 docking_action_server_->deactivate();
145 undocking_action_server_->deactivate();
146 dock_db_->deactivate();
147 navigator_->deactivate();
148 vel_publisher_->on_deactivate();
150 remove_on_set_parameters_callback(dyn_params_handler_.get());
151 dyn_params_handler_.reset();
152 tf2_listener_.reset();
157 return nav2_util::CallbackReturn::SUCCESS;
160 nav2_util::CallbackReturn
163 RCLCPP_INFO(get_logger(),
"Cleaning up %s", get_name());
165 docking_action_server_.reset();
166 undocking_action_server_.reset();
169 curr_dock_type_.clear();
171 vel_publisher_.reset();
172 dock_backwards_.reset();
174 return nav2_util::CallbackReturn::SUCCESS;
177 nav2_util::CallbackReturn
180 RCLCPP_INFO(get_logger(),
"Shutting down %s", get_name());
181 return nav2_util::CallbackReturn::SUCCESS;
184 template<
typename ActionT>
186 typename std::shared_ptr<const typename ActionT::Goal> goal,
189 if (action_server->is_preempt_requested()) {
190 goal = action_server->accept_pending_goal();
194 template<
typename ActionT>
197 const std::string & name)
199 if (action_server->is_cancel_requested()) {
200 RCLCPP_WARN(get_logger(),
"Goal was cancelled. Cancelling %s action", name.c_str());
206 template<
typename ActionT>
209 const std::string & name)
211 if (action_server->is_preempt_requested()) {
212 RCLCPP_WARN(get_logger(),
"Goal was preempted. Cancelling %s action", name.c_str());
220 std::lock_guard<std::mutex> lock(*mutex_);
221 action_start_time_ = this->now();
222 rclcpp::Rate loop_rate(controller_frequency_);
224 auto goal = docking_action_server_->get_current_goal();
225 auto result = std::make_shared<DockRobot::Result>();
226 result->success =
false;
228 if (!docking_action_server_ || !docking_action_server_->is_server_active()) {
229 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
234 docking_action_server_->terminate_all();
239 Dock * dock{
nullptr};
244 if (goal->use_dock_id) {
247 "Attempting to dock robot at %s.", goal->dock_id.c_str());
248 dock = dock_db_->findDock(goal->dock_id);
252 "Attempting to dock robot at position (%0.2f, %0.2f).",
253 goal->dock_pose.pose.position.x, goal->dock_pose.pose.position.y);
258 if (dock->plugin->isCharger() && (dock->plugin->isDocked() || dock->plugin->isCharging())) {
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);
268 const auto initial_staging_pose = dock->getStagingPose();
270 if (!goal->navigate_to_staging_pose ||
271 utils::l2Norm(robot_pose.pose, initial_staging_pose.pose) < dock_prestaging_tolerance_)
273 RCLCPP_INFO(get_logger(),
"Robot already within pre-staging pose tolerance for dock");
275 std::function<bool()> isPreempted = [
this]() {
280 navigator_->goToPose(
281 initial_staging_pose,
282 rclcpp::Duration::from_seconds(goal->max_staging_time),
284 RCLCPP_INFO(get_logger(),
"Successful navigation to staging pose");
288 auto dock_pose = utils::getDockPoseStamped(dock, rclcpp::Time(0));
289 tf2_buffer_->transform(dock_pose, dock_pose, fixed_frame_);
293 RCLCPP_INFO(get_logger(),
"Successful initial dock detection");
296 bool dock_backward = dock_backwards_.has_value() ?
297 dock_backwards_.value() :
298 (dock->plugin->getDockDirection() == opennav_docking_core::DockDirection::BACKWARD);
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);
309 rclcpp::Time dock_contact_time;
310 while (rclcpp::ok()) {
313 if (dock->plugin->shouldRotateToDock()) {
320 get_logger(),
"Made contact with dock, waiting for charge to start (if applicable).");
322 if (dock->plugin->isCharger()) {
323 RCLCPP_INFO(get_logger(),
"Robot is charging!");
325 RCLCPP_INFO(get_logger(),
"Docking was successful!");
327 result->success =
true;
328 result->num_retries = num_retries_;
331 docking_action_server_->succeeded_current(result);
339 docking_action_server_->terminate_all(result);
342 if (++num_retries_ > max_retries_) {
343 RCLCPP_ERROR(get_logger(),
"Failed to dock, all retries have been used");
346 RCLCPP_WARN(get_logger(),
"Docking failed, will retry: %s", e.what());
354 docking_action_server_->terminate_all(result);
357 RCLCPP_INFO(get_logger(),
"Returned to staging pose, attempting docking again");
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;
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;
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());
399 result->num_retries = num_retries_;
401 docking_action_server_->terminate_current(result);
406 if (dock && successful) {
407 curr_dock_type_ = dock->type;
410 if (!use_dock_id && dock) {
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);
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) {
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);
454 rclcpp::Rate loop_rate(controller_frequency_);
455 auto start = this->now();
456 auto timeout = rclcpp::Duration::from_seconds(rotate_to_dock_timeout_);
458 while (rclcpp::ok()) {
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_) {
466 auto current_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
467 current_vel->twist.angular.z = odom_sub_->getTwist().theta;
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);
474 vel_publisher_->publish(std::move(command));
476 if (this->now() - start > timeout) {
485 Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose,
bool backward)
487 rclcpp::Rate loop_rate(controller_frequency_);
488 auto start = this->now();
489 auto timeout = rclcpp::Duration::from_seconds(dock_approach_timeout_);
491 while (rclcpp::ok()) {
495 if (dock->plugin->isDocked() || (dock->plugin->isCharger() && dock->plugin->isCharging())) {
507 if (!dock->plugin->getRefinedPose(dock_pose, dock->id) && !dock->plugin->shouldRotateToDock()) {
512 geometry_msgs::msg::PoseStamped target_pose = dock_pose;
513 target_pose.header.stamp = rclcpp::Time(0);
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_);
528 target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
529 tf2::getYaw(target_pose.pose.orientation) + M_PI);
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)) {
538 vel_publisher_->publish(std::move(command));
540 if (this->now() - start > timeout) {
542 "Timed out approaching dock; dock nor charging (if applicable) detected");
553 if (!dock->plugin->isCharger()) {
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()) {
563 if (dock->plugin->isCharging()) {
573 if (this->now() - start > timeout) {
583 const geometry_msgs::msg::PoseStamped & staging_pose,
bool backward)
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()) {
599 auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
600 command->header.stamp = now();
602 command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_,
false,
607 vel_publisher_->publish(std::move(command));
609 if (this->now() - start > timeout) {
619 geometry_msgs::msg::Twist & cmd,
const geometry_msgs::msg::PoseStamped & pose,
620 double linear_tolerance,
double angular_tolerance,
bool is_docking,
bool backward)
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) {
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_);
643 if (!controller_->computeVelocityCommand(target_pose.pose, cmd, is_docking, backward)) {
653 std::lock_guard<std::mutex> lock(*mutex_);
654 action_start_time_ = this->now();
655 rclcpp::Rate loop_rate(controller_frequency_);
657 auto goal = undocking_action_server_->get_current_goal();
658 auto result = std::make_shared<UndockRobot::Result>();
659 result->success =
false;
661 if (!undocking_action_server_ || !undocking_action_server_->is_server_active()) {
662 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
667 undocking_action_server_->terminate_all(result);
672 auto max_duration = rclcpp::Duration::from_seconds(goal->max_undocking_time);
676 std::string dock_type = curr_dock_type_;
677 if (!goal->dock_type.empty()) {
678 dock_type = goal->dock_type;
681 ChargingDock::Ptr dock = dock_db_->findDockPlugin(dock_type);
687 "Attempting to undock robot of dock type %s.", dock->getName().c_str());
690 if (dock->isCharger() && (!dock->isDocked() && !dock->isCharging())) {
691 RCLCPP_INFO(get_logger(),
"Robot is not in the dock, no need to undock");
695 bool dock_backward = dock_backwards_.has_value() ?
696 dock_backwards_.value() :
697 (dock->getDockDirection() == opennav_docking_core::DockDirection::BACKWARD);
704 dock_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
705 tf2::getYaw(dock_pose.pose.orientation) + M_PI);
709 geometry_msgs::msg::PoseStamped staging_pose =
710 dock->getStagingPose(dock_pose.pose, dock_pose.header.frame_id);
714 if (dock->shouldRotateToDock()) {
715 staging_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
716 tf2::getYaw(staging_pose.pose.orientation) + M_PI);
720 rclcpp::Time loop_start = this->now();
721 while (rclcpp::ok()) {
723 auto timeout = rclcpp::Duration::from_seconds(goal->max_undocking_time);
724 if (this->now() - loop_start > timeout) {
733 undocking_action_server_->terminate_all(result);
738 if (dock->isCharger() && !dock->disableCharging()) {
744 auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
745 command->header.stamp = now();
748 command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_,
false,
752 if (dock->shouldRotateToDock()) {
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);
772 vel_publisher_->publish(std::move(command));
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;
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;
798 undocking_action_server_->terminate_current(result);
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);
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));
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);
826 rcl_interfaces::msg::SetParametersResult
829 std::lock_guard<std::mutex> lock(*mutex_);
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) {
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();
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();
859 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
860 if (param_name ==
"max_retries") {
861 max_retries_ = parameter.as_int();
866 result.successful =
true;
872 #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.
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.
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.