18 #include "nav2_ros_common/node_utils.hpp"
19 #include "opennav_docking/simple_non_charging_dock.hpp"
20 #include "opennav_docking/utils.hpp"
22 using namespace std::chrono_literals;
24 namespace opennav_docking
27 void SimpleNonChargingDock::configure(
28 const nav2::LifecycleNode::WeakPtr & parent,
29 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf)
33 node_ = parent.lock();
35 throw std::runtime_error{
"Failed to lock node"};
39 nav2::declare_parameter_if_not_declared(
40 node_, name +
".use_external_detection_pose", rclcpp::ParameterValue(
false));
41 nav2::declare_parameter_if_not_declared(
42 node_, name +
".external_detection_timeout", rclcpp::ParameterValue(1.0));
43 nav2::declare_parameter_if_not_declared(
44 node_, name +
".external_detection_translation_x", rclcpp::ParameterValue(-0.20));
45 nav2::declare_parameter_if_not_declared(
46 node_, name +
".external_detection_translation_y", rclcpp::ParameterValue(0.0));
47 nav2::declare_parameter_if_not_declared(
48 node_, name +
".external_detection_rotation_yaw", rclcpp::ParameterValue(0.0));
49 nav2::declare_parameter_if_not_declared(
50 node_, name +
".external_detection_rotation_pitch", rclcpp::ParameterValue(1.57));
51 nav2::declare_parameter_if_not_declared(
52 node_, name +
".external_detection_rotation_roll", rclcpp::ParameterValue(-1.57));
53 nav2::declare_parameter_if_not_declared(
54 node_, name +
".filter_coef", rclcpp::ParameterValue(0.1));
57 nav2::declare_parameter_if_not_declared(
58 node_, name +
".detector_service_name", rclcpp::ParameterValue(
""));
59 nav2::declare_parameter_if_not_declared(
60 node_, name +
".detector_service_timeout", rclcpp::ParameterValue(5.0));
61 nav2::declare_parameter_if_not_declared(
62 node_, name +
".subscribe_toggle", rclcpp::ParameterValue(
false));
65 nav2::declare_parameter_if_not_declared(
66 node_, name +
".use_stall_detection", rclcpp::ParameterValue(
false));
67 nav2::declare_parameter_if_not_declared(
68 node_, name +
".stall_joint_names", rclcpp::PARAMETER_STRING_ARRAY);
69 nav2::declare_parameter_if_not_declared(
70 node_, name +
".stall_velocity_threshold", rclcpp::ParameterValue(1.0));
71 nav2::declare_parameter_if_not_declared(
72 node_, name +
".stall_effort_threshold", rclcpp::ParameterValue(1.0));
75 nav2::declare_parameter_if_not_declared(
76 node_, name +
".docking_threshold", rclcpp::ParameterValue(0.05));
79 nav2::declare_parameter_if_not_declared(
80 node_, name +
".staging_x_offset", rclcpp::ParameterValue(-0.7));
81 nav2::declare_parameter_if_not_declared(
82 node_, name +
".staging_yaw_offset", rclcpp::ParameterValue(0.0));
85 nav2::declare_parameter_if_not_declared(
86 node_, name +
".dock_direction", rclcpp::ParameterValue(std::string(
"forward")));
87 nav2::declare_parameter_if_not_declared(
88 node_, name +
".rotate_to_dock", rclcpp::ParameterValue(
false));
90 node_->get_parameter(name +
".use_external_detection_pose", use_external_detection_pose_);
91 node_->get_parameter(name +
".external_detection_timeout", external_detection_timeout_);
93 name +
".external_detection_translation_x", external_detection_translation_x_);
95 name +
".external_detection_translation_y", external_detection_translation_y_);
96 double yaw, pitch, roll;
97 node_->get_parameter(name +
".external_detection_rotation_yaw", yaw);
98 node_->get_parameter(name +
".external_detection_rotation_pitch", pitch);
99 node_->get_parameter(name +
".external_detection_rotation_roll", roll);
100 external_detection_rotation_.setEuler(pitch, roll, yaw);
101 node_->get_parameter(name +
".stall_velocity_threshold", stall_velocity_threshold_);
102 node_->get_parameter(name +
".stall_effort_threshold", stall_effort_threshold_);
103 node_->get_parameter(name +
".docking_threshold", docking_threshold_);
104 node_->get_parameter(
"base_frame", base_frame_id_);
105 node_->get_parameter(name +
".staging_x_offset", staging_x_offset_);
106 node_->get_parameter(name +
".staging_yaw_offset", staging_yaw_offset_);
108 node_->get_parameter(name +
".detector_service_name", detector_service_name_);
109 node_->get_parameter(name +
".detector_service_timeout", detector_service_timeout_);
110 node_->get_parameter(name +
".subscribe_toggle", subscribe_toggle_);
113 detection_active_ =
false;
114 initial_pose_received_ =
false;
117 if (use_external_detection_pose_ && !subscribe_toggle_) {
118 dock_pose_.header.stamp = rclcpp::Time(0);
119 dock_pose_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
120 "detected_dock_pose",
121 [
this](
const geometry_msgs::msg::PoseStamped::SharedPtr pose) {
122 detected_dock_pose_ = *pose;
123 initial_pose_received_ =
true;
128 std::string dock_direction;
129 node_->get_parameter(name +
".dock_direction", dock_direction);
130 dock_direction_ = utils::getDockDirectionFromString(dock_direction);
131 if (dock_direction_ == opennav_docking_core::DockDirection::UNKNOWN) {
132 throw std::runtime_error{
"Dock direction is not valid. Valid options are: forward or backward"};
135 node_->get_parameter(name +
".rotate_to_dock", rotate_to_dock_);
136 if (rotate_to_dock_ && dock_direction_ != opennav_docking_core::DockDirection::BACKWARD) {
137 throw std::runtime_error{
"Parameter rotate_to_dock is enabled but dock direction is not "
138 "backward. Please set dock direction to backward."};
143 node_->get_parameter(name +
".filter_coef", filter_coef);
144 filter_ = std::make_unique<PoseFilter>(filter_coef, external_detection_timeout_);
146 if (!detector_service_name_.empty()) {
147 detector_client_ = node_->create_client<std_srvs::srv::Trigger>(
148 detector_service_name_,
false);
151 bool use_stall_detection;
152 node_->get_parameter(name +
".use_stall_detection", use_stall_detection);
153 if (use_stall_detection) {
155 node_->get_parameter(name +
".stall_joint_names", stall_joint_names_);
156 if (stall_joint_names_.size() < 1) {
157 RCLCPP_ERROR(node_->get_logger(),
"stall_joint_names cannot be empty!");
159 joint_state_sub_ = node_->create_subscription<sensor_msgs::msg::JointState>(
161 std::bind(&SimpleNonChargingDock::jointStateCallback,
this, std::placeholders::_1),
165 dock_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>(
"dock_pose");
166 filtered_dock_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>(
167 "filtered_dock_pose");
168 staging_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>(
"staging_pose");
171 geometry_msgs::msg::PoseStamped SimpleNonChargingDock::getStagingPose(
172 const geometry_msgs::msg::Pose & pose,
const std::string & frame)
175 if (!use_external_detection_pose_) {
178 dock_pose_.header.frame_id = frame;
179 dock_pose_.pose = pose;
183 const double yaw = tf2::getYaw(pose.orientation);
184 geometry_msgs::msg::PoseStamped staging_pose;
185 staging_pose.header.frame_id = frame;
186 staging_pose.header.stamp = node_->now();
187 staging_pose.pose = pose;
188 staging_pose.pose.position.x += cos(yaw) * staging_x_offset_;
189 staging_pose.pose.position.y += sin(yaw) * staging_x_offset_;
190 tf2::Quaternion orientation;
191 orientation.setEuler(0.0, 0.0, yaw + staging_yaw_offset_);
192 staging_pose.pose.orientation = tf2::toMsg(orientation);
195 staging_pose_pub_->publish(staging_pose);
199 bool SimpleNonChargingDock::getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string)
202 if (!use_external_detection_pose_) {
203 dock_pose_pub_->publish(pose);
209 if (!initial_pose_received_) {
210 RCLCPP_WARN(node_->get_logger(),
"Waiting for first detected_dock_pose; none received yet");
215 geometry_msgs::msg::PoseStamped detected = detected_dock_pose_;
218 auto timeout = rclcpp::Duration::from_seconds(external_detection_timeout_);
219 if (node_->now() - detected.header.stamp > timeout) {
220 RCLCPP_WARN(node_->get_logger(),
"Lost detection or did not detect: timeout exceeded");
227 if (detected.header.frame_id != pose.header.frame_id) {
229 if (!tf2_buffer_->canTransform(
230 pose.header.frame_id, detected.header.frame_id,
231 detected.header.stamp, rclcpp::Duration::from_seconds(0.2)))
233 RCLCPP_WARN(node_->get_logger(),
"Failed to transform detected dock pose");
236 tf2_buffer_->transform(detected, detected, pose.header.frame_id);
237 }
catch (
const tf2::TransformException & ex) {
238 RCLCPP_WARN(node_->get_logger(),
"Failed to transform detected dock pose");
244 detected = filter_->update(detected);
245 filtered_dock_pose_pub_->publish(detected);
248 geometry_msgs::msg::PoseStamped just_orientation;
249 just_orientation.pose.orientation = tf2::toMsg(external_detection_rotation_);
250 geometry_msgs::msg::TransformStamped transform;
251 transform.transform.rotation = detected.pose.orientation;
252 tf2::doTransform(just_orientation, just_orientation, transform);
254 tf2::Quaternion orientation;
255 orientation.setEuler(0.0, 0.0, tf2::getYaw(just_orientation.pose.orientation));
256 dock_pose_.pose.orientation = tf2::toMsg(orientation);
259 dock_pose_.header = detected.header;
260 dock_pose_.pose.position = detected.pose.position;
261 const double yaw = tf2::getYaw(dock_pose_.pose.orientation);
262 dock_pose_.pose.position.x += cos(yaw) * external_detection_translation_x_ -
263 sin(yaw) * external_detection_translation_y_;
264 dock_pose_.pose.position.y += sin(yaw) * external_detection_translation_x_ +
265 cos(yaw) * external_detection_translation_y_;
266 dock_pose_.pose.position.z = 0.0;
269 dock_pose_pub_->publish(dock_pose_);
274 bool SimpleNonChargingDock::isDocked()
276 if (joint_state_sub_) {
281 if (dock_pose_.header.frame_id.empty()) {
287 geometry_msgs::msg::PoseStamped base_pose;
288 base_pose.header.stamp = rclcpp::Time(0);
289 base_pose.header.frame_id = base_frame_id_;
290 base_pose.pose.orientation.w = 1.0;
292 tf2_buffer_->transform(base_pose, base_pose, dock_pose_.header.frame_id);
293 }
catch (
const tf2::TransformException & ex) {
298 double d = std::hypot(
299 base_pose.pose.position.x - dock_pose_.pose.position.x,
300 base_pose.pose.position.y - dock_pose_.pose.position.y);
301 return d < docking_threshold_;
304 void SimpleNonChargingDock::jointStateCallback(
const sensor_msgs::msg::JointState::SharedPtr state)
306 double velocity = 0.0;
308 for (
size_t i = 0; i < state->name.size(); ++i) {
309 for (
auto & name : stall_joint_names_) {
310 if (state->name[i] == name) {
312 velocity += abs(state->velocity[i]);
313 effort += abs(state->effort[i]);
319 effort /= stall_joint_names_.size();
320 velocity /= stall_joint_names_.size();
322 is_stalled_ = (velocity < stall_velocity_threshold_) && (effort > stall_effort_threshold_);
325 bool SimpleNonChargingDock::startDetectionProcess()
328 if (detection_active_) {
333 if (detector_client_) {
334 auto req = std::make_shared<std_srvs::srv::Trigger::Request>();
336 auto future = detector_client_->invoke(
338 std::chrono::duration_cast<std::chrono::nanoseconds>(
339 std::chrono::duration<double>(detector_service_timeout_)));
341 if (!future || !future->success) {
343 node_->get_logger(),
"Detector service '%s' failed to start.",
344 detector_service_name_.c_str());
347 }
catch (
const std::exception & e) {
349 node_->get_logger(),
"Calling detector service '%s' failed: %s",
350 detector_service_name_.c_str(), e.what());
357 if (subscribe_toggle_ && !dock_pose_sub_) {
358 dock_pose_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
359 "detected_dock_pose",
360 [
this](
const geometry_msgs::msg::PoseStamped::SharedPtr pose) {
361 detected_dock_pose_ = *pose;
362 initial_pose_received_ =
true;
367 detection_active_ =
true;
368 RCLCPP_INFO(node_->get_logger(),
"External detector activation requested.");
372 bool SimpleNonChargingDock::stopDetectionProcess()
375 if (!detection_active_) {
380 if (detector_client_) {
381 auto req = std::make_shared<std_srvs::srv::Trigger::Request>();
383 auto future = detector_client_->invoke(
385 std::chrono::duration_cast<std::chrono::nanoseconds>(
386 std::chrono::duration<double>(detector_service_timeout_)));
388 if (!future || !future->success) {
390 node_->get_logger(),
"Detector service '%s' failed to stop.",
391 detector_service_name_.c_str());
394 }
catch (
const std::exception & e) {
396 node_->get_logger(),
"Calling detector service '%s' failed: %s",
397 detector_service_name_.c_str(), e.what());
404 if (subscribe_toggle_ && dock_pose_sub_) {
405 dock_pose_sub_.reset();
408 detection_active_ =
false;
409 initial_pose_received_ =
false;
410 RCLCPP_INFO(node_->get_logger(),
"External detector deactivation requested.");
414 void SimpleNonChargingDock::activate()
416 dock_pose_pub_->on_activate();
417 filtered_dock_pose_pub_->on_activate();
418 staging_pose_pub_->on_activate();
421 void SimpleNonChargingDock::deactivate()
423 stopDetectionProcess();
424 dock_pose_pub_->on_deactivate();
425 filtered_dock_pose_pub_->on_deactivate();
426 staging_pose_pub_->on_deactivate();
427 RCLCPP_DEBUG(node_->get_logger(),
"SimpleNonChargingDock deactivated");
430 void SimpleNonChargingDock::cleanup()
432 detector_client_.reset();
433 dock_pose_sub_.reset();
434 detection_active_ =
false;
435 initial_pose_received_ =
false;
436 RCLCPP_DEBUG(node_->get_logger(),
"SimpleNonChargingDock cleaned up");
441 #include "pluginlib/class_list_macros.hpp"
A QoS profile for standard reliable topics with a history of 10 messages.
Abstract interface for a charging dock for the docking framework.