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