mavlink_msg_sys_status.h 26.2 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
 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
lm's avatar
lm committed
10
 uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
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 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 15 16 17 18
 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
19
 int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
James Goppert's avatar
James Goppert committed
20 21
} mavlink_sys_status_t;

lm's avatar
lm committed
22 23
#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31
#define MAVLINK_MSG_ID_1_LEN 31
lm's avatar
lm committed
24 25 26 27 28



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


James Goppert's avatar
James Goppert committed
47 48 49 50 51 52
/**
 * @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
 *
53 54 55
 * @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
lm's avatar
lm committed
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
LM's avatar
LM committed
59 60
 * @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)
61 62 63 64 65
 * @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
66 67
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
68
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
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)
James Goppert's avatar
James Goppert committed
70
{
LM's avatar
LM committed
71
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
72
	char buf[31];
LM's avatar
LM committed
73 74 75 76 77 78
	_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);
lm's avatar
lm committed
79 80 81 82 83 84 85 86
	_mav_put_uint16_t(buf, 18, drop_rate_comm);
	_mav_put_uint16_t(buf, 20, errors_comm);
	_mav_put_uint16_t(buf, 22, errors_count1);
	_mav_put_uint16_t(buf, 24, errors_count2);
	_mav_put_uint16_t(buf, 26, errors_count3);
	_mav_put_uint16_t(buf, 28, errors_count4);
	_mav_put_int8_t(buf, 30, battery_remaining);

87
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 31);
LM's avatar
LM committed
88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103
#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.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;

104
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 31);
LM's avatar
LM committed
105
#endif
James Goppert's avatar
James Goppert committed
106

LM's avatar
LM committed
107
	msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
lm's avatar
lm committed
108
	return mavlink_finalize_message(msg, system_id, component_id, 31, 124);
James Goppert's avatar
James Goppert committed
109 110 111
}

/**
lm's avatar
lm committed
112
 * @brief Pack a sys_status message on a channel
James Goppert's avatar
James Goppert committed
113 114 115 116
 * @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
117 118 119
 * @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
lm's avatar
lm committed
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
LM's avatar
LM committed
123 124
 * @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)
125 126 127 128 129
 * @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
130 131
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
132 133
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
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)
lm's avatar
lm committed
135
{
LM's avatar
LM committed
136
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
137
	char buf[31];
LM's avatar
LM committed
138 139 140 141 142 143
	_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);
lm's avatar
lm committed
144 145 146 147 148 149 150 151
	_mav_put_uint16_t(buf, 18, drop_rate_comm);
	_mav_put_uint16_t(buf, 20, errors_comm);
	_mav_put_uint16_t(buf, 22, errors_count1);
	_mav_put_uint16_t(buf, 24, errors_count2);
	_mav_put_uint16_t(buf, 26, errors_count3);
	_mav_put_uint16_t(buf, 28, errors_count4);
	_mav_put_int8_t(buf, 30, battery_remaining);

152
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 31);
LM's avatar
LM committed
153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168
#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.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;

169
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 31);
LM's avatar
LM committed
170
#endif
lm's avatar
lm committed
171

LM's avatar
LM committed
172
	msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
lm's avatar
lm committed
173
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 31, 124);
lm's avatar
lm committed
174 175
}

James Goppert's avatar
James Goppert committed
176 177 178 179 180 181 182 183 184 185
/**
 * @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
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);
James Goppert's avatar
James Goppert committed
187 188 189 190 191 192
}

/**
 * @brief Send a sys_status message
 * @param chan MAVLink channel to send the message
 *
193 194 195
 * @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
lm's avatar
lm committed
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
LM's avatar
LM committed
199 200
 * @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)
201 202 203 204 205
 * @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
206
 */
lm's avatar
lm committed
207 208
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
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)
lm's avatar
lm committed
210
{
LM's avatar
LM committed
211
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
212
	char buf[31];
LM's avatar
LM committed
213 214 215 216 217 218
	_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);
lm's avatar
lm committed
219 220 221 222 223 224 225 226 227
	_mav_put_uint16_t(buf, 18, drop_rate_comm);
	_mav_put_uint16_t(buf, 20, errors_comm);
	_mav_put_uint16_t(buf, 22, errors_count1);
	_mav_put_uint16_t(buf, 24, errors_count2);
	_mav_put_uint16_t(buf, 26, errors_count3);
	_mav_put_uint16_t(buf, 28, errors_count4);
	_mav_put_int8_t(buf, 30, battery_remaining);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, 31, 124);
LM's avatar
LM committed
228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243
#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.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;

lm's avatar
lm committed
244
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, 31, 124);
LM's avatar
LM committed
245
#endif
James Goppert's avatar
James Goppert committed
246 247 248
}

