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

Public Types

enum  : FSM::Event {
  READY = (1<<0), DEPLOYED = (1<<1), STOWED = (1<<2), GOAL_DEPLOY = (1<<3),
  GOAL_STOW = (1<<4), GOAL_MOVE = (1<<5), GOAL_SET = (1<<6), GOAL_DISABLE = (1<<7),
  GOAL_CANCEL = (1<<8), PAN_COMPLETE = (1<<9), TILT_COMPLETE = (1<<10), GRIPPER_COMPLETE = (1<<11),
  TIMEOUT = (1<<12), MANUAL_STATE_SET = (1<<13)
}
 
- Public Types inherited from ff_util::FreeFlyerNodelet
enum  ResolveType : uint8_t { NAMESPACE = 0, TRANSFORM = 1, RESOURCE = 1 }
 

Public Member Functions

 ArmNodelet ()
 
 ~ArmNodelet ()
 
- 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)
 
bool ReconfigureCallback (dynamic_reconfigure::Config &config)
 
void UpdateCallback (FSM::State const &state, FSM::Event const &event)
 
int32_t Result (int32_t response, bool send=false)
 
bool SetStateCallback (ff_msgs::SetState::Request &req, ff_msgs::SetState::Response &res)
 
bool Equal (JointType t, double v)
 
bool IsStowed ()
 
bool RequiresClosing ()
 
bool Arm (JointType type)
 
void JointStateCallback (sensor_msgs::JointState::ConstPtr const &msg)
 
void TimeoutCallback (ros::TimerEvent const &event)
 
void WatchdogCallback (ros::TimerEvent const &event)
 
void GoalCallback (ff_msgs::ArmGoalConstPtr const &goal)
 
void PreemptCallback ()
 
void CancelCallback ()
 
bool CalibrateGripper (void)
 
bool EnableServo (ServoID servo_number, bool servo_enable)
 
- 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::ConfigServer cfg_
 
ff_util::FreeFlyerActionServer< ff_msgs::ArmAction > server_
 
JointMap joints_
 
JointDictionary dictionary_
 
ros::Timer timer_goal_
 
ros::Timer timer_watchdog_
 
ros::Publisher pub_state_
 
ros::ServiceServer srv_set_state_
 
ros::Subscriber sub_joint_states_
 
ros::Publisher pub_joint_goals_
 
ros::Publisher pub_arm_state_
 
ros::Publisher pub_joint_sample_
 
ros::ServiceClient client_enable_prox_servo_
 
ros::ServiceClient client_enable_dist_servo_
 
ros::ServiceClient client_enable_grip_servo_
 
ros::ServiceClient client_calibrate_gripper_
 
bool calibrated_ = false
 
bool goal_stow_ = false
 
bool goal_set_ = false
 
- Protected Attributes inherited from ff_util::FreeFlyerNodelet
std::map< std::string, int > faults_
 

Static Protected Attributes

static constexpr double K_PAN_OFFSET = 0.0
 
static constexpr double K_PAN_MIN = -90.0
 
static constexpr double K_PAN_MAX = 90.0
 
static constexpr double K_PAN_STOW = 0.0
 
static constexpr double K_PAN_DEPLOY = 0.0
 
static constexpr double K_TILT_OFFSET = 90.0
 
static constexpr double K_TILT_MIN = -20.0
 
static constexpr double K_TILT_MAX = 180.0
 
static constexpr double K_TILT_STOW = 180.0
 
static constexpr double K_TILT_DEPLOY = 0.0
 
static constexpr double K_TILT_SAFE = 90.0
 
static constexpr double K_TILT_GRIP = 160.0
 
static constexpr double K_GRIPPER_STOW = 0.0
 
static constexpr double K_GRIPPER_DEPLOY = 0.0
 
static constexpr double K_GRIPPER_OPEN = 100.0
 
static constexpr double K_GRIPPER_CLOSE = 0.0
 
static constexpr double K_RADS_TO_DEGS = 180.0 / M_PI
 
static constexpr double K_DEGS_TO_RADS = M_PI / 180.0
 

Member Enumeration Documentation

◆ anonymous enum

anonymous enum : FSM::Event
Enumerator
READY 
DEPLOYED 
STOWED 
GOAL_DEPLOY 
GOAL_STOW 
GOAL_MOVE 
GOAL_SET 
GOAL_DISABLE 
GOAL_CANCEL 
PAN_COMPLETE 
TILT_COMPLETE 
GRIPPER_COMPLETE 
TIMEOUT 
MANUAL_STATE_SET 

Constructor & Destructor Documentation

◆ ArmNodelet()

arm::ArmNodelet::ArmNodelet ( )
inline

◆ ~ArmNodelet()

arm::ArmNodelet::~ArmNodelet ( )
inline

Member Function Documentation

◆ Arm()

bool arm::ArmNodelet::Arm ( JointType  type)
inlineprotected

◆ CalibrateGripper()

bool arm::ArmNodelet::CalibrateGripper ( void  )
inlineprotected

◆ CancelCallback()

void arm::ArmNodelet::CancelCallback ( )
inlineprotected

◆ EnableServo()

bool arm::ArmNodelet::EnableServo ( ServoID  servo_number,
bool  servo_enable 
)
inlineprotected

◆ Equal()

bool arm::ArmNodelet::Equal ( JointType  t,
double  v 
)
inlineprotected

◆ GoalCallback()

void arm::ArmNodelet::GoalCallback ( ff_msgs::ArmGoalConstPtr const &  goal)
inlineprotected

◆ Initialize()

void arm::ArmNodelet::Initialize ( ros::NodeHandle *  nh)
inlineprotectedvirtual

Reimplemented from ff_util::FreeFlyerNodelet.

◆ IsStowed()

bool arm::ArmNodelet::IsStowed ( )
inlineprotected

◆ JointStateCallback()

void arm::ArmNodelet::JointStateCallback ( sensor_msgs::JointState::ConstPtr const &  msg)
inlineprotected

◆ PreemptCallback()

void arm::ArmNodelet::PreemptCallback ( )
inlineprotected

◆ ReconfigureCallback()

bool arm::ArmNodelet::ReconfigureCallback ( dynamic_reconfigure::Config &  config)
inlineprotected

◆ RequiresClosing()

bool arm::ArmNodelet::RequiresClosing ( )
inlineprotected

◆ Result()

int32_t arm::ArmNodelet::Result ( int32_t  response,
bool  send = false 
)
inlineprotected

◆ SetStateCallback()

bool arm::ArmNodelet::SetStateCallback ( ff_msgs::SetState::Request &  req,
ff_msgs::SetState::Response &  res 
)
inlineprotected

◆ TimeoutCallback()

void arm::ArmNodelet::TimeoutCallback ( ros::TimerEvent const &  event)
inlineprotected

◆ UpdateCallback()

void arm::ArmNodelet::UpdateCallback ( FSM::State const &  state,
FSM::Event const &  event 
)
inlineprotected

◆ WatchdogCallback()

void arm::ArmNodelet::WatchdogCallback ( ros::TimerEvent const &  event)
inlineprotected

Member Data Documentation

◆ calibrated_

bool arm::ArmNodelet::calibrated_ = false
protected

◆ cfg_

ff_util::ConfigServer arm::ArmNodelet::cfg_
protected

◆ client_calibrate_gripper_

ros::ServiceClient arm::ArmNodelet::client_calibrate_gripper_
protected

◆ client_enable_dist_servo_

ros::ServiceClient arm::ArmNodelet::client_enable_dist_servo_
protected

◆ client_enable_grip_servo_

ros::ServiceClient arm::ArmNodelet::client_enable_grip_servo_
protected

◆ client_enable_prox_servo_

ros::ServiceClient arm::ArmNodelet::client_enable_prox_servo_
protected

◆ dictionary_

JointDictionary arm::ArmNodelet::dictionary_
protected

