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.hpp"
27 #include "nav2_ros_common/lifecycle_node.hpp"
29 #include "opennav_docking_core/charging_dock.hpp"
30 #include "opennav_docking/pose_filter.hpp"
32 namespace opennav_docking
51 const nav2::LifecycleNode::WeakPtr & parent,
52 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf);
78 const geometry_msgs::msg::Pose & pose,
const std::string & frame);
85 virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string
id);
108 void jointStateCallback(
const sensor_msgs::msg::JointState::SharedPtr state);
111 nav2::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_;
112 rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
113 rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
114 rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
116 geometry_msgs::msg::PoseStamped detected_dock_pose_;
119 geometry_msgs::msg::PoseStamped dock_pose_;
122 nav2::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_;
124 bool use_battery_status_;
127 nav2::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_;
128 std::vector<std::string> stall_joint_names_;
129 double stall_velocity_threshold_, stall_effort_threshold_;
133 bool use_external_detection_pose_;
134 double external_detection_timeout_;
135 tf2::Quaternion external_detection_rotation_;
136 double external_detection_translation_x_;
137 double external_detection_translation_y_;
140 std::shared_ptr<PoseFilter> filter_;
143 double charging_threshold_;
145 double docking_threshold_;
146 std::string base_frame_id_;
148 double staging_x_offset_;
149 double staging_yaw_offset_;
151 nav2::LifecycleNode::SharedPtr node_;
152 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 void configure(const nav2::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf)
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 deactivate()
Method to deactivate 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.