Go to the source code of this file.
Classes | |
struct | __mavlink_sys_status_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_SYS_STATUS |
#define | MAVLINK_MSG_ID_1_CRC 124 |
#define | MAVLINK_MSG_ID_1_LEN 31 |
#define | MAVLINK_MSG_ID_SYS_STATUS 1 |
#define | MAVLINK_MSG_ID_SYS_STATUS_CRC 124 |
#define | MAVLINK_MSG_ID_SYS_STATUS_LEN 31 |
Typedefs | |
typedef struct __mavlink_sys_status_t | mavlink_sys_status_t |
Functions | |
static void | mavlink_msg_sys_status_decode (const mavlink_message_t *msg, mavlink_sys_status_t *sys_status) |
Decode a sys_status message into a struct. More... | |
static uint16_t | mavlink_msg_sys_status_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_sys_status_t *sys_status) |
Encode a sys_status struct. More... | |
static uint16_t | mavlink_msg_sys_status_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_sys_status_t *sys_status) |
Encode a sys_status struct on a channel. More... | |
static int8_t | mavlink_msg_sys_status_get_battery_remaining (const mavlink_message_t *msg) |
Get field battery_remaining from sys_status message. More... | |
static int16_t | mavlink_msg_sys_status_get_current_battery (const mavlink_message_t *msg) |
Get field current_battery from sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_get_drop_rate_comm (const mavlink_message_t *msg) |
Get field drop_rate_comm from sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_get_errors_comm (const mavlink_message_t *msg) |
Get field errors_comm from sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_get_errors_count1 (const mavlink_message_t *msg) |
Get field errors_count1 from sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_get_errors_count2 (const mavlink_message_t *msg) |
Get field errors_count2 from sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_get_errors_count3 (const mavlink_message_t *msg) |
Get field errors_count3 from sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_get_errors_count4 (const mavlink_message_t *msg) |
Get field errors_count4 from sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_get_load (const mavlink_message_t *msg) |
Get field load from sys_status message. More... | |
static uint32_t | mavlink_msg_sys_status_get_onboard_control_sensors_enabled (const mavlink_message_t *msg) |
Get field onboard_control_sensors_enabled from sys_status message. More... | |
static uint32_t | mavlink_msg_sys_status_get_onboard_control_sensors_health (const mavlink_message_t *msg) |
Get field onboard_control_sensors_health from sys_status message. More... | |
static uint32_t | mavlink_msg_sys_status_get_onboard_control_sensors_present (const mavlink_message_t *msg) |
Send a sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_get_voltage_battery (const mavlink_message_t *msg) |
Get field voltage_battery from sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) |
Pack a sys_status message. More... | |
static uint16_t | mavlink_msg_sys_status_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) |
Pack a sys_status message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_SYS_STATUS |
Definition at line 30 of file mavlink_msg_sys_status.h.
#define MAVLINK_MSG_ID_1_CRC 124 |
Definition at line 26 of file mavlink_msg_sys_status.h.
#define MAVLINK_MSG_ID_1_LEN 31 |
Definition at line 23 of file mavlink_msg_sys_status.h.
#define MAVLINK_MSG_ID_SYS_STATUS 1 |
Definition at line 3 of file mavlink_msg_sys_status.h.
#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124 |
Definition at line 25 of file mavlink_msg_sys_status.h.
#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 |
Definition at line 22 of file mavlink_msg_sys_status.h.
typedef struct __mavlink_sys_status_t mavlink_sys_status_t |
|
inlinestatic |
Decode a sys_status message into a struct.
msg | The message to decode |
sys_status | C-struct to decode the message contents into |
Definition at line 478 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Encode a sys_status struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
sys_status | C-struct to read the message contents from |
Definition at line 195 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Encode a sys_status struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
sys_status | C-struct to read the message contents from |
Definition at line 209 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field battery_remaining from sys_status message.
Definition at line 407 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field current_battery from sys_status message.
Definition at line 397 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field drop_rate_comm from sys_status message.
Definition at line 417 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field errors_comm from sys_status message.
Definition at line 427 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field errors_count1 from sys_status message.
Definition at line 437 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field errors_count2 from sys_status message.
Definition at line 447 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field errors_count3 from sys_status message.
Definition at line 457 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field errors_count4 from sys_status message.
Definition at line 467 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field load from sys_status message.
Definition at line 377 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field onboard_control_sensors_enabled from sys_status message.
Definition at line 357 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field onboard_control_sensors_health from sys_status message.
Definition at line 367 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Send a sys_status message.
chan | MAVLink channel to send the message |
onboard_control_sensors_present | Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
onboard_control_sensors_enabled | Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
onboard_control_sensors_health | Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
load | Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 |
voltage_battery | Battery voltage, in millivolts (1 = 1 millivolt) |
current_battery | Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
battery_remaining | Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery |
drop_rate_comm | Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) |
errors_comm | Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) |
errors_count1 | Autopilot-specific errors |
errors_count2 | Autopilot-specific errors |
errors_count3 | Autopilot-specific errors |
errors_count4 | Autopilot-specific errors Get field onboard_control_sensors_present from sys_status message |
Definition at line 347 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Get field voltage_battery from sys_status message.
Definition at line 387 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Pack a sys_status message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
onboard_control_sensors_present | Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
onboard_control_sensors_enabled | Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
onboard_control_sensors_health | Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
load | Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 |
voltage_battery | Battery voltage, in millivolts (1 = 1 millivolt) |
current_battery | Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
battery_remaining | Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery |
drop_rate_comm | Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) |
errors_comm | Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) |
errors_count1 | Autopilot-specific errors |
errors_count2 | Autopilot-specific errors |
errors_count3 | Autopilot-specific errors |
errors_count4 | Autopilot-specific errors |
Definition at line 71 of file mavlink_msg_sys_status.h.
|
inlinestatic |
Pack a sys_status message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
onboard_control_sensors_present | Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
onboard_control_sensors_enabled | Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
onboard_control_sensors_health | Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR |
load | Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 |
voltage_battery | Battery voltage, in millivolts (1 = 1 millivolt) |
current_battery | Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
battery_remaining | Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery |
drop_rate_comm | Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) |
errors_comm | Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) |
errors_count1 | Autopilot-specific errors |
errors_count2 | Autopilot-specific errors |
errors_count3 | Autopilot-specific errors |
errors_count4 | Autopilot-specific errors |
Definition at line 139 of file mavlink_msg_sys_status.h.