1 // MESSAGE SYS_STATUS PACKING
3 #define MAVLINK_MSG_ID_SYS_STATUS 1
5 typedef struct __mavlink_sys_status_t
{
6 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: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
7 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: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
8 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: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
9 uint16_t load
; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
10 uint16_t voltage_battery
; ///< Battery voltage, in millivolts (1 = 1 millivolt)
11 int16_t current_battery
; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
12 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)
13 uint16_t errors_comm
; ///< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
14 uint16_t errors_count1
; ///< Autopilot-specific errors
15 uint16_t errors_count2
; ///< Autopilot-specific errors
16 uint16_t errors_count3
; ///< Autopilot-specific errors
17 uint16_t errors_count4
; ///< Autopilot-specific errors
18 int8_t battery_remaining
; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
19 } mavlink_sys_status_t
;
21 #define MAVLINK_MSG_ID_SYS_STATUS_LEN 31
22 #define MAVLINK_MSG_ID_1_LEN 31
25 #define MAVLINK_MESSAGE_INFO_SYS_STATUS \
30 { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \
31 { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \
32 { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \
33 { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \
34 { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \
35 { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \
36 { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \
37 { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \
38 { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \
39 { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \
40 { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \
41 { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \
42 { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \
48 * @brief Pack a sys_status message
49 * @param system_id ID of this system
50 * @param component_id ID of this component (e.g. 200 for IMU)
51 * @param msg The MAVLink message to compress the data into
53 * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
54 * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
55 * @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: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
56 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
57 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
58 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
59 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
60 * @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)
61 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
62 * @param errors_count1 Autopilot-specific errors
63 * @param errors_count2 Autopilot-specific errors
64 * @param errors_count3 Autopilot-specific errors
65 * @param errors_count4 Autopilot-specific errors
66 * @return length of the message in bytes (excluding serial stream start sign)
68 static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
69 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
)
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73 _mav_put_uint32_t(buf
, 0, onboard_control_sensors_present
);
74 _mav_put_uint32_t(buf
, 4, onboard_control_sensors_enabled
);
75 _mav_put_uint32_t(buf
, 8, onboard_control_sensors_health
);
76 _mav_put_uint16_t(buf
, 12, load
);
77 _mav_put_uint16_t(buf
, 14, voltage_battery
);
78 _mav_put_int16_t(buf
, 16, current_battery
);
79 _mav_put_uint16_t(buf
, 18, drop_rate_comm
);
80 _mav_put_uint16_t(buf
, 20, errors_comm
);
81 _mav_put_uint16_t(buf
, 22, errors_count1
);
82 _mav_put_uint16_t(buf
, 24, errors_count2
);
83 _mav_put_uint16_t(buf
, 26, errors_count3
);
84 _mav_put_uint16_t(buf
, 28, errors_count4
);
85 _mav_put_int8_t(buf
, 30, battery_remaining
);
87 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 31);
89 mavlink_sys_status_t packet
;
90 packet
.onboard_control_sensors_present
= onboard_control_sensors_present
;
91 packet
.onboard_control_sensors_enabled
= onboard_control_sensors_enabled
;
92 packet
.onboard_control_sensors_health
= onboard_control_sensors_health
;
94 packet
.voltage_battery
= voltage_battery
;
95 packet
.current_battery
= current_battery
;
96 packet
.drop_rate_comm
= drop_rate_comm
;
97 packet
.errors_comm
= errors_comm
;
98 packet
.errors_count1
= errors_count1
;
99 packet
.errors_count2
= errors_count2
;
100 packet
.errors_count3
= errors_count3
;
101 packet
.errors_count4
= errors_count4
;
102 packet
.battery_remaining
= battery_remaining
;
104 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 31);
105 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 msg
->msgid
= MAVLINK_MSG_ID_SYS_STATUS
;
108 return mavlink_finalize_message(msg
, system_id
, component_id
, 31, 124);
112 * @brief Pack a sys_status message on a channel
113 * @param system_id ID of this system
114 * @param component_id ID of this component (e.g. 200 for IMU)
115 * @param chan The MAVLink channel this message was sent over
116 * @param msg The MAVLink message to compress the data into
117 * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
118 * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
119 * @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: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
120 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
121 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
122 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
123 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
124 * @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)
125 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
126 * @param errors_count1 Autopilot-specific errors
127 * @param errors_count2 Autopilot-specific errors
128 * @param errors_count3 Autopilot-specific errors
129 * @param errors_count4 Autopilot-specific errors
130 * @return length of the message in bytes (excluding serial stream start sign)
132 static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
133 mavlink_message_t
*msg
,
134 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
)
136 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
138 _mav_put_uint32_t(buf
, 0, onboard_control_sensors_present
);
139 _mav_put_uint32_t(buf
, 4, onboard_control_sensors_enabled
);
140 _mav_put_uint32_t(buf
, 8, onboard_control_sensors_health
);
141 _mav_put_uint16_t(buf
, 12, load
);
142 _mav_put_uint16_t(buf
, 14, voltage_battery
);
143 _mav_put_int16_t(buf
, 16, current_battery
);
144 _mav_put_uint16_t(buf
, 18, drop_rate_comm
);
145 _mav_put_uint16_t(buf
, 20, errors_comm
);
146 _mav_put_uint16_t(buf
, 22, errors_count1
);
147 _mav_put_uint16_t(buf
, 24, errors_count2
);
148 _mav_put_uint16_t(buf
, 26, errors_count3
);
149 _mav_put_uint16_t(buf
, 28, errors_count4
);
150 _mav_put_int8_t(buf
, 30, battery_remaining
);
152 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 31);
154 mavlink_sys_status_t packet
;
155 packet
.onboard_control_sensors_present
= onboard_control_sensors_present
;
156 packet
.onboard_control_sensors_enabled
= onboard_control_sensors_enabled
;
157 packet
.onboard_control_sensors_health
= onboard_control_sensors_health
;
159 packet
.voltage_battery
= voltage_battery
;
160 packet
.current_battery
= current_battery
;
161 packet
.drop_rate_comm
= drop_rate_comm
;
162 packet
.errors_comm
= errors_comm
;
163 packet
.errors_count1
= errors_count1
;
164 packet
.errors_count2
= errors_count2
;
165 packet
.errors_count3
= errors_count3
;
166 packet
.errors_count4
= errors_count4
;
167 packet
.battery_remaining
= battery_remaining
;
169 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 31);
170 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
172 msg
->msgid
= MAVLINK_MSG_ID_SYS_STATUS
;
173 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 31, 124);
177 * @brief Encode a sys_status struct into a message
179 * @param system_id ID of this system
180 * @param component_id ID of this component (e.g. 200 for IMU)
181 * @param msg The MAVLink message to compress the data into
182 * @param sys_status C-struct to read the message contents from
184 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
)
186 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
);
190 * @brief Send a sys_status message
191 * @param chan MAVLink channel to send the message
193 * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
194 * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
195 * @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: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
196 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
197 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
198 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
199 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
200 * @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)
201 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
202 * @param errors_count1 Autopilot-specific errors
203 * @param errors_count2 Autopilot-specific errors
204 * @param errors_count3 Autopilot-specific errors
205 * @param errors_count4 Autopilot-specific errors
207 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
209 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
)
211 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 _mav_put_uint32_t(buf
, 0, onboard_control_sensors_present
);
214 _mav_put_uint32_t(buf
, 4, onboard_control_sensors_enabled
);
215 _mav_put_uint32_t(buf
, 8, onboard_control_sensors_health
);
216 _mav_put_uint16_t(buf
, 12, load
);
217 _mav_put_uint16_t(buf
, 14, voltage_battery
);
218 _mav_put_int16_t(buf
, 16, current_battery
);
219 _mav_put_uint16_t(buf
, 18, drop_rate_comm
);
220 _mav_put_uint16_t(buf
, 20, errors_comm
);
221 _mav_put_uint16_t(buf
, 22, errors_count1
);
222 _mav_put_uint16_t(buf
, 24, errors_count2
);
223 _mav_put_uint16_t(buf
, 26, errors_count3
);
224 _mav_put_uint16_t(buf
, 28, errors_count4
);
225 _mav_put_int8_t(buf
, 30, battery_remaining
);
227 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, buf
, 31, 124);
229 mavlink_sys_status_t packet
;
230 packet
.onboard_control_sensors_present
= onboard_control_sensors_present
;
231 packet
.onboard_control_sensors_enabled
= onboard_control_sensors_enabled
;
232 packet
.onboard_control_sensors_health
= onboard_control_sensors_health
;
234 packet
.voltage_battery
= voltage_battery
;
235 packet
.current_battery
= current_battery
;
236 packet
.drop_rate_comm
= drop_rate_comm
;
237 packet
.errors_comm
= errors_comm
;
238 packet
.errors_count1
= errors_count1
;
239 packet
.errors_count2
= errors_count2
;
240 packet
.errors_count3
= errors_count3
;
241 packet
.errors_count4
= errors_count4
;
242 packet
.battery_remaining
= battery_remaining
;
244 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYS_STATUS
, (const char *)&packet
, 31, 124);
245 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
248 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
250 // MESSAGE SYS_STATUS UNPACKING
254 * @brief Get field onboard_control_sensors_present from sys_status message
256 * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
258 static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t
*msg
)
260 return _MAV_RETURN_uint32_t(msg
, 0);
264 * @brief Get field onboard_control_sensors_enabled from sys_status message
266 * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
268 static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t
*msg
)
270 return _MAV_RETURN_uint32_t(msg
, 4);
274 * @brief Get field onboard_control_sensors_health from sys_status message
276 * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
278 static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t
*msg
)
280 return _MAV_RETURN_uint32_t(msg
, 8);
284 * @brief Get field load from sys_status message
286 * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
288 static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t
*msg
)
290 return _MAV_RETURN_uint16_t(msg
, 12);
294 * @brief Get field voltage_battery from sys_status message
296 * @return Battery voltage, in millivolts (1 = 1 millivolt)
298 static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t
*msg
)
300 return _MAV_RETURN_uint16_t(msg
, 14);
304 * @brief Get field current_battery from sys_status message
306 * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
308 static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t
*msg
)
310 return _MAV_RETURN_int16_t(msg
, 16);
314 * @brief Get field battery_remaining from sys_status message
316 * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
318 static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t
*msg
)
320 return _MAV_RETURN_int8_t(msg
, 30);
324 * @brief Get field drop_rate_comm from sys_status message
326 * @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)
328 static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t
*msg
)
330 return _MAV_RETURN_uint16_t(msg
, 18);
334 * @brief Get field errors_comm from sys_status message
336 * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
338 static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t
*msg
)
340 return _MAV_RETURN_uint16_t(msg
, 20);
344 * @brief Get field errors_count1 from sys_status message
346 * @return Autopilot-specific errors
348 static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t
*msg
)
350 return _MAV_RETURN_uint16_t(msg
, 22);
354 * @brief Get field errors_count2 from sys_status message
356 * @return Autopilot-specific errors
358 static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t
*msg
)
360 return _MAV_RETURN_uint16_t(msg
, 24);
364 * @brief Get field errors_count3 from sys_status message
366 * @return Autopilot-specific errors
368 static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t
*msg
)
370 return _MAV_RETURN_uint16_t(msg
, 26);
374 * @brief Get field errors_count4 from sys_status message
376 * @return Autopilot-specific errors
378 static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t
*msg
)
380 return _MAV_RETURN_uint16_t(msg
, 28);
384 * @brief Decode a sys_status message into a struct
386 * @param msg The message to decode
387 * @param sys_status C-struct to decode the message contents into
389 static inline void mavlink_msg_sys_status_decode(const mavlink_message_t
*msg
, mavlink_sys_status_t
*sys_status
)
391 #if MAVLINK_NEED_BYTE_SWAP
392 sys_status
->onboard_control_sensors_present
= mavlink_msg_sys_status_get_onboard_control_sensors_present(msg
);
393 sys_status
->onboard_control_sensors_enabled
= mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg
);
394 sys_status
->onboard_control_sensors_health
= mavlink_msg_sys_status_get_onboard_control_sensors_health(msg
);
395 sys_status
->load
= mavlink_msg_sys_status_get_load(msg
);
396 sys_status
->voltage_battery
= mavlink_msg_sys_status_get_voltage_battery(msg
);
397 sys_status
->current_battery
= mavlink_msg_sys_status_get_current_battery(msg
);
398 sys_status
->drop_rate_comm
= mavlink_msg_sys_status_get_drop_rate_comm(msg
);
399 sys_status
->errors_comm
= mavlink_msg_sys_status_get_errors_comm(msg
);
400 sys_status
->errors_count1
= mavlink_msg_sys_status_get_errors_count1(msg
);
401 sys_status
->errors_count2
= mavlink_msg_sys_status_get_errors_count2(msg
);
402 sys_status
->errors_count3
= mavlink_msg_sys_status_get_errors_count3(msg
);
403 sys_status
->errors_count4
= mavlink_msg_sys_status_get_errors_count4(msg
);
404 sys_status
->battery_remaining
= mavlink_msg_sys_status_get_battery_remaining(msg
);
406 memcpy(sys_status
, _MAV_PAYLOAD(msg
), 31);