mavlink_msg_sys_status.h 26.9 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE SYS_STATUS PACKING

3
#define MAVLINK_MSG_ID_SYS_STATUS 1
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_sys_status_t
James Goppert's avatar
James Goppert committed
6
{
7 8 9 10
 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
 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
 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
 uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
lm's avatar
lm committed
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
lm's avatar
lm committed
13
 uint16_t watt; ///< Watts consumed from this battery since startup
LM's avatar
LM committed
14
 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)
15 16 17 18 19
 uint16_t errors_comm; ///< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
 uint16_t errors_count1; ///< Autopilot-specific errors
 uint16_t errors_count2; ///< Autopilot-specific errors
 uint16_t errors_count3; ///< Autopilot-specific errors
 uint16_t errors_count4; ///< Autopilot-specific errors
LM's avatar
LM committed
20
 int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
James Goppert's avatar
James Goppert committed
21 22
} mavlink_sys_status_t;

LM's avatar
LM committed
23 24
#define MAVLINK_MSG_ID_SYS_STATUS_LEN 33
#define MAVLINK_MSG_ID_1_LEN 33
lm's avatar
lm committed
25 26 27 28 29



#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
	"SYS_STATUS", \
LM's avatar
LM committed
30
	14, \
31 32 33 34 35 36 37
	{  { "onboard_control_sensors_present", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \
         { "onboard_control_sensors_enabled", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \
         { "onboard_control_sensors_health", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \
         { "load", MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \
         { "voltage_battery", MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \
         { "current_battery", MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \
         { "watt", MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, watt) }, \
LM's avatar
LM committed
38 39 40 41 42 43 44
         { "drop_rate_comm", MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \
         { "errors_comm", MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_comm) }, \
         { "errors_count1", MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count1) }, \
         { "errors_count2", MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count2) }, \
         { "errors_count3", MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count3) }, \
         { "errors_count4", MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_sys_status_t, errors_count4) }, \
         { "battery_remaining", MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_sys_status_t, battery_remaining) }, \
lm's avatar
lm committed
45 46 47 48
         } \
}


