|
| void | Initialize (ros::NodeHandle *nh) |
| |
| void | Sleep (uint32_t microseconds) |
| |
| bool | Init (void) |
| |
| bool | GetParams () |
| |
| void | Exit (int status) |
| |
| sensor_msgs::BatteryState | BatteryStateConversion (EPS::BatteryInfo const &info, std_msgs::Header const &header) |
| |
| sensor_msgs::Temperature | BatteryTemperatureConversion (EPS::BatteryInfo const &info, std_msgs::Header const &header) |
| |
| void | TelemetryCallback (const ros::TimerEvent &) |
| |
| void | DockCheckCallback (const ros::TimerEvent &) |
| |
| void | FaultCheckCallback (const ros::TimerEvent &) |
| |
| bool | ResetCallback (ff_hw_msgs::Reset::Request &req, ff_hw_msgs::Reset::Response &res) |
| |
| bool | LedsConfigureCallback (ff_hw_msgs::ConfigureSystemLeds::Request &req, ff_hw_msgs::ConfigureSystemLeds::Response &res) |
| |
| bool | PayloadConfigureCallback (ff_hw_msgs::ConfigurePayloadPower::Request &req, ff_hw_msgs::ConfigurePayloadPower::Response &res) |
| |
| bool | AdvancedConfigureCallback (ff_hw_msgs::ConfigureAdvancedPower::Request &req, ff_hw_msgs::ConfigureAdvancedPower::Response &res) |
| |
| bool | RingBuzzerCallback (ff_hw_msgs::RingBuzzer::Request &req, ff_hw_msgs::RingBuzzer::Response &res) |
| |
| bool | EnablePmcsCallback (ff_hw_msgs::SetEnabled::Request &req, ff_hw_msgs::SetEnabled::Response &res) |
| |
| bool | GetBatteryStatusCallback (ff_hw_msgs::GetBatteryStatus::Request &req, ff_hw_msgs::GetBatteryStatus::Response &res) |
| |
| bool | GetTemperaturesCallback (ff_hw_msgs::GetTemperatures::Request &req, ff_hw_msgs::GetTemperatures::Response &res) |
| |
| bool | UndockCallback (ff_hw_msgs::Undock::Request &req, ff_hw_msgs::Undock::Response &res) |
| |
| bool | GetBoardInfoCallback (ff_hw_msgs::GetBoardInfo::Request &req, ff_hw_msgs::GetBoardInfo::Response &res) |
| |
| bool | ClearTerminateCallback (ff_hw_msgs::ClearTerminate::Request &req, ff_hw_msgs::ClearTerminate::Response &res) |
| |
| 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) |
| |