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

Public Types

enum  : FSM::Event {
  READY = (1<<0), GOAL_PERCH = (1<<1), GOAL_UNPERCH = (1<<2), GOAL_CANCEL = (1<<3),
  GOAL_PREEMPT = (1<<4), ARM_DEPLOYED = (1<<5), ARM_STOWED = (1<<6), ARM_SUCCESS = (1<<7),
  ARM_FAILED = (1<<8), SWITCH_SUCCESS = (1<<9), SWITCH_FAILED = (1<<10), MOTION_SUCCESS = (1<<11),
  MOTION_FAILED = (1<<12), MANUAL_STATE_SET = (1<<13)
}
 
enum  PerchPose {
  APPROACH_POSE, COMPLETE_POSE, RECOVERY_POSE, UNPERCHED_POSE,
  PERCHED_POSE
}
 
enum  ServoID { PROXIMAL, DISTAL, GRIPPER, ALL_SERVOS }
 
- Public Types inherited from ff_util::FreeFlyerNodelet
enum  ResolveType : uint8_t { NAMESPACE = 0, TRANSFORM = 1, RESOURCE = 1 }
 

Public Member Functions

 PerchNodelet ()
 
 ~PerchNodelet ()
 
- 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 ConnectedCallback ()
 
bool SetStateCallback (ff_msgs::SetState::Request &req, ff_msgs::SetState::Response &res)
 
FSM::State Result (int32_t response, std::string const &msg="")
 
void UpdateCallback (FSM::State const &state, FSM::Event const &event)
 
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)
 
void ArmStateStampedCallback (ff_msgs::ArmStateStamped::ConstPtr const &msg)
 
bool Arm (uint8_t command)
 
void AFeedbackCallback (ff_msgs::ArmFeedbackConstPtr const &feedback)
 
void AResultCallback (ff_util::FreeFlyerActionState::Enum result_code, ff_msgs::ArmResultConstPtr const &result)
 
void SaveApproachPose (void)
 
bool OpticalFlow (bool enable)
 
bool HandraiLReset (void)
 
bool Prep (std::string const &flight_mode)
 
