NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
dock::DockNodelet Class Reference
Inheritance diagram for dock::DockNodelet:
Inheritance graph

Public Types

enum  : FSM::Event {
  READY = (1<<0), GOAL_DOCK = (1<<1), GOAL_UNDOCK = (1<<2), GOAL_CANCEL = (1<<3),
  GOAL_PREEMPT = (1<<4), EPS_DOCKED = (1<<5), EPS_UNDOCKED = (1<<6), EPS_TIMEOUT = (1<<7),
  SWITCH_SUCCESS = (1<<8), SWITCH_FAILED = (1<<9), MOTION_SUCCESS = (1<<10), MOTION_FAILED = (1<<11),
  MANUAL_STATE_SET = (1<<12)
}
 
enum  DockPose { APPROACH_POSE, BERTHING_POSE }
 
- Public Types inherited from ff_util::FreeFlyerNodelet
enum  ResolveType : uint8_t { NAMESPACE = 0, TRANSFORM = 1, RESOURCE = 1 }
 

Public Member Functions

 DockNodelet ()
 
 ~DockNodelet ()
 
- Public Member Functions inherited from ff_util::FreeFlyerNodelet
 FreeFlyerNodelet (bool autostart_hb_timer=true)
 
 FreeFlyerNodelet (std::string const &name, bool autostart_hb_timer=true)
 
virtual ~FreeFlyerNodelet ()
 
void AssertFault (FaultKeys enum_key, std::string const &message, ros::Time time_fault_occurred=ros::Time::now())
 
void ClearAllFaults ()
 
void ClearFault (FaultKeys enum_key)
 
void PrintFaults ()
 
ros::NodeHandle * GetPlatformHandle (bool multithreaded=false)
 
ros::NodeHandle * GetPrivateHandle (bool multithreaded=false)
 
std::string GetName ()
 
std::string GetPlatform ()
 
std::string GetTransform (std::string const &child)
 

Protected Member Functions

void Initialize (ros::NodeHandle *nh)
 
void EnableTimeoutCallback (void)
 
void UndockTimeoutCallback (void)
 
void ConnectedCallback ()
 
bool SetStateCallback (ff_msgs::SetState::Request &req, ff_msgs::SetState::Response &res)
 
void Result (int32_t response, std::string const &msg="")
 
void UpdateCallback (FSM::State const &state, FSM::Event const &event)
 
bool CloseEnoughToApproach (std::string berth)
 
bool CheckBerth ()
 
bool Undock ()
 
void DockStateCallback (ff_hw_msgs::EpsDockStateStamped::ConstPtr const &msg)
 
void DockTimerCallback (const ros::TimerEvent &)
 
bool Switch (std::string const &pipeline)
 
void SFeedbackCallback (ff_msgs::LocalizationFeedbackConstPtr const &feedback)
 
void SResultCallback (ff_util::FreeFlyerActionState::Enum result_code, ff_msgs::LocalizationResultConstPtr const &result)
 
bool Prep (std::string const &flight_mode)
 
bool Move (DockPose type, std::string const &mode)
 
void MFeedbackCallback (ff_msgs::MotionFeedbackConstPtr const &feedback)
 
void MResultCallback (ff_util::FreeFlyerActionState::Enum result_code, ff_msgs::MotionResultConstPtr const &result)
 
void GoalCallback (ff_msgs::DockGoalConstPtr const &goal)
 
void PreemptCallback ()
 
void CancelCallback ()
 
bool ReconfigureCallback (dynamic_reconfigure::Config &config)
 
- Protected Member Functions inherited from ff_util::FreeFlyerNodelet
virtual void Reset ()
 
virtual void Sleep ()
 
virtual void Wakeup ()
 
void StopHeartbeat ()
 
void SendDiagnostics (const std::vector< diagnostic_msgs::KeyValue > &keyval)
 
void Setup (ros::NodeHandle &nh, ros::NodeHandle &nh_mt, std::string plugin_name)
 

Protected Attributes

std::map< uint8_t, std::string > berths_
 
ff_util::FSM fsm_
 
ff_util::FreeFlyerActionClient< ff_msgs::MotionAction > client_m_
 
ff_util::FreeFlyerActionClient< ff_msgs::LocalizationAction > client_s_
 
ff_util::FreeFlyerServiceClient< ff_msgs::GetPipelines > client_l_
 
ff_util::FreeFlyerServiceClient< ff_hw_msgs::Undock > client_u_
 
ff_util::FreeFlyerActionServer< ff_msgs::DockAction > server_
 
ff_util::ConfigServer cfg_
 
tf2_ros::Buffer tf_buffer_
 
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
 
ros::Publisher pub_
 
ros::Subscriber sub_s_
 
ros::Subscriber sub_p_
 
ros::ServiceServer server_set_state_
 
ros::Timer timer_eps_
 
ros::Timer timer_pmc_
 
std::string frame_
 
int32_t err_
 
std::string err_msg_
 
- Protected Attributes inherited from ff_util::FreeFlyerNodelet
std::map< std::string, int > faults_
 

Member Enumeration Documentation

◆ anonymous enum

anonymous enum : FSM::Event
Enumerator
READY 
GOAL_DOCK 
GOAL_UNDOCK 
GOAL_CANCEL 
GOAL_PREEMPT 
EPS_DOCKED 
EPS_UNDOCKED 
EPS_TIMEOUT 
SWITCH_SUCCESS 
SWITCH_FAILED 
MOTION_SUCCESS 
MOTION_FAILED 
MANUAL_STATE_SET 

◆ DockPose

Enumerator
APPROACH_POSE 
BERTHING_POSE 

