Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
AutoDocking Class Reference

#include <auto_dock.h>

Public Member Functions

 AutoDocking ()
 Autodocking constructor. Object builds action servers for docking and undocking. More...
 
 ~AutoDocking ()
 

Private Types

typedef actionlib::SimpleActionClient< fetch_driver_msgs::DisableChargingAction > charge_lockout_client_t
 
typedef actionlib::SimpleActionServer< fetch_auto_dock_msgs::DockAction > dock_server_t
 
typedef actionlib::SimpleActionServer< fetch_auto_dock_msgs::UndockAction > undock_server_t
 

Private Member Functions

double backupDistance ()
 Method to compute the distance the robot should backup when attemping a docking correction. Method uses a number of state variables in the class to compute distance. TODO(enhancement): Should these be parameterized instead? More...
 
void checkDockChargingConditions ()
 Method to see if the robot seems to be docked but not charging. If the robot does seem to be docked and not charging, try will timeout and set abort condition. More...
 
bool continueDocking (fetch_auto_dock_msgs::DockResult &result)
 Method that checks success or failure of docking. More...
 
void dockCallback (const fetch_auto_dock_msgs::DockGoalConstPtr &goal)
 Method to execute the docking behavior. More...
 
void executeBackupSequence (ros::Rate &r)
 Method to back the robot up under the abort conditon. Once complete, the method resets the abort flag. Robot will backup slightly, straighten out, backup a good distance, and then reorient. Method is blocking. More...
 
void initDockTimeout ()
 Method sets the docking deadline and number of retries. More...
 
bool isApproachBad (double &dock_yaw)
 Method to check approach abort conditions. If we are close to the dock but the robot is too far off side-to-side or at a bad angle, it should abort. Method also returns through the parameter the orientation of the dock wrt the robot for use in correction behaviors. More...
 
bool isDockingTimedOut ()
 Method checks to see if we have run out of time or retries. More...
 
bool lockoutCharger (unsigned seconds)
 Method to disable the charger for a finite amount of time. More...
 
void stateCallback (const fetch_driver_msgs::RobotStateConstPtr &state)
 Method to update the robot charge state. More...
 
void undockCallback (const fetch_auto_dock_msgs::UndockGoalConstPtr &goal)
 Method to execute the undocking behavior. More...
 

Private Attributes

double abort_angle_
 
double abort_distance_
 
double abort_threshold_
 
bool aborting_
 
double backup_limit_
 
bool cancel_docking_
 
charge_lockout_client_t charge_lockout_
 
bool charging_
 
bool charging_timeout_set_
 
BaseController controller_
 
double correction_angle_
 
ros::Time deadline_docking_
 
ros::Time deadline_not_charging_
 
dock_server_t dock_
 
double DOCK_CONNECTOR_CLEARANCE_DISTANCE_
 
double DOCKED_DISTANCE_THRESHOLD_
 
ros::NodeHandle nh_
 
int NUM_OF_RETRIES_
 
int num_of_retries_
 
DockPerception perception_
 
ros::Subscriber state_
 
undock_server_t undock_
 

Detailed Description

Definition at line 37 of file auto_dock.h.

Member Typedef Documentation

◆ charge_lockout_client_t

typedef actionlib::SimpleActionClient<fetch_driver_msgs::DisableChargingAction> AutoDocking::charge_lockout_client_t
private

Definition at line 39 of file auto_dock.h.

◆ dock_server_t

typedef actionlib::SimpleActionServer<fetch_auto_dock_msgs::DockAction> AutoDocking::dock_server_t
private

Definition at line 40 of file auto_dock.h.

◆ undock_server_t

typedef actionlib::SimpleActionServer<fetch_auto_dock_msgs::UndockAction> AutoDocking::undock_server_t
private

Definition at line 41 of file auto_dock.h.

Constructor & Destructor Documentation

◆ AutoDocking()

AutoDocking::AutoDocking ( )

Autodocking constructor. Object builds action servers for docking and undocking.

Definition at line 28 of file auto_dock.cpp.

◆ ~AutoDocking()

AutoDocking::~AutoDocking ( )

Definition at line 58 of file auto_dock.cpp.

Member Function Documentation

◆ backupDistance()

double AutoDocking::backupDistance ( )
private

Method to compute the distance the robot should backup when attemping a docking correction. Method uses a number of state variables in the class to compute distance. TODO(enhancement): Should these be parameterized instead?

Returns
Distance for robot to backup in meters.

Definition at line 325 of file auto_dock.cpp.

◆ checkDockChargingConditions()

void AutoDocking::checkDockChargingConditions ( )
private

Method to see if the robot seems to be docked but not charging. If the robot does seem to be docked and not charging, try will timeout and set abort condition.

Definition at line 233 of file auto_dock.cpp.

◆ continueDocking()

bool AutoDocking::continueDocking ( fetch_auto_dock_msgs::DockResult &  result)
private

Method that checks success or failure of docking.

Parameters
resultDock result message used to set the dock action server state.
Returns
True if we have neither succeeded nor failed to dock.

Definition at line 199 of file auto_dock.cpp.

◆ dockCallback()

void AutoDocking::dockCallback ( const fetch_auto_dock_msgs::DockGoalConstPtr &  goal)
private

Method to execute the docking behavior.