James Goppert's avatar
James Goppert committed
49 50 51 52 53 54
/**
 * @brief Pack a sys_status message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
55 56 57
 * @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
 * @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
 * @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
58
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
59
 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
60
 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
61
 * @param watt Watts consumed from this battery since startup
LM's avatar
LM committed
62 63
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
 * @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 65 66 67 68
 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
 * @param errors_count1 Autopilot-specific errors
 * @param errors_count2 Autopilot-specific errors
 * @param errors_count3 Autopilot-specific errors
 * @param errors_count4 Autopilot-specific errors
James Goppert's avatar
James Goppert committed
69 70
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
71
static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
LM's avatar
LM committed
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, uint16_t watt, 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)
James Goppert's avatar
James Goppert committed
73
{
LM's avatar
LM committed
74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[33];
	_mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
	_mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
	_mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
	_mav_put_uint16_t(buf, 12, load);
	_mav_put_uint16_t(buf, 14, voltage_battery);
	_mav_put_int16_t(buf, 16, current_battery);
	_mav_put_uint16_t(buf, 18, watt);
	_mav_put_uint16_t(buf, 20, drop_rate_comm);
	_mav_put_uint16_t(buf, 22, errors_comm);
	_mav_put_uint16_t(buf, 24, errors_count1);
	_mav_put_uint16_t(buf, 26, errors_count2);
	_mav_put_uint16_t(buf, 28, errors_count3);
	_mav_put_uint16_t(buf, 30, errors_count4);
	_mav_put_int8_t(buf, 32, battery_remaining);

        memcpy(_MAV_PAYLOAD(msg), buf, 33);
#else
	mavlink_sys_status_t packet;
	packet.onboard_control_sensors_present = onboard_control_sensors_present;
	packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
	packet.onboard_control_sensors_health = onboard_control_sensors_health;
	packet.load = load;
	packet.voltage_battery = voltage_battery;
	packet.current_battery = current_battery;
	packet.watt = watt;
	packet.drop_rate_comm = drop_rate_comm;
	packet.errors_comm = errors_comm;
	packet.errors_count1 = errors_count1;
	packet.errors_count2 = errors_count2;
	packet.errors_count3 = errors_count3;
	packet.errors_count4 = errors_count4;
	packet.battery_remaining = battery_remaining;

        memcpy(_MAV_PAYLOAD(msg), &packet, 33);
#endif
James Goppert's avatar
James Goppert committed
111

LM's avatar
LM committed
112 113
	msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
	return mavlink_finalize_message(msg, system_id, component_id, 33, 28);
James Goppert's avatar
James Goppert committed
114 115 116
}

/**
lm's avatar
lm committed
117
 * @brief Pack a sys_status message on a channel
James Goppert's avatar
James Goppert committed
118 119 120 121
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
122 123 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: 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
 * @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
 * @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
125
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
126
 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
127
 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
128
 * @param watt Watts consumed from this battery since startup
LM's avatar
LM committed
129 130
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
 * @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)
131 132 133 134 135
 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
 * @param errors_count1 Autopilot-specific errors
 * @param errors_count2 Autopilot-specific errors
 * @param errors_count3 Autopilot-specific errors
 * @param errors_count4 Autopilot-specific errors
James Goppert's avatar
James Goppert committed
136 137
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
138 139
static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
LM's avatar
LM committed
140
						           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,uint16_t watt,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)
lm's avatar
lm committed
141
{
LM's avatar
LM committed
142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[33];
	_mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
	_mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
	_mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
	_mav_put_uint16_t(buf, 12, load);
	_mav_put_uint16_t(buf, 14, voltage_battery);
	_mav_put_int16_t(buf, 16, current_battery);
	_mav_put_uint16_t(buf, 18, watt);
	_mav_put_uint16_t(buf, 20, drop_rate_comm);
	_mav_put_uint16_t(buf, 22, errors_comm);
	_mav_put_uint16_t(buf, 24, errors_count1);
	_mav_put_uint16_t(buf, 26, errors_count2);
	_mav_put_uint16_t(buf, 28, errors_count3);
	_mav_put_uint16_t(buf, 30, errors_count4);
	_mav_put_int8_t(buf, 32, battery_remaining);

        memcpy(_MAV_PAYLOAD(msg), buf, 33);
#else
	mavlink_sys_status_t packet;
	packet.onboard_control_sensors_present = onboard_control_sensors_present;
	packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
	packet.onboard_control_sensors_health = onboard_control_sensors_health;
	packet.load = load;
	packet.voltage_battery = voltage_battery;
	packet.current_battery = current_battery;
	packet.watt = watt;
	packet.drop_rate_comm = drop_rate_comm;
	packet.errors_comm = errors_comm;
	packet.errors_count1 = errors_count1;
	packet.errors_count2 = errors_count2;
	packet.errors_count3 = errors_count3;
	packet.errors_count4 = errors_count4;
	packet.battery_remaining = battery_remaining;

        memcpy(_MAV_PAYLOAD(msg), &packet, 33);
#endif
lm's avatar
lm committed
179

LM's avatar
LM committed
180 181
	msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 28);
lm's avatar
lm committed
182 183
}

James Goppert's avatar
James Goppert committed
184 185 186 187 188 189 190 191 192 193
/**
 * @brief Encode a sys_status struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param sys_status C-struct to read the message contents from
 */
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)
{
LM's avatar
LM committed
194
	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->watt, 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);
James Goppert's avatar
James Goppert committed
195 196 197 198 199 200
}

/**
 * @brief Send a sys_status message
 * @param chan MAVLink channel to send the message
 *
201 202 203
 * @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
 * @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
 * @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
204
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
205
 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
206
 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
207
 * @param watt Watts consumed from this battery since startup
LM's avatar
LM committed
208 209
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
 * @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)
210 211 212 213 214
 * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
 * @param errors_count1 Autopilot-specific errors
 * @param errors_count2 Autopilot-specific errors
 * @param errors_count3 Autopilot-specific errors
 * @param errors_count4 Autopilot-specific errors
James Goppert's avatar
James Goppert committed
215
 */
lm's avatar
lm committed
216 217
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

LM's avatar
LM committed
218
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, uint16_t watt, 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)
lm's avatar
lm committed
219
{
LM's avatar
LM committed
220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[33];
	_mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
	_mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
	_mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
	_mav_put_uint16_t(buf, 12, load);
	_mav_put_uint16_t(buf, 14, voltage_battery);
	_mav_put_int16_t(buf, 16, current_battery);
	_mav_put_uint16_t(buf, 18, watt);
	_mav_put_uint16_t(buf, 20, drop_rate_comm);
	_mav_put_uint16_t(buf, 22, errors_comm);
	_mav_put_uint16_t(buf, 24, errors_count1);
	_mav_put_uint16_t(buf, 26, errors_count2);
	_mav_put_uint16_t(buf, 28, errors_count3);
	_mav_put_uint16_t(buf, 30, errors_count4);
	_mav_put_int8_t(buf, 32, battery_remaining);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, 33, 28);
#else
	mavlink_sys_status_t packet;
	packet.onboard_control_sensors_present = onboard_control_sensors_present;
	packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
	packet.onboard_control_sensors_health = onboard_control_sensors_health;
	packet.load = load;
	packet.voltage_battery = voltage_battery;
	packet.current_battery = current_battery;
	packet.watt = watt;
	packet.drop_rate_comm = drop_rate_comm;
	packet.errors_comm = errors_comm;
	packet.errors_count1 = errors_count1;
	packet.errors_count2 = errors_count2;
	packet.errors_count3 = errors_count3;
	packet.errors_count4 = errors_count4;
	packet.battery_remaining = battery_remaining;

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, 33, 28);
#endif
James Goppert's avatar
James Goppert committed
257 258 259
}

#endif
lm's avatar
lm committed
260

James Goppert's avatar
James Goppert committed
261 262
// MESSAGE SYS_STATUS UNPACKING

lm's avatar
lm committed
263

James Goppert's avatar
James Goppert committed
264
/**
265
 * @brief Get field onboard_control_sensors_present from sys_status message
James Goppert's avatar
James Goppert committed
266
 *
267
 * @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
James Goppert's avatar
James Goppert committed
268
 */
269
static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
270
{
LM's avatar
LM committed
271
	return _MAV_RETURN_uint32_t(msg,  0);
James Goppert's avatar
James Goppert committed
272 273 274
}

/**
275
 * @brief Get field onboard_control_sensors_enabled from sys_status message
James Goppert's avatar
James Goppert committed
276
 *
277
 * @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
James Goppert's avatar
James Goppert committed
278
 */
279
static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
280
{
LM's avatar
LM committed
281
	return _MAV_RETURN_uint32_t(msg,  4);
James Goppert's avatar
James Goppert committed
282 283 284
}

/**
285
 * @brief Get field onboard_control_sensors_health from sys_status message
James Goppert's avatar
James Goppert committed
286
 *
287
 * @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
James Goppert's avatar
James Goppert committed
288
 */
289
static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
290
{
LM's avatar
LM committed
291
	return _MAV_RETURN_uint32_t(msg,  8);
James Goppert's avatar
James Goppert committed
292 293 294 295 296
}

/**
 * @brief Get field load from sys_status message
 *
297
 * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
James Goppert's avatar
James Goppert committed
298 299 300
 */
static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg)
{
LM's avatar
LM committed
301
	return _MAV_RETURN_uint16_t(msg,  12);
James Goppert's avatar
James Goppert committed
302 303 304
}

/**
305
 * @brief Get field voltage_battery from sys_status message
James Goppert's avatar
James Goppert committed
306 307 308
 *
 * @return Battery voltage, in millivolts (1 = 1 millivolt)
 */
