17 #include "nav2_util/node_utils.hpp"
18 #include "opennav_docking/simple_charging_dock.hpp"
20 namespace opennav_docking
24 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
25 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf)
30 node_ = parent.lock();
32 throw std::runtime_error{
"Failed to lock node"};
36 nav2_util::declare_parameter_if_not_declared(
37 node_, name +
".use_battery_status", rclcpp::ParameterValue(
true));
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));
58 nav2_util::declare_parameter_if_not_declared(
59 node_, name +
".charging_threshold", rclcpp::ParameterValue(0.5));
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));
72 nav2_util::declare_parameter_if_not_declared(
73 node_, name +
".docking_threshold", rclcpp::ParameterValue(0.05));
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));
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_);
85 name +
".external_detection_translation_x", external_detection_translation_x_);
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_);
98 node_->get_parameter(name +
".staging_x_offset", staging_x_offset_);
99 node_->get_parameter(name +
".staging_yaw_offset", staging_yaw_offset_);
103 node_->get_parameter(name +
".filter_coef", filter_coef);
104 filter_ = std::make_unique<PoseFilter>(filter_coef, external_detection_timeout_);
106 if (use_battery_status_) {
107 battery_sub_ = node_->create_subscription<sensor_msgs::msg::BatteryState>(
109 [
this](
const sensor_msgs::msg::BatteryState::SharedPtr state) {
110 is_charging_ = state->current > charging_threshold_;
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;
123 bool use_stall_detection;
124 node_->get_parameter(name +
".use_stall_detection", use_stall_detection);
125 if (use_stall_detection) {
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!");
131 joint_state_sub_ = node_->create_subscription<sensor_msgs::msg::JointState>(
133 std::bind(&SimpleChargingDock::jointStateCallback,
this, std::placeholders::_1));
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);
143 const geometry_msgs::msg::Pose & pose,
const std::string & frame)
146 if (!use_external_detection_pose_) {
149 dock_pose_.header.frame_id = frame;
150 dock_pose_.pose = pose;
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);
166 staging_pose_pub_->publish(staging_pose);
173 if (!use_external_detection_pose_) {
174 dock_pose_pub_->publish(pose);
180 geometry_msgs::msg::PoseStamped detected = detected_dock_pose_;
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");
192 if (detected.header.frame_id != pose.header.frame_id) {
194 if (!tf2_buffer_->canTransform(
195 pose.header.frame_id, detected.header.frame_id,
196 detected.header.stamp, rclcpp::Duration::from_seconds(0.2)))
198 RCLCPP_WARN(node_->get_logger(),
"Failed to transform detected dock pose");
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");
209 detected = filter_->update(detected);
210 filtered_dock_pose_pub_->publish(detected);
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);
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);
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;
234 dock_pose_pub_->publish(dock_pose_);
241 if (joint_state_sub_) {
246 if (dock_pose_.header.frame_id.empty()) {
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;
257 tf2_buffer_->transform(base_pose, base_pose, dock_pose_.header.frame_id);
258 }
catch (
const tf2::TransformException & ex) {
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_;
271 return use_battery_status_ ? is_charging_ :
isDocked();
284 void SimpleChargingDock::jointStateCallback(
const sensor_msgs::msg::JointState::SharedPtr state)
286 double velocity = 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) {
292 velocity += abs(state->velocity[i]);
293 effort += abs(state->effort[i]);
299 effort /= stall_joint_names_.size();
300 velocity /= stall_joint_names_.size();
302 is_stalled_ = (velocity < stall_velocity_threshold_) && (effort > stall_effort_threshold_);
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.