3 #define MAVLINK_MSG_ID_SYS_STATUS 1
22 #define MAVLINK_MSG_ID_SYS_STATUS_LEN 31
23 #define MAVLINK_MSG_ID_1_LEN 31
25 #define MAVLINK_MSG_ID_SYS_STATUS_CRC 124
26 #define MAVLINK_MSG_ID_1_CRC 124
30 #define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
33 { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \
34 { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \
35 { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \
36 { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \
37 { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \
38 { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \
39 { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \
40 { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \
41 { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \
42 { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \
43 { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \
44 { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \
45 { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \
71 static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72 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)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
111 #if MAVLINK_CRC_EXTRA
139 static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
140 mavlink_message_t* msg,
141 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)
143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
180 #if MAVLINK_CRC_EXTRA
195 static inline 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)
197 return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->
onboard_control_sensors_present, sys_status->
onboard_control_sensors_enabled, sys_status->
onboard_control_sensors_health, sys_status->
load, sys_status->
voltage_battery, sys_status->
current_battery, sys_status->
battery_remaining, sys_status->
drop_rate_comm, sys_status->
errors_comm, sys_status->
errors_count1, sys_status->
errors_count2, sys_status->
errors_count3, sys_status->
errors_count4);
209 static inline 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)
211 return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->
onboard_control_sensors_present, sys_status->
onboard_control_sensors_enabled, sys_status->
onboard_control_sensors_health, sys_status->
load, sys_status->
voltage_battery, sys_status->
current_battery, sys_status->
battery_remaining, sys_status->
drop_rate_comm, sys_status->
errors_comm, sys_status->
errors_count1, sys_status->
errors_count2, sys_status->
errors_count3, sys_status->
errors_count4);
232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
234 static inline void mavlink_msg_sys_status_send(
mavlink_channel_t chan, 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)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
252 #if MAVLINK_CRC_EXTRA
273 #if MAVLINK_CRC_EXTRA
281 #if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
289 static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, 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)
291 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
292 char *buf = (
char *)msgbuf;
307 #if MAVLINK_CRC_EXTRA
328 #if MAVLINK_CRC_EXTRA
347 static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(
const mavlink_message_t* msg)
349 return _MAV_RETURN_uint32_t(msg, 0);
357 static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(
const mavlink_message_t* msg)
359 return _MAV_RETURN_uint32_t(msg, 4);
367 static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(
const mavlink_message_t* msg)
369 return _MAV_RETURN_uint32_t(msg, 8);
377 static inline uint16_t mavlink_msg_sys_status_get_load(
const mavlink_message_t* msg)
379 return _MAV_RETURN_uint16_t(msg, 12);
387 static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(
const mavlink_message_t* msg)
389 return _MAV_RETURN_uint16_t(msg, 14);
397 static inline int16_t mavlink_msg_sys_status_get_current_battery(
const mavlink_message_t* msg)
399 return _MAV_RETURN_int16_t(msg, 16);
407 static inline int8_t mavlink_msg_sys_status_get_battery_remaining(
const mavlink_message_t* msg)
417 static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(
const mavlink_message_t* msg)
419 return _MAV_RETURN_uint16_t(msg, 18);
427 static inline uint16_t mavlink_msg_sys_status_get_errors_comm(
const mavlink_message_t* msg)
429 return _MAV_RETURN_uint16_t(msg, 20);
437 static inline uint16_t mavlink_msg_sys_status_get_errors_count1(
const mavlink_message_t* msg)
439 return _MAV_RETURN_uint16_t(msg, 22);
447 static inline uint16_t mavlink_msg_sys_status_get_errors_count2(
const mavlink_message_t* msg)
449 return _MAV_RETURN_uint16_t(msg, 24);
457 static inline uint16_t mavlink_msg_sys_status_get_errors_count3(
const mavlink_message_t* msg)
459 return _MAV_RETURN_uint16_t(msg, 26);
467 static inline uint16_t mavlink_msg_sys_status_get_errors_count4(
const mavlink_message_t* msg)
469 return _MAV_RETURN_uint16_t(msg, 28);
478 static inline void mavlink_msg_sys_status_decode(
const mavlink_message_t* msg,
mavlink_sys_status_t* sys_status)
480 #if MAVLINK_NEED_BYTE_SWAP
484 sys_status->
load = mavlink_msg_sys_status_get_load(msg);
485 sys_status->
voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg);
486 sys_status->
current_battery = mavlink_msg_sys_status_get_current_battery(msg);
487 sys_status->
drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg);
488 sys_status->
errors_comm = mavlink_msg_sys_status_get_errors_comm(msg);
489 sys_status->
errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg);
490 sys_status->
errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg);
491 sys_status->
errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg);
492 sys_status->
errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg);
493 sys_status->
battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg);
uint32_t onboard_control_sensors_health
Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: n...
Definition: mavlink_msg_sys_status.h:9
struct __mavlink_sys_status_t mavlink_sys_status_t
int16_t current_battery
Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current...
Definition: mavlink_msg_sys_status.h:12
uint16_t errors_count3
Autopilot-specific errors.
Definition: mavlink_msg_sys_status.h:17
#define MAVLINK_MSG_ID_SYS_STATUS
Definition: mavlink_msg_sys_status.h:3
uint16_t load
Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000...
Definition: mavlink_msg_sys_status.h:10
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
uint32_t onboard_control_sensors_present
Bitmask showing which onboard controllers and sensors are present. Value of 0: not present...
Definition: mavlink_msg_sys_status.h:7
#define MAVLINK_MSG_ID_SYS_STATUS_CRC
Definition: mavlink_msg_sys_status.h:25
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
uint32_t onboard_control_sensors_enabled
Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled...
Definition: mavlink_msg_sys_status.h:8
uint16_t errors_count2
Autopilot-specific errors.
Definition: mavlink_msg_sys_status.h:16
#define _MAV_RETURN_int8_t(msg, wire_offset)
Definition: protocol.h:237
mavlink_channel_t
Definition: mavlink_types.h:178
uint16_t errors_comm
Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted...
Definition: mavlink_msg_sys_status.h:14
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint16_t errors_count4
Autopilot-specific errors.
Definition: mavlink_msg_sys_status.h:18
#define MAVLINK_MSG_ID_SYS_STATUS_LEN
Definition: mavlink_msg_sys_status.h:22
int8_t battery_remaining
Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery...
Definition: mavlink_msg_sys_status.h:19
uint16_t voltage_battery
Battery voltage, in millivolts (1 = 1 millivolt)
Definition: mavlink_msg_sys_status.h:11
uint16_t errors_count1
Autopilot-specific errors.
Definition: mavlink_msg_sys_status.h:15
#define _mav_put_int8_t(buf, wire_offset, b)
Definition: protocol.h:135
Definition: mavlink_msg_sys_status.h:5
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
uint16_t drop_rate_comm
Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all ...
Definition: mavlink_msg_sys_status.h:13
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141