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