Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Abstract interface for a non-charging dock for the docking framework. More...
#include <nav2_docking/opennav_docking_core/include/opennav_docking_core/non_charging_dock.hpp>
Public Types | |
using | Ptr = std::shared_ptr< NonChargingDock > |
![]() | |
using | Ptr = std::shared_ptr< ChargingDock > |
Public Member Functions | |
virtual | ~NonChargingDock () |
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 deactivate 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... | |
bool | isCharging () final |
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... | |
bool | disableCharging () final |
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... | |
bool | hasStoppedCharging () final |
Similar to isCharging() but called when undocking. | |
bool | isCharger () final |
Gets if this is a charging-typed dock. | |
![]() | |
virtual | ~ChargingDock () |
Virtual destructor. | |
DockDirection | getDockDirection () |
Indicates the direction of the dock. This is used to determine if the robot should drive forwards or backwards onto the dock. More... | |
bool | shouldRotateToDock () |
Determines whether the robot should rotate 180ยบ to face away from the dock. For example, to perform a backward docking without detections. More... | |
std::string | getName () |
Additional Inherited Members | |
![]() | |
std::string | name_ |
DockDirection | dock_direction_ {DockDirection::UNKNOWN} |
bool | rotate_to_dock_ {false} |
Abstract interface for a non-charging dock for the docking framework.
Definition at line 31 of file non_charging_dock.hpp.
|
pure virtual |
parent | pointer to user's node |
name | The name of this planner |
tf | A pointer to a TF buffer |
Implements opennav_docking_core::ChargingDock.
Implemented in opennav_docking::SimpleNonChargingDock.
|
inlinefinalvirtual |
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.
Implements opennav_docking_core::ChargingDock.
Definition at line 115 of file non_charging_dock.hpp.
|
pure virtual |
Method to obtain the refined pose of the dock, usually based on sensors.
pose | The initial estimate of the dock pose. |
frame | The frame of the initial estimate. |
Implements opennav_docking_core::ChargingDock.
Implemented in opennav_docking::SimpleNonChargingDock.
|
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.
Implements opennav_docking_core::ChargingDock.
Implemented in opennav_docking::SimpleNonChargingDock.
|
inlinefinalvirtual |
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.
Implements opennav_docking_core::ChargingDock.
Definition at line 101 of file non_charging_dock.hpp.
|
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.
Implements opennav_docking_core::ChargingDock.
Implemented in opennav_docking::SimpleNonChargingDock.