Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
simple_charging_dock.hpp
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 #ifndef OPENNAV_DOCKING__SIMPLE_CHARGING_DOCK_HPP_
16 #define OPENNAV_DOCKING__SIMPLE_CHARGING_DOCK_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <vector>
21 
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "sensor_msgs/msg/battery_state.hpp"
24 #include "sensor_msgs/msg/joint_state.hpp"
25 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
26 #include "tf2/utils.h"
27 
28 #include "opennav_docking_core/charging_dock.hpp"
29 #include "opennav_docking/pose_filter.hpp"
30 
31 namespace opennav_docking
32 {
33 
35 {
36 public:
41  : ChargingDock()
42  {}
43 
49  virtual void configure(
50  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
51  const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf);
52 
56  virtual void cleanup() {}
57 
61  virtual void activate() {}
62 
66  virtual void deactivate() {}
67 
76  virtual geometry_msgs::msg::PoseStamped getStagingPose(
77  const geometry_msgs::msg::Pose & pose, const std::string & frame);
78 
84  virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string id);
85 
89  virtual bool isDocked();
90 
94  virtual bool isCharging();
95 
99  virtual bool disableCharging();
100 
104  virtual bool hasStoppedCharging();
105 
106 protected:
107  void jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state);
108 
109  // Optionally subscribe to a detected dock pose topic
110  rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_;
111  rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
112  rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
113  rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
114  // If subscribed to a detected pose topic, will contain latest message
115  geometry_msgs::msg::PoseStamped detected_dock_pose_;
116  // This is the actual dock pose once it has the specified translation/rotation applied
117  // If not subscribed to a topic, this is simply the database dock pose
118  geometry_msgs::msg::PoseStamped dock_pose_;
119 
120  // Subscribe to battery message, used to determine if charging
121  rclcpp::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_;
122  bool is_charging_;
123  bool use_battery_status_;
124 
125  // Optionally subscribe to joint state message, used to determine if stalled
126  rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_;
127  std::vector<std::string> stall_joint_names_;
128  double stall_velocity_threshold_, stall_effort_threshold_;
129  bool is_stalled_;
130 
131  // An external reference (such as image_proc::TrackMarkerNode) can be used to detect dock
132  bool use_external_detection_pose_;
133  double external_detection_timeout_;
134  tf2::Quaternion external_detection_rotation_;
135  double external_detection_translation_x_;
136  double external_detection_translation_y_;
137 
138  // Filtering of detected poses
139  std::shared_ptr<PoseFilter> filter_;
140 
141  // Threshold that battery current must exceed to be "charging" (in Amperes)
142  double charging_threshold_;
143  // If not using an external pose reference, this is the distance threshold
144  double docking_threshold_;
145  std::string base_frame_id_;
146  // Offset for staging pose relative to dock pose
147  double staging_x_offset_;
148  double staging_yaw_offset_;
149 
150  rclcpp_lifecycle::LifecycleNode::SharedPtr node_;
151  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
152 };
153 
154 } // namespace opennav_docking
155 
156 #endif // OPENNAV_DOCKING__SIMPLE_CHARGING_DOCK_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 void activate()
Method to active Behavior and any threads involved in execution.
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 void deactivate()
Method to deactive Behavior and any threads involved in execution.
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.
virtual void cleanup()
Method to cleanup resources used on shutdown.
Abstract interface for a charging dock for the docking framework.