1 // MESSAGE SYS_STATUS PACKING
3 #define MAVLINK_MSG_ID_SYS_STATUS 1
5 typedef struct __mavlink_sys_status_t
7 uint32_t 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
8 uint32_t 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
9 uint32_t 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
10 uint16_t load
; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
11 uint16_t voltage_battery
; ///< Battery voltage, in millivolts (1 = 1 millivolt)
12 int16_t current_battery
; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
13 uint16_t 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)
14 uint16_t errors_comm
; ///< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
15 uint16_t errors_count1
; ///< Autopilot-specific errors
16 uint16_t errors_count2
; ///< Autopilot-specific errors
17 uint16_t errors_count3
; ///< Autopilot-specific errors
18 uint16_t errors_count4
; ///< Autopilot-specific errors
19 int8_t battery_remaining
; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
20 } mavlink_sys_status_t
;
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) }, \
51 * @brief Pack a sys_status message
52 * @param system_id ID of this system
53 * @param component_id ID of this component (e.g. 200 for IMU)
54 * @param msg The MAVLink message to compress the data into
56 * @param 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
57 * @param 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
58 * @param 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
59 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
60 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
61 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
62 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
63 * @param 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)
64 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
65 * @param errors_count1 Autopilot-specific errors
66 * @param errors_count2 Autopilot-specific errors
67 * @param errors_count3 Autopilot-specific errors
68 * @param errors_count4 Autopilot-specific errors
69 * @return length of the message in bytes (excluding serial stream start sign)
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
75 char buf
[MAVLINK_MSG_ID_SYS_STATUS_LEN
];
76 _mav_put_uint32_t(buf
, 0, onboard_control_sensors_present
);
77 _mav_put_uint32_t(buf
, 4, onboard_control_sensors_enabled
);
78 _mav_put_uint32_t(buf
, 8, onboard_control_sensors_health
);
79 _mav_put_uint16_t(buf
, 12, load
);
80 _mav_put_uint16_t(buf
, 14, voltage_battery
);
81 _mav_put_int16_t(buf
, 16, current_battery
);
82 _mav_put_uint16_t(buf
, 18, drop_rate_comm
);
83 _mav_put_uint16_t(buf
, 20, errors_comm
);
84 _mav_put_uint16_t(buf
, 22, errors_count1
);
85 _mav_put_uint16_t(buf
, 24, errors_count2
);
86 _mav_put_uint16_t(buf
, 26, errors_count3
);
87 _mav_put_uint16_t(buf
, 28, errors_count4
);
88 _mav_put_int8_t(buf
, 30, battery_remaining
);
90 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
92 mavlink_sys_status_t packet
;
93 packet
.onboard_control_sensors_present
= onboard_control_sensors_present
;
94 packet
.onboard_control_sensors_enabled
= onboard_control_sensors_enabled
;
95 packet
.onboard_control_sensors_health
= onboard_control_sensors_health
;
97 packet
.voltage_battery
= voltage_battery
;
98 packet
.current_battery
= current_battery
;
99 packet
.drop_rate_comm
= drop_rate_comm
;
100 packet
.errors_comm
= errors_comm
;
101 packet
.errors_count1
= errors_count1
;
102 packet
.errors_count2
= errors_count2
;
103 packet
.errors_count3
= errors_count3
;
104 packet
.errors_count4
= errors_count4
;
105 packet
.battery_remaining
= battery_remaining
;
107 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
110 msg
->msgid
= MAVLINK_MSG_ID_SYS_STATUS
;
111 #if MAVLINK_CRC_EXTRA
112 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_SYS_STATUS_LEN
, MAVLINK_MSG_ID_SYS_STATUS_CRC
);
114 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
119 * @brief Pack a sys_status message on a channel
120 * @param system_id ID of this system
121 * @param component_id ID of this component (e.g. 200 for IMU)
122 * @param chan The MAVLink channel this message will be sent over
123 * @param msg The MAVLink message to compress the data into
124 * @param 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
125 * @param 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
126 * @param 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
127 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
128 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
129 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
130 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
131 * @param 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)
132 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
133 * @param errors_count1 Autopilot-specific errors
134 * @param errors_count2 Autopilot-specific errors
135 * @param errors_count3 Autopilot-specific errors
136 * @param errors_count4 Autopilot-specific errors
137 * @return length of the message in bytes (excluding serial stream start sign)
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
144 char buf
[MAVLINK_MSG_ID_SYS_STATUS_LEN
];
145 _mav_put_uint32_t(buf
, 0, onboard_control_sensors_present
);
146 _mav_put_uint32_t(buf
, 4, onboard_control_sensors_enabled
);
147 _mav_put_uint32_t(buf
, 8, onboard_control_sensors_health
);
148 _mav_put_uint16_t(buf
, 12, load
);
149 _mav_put_uint16_t(buf
, 14, voltage_battery
);
150 _mav_put_int16_t(buf
, 16, current_battery
);
151 _mav_put_uint16_t(buf
, 18, drop_rate_comm
);
152 _mav_put_uint16_t(buf
, 20, errors_comm
);
153 _mav_put_uint16_t(buf
, 22, errors_count1
);
154 _mav_put_uint16_t(buf
, 24, errors_count2
);
155 _mav_put_uint16_t(buf
, 26, errors_count3
);
156 _mav_put_uint16_t(buf
, 28, errors_count4
);
157 _mav_put_int8_t(buf
, 30, battery_remaining
);
159 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
161 mavlink_sys_status_t packet
;
162 packet
.onboard_control_sensors_present
= onboard_control_sensors_present
;
163 packet
.onboard_control_sensors_enabled
= onboard_control_sensors_enabled
;
164 packet
.onboard_control_sensors_health
= onboard_control_sensors_health
;
166 packet
.voltage_battery
= voltage_battery
;
167 packet
.current_battery
= current_battery
;
168 packet
.drop_rate_comm
= drop_rate_comm
;
169 packet
.errors_comm
= errors_comm
;
170 packet
.errors_count1
= errors_count1
;
171 packet
.errors_count2
= errors_count2
;
172 packet
.errors_count3
= errors_count3
;
173 packet
.errors_count4
= errors_count4
;
174 packet
.battery_remaining
= battery_remaining
;
176 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
179 msg
->msgid
= MAVLINK_MSG_ID_SYS_STATUS
;
180 #if MAVLINK_CRC_EXTRA
181 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_SYS_STATUS_LEN
, MAVLINK_MSG_ID_SYS_STATUS_CRC
);
183 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
188 * @brief Encode a sys_status struct
190 * @param system_id ID of this system
191 * @param component_id ID of this component (e.g. 200 for IMU)
192 * @param msg The MAVLink message to compress the data into
193 * @param sys_status C-struct to read the message contents from
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
);
201 * @brief Encode a sys_status struct on a channel
203 * @param system_id ID of this system
204 * @param component_id ID of this component (e.g. 200 for IMU)
205 * @param chan The MAVLink channel this message will be sent over
206 * @param msg The MAVLink message to compress the data into
207 * @param sys_status C-struct to read the message contents from
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
);
215 * @brief Send a sys_status message
216 * @param chan MAVLink channel to send the message
218 * @param 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
219 * @param 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
220 * @param 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
221 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
222 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
223 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
224 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
225 * @param 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)
226 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
227 * @param errors_count1 Autopilot-specific errors
228 * @param errors_count2 Autopilot-specific errors
229 * @param errors_count3 Autopilot-specific errors
230 * @param errors_count4 Autopilot-specific errors
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
237 char buf
[MAVLINK_MSG_ID_SYS_STATUS_LEN
];
238 _mav_put_uint32_t(buf
, 0, onboard_control_sensors_present
);
239 _mav_put_uint32_t(buf
, 4, onboard_control_sensors_enabled
);
240 _mav_put_uint32_t(buf
, 8, onboard_control_sensors_health
);
241 _mav_put_uint16_t(buf
, 12, load
);
242 _mav_put_uint16_t(buf
, 14, voltage_battery
);
243 _mav_put_int16_t(buf
, 16, current_battery
);
244 _mav_put_uint16_t(buf
, 18, drop_rate_comm
);
245 _mav_put_uint16_t(buf
, 20, errors_comm
);
246 _mav_put_uint16_t(buf
, 22, errors_count1
);
247 _mav_put_uint16_t(buf
, 24, errors_count2
);
248 _mav_put_uint16_t(buf
, 26, errors_count3
);
249 _mav_put_uint16_t(buf
, 28, errors_count4
);
250 _mav_put_int8_t(buf
, 30, battery_remaining
);
252 #if MAVLINK_CRC_EXTRA
253 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, buf
, MAVLINK_MSG_ID_SYS_STATUS_LEN
, MAVLINK_MSG_ID_SYS_STATUS_CRC
);
255 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, buf
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
258 mavlink_sys_status_t packet
;
259 packet
.onboard_control_sensors_present
= onboard_control_sensors_present
;
260 packet
.onboard_control_sensors_enabled
= onboard_control_sensors_enabled
;
261 packet
.onboard_control_sensors_health
= onboard_control_sensors_health
;
263 packet
.voltage_battery
= voltage_battery
;
264 packet
.current_battery
= current_battery
;
265 packet
.drop_rate_comm
= drop_rate_comm
;
266 packet
.errors_comm
= errors_comm
;
267 packet
.errors_count1
= errors_count1
;
268 packet
.errors_count2
= errors_count2
;
269 packet
.errors_count3
= errors_count3
;
270 packet
.errors_count4
= errors_count4
;
271 packet
.battery_remaining
= battery_remaining
;
273 #if MAVLINK_CRC_EXTRA
274 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, (const char *)&packet
, MAVLINK_MSG_ID_SYS_STATUS_LEN
, MAVLINK_MSG_ID_SYS_STATUS_CRC
);
276 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, (const char *)&packet
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
281 #if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
283 This varient of _send() can be used to save stack space by re-using
284 memory from the receive buffer. The caller provides a
285 mavlink_message_t which is the size of a full mavlink message. This
286 is usually the receive buffer for the channel, and allows a reply to an
287 incoming message with minimum stack space usage.
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
;
293 _mav_put_uint32_t(buf
, 0, onboard_control_sensors_present
);
294 _mav_put_uint32_t(buf
, 4, onboard_control_sensors_enabled
);
295 _mav_put_uint32_t(buf
, 8, onboard_control_sensors_health
);
296 _mav_put_uint16_t(buf
, 12, load
);
297 _mav_put_uint16_t(buf
, 14, voltage_battery
);
298 _mav_put_int16_t(buf
, 16, current_battery
);
299 _mav_put_uint16_t(buf
, 18, drop_rate_comm
);
300 _mav_put_uint16_t(buf
, 20, errors_comm
);
301 _mav_put_uint16_t(buf
, 22, errors_count1
);
302 _mav_put_uint16_t(buf
, 24, errors_count2
);
303 _mav_put_uint16_t(buf
, 26, errors_count3
);
304 _mav_put_uint16_t(buf
, 28, errors_count4
);
305 _mav_put_int8_t(buf
, 30, battery_remaining
);
307 #if MAVLINK_CRC_EXTRA
308 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, buf
, MAVLINK_MSG_ID_SYS_STATUS_LEN
, MAVLINK_MSG_ID_SYS_STATUS_CRC
);
310 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, buf
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
313 mavlink_sys_status_t
*packet
= (mavlink_sys_status_t
*)msgbuf
;
314 packet
->onboard_control_sensors_present
= onboard_control_sensors_present
;
315 packet
->onboard_control_sensors_enabled
= onboard_control_sensors_enabled
;
316 packet
->onboard_control_sensors_health
= onboard_control_sensors_health
;
318 packet
->voltage_battery
= voltage_battery
;
319 packet
->current_battery
= current_battery
;
320 packet
->drop_rate_comm
= drop_rate_comm
;
321 packet
->errors_comm
= errors_comm
;
322 packet
->errors_count1
= errors_count1
;
323 packet
->errors_count2
= errors_count2
;
324 packet
->errors_count3
= errors_count3
;
325 packet
->errors_count4
= errors_count4
;
326 packet
->battery_remaining
= battery_remaining
;
328 #if MAVLINK_CRC_EXTRA
329 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, (const char *)packet
, MAVLINK_MSG_ID_SYS_STATUS_LEN
, MAVLINK_MSG_ID_SYS_STATUS_CRC
);
331 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, (const char *)packet
, MAVLINK_MSG_ID_SYS_STATUS_LEN
);
339 // MESSAGE SYS_STATUS UNPACKING
343 * @brief Get field onboard_control_sensors_present from sys_status message
345 * @return 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
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);
353 * @brief Get field onboard_control_sensors_enabled from sys_status message
355 * @return 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
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);
363 * @brief Get field onboard_control_sensors_health from sys_status message
365 * @return 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
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);
373 * @brief Get field load from sys_status message
375 * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
377 static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t
* msg
)
379 return _MAV_RETURN_uint16_t(msg
, 12);
383 * @brief Get field voltage_battery from sys_status message
385 * @return Battery voltage, in millivolts (1 = 1 millivolt)
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);
393 * @brief Get field current_battery from sys_status message
395 * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
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);
403 * @brief Get field battery_remaining from sys_status message
405 * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
407 static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t
* msg
)
409 return _MAV_RETURN_int8_t(msg
, 30);
413 * @brief Get field drop_rate_comm from sys_status message
415 * @return 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)
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);
423 * @brief Get field errors_comm from sys_status message
425 * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
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);
433 * @brief Get field errors_count1 from sys_status message
435 * @return Autopilot-specific errors
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);
443 * @brief Get field errors_count2 from sys_status message
445 * @return Autopilot-specific errors
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);
453 * @brief Get field errors_count3 from sys_status message
455 * @return Autopilot-specific errors
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);
463 * @brief Get field errors_count4 from sys_status message
465 * @return Autopilot-specific errors
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);
473 * @brief Decode a sys_status message into a struct
475 * @param msg The message to decode
476 * @param sys_status C-struct to decode the message contents into
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
481 sys_status
->onboard_control_sensors_present
= mavlink_msg_sys_status_get_onboard_control_sensors_present(msg
);
482 sys_status
->onboard_control_sensors_enabled
= mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg
);
483 sys_status
->onboard_control_sensors_health
= mavlink_msg_sys_status_get_onboard_control_sensors_health(msg
);
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
);
495 memcpy(sys_status
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_SYS_STATUS_LEN
);