|
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)
} |
|
enum | ResolveType : uint8_t { NAMESPACE = 0,
TRANSFORM = 1,
RESOURCE = 1
} |
|
◆ anonymous enum
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 | |
◆ ArmNodelet()
arm::ArmNodelet::ArmNodelet |
( |
| ) |
|
|
inline |
◆ ~ArmNodelet()
arm::ArmNodelet::~ArmNodelet |
( |
| ) |
|
|
inline |
◆ Arm()
◆ 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 |
◆ 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()
◆ WatchdogCallback()
void arm::ArmNodelet::WatchdogCallback |
( |
ros::TimerEvent const & |
event | ) |
|
|
inlineprotected |
◆ calibrated_
bool arm::ArmNodelet::calibrated_ = false |
|
protected |
◆ cfg_
◆ 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_
◆ fsm_
◆ goal_set_
bool arm::ArmNodelet::goal_set_ = false |
|
protected |
◆ goal_stow_
bool arm::ArmNodelet::goal_stow_ = false |
|
protected |
◆ joints_
◆ 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_
◆ 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: