15 #ifndef OPENNAV_DOCKING__SIMPLE_CHARGING_DOCK_HPP_
16 #define OPENNAV_DOCKING__SIMPLE_CHARGING_DOCK_HPP_
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"
28 #include "opennav_docking_core/charging_dock.hpp"
29 #include "opennav_docking/pose_filter.hpp"
31 namespace opennav_docking
50 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
51 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf);
77 const geometry_msgs::msg::Pose & pose,
const std::string & frame);
84 virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string
id);
107 void jointStateCallback(
const sensor_msgs::msg::JointState::SharedPtr state);
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_;
115 geometry_msgs::msg::PoseStamped detected_dock_pose_;
118 geometry_msgs::msg::PoseStamped dock_pose_;
121 rclcpp::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_;
123 bool use_battery_status_;
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_;
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_;
139 std::shared_ptr<PoseFilter> filter_;
142 double charging_threshold_;
144 double docking_threshold_;
145 std::string base_frame_id_;
147 double staging_x_offset_;
148 double staging_yaw_offset_;
150 rclcpp_lifecycle::LifecycleNode::SharedPtr node_;
151 std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
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...
SimpleChargingDock()
Constructor.
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.