bool Move (PerchPose 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::PerchGoalConstPtr 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

ff_util::FSM fsm_
 
ff_util::FreeFlyerActionClient< ff_msgs::MotionAction > client_m_
 
ff_util::FreeFlyerActionClient< ff_msgs::LocalizationAction > client_s_
 
ff_util::FreeFlyerActionClient< ff_msgs::ArmAction > client_a_
 
ff_util::FreeFlyerActionServer< ff_msgs::PerchAction > server_
 
ff_util::ConfigServer cfg_
 
tf2_ros::Buffer tf_buffer_
 
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
 
ros::Publisher pub_
 
ros::Subscriber sub_
 
ros::ServiceServer server_set_state_
 
ros::ServiceClient client_service_of_enable_
 
ros::ServiceClient client_service_hr_reset_
 
geometry_msgs::Transform approach_pose_
 
int32_t err_
 
std::string err_msg_
 
std::string platform_name_
 
- 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_PERCH 
GOAL_UNPERCH 
GOAL_CANCEL 
GOAL_PREEMPT 
ARM_DEPLOYED 
ARM_STOWED 
ARM_SUCCESS 
ARM_FAILED 
SWITCH_SUCCESS 
SWITCH_FAILED 
MOTION_SUCCESS 
MOTION_FAILED 
MANUAL_STATE_SET 

◆ PerchPose

Enumerator
APPROACH_POSE 
COMPLETE_POSE 
RECOVERY_POSE 
UNPERCHED_POSE 
PERCHED_POSE 

◆ ServoID

Enumerator
PROXIMAL 
DISTAL 
GRIPPER 
ALL_SERVOS 

Constructor & Destructor Documentation

◆ PerchNodelet()

perch::PerchNodelet::PerchNodelet ( )
inline

◆ ~PerchNodelet()

perch::PerchNodelet::~PerchNodelet ( )
inline

Member Function Documentation

◆ AFeedbackCallback()

void perch::PerchNodelet::AFeedbackCallback ( ff_msgs::ArmFeedbackConstPtr const &  feedback)
inlineprotected

◆ AResultCallback()

void perch::PerchNodelet::AResultCallback ( ff_util::FreeFlyerActionState::Enum  result_code,
ff_msgs::ArmResultConstPtr const &  result 
)
inlineprotected

◆ Arm()

bool perch::PerchNodelet::Arm ( uint8_t  command)
inlineprotected

◆ ArmStateStampedCallback()

void perch::PerchNodelet::ArmStateStampedCallback ( ff_msgs::ArmStateStamped::ConstPtr const &  msg)
inlineprotected

◆ CancelCallback()

void perch::PerchNodelet::CancelCallback ( )
inlineprotected

◆ ConnectedCallback()

void perch::PerchNodelet::ConnectedCallback ( )
inlineprotected

◆ GoalCallback()

void perch::PerchNodelet::GoalCallback ( ff_msgs::PerchGoalConstPtr const &  goal)
inlineprotected

◆ HandraiLReset()

bool perch::PerchNodelet::HandraiLReset ( void  )
inlineprotected

◆ Initialize()

void perch::PerchNodelet::Initialize ( ros::NodeHandle *  nh)
inlineprotectedvirtual

Reimplemented from ff_util::FreeFlyerNodelet.

◆ MFeedbackCallback()

void perch::PerchNodelet::MFeedbackCallback ( ff_msgs::MotionFeedbackConstPtr const &  feedback)
inlineprotected

◆ Move()

bool perch::PerchNodelet::Move ( PerchPose  type,
std::string const &  mode 
)
inlineprotected

◆ MResultCallback()

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

◆ OpticalFlow()

bool perch::PerchNodelet::OpticalFlow ( bool  enable)
inlineprotected

◆ PreemptCallback()

void perch::PerchNodelet::PreemptCallback ( )
inlineprotected

◆ Prep()

bool perch::PerchNodelet::Prep ( std::string const &  flight_mode)
inlineprotected

◆ ReconfigureCallback()

bool perch::PerchNodelet::ReconfigureCallback ( dynamic_reconfigure::Config &  config)
inlineprotected

◆ Result()

FSM::State perch::PerchNodelet::Result ( int32_t  response,
std::string const &  msg = "" 
)
inlineprotected

◆ SaveApproachPose()

void perch::PerchNodelet::SaveApproachPose ( void  )
inlineprotected

◆ SetStateCallback()

bool perch::PerchNodelet::SetStateCallback ( ff_msgs::SetState::Request &  req,
ff_msgs::SetState::Response &  res 
)
inlineprotected

◆ SFeedbackCallback()

void perch::PerchNodelet::SFeedbackCallback ( ff_msgs::LocalizationFeedbackConstPtr const &  feedback)
inlineprotected

◆ SResultCallback()

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

◆ Switch()

bool perch::PerchNodelet::Switch ( std::string const &  pipeline)
inlineprotected

◆ UpdateCallback()

void perch::PerchNodelet::UpdateCallback ( FSM::State const &  state,
FSM::Event const &  event 
)
inlineprotected

Member Data Documentation

◆ approach_pose_

geometry_msgs::Transform perch::PerchNodelet::approach_pose_
protected

◆ cfg_

ff_util::ConfigServer perch::PerchNodelet::cfg_
protected

◆ client_a_

ff_util::FreeFlyerActionClient<ff_msgs::ArmAction> perch::PerchNodelet::client_a_
protected

◆ client_m_

ff_util::FreeFlyerActionClient<ff_msgs::MotionAction> perch::PerchNodelet::client_m_
protected

◆ client_s_

ff_util::FreeFlyerActionClient<ff_msgs::LocalizationAction> perch::PerchNodelet::client_s_
protected

◆ client_service_hr_reset_

ros::ServiceClient perch::PerchNodelet::client_service_hr_reset_
protected

◆ client_service_of_enable_

ros::ServiceClient perch::PerchNodelet::client_service_of_enable_
protected

◆ err_

int32_t perch::PerchNodelet::err_
protected

◆ err_msg_

std::string perch::PerchNodelet::err_msg_
protected

◆ fsm_

ff_util::FSM perch::PerchNodelet::fsm_
protected

◆ platform_name_

std::string perch::PerchNodelet::platform_name_
protected

◆ pub_

ros::Publisher perch::PerchNodelet::pub_
protected

◆ server_

ff_util::FreeFlyerActionServer<ff_msgs::PerchAction> perch::PerchNodelet::server_
protected

◆ server_set_state_

ros::ServiceServer perch::PerchNodelet::server_set_state_
protected

◆ sub_

ros::Subscriber perch::PerchNodelet::sub_
protected

◆ tf_buffer_

tf2_ros::Buffer perch::PerchNodelet::tf_buffer_
protected

◆ tf_listener_

std::shared_ptr<tf2_ros::TransformListener> perch::PerchNodelet::tf_listener_
protected

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