◆ fsm_

ff_util::FSM arm::ArmNodelet::fsm_
protected

◆ goal_set_

bool arm::ArmNodelet::goal_set_ = false
protected

◆ goal_stow_

bool arm::ArmNodelet::goal_stow_ = false
protected

◆ joints_

JointMap arm::ArmNodelet::joints_
protected

◆ K_DEGS_TO_RADS

constexpr double arm::ArmNodelet::K_DEGS_TO_RADS = M_PI / 180.0
staticconstexprprotected

◆ K_GRIPPER_CLOSE

constexpr double arm::ArmNodelet::K_GRIPPER_CLOSE = 0.0
staticconstexprprotected

◆ K_GRIPPER_DEPLOY

constexpr double arm::ArmNodelet::K_GRIPPER_DEPLOY = 0.0
staticconstexprprotected

◆ K_GRIPPER_OPEN

constexpr double arm::ArmNodelet::K_GRIPPER_OPEN = 100.0
staticconstexprprotected

◆ K_GRIPPER_STOW

constexpr double arm::ArmNodelet::K_GRIPPER_STOW = 0.0
staticconstexprprotected

◆ K_PAN_DEPLOY

constexpr double arm::ArmNodelet::K_PAN_DEPLOY = 0.0
staticconstexprprotected

◆ K_PAN_MAX

constexpr double arm::ArmNodelet::K_PAN_MAX = 90.0
staticconstexprprotected

◆ K_PAN_MIN

constexpr double arm::ArmNodelet::K_PAN_MIN = -90.0
staticconstexprprotected

◆ K_PAN_OFFSET

constexpr double arm::ArmNodelet::K_PAN_OFFSET = 0.0
staticconstexprprotected

◆ K_PAN_STOW

constexpr double arm::ArmNodelet::K_PAN_STOW = 0.0
staticconstexprprotected

◆ K_RADS_TO_DEGS

constexpr double arm::ArmNodelet::K_RADS_TO_DEGS = 180.0 / M_PI
staticconstexprprotected

◆ K_TILT_DEPLOY

constexpr double arm::ArmNodelet::K_TILT_DEPLOY = 0.0
staticconstexprprotected

◆ K_TILT_GRIP

constexpr double arm::ArmNodelet::K_TILT_GRIP = 160.0
staticconstexprprotected

◆ K_TILT_MAX

constexpr double arm::ArmNodelet::K_TILT_MAX = 180.0
staticconstexprprotected

◆ K_TILT_MIN

constexpr double arm::ArmNodelet::K_TILT_MIN = -20.0
staticconstexprprotected

◆ K_TILT_OFFSET

constexpr double arm::ArmNodelet::K_TILT_OFFSET = 90.0
staticconstexprprotected

◆ K_TILT_SAFE

constexpr double arm::ArmNodelet::K_TILT_SAFE = 90.0
staticconstexprprotected

◆ K_TILT_STOW

constexpr double arm::ArmNodelet::K_TILT_STOW = 180.0
staticconstexprprotected

◆ pub_arm_state_

ros::Publisher arm::ArmNodelet::pub_arm_state_
protected

◆ pub_joint_goals_

ros::Publisher arm::ArmNodelet::pub_joint_goals_
protected

◆ pub_joint_sample_

ros::Publisher arm::ArmNodelet::pub_joint_sample_
protected

◆ pub_state_

ros::Publisher arm::ArmNodelet::pub_state_
protected

◆ server_

ff_util::FreeFlyerActionServer<ff_msgs::ArmAction> arm::ArmNodelet::server_
protected

◆ srv_set_state_

ros::ServiceServer arm::ArmNodelet::srv_set_state_
protected

◆ sub_joint_states_

ros::Subscriber arm::ArmNodelet::sub_joint_states_
protected

◆ timer_goal_

ros::Timer arm::ArmNodelet::timer_goal_
protected

◆ timer_watchdog_

ros::Timer arm::ArmNodelet::timer_watchdog_
protected

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