Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Attributes | List of all members
opennav_docking_core::ChargingDock Class Referenceabstract

Abstract interface for a charging dock for the docking framework. More...

#include <nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp>

Inheritance diagram for opennav_docking_core::ChargingDock:
Inheritance graph
[legend]
Collaboration diagram for opennav_docking_core::ChargingDock:
Collaboration graph
[legend]

Public Types

using Ptr = std::shared_ptr< ChargingDock >
 

Public Member Functions

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 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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
virtual bool hasStoppedCharging ()=0
 Similar to isCharging() but called when undocking.
 
virtual bool isCharger ()
 Gets if this is a charging-typed dock.
 
std::string getName ()
 

Protected Attributes

std::string name_
 

Detailed Description

Abstract interface for a charging dock for the docking framework.

Definition at line 34 of file charging_dock.hpp.

Member Function Documentation

◆ configure()

virtual void opennav_docking_core::ChargingDock::configure ( const rclcpp_lifecycle::LifecycleNode::WeakPtr &  parent,
const std::string &  name,
std::shared_ptr< tf2_ros::Buffer >  tf 
)
pure virtual
Parameters
parentpointer to user's node
nameThe name of this planner
tfA pointer to a TF buffer

Implemented in opennav_docking_core::NonChargingDock, opennav_docking::SimpleNonChargingDock, and opennav_docking::SimpleChargingDock.

◆ disableCharging()

virtual bool opennav_docking_core::ChargingDock::disableCharging ( )
pure virtual

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.

Implemented in opennav_docking_core::NonChargingDock, and opennav_docking::SimpleChargingDock.

◆ getRefinedPose()

virtual bool opennav_docking_core::ChargingDock::getRefinedPose ( geometry_msgs::msg::PoseStamped &  pose,
std::string  id 
)
pure virtual

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

Parameters
poseThe initial estimate of the dock pose.
frameThe frame of the initial estimate.

Implemented in opennav_docking_core::NonChargingDock, opennav_docking::SimpleNonChargingDock, and opennav_docking::SimpleChargingDock.

◆ getStagingPose()

virtual geometry_msgs::msg::PoseStamped opennav_docking_core::ChargingDock::getStagingPose ( const geometry_msgs::msg::Pose &  pose,
const std::string &  frame 
)
pure virtual

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
poseDock pose
frameDock's frame of pose
Returns
PoseStamped of staging pose in the specified frame

Implemented in opennav_docking_core::NonChargingDock, opennav_docking::SimpleNonChargingDock, and opennav_docking::SimpleChargingDock.

◆ isCharging()

virtual bool opennav_docking_core::ChargingDock::isCharging ( )
pure virtual

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.

Implemented in opennav_docking_core::NonChargingDock, and opennav_docking::SimpleChargingDock.

◆ isDocked()

virtual bool opennav_docking_core::ChargingDock::isDocked ( )
pure virtual

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.

Implemented in opennav_docking_core::NonChargingDock, opennav_docking::SimpleNonChargingDock, and opennav_docking::SimpleChargingDock.


The documentation for this class was generated from the following file: