Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
simple_charging_dock.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 <cmath>
16 
17 #include "nav2_util/node_utils.hpp"
18 #include "opennav_docking/simple_charging_dock.hpp"
19 
20 namespace opennav_docking
21 {
22 
24  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
25  const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf)
26 {
27  name_ = name;
28  tf2_buffer_ = tf;
29  is_charging_ = false;
30  node_ = parent.lock();
31  if (!node_) {
32  throw std::runtime_error{"Failed to lock node"};
33  }
34 
35  // Optionally use battery info to check when charging, else say charging if docked
36  nav2_util::declare_parameter_if_not_declared(
37  node_, name + ".use_battery_status", rclcpp::ParameterValue(true));
38 
39  // Parameters for optional external detection of dock pose
40  nav2_util::declare_parameter_if_not_declared(
41  node_, name + ".use_external_detection_pose", rclcpp::ParameterValue(false));
42  nav2_util::declare_parameter_if_not_declared(
43  node_, name + ".external_detection_timeout", rclcpp::ParameterValue(1.0));
44  nav2_util::declare_parameter_if_not_declared(
45  node_, name + ".external_detection_translation_x", rclcpp::ParameterValue(-0.20));
46  nav2_util::declare_parameter_if_not_declared(
47  node_, name + ".external_detection_translation_y", rclcpp::ParameterValue(0.0));
48  nav2_util::declare_parameter_if_not_declared(
49  node_, name + ".external_detection_rotation_yaw", rclcpp::ParameterValue(0.0));
50  nav2_util::declare_parameter_if_not_declared(
51  node_, name + ".external_detection_rotation_pitch", rclcpp::ParameterValue(1.57));
52  nav2_util::declare_parameter_if_not_declared(
53  node_, name + ".external_detection_rotation_roll", rclcpp::ParameterValue(-1.57));
54  nav2_util::declare_parameter_if_not_declared(
55  node_, name + ".filter_coef", rclcpp::ParameterValue(0.1));
56 
57  // Charging threshold from BatteryState message
58  nav2_util::declare_parameter_if_not_declared(
59  node_, name + ".charging_threshold", rclcpp::ParameterValue(0.5));
60 
61  // Optionally determine if docked via stall detection using joint_states
62  nav2_util::declare_parameter_if_not_declared(
63  node_, name + ".use_stall_detection", rclcpp::ParameterValue(false));
64  nav2_util::declare_parameter_if_not_declared(
65  node_, name + ".stall_joint_names", rclcpp::PARAMETER_STRING_ARRAY);
66  nav2_util::declare_parameter_if_not_declared(
67  node_, name + ".stall_velocity_threshold", rclcpp::ParameterValue(1.0));
68  nav2_util::declare_parameter_if_not_declared(
69  node_, name + ".stall_effort_threshold", rclcpp::ParameterValue(1.0));
70 
71  // If not using stall detection, this is how close robot should get to pose
72  nav2_util::declare_parameter_if_not_declared(
73  node_, name + ".docking_threshold", rclcpp::ParameterValue(0.05));
74 
75  // Staging pose configuration
76  nav2_util::declare_parameter_if_not_declared(
77  node_, name + ".staging_x_offset", rclcpp::ParameterValue(-0.7));
78  nav2_util::declare_parameter_if_not_declared(
79  node_, name + ".staging_yaw_offset", rclcpp::ParameterValue(0.0));
80 
81  node_->get_parameter(name + ".use_battery_status", use_battery_status_);
82  node_->get_parameter(name + ".use_external_detection_pose", use_external_detection_pose_);
83  node_->get_parameter(name + ".external_detection_timeout", external_detection_timeout_);
84  node_->get_parameter(
85  name + ".external_detection_translation_x", external_detection_translation_x_);
86  node_->get_parameter(
87  name + ".external_detection_translation_y", external_detection_translation_y_);
88  double yaw, pitch, roll;
89  node_->get_parameter(name + ".external_detection_rotation_yaw", yaw);
90  node_->get_parameter(name + ".external_detection_rotation_pitch", pitch);
91  node_->get_parameter(name + ".external_detection_rotation_roll", roll);
92  external_detection_rotation_.setEuler(pitch, roll, yaw);
93  node_->get_parameter(name + ".charging_threshold", charging_threshold_);
94  node_->get_parameter(name + ".stall_velocity_threshold", stall_velocity_threshold_);
95  node_->get_parameter(name + ".stall_effort_threshold", stall_effort_threshold_);
96  node_->get_parameter(name + ".docking_threshold", docking_threshold_);
97  node_->get_parameter("base_frame", base_frame_id_); // Get server base frame ID
98  node_->get_parameter(name + ".staging_x_offset", staging_x_offset_);
99  node_->get_parameter(name + ".staging_yaw_offset", staging_yaw_offset_);
100 
101  // Setup filter
102  double filter_coef;
103  node_->get_parameter(name + ".filter_coef", filter_coef);
104  filter_ = std::make_unique<PoseFilter>(filter_coef, external_detection_timeout_);
105 
106  if (use_battery_status_) {
107  battery_sub_ = node_->create_subscription<sensor_msgs::msg::BatteryState>(
108  "battery_state", 1,
109  [this](const sensor_msgs::msg::BatteryState::SharedPtr state) {
110  is_charging_ = state->current > charging_threshold_;
111  });
112  }
113 
114  if (use_external_detection_pose_) {
115  dock_pose_.header.stamp = rclcpp::Time(0);
116  dock_pose_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
117  "detected_dock_pose", 1,
118  [this](const geometry_msgs::msg::PoseStamped::SharedPtr pose) {
119  detected_dock_pose_ = *pose;
120  });
121  }
122 
123  bool use_stall_detection;
124  node_->get_parameter(name + ".use_stall_detection", use_stall_detection);
125  if (use_stall_detection) {
126  is_stalled_ = false;
127  node_->get_parameter(name + ".stall_joint_names", stall_joint_names_);
128  if (stall_joint_names_.size() < 1) {
129  RCLCPP_ERROR(node_->get_logger(), "stall_joint_names cannot be empty!");
130  }
131  joint_state_sub_ = node_->create_subscription<sensor_msgs::msg::JointState>(
132  "joint_states", 1,
133  std::bind(&SimpleChargingDock::jointStateCallback, this, std::placeholders::_1));
134  }
135 
136  dock_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>("dock_pose", 1);
137  filtered_dock_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>(
138  "filtered_dock_pose", 1);
139  staging_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>("staging_pose", 1);
140 }
141 
142 geometry_msgs::msg::PoseStamped SimpleChargingDock::getStagingPose(
143  const geometry_msgs::msg::Pose & pose, const std::string & frame)
144 {
145  // If not using detection, set the dock pose as the given dock pose estimate
146  if (!use_external_detection_pose_) {
147  // This gets called at the start of docking
148  // Reset our internally tracked dock pose
149  dock_pose_.header.frame_id = frame;
150  dock_pose_.pose = pose;
151  }
152 
153  // Compute the staging pose with given offsets
154  const double yaw = tf2::getYaw(pose.orientation);
155  geometry_msgs::msg::PoseStamped staging_pose;
156  staging_pose.header.frame_id = frame;
157  staging_pose.header.stamp = node_->now();
158  staging_pose.pose = pose;
159  staging_pose.pose.position.x += cos(yaw) * staging_x_offset_;
160  staging_pose.pose.position.y += sin(yaw) * staging_x_offset_;
161  tf2::Quaternion orientation;
162  orientation.setEuler(0.0, 0.0, yaw + staging_yaw_offset_);
163  staging_pose.pose.orientation = tf2::toMsg(orientation);
164 
165  // Publish staging pose for debugging purposes
166  staging_pose_pub_->publish(staging_pose);
167  return staging_pose;
168 }
169 
170 bool SimpleChargingDock::getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string /*id*/)
171 {
172  // If using not detection, set the dock pose to the static fixed-frame version
173  if (!use_external_detection_pose_) {
174  dock_pose_pub_->publish(pose);
175  dock_pose_ = pose;
176  return true;
177  }
178 
179  // If using detections, get current detections, transform to frame, and apply offsets
180  geometry_msgs::msg::PoseStamped detected = detected_dock_pose_;
181 
182  // Validate that external pose is new enough
183  auto timeout = rclcpp::Duration::from_seconds(external_detection_timeout_);
184  if (node_->now() - detected.header.stamp > timeout) {
185  RCLCPP_WARN(node_->get_logger(), "Lost detection or did not detect: timeout exceeded");
186  return false;
187  }
188 
189  // Transform detected pose into fixed frame. Note that the argument pose
190  // is the output of detection, but also acts as the initial estimate
191  // and contains the frame_id of docking
192  if (detected.header.frame_id != pose.header.frame_id) {
193  try {
194  if (!tf2_buffer_->canTransform(
195  pose.header.frame_id, detected.header.frame_id,
196  detected.header.stamp, rclcpp::Duration::from_seconds(0.2)))
197  {
198  RCLCPP_WARN(node_->get_logger(), "Failed to transform detected dock pose");
199  return false;
200  }
201  tf2_buffer_->transform(detected, detected, pose.header.frame_id);
202  } catch (const tf2::TransformException & ex) {
203  RCLCPP_WARN(node_->get_logger(), "Failed to transform detected dock pose");
204  return false;
205  }
206  }
207 
208  // Filter the detected pose
209  detected = filter_->update(detected);
210  filtered_dock_pose_pub_->publish(detected);
211 
212  // Rotate the just the orientation, then remove roll/pitch
213  geometry_msgs::msg::PoseStamped just_orientation;
214  just_orientation.pose.orientation = tf2::toMsg(external_detection_rotation_);
215  geometry_msgs::msg::TransformStamped transform;
216  transform.transform.rotation = detected.pose.orientation;
217  tf2::doTransform(just_orientation, just_orientation, transform);
218 
219  tf2::Quaternion orientation;
220  orientation.setEuler(0.0, 0.0, tf2::getYaw(just_orientation.pose.orientation));
221  dock_pose_.pose.orientation = tf2::toMsg(orientation);
222 
223  // Construct dock_pose_ by applying translation/rotation
224  dock_pose_.header = detected.header;
225  dock_pose_.pose.position = detected.pose.position;
226  const double yaw = tf2::getYaw(dock_pose_.pose.orientation);
227  dock_pose_.pose.position.x += cos(yaw) * external_detection_translation_x_ -
228  sin(yaw) * external_detection_translation_y_;
229  dock_pose_.pose.position.y += sin(yaw) * external_detection_translation_x_ +
230  cos(yaw) * external_detection_translation_y_;
231  dock_pose_.pose.position.z = 0.0;
232 
233  // Publish & return dock pose for debugging purposes
234  dock_pose_pub_->publish(dock_pose_);
235  pose = dock_pose_;
236  return true;
237 }
238 
240 {
241  if (joint_state_sub_) {
242  // Using stall detection
243  return is_stalled_;
244  }
245 
246  if (dock_pose_.header.frame_id.empty()) {
247  // Dock pose is not yet valid
248  return false;
249  }
250 
251  // Find base pose in target frame
252  geometry_msgs::msg::PoseStamped base_pose;
253  base_pose.header.stamp = rclcpp::Time(0);
254  base_pose.header.frame_id = base_frame_id_;
255  base_pose.pose.orientation.w = 1.0;
256  try {
257  tf2_buffer_->transform(base_pose, base_pose, dock_pose_.header.frame_id);
258  } catch (const tf2::TransformException & ex) {
259  return false;
260  }
261 
262  // If we are close enough, pretend we are charging
263  double d = std::hypot(
264  base_pose.pose.position.x - dock_pose_.pose.position.x,
265  base_pose.pose.position.y - dock_pose_.pose.position.y);
266  return d < docking_threshold_;
267 }
268 
270 {
271  return use_battery_status_ ? is_charging_ : isDocked();
272 }
273 
275 {
276  return true;
277 }
278 
280 {
281  return !isCharging();
282 }
283 
284 void SimpleChargingDock::jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state)
285 {
286  double velocity = 0.0;
287  double effort = 0.0;
288  for (size_t i = 0; i < state->name.size(); ++i) {
289  for (auto & name : stall_joint_names_) {
290  if (state->name[i] == name) {
291  // Tracking this joint
292  velocity += abs(state->velocity[i]);
293  effort += abs(state->effort[i]);
294  }
295  }
296  }
297 
298  // Take average
299  effort /= stall_joint_names_.size();
300  velocity /= stall_joint_names_.size();
301 
302  is_stalled_ = (velocity < stall_velocity_threshold_) && (effort > stall_effort_threshold_);
303 }
304 
305 } // namespace opennav_docking
306 
307 #include "pluginlib/class_list_macros.hpp"
virtual geometry_msgs::msg::PoseStamped getStagingPose(const geometry_msgs::msg::Pose &pose, const std::string &frame)
Method to obtain the dock's staging pose. This method should likely be using TF and the dock's pose i...
virtual bool disableCharging()
Undocking while current is still flowing can damage a charge dock so some charge docks provide the ab...
virtual bool isCharging()
Are we charging? If a charge dock requires any sort of negotiation to begin charging,...
virtual bool isDocked()
Have we made contact with dock? This can be implemented in a variety of ways: by establishing communi...
virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf)
virtual bool hasStoppedCharging()
Similar to isCharging() but called when undocking.
virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &pose, std::string id)
Method to obtain the refined pose of the dock, usually based on sensors.
Abstract interface for a charging dock for the docking framework.