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::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(
"odom_duration", 0.3);
46 declare_parameter(
"rotation_angular_tolerance", 0.05);
52 RCLCPP_INFO(get_logger(),
"Configuring %s", get_name());
55 get_parameter(
"controller_frequency", controller_frequency_);
56 get_parameter(
"initial_perception_timeout", initial_perception_timeout_);
57 get_parameter(
"wait_charge_timeout", wait_charge_timeout_);
58 get_parameter(
"dock_approach_timeout", dock_approach_timeout_);
59 get_parameter(
"rotate_to_dock_timeout", rotate_to_dock_timeout_);
60 get_parameter(
"undock_linear_tolerance", undock_linear_tolerance_);
61 get_parameter(
"undock_angular_tolerance", undock_angular_tolerance_);
62 get_parameter(
"max_retries", max_retries_);
63 get_parameter(
"base_frame", base_frame_);
64 get_parameter(
"fixed_frame", fixed_frame_);
65 get_parameter(
"dock_prestaging_tolerance", dock_prestaging_tolerance_);
66 get_parameter(
"rotation_angular_tolerance", rotation_angular_tolerance_);
68 RCLCPP_INFO(get_logger(),
"Controller frequency set to %.4fHz", controller_frequency_);
71 bool dock_backwards =
false;
73 if (get_parameter(
"dock_backwards", dock_backwards)) {
74 dock_backwards_ = dock_backwards;
75 RCLCPP_WARN(get_logger(),
"Parameter dock_backwards is deprecated. "
76 "Please use the dock_direction parameter in your dock plugin instead.");
78 }
catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
81 vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node,
"cmd_vel");
82 tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(node->get_clock());
85 std::string odom_topic;
86 get_parameter(
"odom_topic", odom_topic);
88 get_parameter(
"odom_duration", odom_duration);
89 odom_sub_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration, odom_topic);
92 docking_action_server_ = node->create_action_server<DockRobot>(
95 nullptr, std::chrono::milliseconds(500),
98 undocking_action_server_ = node->create_action_server<UndockRobot>(
101 nullptr, std::chrono::milliseconds(500),
105 mutex_ = std::make_shared<std::mutex>();
106 controller_ = std::make_unique<Controller>(node, tf2_buffer_, fixed_frame_, base_frame_);
107 navigator_ = std::make_unique<Navigator>(node);
108 dock_db_ = std::make_unique<DockDatabase>(mutex_);
109 if (!dock_db_->initialize(node, tf2_buffer_)) {
111 return nav2::CallbackReturn::FAILURE;
114 return nav2::CallbackReturn::SUCCESS;
120 RCLCPP_INFO(get_logger(),
"Activating %s", get_name());
124 tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_,
this,
true);
125 dock_db_->activate();
126 navigator_->activate();
127 vel_publisher_->on_activate();
128 docking_action_server_->activate();
129 undocking_action_server_->activate();
130 curr_dock_type_.clear();
133 dyn_params_handler_ = node->add_on_set_parameters_callback(
139 return nav2::CallbackReturn::SUCCESS;
145 RCLCPP_INFO(get_logger(),
"Deactivating %s", get_name());
147 docking_action_server_->deactivate();
148 undocking_action_server_->deactivate();
149 dock_db_->deactivate();
150 navigator_->deactivate();
151 vel_publisher_->on_deactivate();
153 remove_on_set_parameters_callback(dyn_params_handler_.get());
154 dyn_params_handler_.reset();
155 tf2_listener_.reset();
160 return nav2::CallbackReturn::SUCCESS;
166 RCLCPP_INFO(get_logger(),
"Cleaning up %s", get_name());
168 docking_action_server_.reset();
169 undocking_action_server_.reset();
172 curr_dock_type_.clear();
174 vel_publisher_.reset();
175 dock_backwards_.reset();
177 return nav2::CallbackReturn::SUCCESS;
183 RCLCPP_INFO(get_logger(),
"Shutting down %s", get_name());
184 return nav2::CallbackReturn::SUCCESS;
187 template<
typename ActionT>
189 typename std::shared_ptr<const typename ActionT::Goal> goal,
190 const typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server)
197 template<
typename ActionT>
199 typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server,
200 const std::string & name)
203 RCLCPP_WARN(get_logger(),
"Goal was cancelled. Cancelling %s action", name.c_str());
209 template<
typename ActionT>
211 typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server,
212 const std::string & name)
215 RCLCPP_WARN(get_logger(),
"Goal was preempted. Cancelling %s action", name.c_str());
223 std::lock_guard<std::mutex> lock(*mutex_);
224 action_start_time_ = this->now();
225 rclcpp::Rate loop_rate(controller_frequency_);
227 auto goal = docking_action_server_->get_current_goal();
228 auto result = std::make_shared<DockRobot::Result>();
229 result->success =
false;
231 if (!docking_action_server_ || !docking_action_server_->is_server_active()) {
232 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
236 if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_,
"dock_robot")) {
237 docking_action_server_->terminate_all();
241 getPreemptedGoalIfRequested<DockRobot>(goal, docking_action_server_);
242 Dock * dock{
nullptr};
247 if (goal->use_dock_id) {
250 "Attempting to dock robot at %s.", goal->dock_id.c_str());
251 dock = dock_db_->findDock(goal->dock_id);
255 "Attempting to dock robot at position (%0.2f, %0.2f).",
256 goal->dock_pose.pose.position.x, goal->dock_pose.pose.position.y);
261 if (dock->plugin->isCharger() && (dock->plugin->isDocked() || dock->plugin->isCharging())) {
263 get_logger(),
"Robot is already docked and/or charging (if applicable), no need to dock");
264 result->success =
true;
265 docking_action_server_->succeeded_current(result);
271 const auto initial_staging_pose = dock->getStagingPose();
273 if (!goal->navigate_to_staging_pose ||
274 utils::l2Norm(robot_pose.pose, initial_staging_pose.pose) < dock_prestaging_tolerance_)
276 RCLCPP_INFO(get_logger(),
"Robot already within pre-staging pose tolerance for dock");
278 std::function<bool()> isPreempted = [
this]() {
279 return checkAndWarnIfCancelled<DockRobot>(docking_action_server_,
"dock_robot") ||
280 checkAndWarnIfPreempted<DockRobot>(docking_action_server_,
"dock_robot");
283 navigator_->goToPose(
284 initial_staging_pose,
285 rclcpp::Duration::from_seconds(goal->max_staging_time),
287 RCLCPP_INFO(get_logger(),
"Successful navigation to staging pose");
291 auto dock_pose = utils::getDockPoseStamped(dock, rclcpp::Time(0));
292 tf2_buffer_->transform(dock_pose, dock_pose, fixed_frame_);
296 RCLCPP_INFO(get_logger(),
"Successful initial dock detection");
299 bool dock_backward = dock_backwards_.has_value() ?
300 dock_backwards_.value() :
301 (dock->plugin->getDockDirection() == opennav_docking_core::DockDirection::BACKWARD);
305 auto staging_pose = dock->getStagingPose();
306 if (dock->plugin->shouldRotateToDock()) {
307 staging_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
308 tf2::getYaw(staging_pose.pose.orientation) + M_PI);
312 rclcpp::Time dock_contact_time;
313 while (rclcpp::ok()) {
316 if (dock->plugin->shouldRotateToDock()) {
323 get_logger(),
"Made contact with dock, waiting for charge to start (if applicable).");
325 if (dock->plugin->isCharger()) {
326 RCLCPP_INFO(get_logger(),
"Robot is charging!");
328 RCLCPP_INFO(get_logger(),
"Docking was successful!");
330 result->success =
true;
331 result->num_retries = num_retries_;
334 dock->plugin->stopDetectionProcess();
335 docking_action_server_->succeeded_current(result);
343 dock->plugin->stopDetectionProcess();
344 docking_action_server_->terminate_all(result);
347 if (++num_retries_ > max_retries_) {
348 RCLCPP_ERROR(get_logger(),
"Failed to dock, all retries have been used");
351 RCLCPP_WARN(get_logger(),
"Docking failed, will retry: %s", e.what());
359 dock->plugin->stopDetectionProcess();
360 docking_action_server_->terminate_all(result);
363 RCLCPP_INFO(get_logger(),
"Returned to staging pose, attempting docking again");
365 }
catch (
const tf2::TransformException & e) {
366 result->error_msg = std::string(
"Transform error: ") + e.what();
367 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
368 result->error_code = DockRobot::Result::UNKNOWN;
370 result->error_msg = e.what();
371 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
372 result->error_code = DockRobot::Result::DOCK_NOT_IN_DB;
374 result->error_msg = e.what();
375 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
376 result->error_code = DockRobot::Result::DOCK_NOT_VALID;
378 result->error_msg = e.what();
379 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
380 result->error_code = DockRobot::Result::FAILED_TO_STAGE;
382 result->error_msg = e.what();
383 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
384 result->error_code = DockRobot::Result::FAILED_TO_DETECT_DOCK;
386 result->error_msg = e.what();
387 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
388 result->error_code = DockRobot::Result::FAILED_TO_CONTROL;
390 result->error_msg = e.what();
391 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
392 result->error_code = DockRobot::Result::FAILED_TO_CHARGE;
394 result->error_msg = e.what();
395 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
396 result->error_code = DockRobot::Result::UNKNOWN;
397 }
catch (std::exception & e) {
398 result->error_code = DockRobot::Result::UNKNOWN;
399 result->error_msg = e.what();
400 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
405 result->num_retries = num_retries_;
407 dock->plugin->stopDetectionProcess();
408 docking_action_server_->terminate_current(result);
413 if (dock && successful) {
414 curr_dock_type_ = dock->type;
417 if (!use_dock_id && dock) {
425 auto dock =
new Dock();
426 dock->frame = goal->dock_pose.header.frame_id;
427 dock->pose = goal->dock_pose.pose;
428 dock->type = goal->dock_type;
429 dock->plugin = dock_db_->findDockPlugin(dock->type);
437 if (!dock->plugin->startDetectionProcess()) {
441 rclcpp::Rate loop_rate(controller_frequency_);
442 auto start = this->now();
443 auto timeout = rclcpp::Duration::from_seconds(initial_perception_timeout_);
444 while (!dock->plugin->getRefinedPose(dock_pose, dock->id)) {
445 if (this->now() - start > timeout) {
447 "Failed initial dock detection: Timeout exceeded");
450 if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_,
"dock_robot") ||
451 checkAndWarnIfPreempted<DockRobot>(docking_action_server_,
"dock_robot"))
462 const double dt = 1.0 / controller_frequency_;
463 auto target_pose = dock_pose;
464 target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
465 tf2::getYaw(target_pose.pose.orientation) + M_PI);
467 rclcpp::Rate loop_rate(controller_frequency_);
468 auto start = this->now();
469 auto timeout = rclcpp::Duration::from_seconds(rotate_to_dock_timeout_);
471 while (rclcpp::ok()) {
473 auto angular_distance_to_heading = angles::shortest_angular_distance(
474 tf2::getYaw(robot_pose.pose.orientation), tf2::getYaw(target_pose.pose.orientation));
475 if (fabs(angular_distance_to_heading) < rotation_angular_tolerance_) {
479 auto current_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
480 current_vel->twist.angular.z = odom_sub_->getRawTwist().angular.z;
482 auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
483 command->header = robot_pose.header;
484 command->twist = controller_->computeRotateToHeadingCommand(
485 angular_distance_to_heading, current_vel->twist, dt);
487 vel_publisher_->publish(std::move(command));
489 if (this->now() - start > timeout) {
498 Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose,
bool backward)
500 rclcpp::Rate loop_rate(controller_frequency_);
501 auto start = this->now();
502 auto timeout = rclcpp::Duration::from_seconds(dock_approach_timeout_);
504 while (rclcpp::ok()) {
508 if (dock->plugin->isDocked() || (dock->plugin->isCharger() && dock->plugin->isCharging())) {
513 if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_,
"dock_robot") ||
514 checkAndWarnIfPreempted<DockRobot>(docking_action_server_,
"dock_robot"))
520 if (!dock->plugin->getRefinedPose(dock_pose, dock->id) && !dock->plugin->shouldRotateToDock()) {
525 geometry_msgs::msg::PoseStamped target_pose = dock_pose;
526 target_pose.header.stamp = rclcpp::Time(0);
532 const double backward_projection = 0.25;
533 const double yaw = tf2::getYaw(target_pose.pose.orientation);
534 target_pose.pose.position.x += cos(yaw) * backward_projection;
535 target_pose.pose.position.y += sin(yaw) * backward_projection;
536 tf2_buffer_->transform(target_pose, target_pose, base_frame_);
541 target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
542 tf2::getYaw(target_pose.pose.orientation) + M_PI);
546 auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
547 command->header.stamp = now();
548 if (!controller_->computeVelocityCommand(target_pose.pose, command->twist,
true, backward)) {
551 vel_publisher_->publish(std::move(command));
553 if (this->now() - start > timeout) {
555 "Timed out approaching dock; dock nor charging (if applicable) detected");
566 if (!dock->plugin->isCharger()) {
570 rclcpp::Rate loop_rate(controller_frequency_);
571 auto start = this->now();
572 auto timeout = rclcpp::Duration::from_seconds(wait_charge_timeout_);
573 while (rclcpp::ok()) {
576 if (dock->plugin->isCharging()) {
580 if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_,
"dock_robot") ||
581 checkAndWarnIfPreempted<DockRobot>(docking_action_server_,
"dock_robot"))
586 if (this->now() - start > timeout) {
596 const geometry_msgs::msg::PoseStamped & staging_pose,
bool backward)
598 rclcpp::Rate loop_rate(controller_frequency_);
599 auto start = this->now();
600 auto timeout = rclcpp::Duration::from_seconds(dock_approach_timeout_);
601 while (rclcpp::ok()) {
605 if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_,
"dock_robot") ||
606 checkAndWarnIfPreempted<DockRobot>(docking_action_server_,
"dock_robot"))
612 auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
613 command->header.stamp = now();
615 command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_,
false,
620 vel_publisher_->publish(std::move(command));
622 if (this->now() - start > timeout) {
632 geometry_msgs::msg::Twist & cmd,
const geometry_msgs::msg::PoseStamped & pose,
633 double linear_tolerance,
double angular_tolerance,
bool is_docking,
bool backward)
641 const double dist = std::hypot(
642 robot_pose.pose.position.x - pose.pose.position.x,
643 robot_pose.pose.position.y - pose.pose.position.y);
644 const double yaw = angles::shortest_angular_distance(
645 tf2::getYaw(robot_pose.pose.orientation), tf2::getYaw(pose.pose.orientation));
646 if (dist < linear_tolerance && abs(yaw) < angular_tolerance) {
651 geometry_msgs::msg::PoseStamped target_pose = pose;
652 target_pose.header.stamp = rclcpp::Time(0);
653 tf2_buffer_->transform(target_pose, target_pose, base_frame_);
656 if (!controller_->computeVelocityCommand(target_pose.pose, cmd, is_docking, backward)) {
666 std::lock_guard<std::mutex> lock(*mutex_);
667 action_start_time_ = this->now();
668 rclcpp::Rate loop_rate(controller_frequency_);
670 auto goal = undocking_action_server_->get_current_goal();
671 auto result = std::make_shared<UndockRobot::Result>();
672 result->success =
false;
674 if (!undocking_action_server_ || !undocking_action_server_->is_server_active()) {
675 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
679 if (checkAndWarnIfCancelled<UndockRobot>(undocking_action_server_,
"undock_robot")) {
680 undocking_action_server_->terminate_all(result);
684 getPreemptedGoalIfRequested<UndockRobot>(goal, undocking_action_server_);
685 auto max_duration = rclcpp::Duration::from_seconds(goal->max_undocking_time);
689 std::string dock_type = curr_dock_type_;
690 if (!goal->dock_type.empty()) {
691 dock_type = goal->dock_type;
694 ChargingDock::Ptr dock = dock_db_->findDockPlugin(dock_type);
700 "Attempting to undock robot of dock type %s.", dock->getName().c_str());
703 if (dock->isCharger() && (!dock->isDocked() && !dock->isCharging())) {
704 RCLCPP_INFO(get_logger(),
"Robot is not in the dock, no need to undock");
708 bool dock_backward = dock_backwards_.has_value() ?
709 dock_backwards_.value() :
710 (dock->getDockDirection() == opennav_docking_core::DockDirection::BACKWARD);
717 dock_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
718 tf2::getYaw(dock_pose.pose.orientation) + M_PI);
722 geometry_msgs::msg::PoseStamped staging_pose =
723 dock->getStagingPose(dock_pose.pose, dock_pose.header.frame_id);
727 if (dock->shouldRotateToDock()) {
728 staging_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
729 tf2::getYaw(staging_pose.pose.orientation) + M_PI);
733 rclcpp::Time loop_start = this->now();
734 while (rclcpp::ok()) {
736 auto timeout = rclcpp::Duration::from_seconds(goal->max_undocking_time);
737 if (this->now() - loop_start > timeout) {
742 if (checkAndWarnIfCancelled<UndockRobot>(undocking_action_server_,
"undock_robot") ||
743 checkAndWarnIfPreempted<UndockRobot>(undocking_action_server_,
"undock_robot"))
746 undocking_action_server_->terminate_all(result);
751 if (dock->isCharger() && !dock->disableCharging()) {
757 auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
758 command->header.stamp = now();
761 command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_,
false,
765 if (dock->shouldRotateToDock()) {
770 RCLCPP_INFO(get_logger(),
"Robot has reached staging pose");
771 vel_publisher_->publish(std::move(command));
772 if (!dock->isCharger() || dock->hasStoppedCharging()) {
773 RCLCPP_INFO(get_logger(),
"Robot has undocked!");
774 result->success =
true;
775 curr_dock_type_.clear();
777 undocking_action_server_->succeeded_current(result);
785 vel_publisher_->publish(std::move(command));
788 }
catch (
const tf2::TransformException & e) {
789 result->error_msg = std::string(
"Transform error: ") + e.what();
790 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
791 result->error_code = DockRobot::Result::UNKNOWN;
793 result->error_msg = e.what();
794 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
795 result->error_code = DockRobot::Result::DOCK_NOT_VALID;
797 result->error_msg = e.what();
798 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
799 result->error_code = DockRobot::Result::FAILED_TO_CONTROL;
801 result->error_msg = e.what();
802 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
803 result->error_code = DockRobot::Result::UNKNOWN;
804 }
catch (std::exception & e) {
805 result->error_msg = std::string(
"Internal error: ") + e.what();
806 RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
807 result->error_code = DockRobot::Result::UNKNOWN;
811 undocking_action_server_->terminate_current(result);
816 geometry_msgs::msg::PoseStamped robot_pose;
817 robot_pose.header.frame_id = base_frame_;
818 robot_pose.header.stamp = rclcpp::Time(0);
819 tf2_buffer_->transform(robot_pose, robot_pose, frame);
825 auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
826 cmd_vel->header.stamp = now();
827 vel_publisher_->publish(std::move(cmd_vel));
832 auto feedback = std::make_shared<DockRobot::Feedback>();
833 feedback->state = state;
834 feedback->docking_time = this->now() - action_start_time_;
835 feedback->num_retries = num_retries_;
836 docking_action_server_->publish_feedback(feedback);
839 rcl_interfaces::msg::SetParametersResult
842 std::lock_guard<std::mutex> lock(*mutex_);
844 rcl_interfaces::msg::SetParametersResult result;
845 for (
auto parameter : parameters) {
846 const auto & param_type = parameter.get_type();
847 const auto & param_name = parameter.get_name();
848 if (param_name.find(
'.') != std::string::npos) {
852 if (param_type == ParameterType::PARAMETER_DOUBLE) {
853 if (param_name ==
"controller_frequency") {
854 controller_frequency_ = parameter.as_double();
855 }
else if (param_name ==
"initial_perception_timeout") {
856 initial_perception_timeout_ = parameter.as_double();
857 }
else if (param_name ==
"wait_charge_timeout") {
858 wait_charge_timeout_ = parameter.as_double();
859 }
else if (param_name ==
"undock_linear_tolerance") {
860 undock_linear_tolerance_ = parameter.as_double();
861 }
else if (param_name ==
"undock_angular_tolerance") {
862 undock_angular_tolerance_ = parameter.as_double();
863 }
else if (param_name ==
"rotation_angular_tolerance") {
864 rotation_angular_tolerance_ = parameter.as_double();
866 }
else if (param_type == ParameterType::PARAMETER_STRING) {
867 if (param_name ==
"base_frame") {
868 base_frame_ = parameter.as_string();
869 }
else if (param_name ==
"fixed_frame") {
870 fixed_frame_ = parameter.as_string();
872 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
873 if (param_name ==
"max_retries") {
874 max_retries_ = parameter.as_int();
879 result.successful =
true;
885 #include "rclcpp_components/register_node_macro.hpp"
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
bool is_cancel_requested() const
Whether or not a cancel command has come in.
bool is_preempt_requested() const
Whether the action server has been asked to be preempted with a new goal.
const std::shared_ptr< const typename ActionT::Goal > accept_pending_goal()
Accept pending goals.
An action server which implements charger docking node for AMRs.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual geometry_msgs::msg::PoseStamped getRobotPoseInFrame(const std::string &frame)
Get the robot pose (aka base_frame pose) in another frame.
bool resetApproach(const geometry_msgs::msg::PoseStamped &staging_pose, bool backward)
Reset the robot for another approach by controlling back to staging pose.
void dockRobot()
Main action callback method to complete docking request.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
bool approachDock(Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose, bool backward)
Use control law and dock perception to approach the charge dock.
void doInitialPerception(Dock *dock, geometry_msgs::msg::PoseStamped &dock_pose)
Do initial perception, up to a timeout.
void publishDockingFeedback(uint16_t state)
Publish feedback from a docking action.
bool checkAndWarnIfCancelled(typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server, const std::string &name)
Checks and logs warning if action canceled.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
bool checkAndWarnIfPreempted(typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server, const std::string &name)
Checks and logs warning if action preempted.
bool getCommandToPose(geometry_msgs::msg::Twist &cmd, const geometry_msgs::msg::PoseStamped &pose, double linear_tolerance, double angular_tolerance, bool is_docking, bool backward)
Run a single iteration of the control loop to approach a pose.
bool waitForCharge(Dock *dock)
Wait for charging to begin.
Dock * generateGoalDock(std::shared_ptr< const DockRobot::Goal > goal)
Generate a dock from action goal.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
void getPreemptedGoalIfRequested(typename std::shared_ptr< const typename ActionT::Goal > goal, const typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server)
Gets a preempted goal if immediately requested.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables.
void publishZeroVelocity()
Publish zero velocity at terminal condition.
void rotateToDock(const geometry_msgs::msg::PoseStamped &dock_pose)
Perform a pure rotation to dock orientation.
void undockRobot()
Main action callback method to complete undocking request.
void stashDockData(bool use_dock_id, Dock *dock, bool successful)
Called at the conclusion of docking actions. Saves relevant docking data for later undocking action.
Dock was not found in the provided dock database.
Dock plugin provided in the database or action was invalid.
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.