#endif
lm's avatar
lm committed
249

James Goppert's avatar
James Goppert committed
250 251
// MESSAGE SYS_STATUS UNPACKING

lm's avatar
lm committed
252

James Goppert's avatar
James Goppert committed
253
/**
254
 * @brief Get field onboard_control_sensors_present from sys_status message
James Goppert's avatar
James Goppert committed
255
 *
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
James Goppert's avatar
James Goppert committed
257
 */
258
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
259
{
LM's avatar
LM committed
260
	return _MAV_RETURN_uint32_t(msg,  0);
James Goppert's avatar
James Goppert committed
261 262 263
}

/**
264
 * @brief Get field onboard_control_sensors_enabled from sys_status message
James Goppert's avatar
James Goppert committed
265
 *
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
James Goppert's avatar
James Goppert committed
267
 */
268
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
269
{
LM's avatar
LM committed
270
	return _MAV_RETURN_uint32_t(msg,  4);
James Goppert's avatar
James Goppert committed
271 272 273
}

/**
274
 * @brief Get field onboard_control_sensors_health from sys_status message
James Goppert's avatar
James Goppert committed
275
 *
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
James Goppert's avatar
James Goppert committed
277
 */
278
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
279
{
LM's avatar
LM committed
280
	return _MAV_RETURN_uint32_t(msg,  8);
James Goppert's avatar
James Goppert committed
281 282 283 284 285
}

/**
 * @brief Get field load from sys_status message
 *
lm's avatar
lm committed
286
 * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
James Goppert's avatar
James Goppert committed
287 288 289
 */
static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg)
{
LM's avatar
LM committed
290
	return _MAV_RETURN_uint16_t(msg,  12);
James Goppert's avatar
James Goppert committed
291 292 293
}

/**
294
 * @brief Get field voltage_battery from sys_status message
James Goppert's avatar
James Goppert committed
295 296 297
 *
 * @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)
James Goppert's avatar
James Goppert committed
299
{
LM's avatar
LM committed
300
	return _MAV_RETURN_uint16_t(msg,  14);
James Goppert's avatar
James Goppert committed
301 302 303
}

/**
304
 * @brief Get field current_battery from sys_status message
James Goppert's avatar
James Goppert committed
305
 *
306
 * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
James Goppert's avatar
James Goppert committed
307
 */
308
static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
309
{
LM's avatar
LM committed
310
	return _MAV_RETURN_int16_t(msg,  16);
James Goppert's avatar
James Goppert committed
311 312
}

313
/**
314
 * @brief Get field battery_remaining from sys_status message
315
 *
LM's avatar
LM committed
316
 * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
317
 */
318
static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
319
{
lm's avatar
lm committed
320
	return _MAV_RETURN_int8_t(msg,  30);
LM's avatar
LM committed
321 322 323 324 325 326 327 328 329
}

/**
 * @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)
{
lm's avatar
lm committed
330
	return _MAV_RETURN_uint16_t(msg,  18);
331 332 333
}

/**
334
 * @brief Get field errors_comm from sys_status message
335
 *
336
 * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
337
 */
338
static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg)
339
{
lm's avatar
lm committed
340
	return _MAV_RETURN_uint16_t(msg,  20);
341 342 343
}

/**
344
 * @brief Get field errors_count1 from sys_status message
345
 *
346
 * @return Autopilot-specific errors
347
 */
348
static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg)
349
{
lm's avatar
lm committed
350
	return _MAV_RETURN_uint16_t(msg,  22);
351 352 353
}

/**
354
 * @brief Get field errors_count2 from sys_status message
355
 *
356
 * @return Autopilot-specific errors
357
 */
358
static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg)
359
{
lm's avatar
lm committed
360
	return _MAV_RETURN_uint16_t(msg,  24);
361 362 363
}

/**
364
 * @brief Get field errors_count3 from sys_status message
365
 *
366
 * @return Autopilot-specific errors
367
 */
368
static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg)
369
{
lm's avatar
lm committed
370
	return _MAV_RETURN_uint16_t(msg,  26);
371 372 373 374 375 376 377 378 379
}

/**
 * @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
380
	return _MAV_RETURN_uint16_t(msg,  28);
James Goppert's avatar
James Goppert committed
381 382 383 384 385 386 387 388 389 390
}

/**
 * @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
391 392 393 394 395 396 397
#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);
LM's avatar
LM committed
398
	sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg);
399 400 401 402 403 404
	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
405
#else
lm's avatar
lm committed
406
	memcpy(sys_status, _MAV_PAYLOAD(msg), 31);
lm's avatar
lm committed
407
#endif
James Goppert's avatar
James Goppert committed
408
}