Class ChargingDock

Class Documentation

class ChargingDock

Abstract interface for a charging dock for the docking framework.

Public Types

using Ptr = std::shared_ptr<ChargingDock>

Public Functions

inline 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
Parameters:
  • parent – pointer to user’s node

  • name – The name of this planner

  • tf – A pointer to a TF buffer

virtual void cleanup() = 0

Method to cleanup resources used on shutdown.

virtual void activate() = 0

Method to active Behavior and any threads involved in execution.

virtual void deactivate() = 0

Method to deactive Behavior and any threads involved in execution.

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 information to find the staging pose from a static or parameterized staging pose relative to the docking pose.

Parameters:
  • pose – Dock pose

  • frame – Dock’s frame of pose

Returns:

PoseStamped of staging pose in the specified frame

virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &pose) = 0

Method to obtain the refined pose of the dock, usually based on sensors.

Parameters:
  • pose – The initial estimate of the dock pose.

  • frame – The frame of the initial estimate.

virtual bool isDocked() = 0

Have we made contact with dock? This can be implemented in a variety of ways: by establishing communications with the dock, by monitoring the the drive motor efforts, etc.

NOTE: this function is expected to return QUICKLY. Blocking here will block the docking controller loop.

virtual bool isCharging() = 0

Are we charging? If a charge dock requires any sort of negotiation to begin charging, that should happen inside this function as this function will be called repeatedly after the docking loop to check if successful.

NOTE: this function is expected to return QUICKLY. Blocking here will block the docking controller loop.

virtual bool disableCharging() = 0

Undocking while current is still flowing can damage a charge dock so some charge docks provide the ability to disable charging before the robot physically disconnects. The undocking action will not command the robot to move until this returns true.

NOTE: this function is expected to return QUICKLY. Blocking here will block the docking controller loop.

virtual bool hasStoppedCharging() = 0

Similar to isCharging() but called when undocking.

inline std::string getName()

Protected Attributes

std::string name_