17 #include "nav2_util/node_utils.hpp"
18 #include "opennav_docking/simple_non_charging_dock.hpp"
19 #include "opennav_docking/utils.hpp"
21 namespace opennav_docking
25 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
26 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_external_detection_pose", rclcpp::ParameterValue(
false));
38 nav2_util::declare_parameter_if_not_declared(
39 node_, name +
".external_detection_timeout", rclcpp::ParameterValue(1.0));
40 nav2_util::declare_parameter_if_not_declared(
41 node_, name +
".external_detection_translation_x", rclcpp::ParameterValue(-0.20));
42 nav2_util::declare_parameter_if_not_declared(
43 node_, name +
".external_detection_translation_y", rclcpp::ParameterValue(0.0));
44 nav2_util::declare_parameter_if_not_declared(
45 node_, name +
".external_detection_rotation_yaw", rclcpp::ParameterValue(0.0));
46 nav2_util::declare_parameter_if_not_declared(
47 node_, name +
".external_detection_rotation_pitch", rclcpp::ParameterValue(1.57));
48 nav2_util::declare_parameter_if_not_declared(
49 node_, name +
".external_detection_rotation_roll", rclcpp::ParameterValue(-1.57));
50 nav2_util::declare_parameter_if_not_declared(
51 node_, name +
".filter_coef", rclcpp::ParameterValue(0.1));
54 nav2_util::declare_parameter_if_not_declared(
55 node_, name +
".use_stall_detection", rclcpp::ParameterValue(
false));
56 nav2_util::declare_parameter_if_not_declared(
57 node_, name +
".stall_joint_names", rclcpp::PARAMETER_STRING_ARRAY);
58 nav2_util::declare_parameter_if_not_declared(
59 node_, name +
".stall_velocity_threshold", rclcpp::ParameterValue(1.0));
60 nav2_util::declare_parameter_if_not_declared(
61 node_, name +
".stall_effort_threshold", rclcpp::ParameterValue(1.0));
64 nav2_util::declare_parameter_if_not_declared(
65 node_, name +
".docking_threshold", rclcpp::ParameterValue(0.05));
68 nav2_util::declare_parameter_if_not_declared(
69 node_, name +
".staging_x_offset", rclcpp::ParameterValue(-0.7));
70 nav2_util::declare_parameter_if_not_declared(
71 node_, name +
".staging_yaw_offset", rclcpp::ParameterValue(0.0));
74 nav2_util::declare_parameter_if_not_declared(
75 node_, name +
".dock_direction", rclcpp::ParameterValue(std::string(
"forward")));
76 nav2_util::declare_parameter_if_not_declared(
77 node_, name +
".rotate_to_dock", rclcpp::ParameterValue(
false));
79 node_->get_parameter(name +
".use_external_detection_pose", use_external_detection_pose_);
80 node_->get_parameter(name +
".external_detection_timeout", external_detection_timeout_);
82 name +
".external_detection_translation_x", external_detection_translation_x_);
84 name +
".external_detection_translation_y", external_detection_translation_y_);
85 double yaw, pitch, roll;
86 node_->get_parameter(name +
".external_detection_rotation_yaw", yaw);
87 node_->get_parameter(name +
".external_detection_rotation_pitch", pitch);
88 node_->get_parameter(name +
".external_detection_rotation_roll", roll);
89 external_detection_rotation_.setEuler(pitch, roll, yaw);
90 node_->get_parameter(name +
".stall_velocity_threshold", stall_velocity_threshold_);
91 node_->get_parameter(name +
".stall_effort_threshold", stall_effort_threshold_);
92 node_->get_parameter(name +
".docking_threshold", docking_threshold_);
93 node_->get_parameter(
"base_frame", base_frame_id_);
94 node_->get_parameter(name +
".staging_x_offset", staging_x_offset_);
95 node_->get_parameter(name +
".staging_yaw_offset", staging_yaw_offset_);
97 std::string dock_direction;
98 node_->get_parameter(name +
".dock_direction", dock_direction);
99 dock_direction_ = utils::getDockDirectionFromString(dock_direction);
100 if (dock_direction_ == opennav_docking_core::DockDirection::UNKNOWN) {
101 throw std::runtime_error{
"Dock direction is not valid. Valid options are: forward or backward"};
104 node_->get_parameter(name +
".rotate_to_dock", rotate_to_dock_);
105 if (rotate_to_dock_ && dock_direction_ != opennav_docking_core::DockDirection::BACKWARD) {
106 throw std::runtime_error{
"Parameter rotate_to_dock is enabled but dock direction is not "
107 "backward. Please set dock direction to backward."};
112 node_->get_parameter(name +
".filter_coef", filter_coef);
113 filter_ = std::make_unique<PoseFilter>(filter_coef, external_detection_timeout_);
115 if (use_external_detection_pose_) {
116 dock_pose_.header.stamp = rclcpp::Time(0);
117 dock_pose_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
118 "detected_dock_pose", 1,
119 [
this](
const geometry_msgs::msg::PoseStamped::SharedPtr pose) {
120 detected_dock_pose_ = *pose;
124 bool use_stall_detection;
125 node_->get_parameter(name +
".use_stall_detection", use_stall_detection);
126 if (use_stall_detection) {
128 node_->get_parameter(name +
".stall_joint_names", stall_joint_names_);
129 if (stall_joint_names_.size() < 1) {
130 RCLCPP_ERROR(node_->get_logger(),
"stall_joint_names cannot be empty!");
132 joint_state_sub_ = node_->create_subscription<sensor_msgs::msg::JointState>(
134 std::bind(&SimpleNonChargingDock::jointStateCallback,
this, std::placeholders::_1));
137 dock_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>(
"dock_pose", 1);
138 filtered_dock_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>(
139 "filtered_dock_pose", 1);
140 staging_pose_pub_ = node_->create_publisher<geometry_msgs::msg::PoseStamped>(
"staging_pose", 1);
144 const geometry_msgs::msg::Pose & pose,
const std::string & frame)
147 if (!use_external_detection_pose_) {
150 dock_pose_.header.frame_id = frame;
151 dock_pose_.pose = pose;
155 const double yaw = tf2::getYaw(pose.orientation);
156 geometry_msgs::msg::PoseStamped staging_pose;
157 staging_pose.header.frame_id = frame;
158 staging_pose.header.stamp = node_->now();
159 staging_pose.pose = pose;
160 staging_pose.pose.position.x += cos(yaw) * staging_x_offset_;
161 staging_pose.pose.position.y += sin(yaw) * staging_x_offset_;
162 tf2::Quaternion orientation;
163 orientation.setEuler(0.0, 0.0, yaw + staging_yaw_offset_);
164 staging_pose.pose.orientation = tf2::toMsg(orientation);
167 staging_pose_pub_->publish(staging_pose);
174 if (!use_external_detection_pose_) {
175 dock_pose_pub_->publish(pose);
181 geometry_msgs::msg::PoseStamped detected = detected_dock_pose_;
184 auto timeout = rclcpp::Duration::from_seconds(external_detection_timeout_);
185 if (node_->now() - detected.header.stamp > timeout) {
186 RCLCPP_WARN(node_->get_logger(),
"Lost detection or did not detect: timeout exceeded");
193 if (detected.header.frame_id != pose.header.frame_id) {
195 if (!tf2_buffer_->canTransform(
196 pose.header.frame_id, detected.header.frame_id,
197 detected.header.stamp, rclcpp::Duration::from_seconds(0.2)))
199 RCLCPP_WARN(node_->get_logger(),
"Failed to transform detected dock pose");
202 tf2_buffer_->transform(detected, detected, pose.header.frame_id);
203 }
catch (
const tf2::TransformException & ex) {
204 RCLCPP_WARN(node_->get_logger(),
"Failed to transform detected dock pose");
210 detected = filter_->update(detected);
211 filtered_dock_pose_pub_->publish(detected);
214 geometry_msgs::msg::PoseStamped just_orientation;
215 just_orientation.pose.orientation = tf2::toMsg(external_detection_rotation_);
216 geometry_msgs::msg::TransformStamped transform;
217 transform.transform.rotation = detected.pose.orientation;
218 tf2::doTransform(just_orientation, just_orientation, transform);
220 tf2::Quaternion orientation;
221 orientation.setEuler(0.0, 0.0, tf2::getYaw(just_orientation.pose.orientation));
222 dock_pose_.pose.orientation = tf2::toMsg(orientation);
225 dock_pose_.header = detected.header;
226 dock_pose_.pose.position = detected.pose.position;
227 const double yaw = tf2::getYaw(dock_pose_.pose.orientation);
228 dock_pose_.pose.position.x += cos(yaw) * external_detection_translation_x_ -
229 sin(yaw) * external_detection_translation_y_;
230 dock_pose_.pose.position.y += sin(yaw) * external_detection_translation_x_ +
231 cos(yaw) * external_detection_translation_y_;
232 dock_pose_.pose.position.z = 0.0;
235 dock_pose_pub_->publish(dock_pose_);
242 if (joint_state_sub_) {
247 if (dock_pose_.header.frame_id.empty()) {
253 geometry_msgs::msg::PoseStamped base_pose;
254 base_pose.header.stamp = rclcpp::Time(0);
255 base_pose.header.frame_id = base_frame_id_;
256 base_pose.pose.orientation.w = 1.0;
258 tf2_buffer_->transform(base_pose, base_pose, dock_pose_.header.frame_id);
259 }
catch (
const tf2::TransformException & ex) {
264 double d = std::hypot(
265 base_pose.pose.position.x - dock_pose_.pose.position.x,
266 base_pose.pose.position.y - dock_pose_.pose.position.y);
267 return d < docking_threshold_;
270 void SimpleNonChargingDock::jointStateCallback(
const sensor_msgs::msg::JointState::SharedPtr state)
272 double velocity = 0.0;
274 for (
size_t i = 0; i < state->name.size(); ++i) {
275 for (
auto & name : stall_joint_names_) {
276 if (state->name[i] == name) {
278 velocity += abs(state->velocity[i]);
279 effort += abs(state->effort[i]);
285 effort /= stall_joint_names_.size();
286 velocity /= stall_joint_names_.size();
288 is_stalled_ = (velocity < stall_velocity_threshold_) && (effort > stall_effort_threshold_);
293 #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.