Constructor & Destructor Documentation

◆ DockNodelet()

dock::DockNodelet::DockNodelet ( )
inline

◆ ~DockNodelet()

dock::DockNodelet::~DockNodelet ( )
inline

Member Function Documentation

◆ CancelCallback()

void dock::DockNodelet::CancelCallback ( )
inlineprotected

◆ CheckBerth()

bool dock::DockNodelet::CheckBerth ( )
inlineprotected

◆ CloseEnoughToApproach()

bool dock::DockNodelet::CloseEnoughToApproach ( std::string  berth)
inlineprotected

◆ ConnectedCallback()

void dock::DockNodelet::ConnectedCallback ( )
inlineprotected

◆ DockStateCallback()

void dock::DockNodelet::DockStateCallback ( ff_hw_msgs::EpsDockStateStamped::ConstPtr const &  msg)
inlineprotected

◆ DockTimerCallback()

void dock::DockNodelet::DockTimerCallback ( const ros::TimerEvent &  )
inlineprotected

◆ EnableTimeoutCallback()

void dock::DockNodelet::EnableTimeoutCallback ( void  )
inlineprotected

◆ GoalCallback()

void dock::DockNodelet::GoalCallback ( ff_msgs::DockGoalConstPtr const &  goal)
inlineprotected

◆ Initialize()

void dock::DockNodelet::Initialize ( ros::NodeHandle *  nh)
inlineprotectedvirtual

Reimplemented from ff_util::FreeFlyerNodelet.

◆ MFeedbackCallback()

void dock::DockNodelet::MFeedbackCallback ( ff_msgs::MotionFeedbackConstPtr const &  feedback)
inlineprotected

◆ Move()

bool dock::DockNodelet::Move ( DockPose  type,
std::string const &  mode 
)
inlineprotected

◆ MResultCallback()

void dock::DockNodelet::MResultCallback ( ff_util::FreeFlyerActionState::Enum  result_code,
ff_msgs::MotionResultConstPtr const &  result 
)
inlineprotected

◆ PreemptCallback()

void dock::DockNodelet::PreemptCallback ( )
inlineprotected

◆ Prep()

bool dock::DockNodelet::Prep ( std::string const &  flight_mode)
inlineprotected

◆ ReconfigureCallback()

bool dock::DockNodelet::ReconfigureCallback ( dynamic_reconfigure::Config &  config)
inlineprotected

◆ Result()

void dock::DockNodelet::Result ( int32_t  response,
std::string const &  msg = "" 
)
inlineprotected

◆ SetStateCallback()

bool dock::DockNodelet::SetStateCallback ( ff_msgs::SetState::Request &  req,
ff_msgs::SetState::Response &  res 
)
inlineprotected

◆ SFeedbackCallback()

void dock::DockNodelet::SFeedbackCallback ( ff_msgs::LocalizationFeedbackConstPtr const &  feedback)
inlineprotected

◆ SResultCallback()

void dock::DockNodelet::SResultCallback ( ff_util::FreeFlyerActionState::Enum  result_code,
ff_msgs::LocalizationResultConstPtr const &  result 
)
inlineprotected

◆ Switch()

bool dock::DockNodelet::Switch ( std::string const &  pipeline)
inlineprotected

◆ Undock()

bool dock::DockNodelet::Undock ( )
inlineprotected

◆ UndockTimeoutCallback()

void dock::DockNodelet::UndockTimeoutCallback ( void  )
inlineprotected

◆ UpdateCallback()

void dock::DockNodelet::UpdateCallback ( FSM::State const &  state,
FSM::Event const &  event 
)
inlineprotected

Member Data Documentation

◆ berths_

std::map<uint8_t, std::string> dock::DockNodelet::berths_
protected

◆ cfg_

ff_util::ConfigServer dock::DockNodelet::cfg_
protected

◆ client_l_

ff_util::FreeFlyerServiceClient<ff_msgs::GetPipelines> dock::DockNodelet::client_l_
protected

◆ client_m_

ff_util::FreeFlyerActionClient<ff_msgs::MotionAction> dock::DockNodelet::client_m_
protected

◆ client_s_

ff_util::FreeFlyerActionClient<ff_msgs::LocalizationAction> dock::DockNodelet::client_s_
protected

◆ client_u_

ff_util::FreeFlyerServiceClient<ff_hw_msgs::Undock> dock::DockNodelet::client_u_
protected

◆ err_

int32_t dock::DockNodelet::err_
protected

◆ err_msg_

std::string dock::DockNodelet::err_msg_
protected

◆ frame_

std::string dock::DockNodelet::frame_
protected

◆ fsm_

ff_util::FSM dock::DockNodelet::fsm_
protected

◆ pub_

ros::Publisher dock::DockNodelet::pub_
protected

◆ server_

ff_util::FreeFlyerActionServer<ff_msgs::DockAction> dock::DockNodelet::server_
protected

◆ server_set_state_

ros::ServiceServer dock::DockNodelet::server_set_state_
protected

◆ sub_p_

ros::Subscriber dock::DockNodelet::sub_p_
protected

◆ sub_s_

ros::Subscriber dock::DockNodelet::sub_s_
protected

◆ tf_buffer_

tf2_ros::Buffer dock::DockNodelet::tf_buffer_
protected

◆ tf_listener_

std::shared_ptr<tf2_ros::TransformListener> dock::DockNodelet::tf_listener_
protected

◆ timer_eps_

ros::Timer dock::DockNodelet::timer_eps_
protected

◆ timer_pmc_

ros::Timer dock::DockNodelet::timer_pmc_
protected

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