NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Public Types | |
enum | Type { POSITION, VELOCITY, EFFORT } |
Public Types inherited from ff_util::FreeFlyerNodelet | |
enum | ResolveType : uint8_t { NAMESPACE = 0, TRANSFORM = 1, RESOURCE = 1 } |
Public Member Functions | |
GazeboModelPluginPerchingArm () | |
~GazeboModelPluginPerchingArm () | |
Public Member Functions inherited from gazebo::FreeFlyerModelPlugin | |
FreeFlyerModelPlugin (std::string const &plugin_name, std::string const &plugin_frame, bool send_heartbeats=false) | |
virtual | ~FreeFlyerModelPlugin () |
Public Member Functions inherited from gazebo::FreeFlyerPlugin | |
FreeFlyerPlugin (std::string const &plugin_name, std::string const &plugin_frame, bool send_heartbeats=false) | |
virtual | ~FreeFlyerPlugin () |
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 | LoadCallback (ros::NodeHandle *nh, physics::ModelPtr model, sdf::ElementPtr sdf) |
void | Reset () |
double | GetGripperJointState (std::string const &name, Type type) |
void | SetGripperJointGoal (std::string const &name, double position) |
void | SetGripperGoal (double position) |
void | SetGripperJointPosition (std::string const &name, double position) |
void | SetGripperPosition (double position) |
void | GoalCallback (sensor_msgs::JointState const &msg) |
void | TimerCallback (ros::TimerEvent const &event) |
bool | SetDistVelCallback (ff_hw_msgs::SetJointMaxVelocity::Request &req, ff_hw_msgs::SetJointMaxVelocity::Response &res) |
bool | SetProxVelCallback (ff_hw_msgs::SetJointMaxVelocity::Request &req, ff_hw_msgs::SetJointMaxVelocity::Response &res) |
bool | EnableProximalServoCallback (ff_hw_msgs::SetEnabled::Request &req, ff_hw_msgs::SetEnabled::Response &res) |
bool | EnableDistalServoCallback (ff_hw_msgs::SetEnabled::Request &req, ff_hw_msgs::SetEnabled::Response &res) |
bool | EnableGripperServoCallback (ff_hw_msgs::SetEnabled::Request &req, ff_hw_msgs::SetEnabled::Response &res) |
bool | CalibrateGripperCallback (ff_hw_msgs::CalibrateGripper::Request &req, ff_hw_msgs::CalibrateGripper::Response &res) |
Protected Member Functions inherited from gazebo::FreeFlyerModelPlugin | |
virtual void | Load (physics::ModelPtr model, sdf::ElementPtr sdf) |
physics::LinkPtr | GetLink () |
physics::WorldPtr | GetWorld () |
physics::ModelPtr | GetModel () |
virtual bool | ExtrinsicsCallback (geometry_msgs::TransformStamped const *tf) |
Protected Member Functions inherited from gazebo::FreeFlyerPlugin | |
void | InitializePlugin (std::string const &robot_name, std::string const &plugin_name) |
void | SetParentFrame (std::string const &parent) |
std::string | GetFrame (std::string target="", std::string delim="/") |
virtual void | OnExtrinsicsReceived (ros::NodeHandle *nh) |
void | SetupExtrinsics (const ros::TimerEvent &event) |
void | CallbackThread () |
Protected Member Functions inherited from ff_util::FreeFlyerNodelet | |
virtual void | Initialize (ros::NodeHandle *nh) |
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) |
Static Protected Attributes | |
static constexpr double | PROXIMAL_DEPLOYED = -1.57079 |
static constexpr double | PROXIMAL_STOWED = 1.57079 |
static constexpr double | PROXIMAL_MIN_TILT = -2.09440 |
static constexpr double | PROXIMAL_MAX_TILT = -1.04718 |
static constexpr double | DISTAL_DEPLOYED = 0.0 |
static constexpr double | DISTAL_STOWED = 0.0 |
static constexpr double | DISTAL_MIN_PAN = -1.57079 |
static constexpr double | DISTAL_MAX_PAN = 1.57079 |
static constexpr double | GRIPPER_OPEN = 100.0 |
static constexpr double | GRIPPER_CLOSED = 0.0 |
static constexpr double | GRIPPER_OFFSET = 100.0 |
static constexpr double | RPM_TO_RADS_PER_S = 0.1047198 |
Additional Inherited Members | |
Protected Attributes inherited from gazebo::FreeFlyerPlugin | |
std::string | robot_name_ |
std::string | plugin_name_ |
std::string | plugin_frame_ |
std::string | parent_frame_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_ff_ |
ros::NodeHandle | nh_ff_mt_ |
std::shared_ptr< tf2_ros::TransformListener > | listener_ |
ros::CallbackQueue | callback_queue_ |
std::thread | thread_ |
ros::Timer | timer_ |
tf2_ros::Buffer | buffer_ |
Protected Attributes inherited from ff_util::FreeFlyerNodelet | |
std::map< std::string, int > | faults_ |
|
inline |
|
inline |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotectedvirtual |
Implements gazebo::FreeFlyerModelPlugin.
|
inlineprotectedvirtual |
Reimplemented from ff_util::FreeFlyerNodelet.
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |
|
staticconstexprprotected |