Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
simple_non_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_non_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  node_ = parent.lock();
30  if (!node_) {
31  throw std::runtime_error{"Failed to lock node"};
32  }
33 
34  // Parameters for optional external detection of dock pose
35  nav2_util::declare_parameter_if_not_declared(
36  node_, name + ".use_external_detection_pose", rclcpp::ParameterValue(false));
37  nav2_util::declare_parameter_if_not_declared(
38  node_, name + ".external_detection_timeout", rclcpp::ParameterValue(1.0));
39  nav2_util::declare_parameter_if_not_declared(
40  node_, name + ".external_detection_translation_x", rclcpp::ParameterValue(-0.20));
41  nav2_util::declare_parameter_if_not_declared(
42  node_, name + ".external_detection_translation_y", rclcpp::ParameterValue(0.0));
43  nav2_util::declare_parameter_if_not_declared(
44  node_, name + ".external_detection_rotation_yaw", rclcpp::ParameterValue(0.0));
45  nav2_util::declare_parameter_if_not_declared(
46  node_, name + ".external_detection_rotation_pitch", rclcpp::ParameterValue(1.57));
47  nav2_util::declare_parameter_if_not_declared(
48  node_, name + ".external_detection_rotation_roll", rclcpp::ParameterValue(-1.57));
49  nav2_util::declare_parameter_if_not_declared(
50  node_, name + ".filter_coef", rclcpp::ParameterValue(0.1));
51 
52  // Optionally determine if docked via stall detection using joint_states
53  nav2_util::declare_parameter_if_not_declared(
54  node_, name + ".use_stall_detection", rclcpp::ParameterValue(false));
55  nav2_util::declare_parameter_if_not_declared(
56  node_, name + ".stall_joint_names", rclcpp::PARAMETER_STRING_ARRAY);
57  nav2_util::declare_parameter_if_not_declared(
58  node_, name + ".stall_velocity_threshold", rclcpp::ParameterValue(1.0));
59  nav2_util::declare_parameter_if_not_declared(
60  node_, name + ".stall_effort_threshold", rclcpp::ParameterValue(1.0));
61 
62  // If not using stall detection, this is how close robot should get to pose
63  nav2_util::declare_parameter_if_not_declared(
64  node_, name + ".docking_threshold", rclcpp::ParameterValue(0.05));
65 
66  // Staging pose configuration
67  nav2_util::declare_parameter_if_not_declared(
68  node_, name + ".staging_x_offset", rclcpp::ParameterValue(-0.7));
69  nav2_util::declare_parameter_if_not_declared(
70  node_, name + ".staging_yaw_offset", rclcpp::ParameterValue(0.0));
71 
72  node_->get_parameter(name + ".use_external_detection_pose", use_external_detection_pose_);
73  node_->get_parameter(name + ".external_detection_timeout", external_detection_timeout_);
74  node_->get_parameter(
75  name + ".external_detection_translation_x", external_detection_translation_x_);
76  node_->get_parameter(
77  name + ".external_detection_translation_y", external_detection_translation_y_);
78  double yaw, pitch, roll;
79  node_->get_parameter(name + ".external_detection_rotation_yaw", yaw);
80  node_->get_parameter(name + ".external_detection_rotation_pitch", pitch);
81  node_->get_parameter(name + ".external_detection_rotation_roll", roll);
82  external_detection_rotation_.setEuler(pitch, roll, yaw);
83  node_->get_parameter(name + ".stall_velocity_threshold", stall_velocity_threshold_);
84  node_->get_parameter(name + ".stall_effort_threshold", stall_effort_threshold_);
85  node_->get_parameter(name + ".docking_threshold", docking_threshold_);
86  node_->get_parameter("base_frame", base_frame_id_); // Get server base frame ID
87  node_->get_parameter(name + ".staging_x_offset", staging_x_offset_);
88  node_->get_parameter(name + ".staging_yaw_offset", staging_yaw_offset_);
89 
90  // Setup filter
91  double filter_coef;
92  node_->get_parameter(name + ".filter_coef", filter_coef);
93  filter_ = std::make_unique<PoseFilter>(filter_coef, external_detection_timeout_);
94 
95  if (use_external_detection_pose_) {
96  dock_pose_.header.stamp = rclcpp::Time(0);
97  dock_pose_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
98  "detected_dock_pose", 1,
99  [this](const geometry_msgs::msg::PoseStamped::SharedPtr pose) {
100  detected_dock_pose_ = *pose;
101  });
102  }
103 
104  bool use_stall_detection;
105  node_->get_parameter(name + ".use_stall_detection", use_stall_detection);
106  if (use_stall_detection) {
107  is_stalled_ = false;
108  node_->get_parameter(name + ".stall_joint_names", stall_joint_names_);
109  if (stall_joint_names_.size() < 1) {
110  RCLCPP_ERROR(node_->get_logger(), "stall_joint_names cannot be empty!");
111  }
112  joint_state_sub_ = node_->create_subscription<sensor_msgs::msg::JointState>(
113  "joint_states", 1,
114  std::bind(&SimpleNonChargingDock::jointStateCallback, this, std::placeholders::_1));
115  }
116 
117  dock_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>("dock_pose", 1);
118  filtered_dock_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>(
119  "filtered_dock_pose", 1);
120  staging_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>("staging_pose", 1);
121 }
122 
123 geometry_msgs::msg::PoseStamped SimpleNonChargingDock::getStagingPose(
124  const geometry_msgs::msg::Pose & pose, const std::string & frame)
125 {
126  // If not using detection, set the dock pose as the given dock pose estimate
127  if (!use_external_detection_pose_) {
128  // This gets called at the start of docking
129  // Reset our internally tracked dock pose
130  dock_pose_.header.frame_id = frame;
131  dock_pose_.pose = pose;
132  }
133 
134  // Compute the staging pose with given offsets
135  const double yaw = tf2::getYaw(pose.orientation);
136  geometry_msgs::msg::PoseStamped staging_pose;
137  staging_pose.header.frame_id = frame;
138  staging_pose.header.stamp = node_->now();
139  staging_pose.pose = pose;
140  staging_pose.pose.position.x += cos(yaw) * staging_x_offset_;
141  staging_pose.pose.position.y += sin(yaw) * staging_x_offset_;
142  tf2::Quaternion orientation;
143  orientation.setEuler(0.0, 0.0, yaw + staging_yaw_offset_);
144  staging_pose.pose.orientation = tf2::toMsg(orientation);
145 
146  // Publish staging pose for debugging purposes
147  staging_pose_pub_->publish(staging_pose);
148  return staging_pose;
149 }
150 
151 bool SimpleNonChargingDock::getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string)
152 {
153  // If using not detection, set the dock pose to the static fixed-frame version
154  if (!use_external_detection_pose_) {
155  dock_pose_pub_->publish(pose);
156  dock_pose_ = pose;
157  return true;
158  }
159 
160  // If using detections, get current detections, transform to frame, and apply offsets
161  geometry_msgs::msg::PoseStamped detected = detected_dock_pose_;
162 
163  // Validate that external pose is new enough
164  auto timeout = rclcpp::Duration::from_seconds(external_detection_timeout_);
165  if (node_->now() - detected.header.stamp > timeout) {
166  RCLCPP_WARN(node_->get_logger(), "Lost detection or did not detect: timeout exceeded");
167  return false;
168  }
169 
170  // Transform detected pose into fixed frame. Note that the argument pose
171  // is the output of detection, but also acts as the initial estimate
172  // and contains the frame_id of docking
173  if (detected.header.frame_id != pose.header.frame_id) {
174  try {
175  if (!tf2_buffer_->canTransform(
176  pose.header.frame_id, detected.header.frame_id,
177  detected.header.stamp, rclcpp::Duration::from_seconds(0.2)))
178  {
179  RCLCPP_WARN(node_->get_logger(), "Failed to transform detected dock pose");
180  return false;
181  }
182  tf2_buffer_->transform(detected, detected, pose.header.frame_id);
183  } catch (const tf2::TransformException & ex) {
184  RCLCPP_WARN(node_->get_logger(), "Failed to transform detected dock pose");
185  return false;
186  }
187  }
188 
189  // Filter the detected pose
190  detected = filter_->update(detected);
191  filtered_dock_pose_pub_->publish(detected);
192 
193  // Rotate the just the orientation, then remove roll/pitch
194  geometry_msgs::msg::PoseStamped just_orientation;
195  just_orientation.pose.orientation = tf2::toMsg(external_detection_rotation_);
196  geometry_msgs::msg::TransformStamped transform;
197  transform.transform.rotation = detected.pose.orientation;
198  tf2::doTransform(just_orientation, just_orientation, transform);
199 
200  tf2::Quaternion orientation;
201  orientation.setEuler(0.0, 0.0, tf2::getYaw(just_orientation.pose.orientation));
202  dock_pose_.pose.orientation = tf2::toMsg(orientation);
203 
204  // Construct dock_pose_ by applying translation/rotation
205  dock_pose_.header = detected.header;
206  dock_pose_.pose.position = detected.pose.position;
207  const double yaw = tf2::getYaw(dock_pose_.pose.orientation);
208  dock_pose_.pose.position.x += cos(yaw) * external_detection_translation_x_ -
209  sin(yaw) * external_detection_translation_y_;
210  dock_pose_.pose.position.y += sin(yaw) * external_detection_translation_x_ +
211  cos(yaw) * external_detection_translation_y_;
212  dock_pose_.pose.position.z = 0.0;
213 
214  // Publish & return dock pose for debugging purposes
215  dock_pose_pub_->publish(dock_pose_);
216  pose = dock_pose_;
217  return true;
218 }
219 
221 {
222  if (joint_state_sub_) {
223  // Using stall detection
224  return is_stalled_;
225  }
226 
227  if (dock_pose_.header.frame_id.empty()) {
228  // Dock pose is not yet valid
229  return false;
230  }
231 
232  // Find base pose in target frame
233  geometry_msgs::msg::PoseStamped base_pose;
234  base_pose.header.stamp = rclcpp::Time(0);
235  base_pose.header.frame_id = base_frame_id_;
236  base_pose.pose.orientation.w = 1.0;
237  try {
238  tf2_buffer_->transform(base_pose, base_pose, dock_pose_.header.frame_id);
239  } catch (const tf2::TransformException & ex) {
240  return false;
241  }
242 
243  // If we are close enough, we are docked
244  double d = std::hypot(
245  base_pose.pose.position.x - dock_pose_.pose.position.x,
246  base_pose.pose.position.y - dock_pose_.pose.position.y);
247  return d < docking_threshold_;
248 }
249 
250 void SimpleNonChargingDock::jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state)
251 {
252  double velocity = 0.0;
253  double effort = 0.0;
254  for (size_t i = 0; i < state->name.size(); ++i) {
255  for (auto & name : stall_joint_names_) {
256  if (state->name[i] == name) {
257  // Tracking this joint
258  velocity += abs(state->velocity[i]);
259  effort += abs(state->effort[i]);
260  }
261  }
262  }
263 
264  // Take average
265  effort /= stall_joint_names_.size();
266  velocity /= stall_joint_names_.size();
267 
268  is_stalled_ = (velocity < stall_velocity_threshold_) && (effort > stall_effort_threshold_);
269 }
270 
271 } // namespace opennav_docking
272 
273 #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 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 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.