|
| void | LoadCallback (ros::NodeHandle *nh, physics::ModelPtr model, sdf::ElementPtr sdf) |
| |
| void | StateCallback (FSM::State const &state, FSM::FSM::Event const &event) |
| |
| void | BerthCallback () |
| |
| void | Lock (bool enable) |
| |
| void | UpdateCallback (const ros::TimerEvent &event) |
| |
| void | DelayCallback (const ros::TimerEvent &event) |
| |
| bool | UndockCallback (ff_hw_msgs::Undock::Request &req, ff_hw_msgs::Undock::Response &res) |
| |
| bool | PayloadConfigureCallback (ff_hw_msgs::ConfigurePayloadPower::Request &req, ff_hw_msgs::ConfigurePayloadPower::Response &res) |
| |
| bool | PowerConfigureCallback (ff_hw_msgs::ConfigureAdvancedPower::Request &req, ff_hw_msgs::ConfigureAdvancedPower::Response &res) |
| |
| bool | LedsConfigureCallback (ff_hw_msgs::ConfigureSystemLeds::Request &req, ff_hw_msgs::ConfigureSystemLeds::Response &res) |
| |
| void | TelemetryCallback (const ros::TimerEvent &event) |
| |
| 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) |
| |
| 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 () |
| |
| virtual void | Initialize (ros::NodeHandle *nh) |
| |
| 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) |
| |
◆ anonymous enum
| Enumerator |
|---|
| UNKNOWN | |
| UNDOCKED | |
| DOCKING | |
| DOCKED | |
| UNDOCKING | |
◆ anonymous enum
| Enumerator |
|---|
| SENSE_NEAR | |
| SENSE_FAR | |
| UNDOCK | |
| TIMEOUT | |
◆ GazeboModelPluginEps()
| gazebo::GazeboModelPluginEps::GazeboModelPluginEps |
( |
| ) |
|
|
inline |
◆ ~GazeboModelPluginEps()
| gazebo::GazeboModelPluginEps::~GazeboModelPluginEps |
( |
| ) |
|
|
inline |
◆ BerthCallback()
| void gazebo::GazeboModelPluginEps::BerthCallback |
( |
| ) |
|
|
inlineprotected |
◆ DelayCallback()
| void gazebo::GazeboModelPluginEps::DelayCallback |
( |
const ros::TimerEvent & |
event | ) |
|
|
inlineprotected |
◆ LedsConfigureCallback()
| bool gazebo::GazeboModelPluginEps::LedsConfigureCallback |
( |
ff_hw_msgs::ConfigureSystemLeds::Request & |
req, |
|
|
ff_hw_msgs::ConfigureSystemLeds::Response & |
res |
|
) |
| |
|
inlineprotected |
◆ LoadCallback()
| void gazebo::GazeboModelPluginEps::LoadCallback |
( |
ros::NodeHandle * |
nh, |
|
|
physics::ModelPtr |
model, |
|
|
sdf::ElementPtr |
sdf |
|
) |
| |
|
inlineprotectedvirtual |
◆ Lock()
| void gazebo::GazeboModelPluginEps::Lock |
( |
bool |
enable | ) |
|
|
inlineprotected |
◆ PayloadConfigureCallback()
| bool gazebo::GazeboModelPluginEps::PayloadConfigureCallback |
( |
ff_hw_msgs::ConfigurePayloadPower::Request & |
req, |
|
|
ff_hw_msgs::ConfigurePayloadPower::Response & |
res |
|
) |
| |
|
inlineprotected |
◆ PowerConfigureCallback()
| bool gazebo::GazeboModelPluginEps::PowerConfigureCallback |
( |
ff_hw_msgs::ConfigureAdvancedPower::Request & |
req, |
|
|
ff_hw_msgs::ConfigureAdvancedPower::Response & |
res |
|
) |
| |
|
inlineprotected |
◆ StateCallback()
◆ TelemetryCallback()
| void gazebo::GazeboModelPluginEps::TelemetryCallback |
( |
const ros::TimerEvent & |
event | ) |
|
|
inlineprotected |
◆ UndockCallback()
| bool gazebo::GazeboModelPluginEps::UndockCallback |
( |
ff_hw_msgs::Undock::Request & |
req, |
|
|
ff_hw_msgs::Undock::Response & |
res |
|
) |
| |
|
inlineprotected |
◆ UpdateCallback()
| void gazebo::GazeboModelPluginEps::UpdateCallback |
( |
const ros::TimerEvent & |
event | ) |
|
|
inlineprotected |
The documentation for this class was generated from the following file: