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

Public Types

enum  : FSM::State { UNKNOWN = 0, RAMPING_UP = 1, RAMPING_DOWN = 2, READY = 3 }
 
enum  : FSM::Event { GOAL_RAMP_UP = (1<<0), GOAL_RAMP_DOWN = (1<<1), PMC1_READY = (1<<2), PMC2_READY = (1<<3) }
 
- Public Types inherited from ff_util::FreeFlyerNodelet
enum  ResolveType : uint8_t { NAMESPACE = 0, TRANSFORM = 1, RESOURCE = 1 }
 

Public Member Functions

 GazeboModelPluginPmc ()
 
void StateCallback (FSM::State const &state, FSM::FSM::Event const &event)
 
 ~GazeboModelPluginPmc ()
 
- 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)
 

Static Public Attributes

static constexpr size_t NUMBER_OF_PMCS = 2
 
static constexpr size_t NUMBER_OF_NOZZLES = 6
 
static constexpr double RADS_PER_SEC_TO_RPM = 9.549296585514
 

Protected Member Functions

void LoadCallback (ros::NodeHandle *nh, physics::ModelPtr model, sdf::ElementPtr sdf)
 
bool GetParams ()
 
void Reset ()
 
void FamCallback (ff_msgs::FamCommand const &msg)
 
void CommandCallback (ff_hw_msgs::PmcCommand const &msg)
 
void WatchdogCallback (ros::TimerEvent const &event)
 
void SendFamCommand (ff_msgs::FamCommand const &msg)
 
void SendCommand (ff_hw_msgs::PmcCommand const &msg)
 
void CommandTimerCallback (ros::TimerEvent const &event)
 
void PublishTelemetry ()
 
bool EnableService (ff_msgs::SetBool::Request &req, ff_msgs::SetBool::Response &res)
 
bool IdlingTimeoutService (ff_msgs::SetFloat::Request &req, ff_msgs::SetFloat::Response &res)
 
void WorldUpdateCallback ()
 
- 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)
 

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_
 

Member Enumeration Documentation

◆ anonymous enum

anonymous enum : FSM::State
Enumerator
UNKNOWN 
RAMPING_UP 
RAMPING_DOWN 
READY 

◆ anonymous enum

anonymous enum : FSM::Event
Enumerator
GOAL_RAMP_UP 
GOAL_RAMP_DOWN 
PMC1_READY 
PMC2_READY 

Constructor & Destructor Documentation

◆ GazeboModelPluginPmc()

gazebo::GazeboModelPluginPmc::GazeboModelPluginPmc ( )
inline

◆ ~GazeboModelPluginPmc()

gazebo::GazeboModelPluginPmc::~GazeboModelPluginPmc ( )
inline

Member Function Documentation

◆ CommandCallback()

void gazebo::GazeboModelPluginPmc::CommandCallback ( ff_hw_msgs::PmcCommand const &  msg)
inlineprotected

◆ CommandTimerCallback()

void gazebo::GazeboModelPluginPmc::CommandTimerCallback ( ros::TimerEvent const &  event)
inlineprotected

◆ EnableService()

bool gazebo::GazeboModelPluginPmc::EnableService ( ff_msgs::SetBool::Request &  req,
ff_msgs::SetBool::Response &  res 
)
inlineprotected

◆ FamCallback()

void gazebo::GazeboModelPluginPmc::FamCallback ( ff_msgs::FamCommand const &  msg)
inlineprotected

◆ GetParams()

bool gazebo::GazeboModelPluginPmc::GetParams ( )
inlineprotected

◆ IdlingTimeoutService()

bool gazebo::GazeboModelPluginPmc::IdlingTimeoutService ( ff_msgs::SetFloat::Request &  req,
ff_msgs::SetFloat::Response &  res 
)
inlineprotected

◆ LoadCallback()

void gazebo::GazeboModelPluginPmc::LoadCallback ( ros::NodeHandle *  nh,
physics::ModelPtr  model,
sdf::ElementPtr  sdf 
)
inlineprotectedvirtual

◆ PublishTelemetry()

void gazebo::GazeboModelPluginPmc::PublishTelemetry ( )
inlineprotected

◆ Reset()

void gazebo::GazeboModelPluginPmc::Reset ( )
inlineprotectedvirtual

Reimplemented from ff_util::FreeFlyerNodelet.

◆ SendCommand()

void gazebo::GazeboModelPluginPmc::SendCommand ( ff_hw_msgs::PmcCommand const &  msg)
inlineprotected

◆ SendFamCommand()

void gazebo::GazeboModelPluginPmc::SendFamCommand ( ff_msgs::FamCommand const &  msg)
inlineprotected

◆ StateCallback()

void gazebo::GazeboModelPluginPmc::StateCallback ( FSM::State const &  state,
FSM::FSM::Event const &  event 
)
inline

◆ WatchdogCallback()

void gazebo::GazeboModelPluginPmc::WatchdogCallback ( ros::TimerEvent const &  event)
inlineprotected

◆ WorldUpdateCallback()

void gazebo::GazeboModelPluginPmc::WorldUpdateCallback ( )
inlineprotected

Member Data Documentation

◆ NUMBER_OF_NOZZLES

constexpr size_t gazebo::GazeboModelPluginPmc::NUMBER_OF_NOZZLES = 6
staticconstexpr

◆ NUMBER_OF_PMCS

constexpr size_t gazebo::GazeboModelPluginPmc::NUMBER_OF_PMCS = 2
staticconstexpr

◆ RADS_PER_SEC_TO_RPM

constexpr double gazebo::GazeboModelPluginPmc::RADS_PER_SEC_TO_RPM = 9.549296585514
staticconstexpr

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