15 #ifndef OPENNAV_DOCKING_CORE__CHARGING_DOCK_HPP_
16 #define OPENNAV_DOCKING_CORE__CHARGING_DOCK_HPP_
21 #include "rclcpp_lifecycle/lifecycle_node.hpp"
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "tf2_ros/buffer.h"
26 namespace opennav_docking_core
33 enum class DockDirection { UNKNOWN, FORWARD, BACKWARD };
42 using Ptr = std::shared_ptr<ChargingDock>;
55 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
56 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf) = 0;
82 const geometry_msgs::msg::Pose & pose,
const std::string & frame) = 0;
89 virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string
id) = 0;
146 std::string getName() {
return name_;}
150 DockDirection dock_direction_{DockDirection::UNKNOWN};
151 bool rotate_to_dock_{
false};
Abstract interface for a charging dock for the docking framework.
virtual void cleanup()=0
Method to cleanup resources used on shutdown.
virtual bool isCharger()
Gets if this is a charging-typed dock.
virtual bool hasStoppedCharging()=0
Similar to isCharging() but called when undocking.
virtual void activate()=0
Method to active Behavior and any threads involved in execution.
virtual bool isCharging()=0
Are we charging? If a charge dock requires any sort of negotiation to begin charging,...
virtual geometry_msgs::msg::PoseStamped getStagingPose(const geometry_msgs::msg::Pose &pose, const std::string &frame)=0
Method to obtain the dock's staging pose. This method should likely be using TF and the dock's pose i...
virtual bool disableCharging()=0
Undocking while current is still flowing can damage a charge dock so some charge docks provide the ab...
virtual ~ChargingDock()
Virtual destructor.
virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf)=0
virtual void deactivate()=0
Method to deactivate Behavior and any threads involved in execution.
virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &pose, std::string id)=0
Method to obtain the refined pose of the dock, usually based on sensors.
virtual bool isDocked()=0
Have we made contact with dock? This can be implemented in a variety of ways: by establishing communi...
DockDirection getDockDirection()
Indicates the direction of the dock. This is used to determine if the robot should drive forwards or ...
bool shouldRotateToDock()
Determines whether the robot should rotate 180ยบ to face away from the dock. For example,...