System status plugin. More...
Public Member Functions | |
const message_map | get_rx_handlers () |
Return map with message rx handlers. | |
void | initialize (UAS &uas_) |
Plugin initializer. | |
SystemStatusPlugin () | |
Private Member Functions | |
void | autopilot_version_cb (const ros::TimerEvent &event) |
void | connection_cb (bool connected) |
void | handle_autopilot_version (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_extended_sys_state (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_heartbeat (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_statustext (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_sys_status (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | heartbeat_cb (const ros::TimerEvent &event) |
void | process_autopilot_version_apm_quirk (mavlink_autopilot_version_t &apv, uint8_t sysid, uint8_t compid) |
void | process_autopilot_version_normal (mavlink_autopilot_version_t &apv, uint8_t sysid, uint8_t compid) |
void | process_statustext_normal (uint8_t severity, std::string &text) |
void | publish_disconnection () |
bool | set_mode_cb (mavros_msgs::SetMode::Request &req, mavros_msgs::SetMode::Response &res) |
bool | set_rate_cb (mavros_msgs::StreamRate::Request &req, mavros_msgs::StreamRate::Response &res) |
void | timeout_cb (const ros::TimerEvent &event) |
Static Private Member Functions | |
static std::string | custom_version_to_hex_string (uint8_t array[8]) |
Private Attributes | |
ros::Timer | autopilot_version_timer |
BatteryStatusDiag | batt_diag |
ros::Publisher | batt_pub |
bool | disable_diag |
ros::Publisher | extended_state_pub |
HeartbeatStatus | hb_diag |
ros::Timer | heartbeat_timer |
HwStatus | hwst_diag |
MemInfo | mem_diag |
ros::ServiceServer | mode_srv |
ros::NodeHandle | nh |
ros::ServiceServer | rate_srv |
ros::Publisher | state_pub |
SystemStatusDiag | sys_diag |
ros::Timer | timeout_timer |
UAS * | uas |
int | version_retries |
Static Private Attributes | |
static constexpr int | RETRIES_COUNT = 6 |