309
static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
310
{
LM's avatar
LM committed
311
	return _MAV_RETURN_uint16_t(msg,  14);
James Goppert's avatar
James Goppert committed
312 313 314
}

/**
315
 * @brief Get field current_battery from sys_status message
James Goppert's avatar
James Goppert committed
316
 *
317
 * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
James Goppert's avatar
James Goppert committed
318
 */
319
static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
320
{
LM's avatar
LM committed
321
	return _MAV_RETURN_int16_t(msg,  16);
James Goppert's avatar
James Goppert committed
322 323 324
}

/**
325
 * @brief Get field watt from sys_status message
James Goppert's avatar
James Goppert committed
326
 *
327
 * @return Watts consumed from this battery since startup
James Goppert's avatar
James Goppert committed
328
 */
329
static inline uint16_t mavlink_msg_sys_status_get_watt(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
330
{
LM's avatar
LM committed
331
	return _MAV_RETURN_uint16_t(msg,  18);
332 333 334
}

/**
335
 * @brief Get field battery_remaining from sys_status message
336
 *
LM's avatar
LM committed
337
 * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
338
 */
339
static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
340
{
LM's avatar
LM committed
341 342 343 344 345 346 347 348 349 350 351
	return _MAV_RETURN_int8_t(msg,  32);
}

/**
 * @brief Get field drop_rate_comm from sys_status message
 *
 * @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)
 */
static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg)
{
	return _MAV_RETURN_uint16_t(msg,  20);
352 353 354
}

/**
355
 * @brief Get field errors_comm from sys_status message
356
 *
357
 * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
358
 */
359
static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg)
360
{
LM's avatar
LM committed
361
	return _MAV_RETURN_uint16_t(msg,  22);
362 363 364
}

/**
365
 * @brief Get field errors_count1 from sys_status message
366
 *
367
 * @return Autopilot-specific errors
368
 */
369
static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg)
370
{
LM's avatar
LM committed
371
	return _MAV_RETURN_uint16_t(msg,  24);
372 373 374
}

/**
375
 * @brief Get field errors_count2 from sys_status message
376
 *
377
 * @return Autopilot-specific errors
378
 */
379
static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg)
380
{
LM's avatar
LM committed
381
	return _MAV_RETURN_uint16_t(msg,  26);
382 383 384
}

/**
385
 * @brief Get field errors_count3 from sys_status message
386
 *
387
 * @return Autopilot-specific errors
388
 */
389
static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg)
390
{
LM's avatar
LM committed
391
	return _MAV_RETURN_uint16_t(msg,  28);
392 393 394 395 396 397 398 399 400
}

/**
 * @brief Get field errors_count4 from sys_status message
 *
 * @return Autopilot-specific errors
 */
static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg)
{
LM's avatar
LM committed
401
	return _MAV_RETURN_uint16_t(msg,  30);
James Goppert's avatar
James Goppert committed
402 403 404 405 406 407 408 409 410 411
}

/**
 * @brief Decode a sys_status message into a struct
 *
 * @param msg The message to decode
 * @param sys_status C-struct to decode the message contents into
 */
static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
{
lm's avatar
lm committed
412 413 414 415 416 417 418 419
#if MAVLINK_NEED_BYTE_SWAP
	sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg);
	sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg);
	sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg);
	sys_status->load = mavlink_msg_sys_status_get_load(msg);
	sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg);
	sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg);
	sys_status->watt = mavlink_msg_sys_status_get_watt(msg);
LM's avatar
LM committed
420
	sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg);
421 422 423 424 425 426
	sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg);
	sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg);
	sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg);
	sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg);
	sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg);
	sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg);
lm's avatar
lm committed
427
#else
LM's avatar
LM committed
428
	memcpy(sys_status, _MAV_PAYLOAD(msg), 33);
lm's avatar
lm committed
429
#endif
James Goppert's avatar
James Goppert committed
430
}