Parameters
goalInitial pose estimate of the dock.

Definition at line 76 of file auto_dock.cpp.

◆ executeBackupSequence()

void AutoDocking::executeBackupSequence ( ros::Rate r)
private

Method to back the robot up under the abort conditon. Once complete, the method resets the abort flag. Robot will backup slightly, straighten out, backup a good distance, and then reorient. Method is blocking.

Parameters
rRate object to control execution loop.

Definition at line 294 of file auto_dock.cpp.

◆ initDockTimeout()

void AutoDocking::initDockTimeout ( )
private

Method sets the docking deadline and number of retries.

Definition at line 267 of file auto_dock.cpp.

◆ isApproachBad()

bool AutoDocking::isApproachBad ( double &  dock_yaw)
private

Method to check approach abort conditions. If we are close to the dock but the robot is too far off side-to-side or at a bad angle, it should abort. Method also returns through the parameter the orientation of the dock wrt the robot for use in correction behaviors.

Parameters
dock_yawYaw angle of the dock wrt the robot in radians.
Returns
True if the robot should abort the approach.

Definition at line 356 of file auto_dock.cpp.

◆ isDockingTimedOut()

bool AutoDocking::isDockingTimedOut ( )
private

Method checks to see if we have run out of time or retries.

Returns
True if we are out of time or tries.

Definition at line 277 of file auto_dock.cpp.

◆ lockoutCharger()

bool AutoDocking::lockoutCharger ( unsigned  seconds)
private

Method to disable the charger for a finite amount of time.

Parameters
secondsNumber of seconds to disable the charger for. Maximum number of seconds is 255. Zero seconds enables the charger.
Returns
True if the number of seconds is valid and the lockout request was successful.

Definition at line 382 of file auto_dock.cpp.

◆ stateCallback()

void AutoDocking::stateCallback ( const fetch_driver_msgs::RobotStateConstPtr &  state)
private

Method to update the robot charge state.

Parameters
stateRobot state message to extract charge state from.

Definition at line 62 of file auto_dock.cpp.

◆ undockCallback()

void AutoDocking::undockCallback ( const fetch_auto_dock_msgs::UndockGoalConstPtr &  goal)
private

Method to execute the undocking behavior.

Parameters
goalDocking control action for rotating off of the goal.

Definition at line 413 of file auto_dock.cpp.

Member Data Documentation

◆ abort_angle_

double AutoDocking::abort_angle_
private

Definition at line 155 of file auto_dock.h.

◆ abort_distance_

double AutoDocking::abort_distance_
private

Definition at line 153 of file auto_dock.h.

◆ abort_threshold_

double AutoDocking::abort_threshold_
private

Definition at line 154 of file auto_dock.h.

◆ aborting_

bool AutoDocking::aborting_
private

Definition at line 159 of file auto_dock.h.

◆ backup_limit_

double AutoDocking::backup_limit_
private

Definition at line 157 of file auto_dock.h.

◆ cancel_docking_

bool AutoDocking::cancel_docking_
private

Definition at line 162 of file auto_dock.h.

◆ charge_lockout_

charge_lockout_client_t AutoDocking::charge_lockout_
private

Definition at line 142 of file auto_dock.h.

◆ charging_

bool AutoDocking::charging_
private

Definition at line 150 of file auto_dock.h.

◆ charging_timeout_set_

bool AutoDocking::charging_timeout_set_
private

Definition at line 165 of file auto_dock.h.

◆ controller_

BaseController AutoDocking::controller_
private

Definition at line 145 of file auto_dock.h.

◆ correction_angle_

double AutoDocking::correction_angle_
private

Definition at line 156 of file auto_dock.h.

◆ deadline_docking_

ros::Time AutoDocking::deadline_docking_
private

Definition at line 163 of file auto_dock.h.

◆ deadline_not_charging_

ros::Time AutoDocking::deadline_not_charging_
private

Definition at line 164 of file auto_dock.h.

◆ dock_

dock_server_t AutoDocking::dock_
private

Definition at line 140 of file auto_dock.h.

◆ DOCK_CONNECTOR_CLEARANCE_DISTANCE_

double AutoDocking::DOCK_CONNECTOR_CLEARANCE_DISTANCE_
private

Definition at line 134 of file auto_dock.h.

◆ DOCKED_DISTANCE_THRESHOLD_

double AutoDocking::DOCKED_DISTANCE_THRESHOLD_
private

Definition at line 136 of file auto_dock.h.

◆ nh_

ros::NodeHandle AutoDocking::nh_
private

Definition at line 139 of file auto_dock.h.

◆ NUM_OF_RETRIES_

int AutoDocking::NUM_OF_RETRIES_
private

Definition at line 132 of file auto_dock.h.

◆ num_of_retries_

int AutoDocking::num_of_retries_
private

Definition at line 160 of file auto_dock.h.

◆ perception_

DockPerception AutoDocking::perception_
private

Definition at line 146 of file auto_dock.h.

◆ state_

ros::Subscriber AutoDocking::state_
private

Definition at line 149 of file auto_dock.h.

◆ undock_

undock_server_t AutoDocking::undock_
private

Definition at line 141 of file auto_dock.h.


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


fetch_open_auto_dock
Author(s): Michael Ferguson, Griswald Brooks
autogenerated on Mon Feb 28 2022 22:21:37