mavlink_msg_sys_status.h 29.6 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
14 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
 int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 200%), -1: autopilot estimate the remaining battery
James Goppert's avatar
James Goppert committed
20 21
} mavlink_sys_status_t;

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", \
29 30 31 32 33 34 35 36 37 38 39 40 41 42
	13, \
	{  { "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) }, \
         { "errors_comm", MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \
         { "errors_count1", MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \
         { "errors_count2", MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \
         { "errors_count3", MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \
         { "errors_count4", MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \
         { "battery_remaining", 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
56
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
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 watt Watts consumed from this battery since startup
60 61 62 63 64 65
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 200%), -1: autopilot estimate the remaining battery
 * @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,
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, uint16_t watt, int8_t battery_remaining, 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 71 72
{
	msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;

73 74 75 76 77 78 79 80 81 82 83 84 85 86 87
	put_uint32_t_by_index(msg, 0, 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
	put_uint32_t_by_index(msg, 4, 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
	put_uint32_t_by_index(msg, 8, 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
	put_uint16_t_by_index(msg, 12, load); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
	put_uint16_t_by_index(msg, 14, voltage_battery); // Battery voltage, in millivolts (1 = 1 millivolt)
	put_int16_t_by_index(msg, 16, current_battery); // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
	put_uint16_t_by_index(msg, 18, watt); // Watts consumed from this battery since startup
	put_uint16_t_by_index(msg, 20, errors_comm); // Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
	put_uint16_t_by_index(msg, 22, errors_count1); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 24, errors_count2); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 26, errors_count3); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 28, errors_count4); // Autopilot-specific errors
	put_int8_t_by_index(msg, 30, battery_remaining); // Remaining battery energy: (0%: 0, 100%: 200%), -1: autopilot estimate the remaining battery

	return mavlink_finalize_message(msg, system_id, component_id, 31, 236);
James Goppert's avatar
James Goppert committed
88 89 90
}

/**
lm's avatar
lm committed
91
 * @brief Pack a sys_status message on a channel
James Goppert's avatar
James Goppert committed
92 93 94 95
 * @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
96 97 98
 * @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
99
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
100
 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
101
 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
102
 * @param watt Watts consumed from this battery since startup
103 104 105 106 107 108
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 200%), -1: autopilot estimate the remaining battery
 * @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
109 110
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
111 112
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,
113
						           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 errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4)
lm's avatar
lm committed
114 115 116
{
	msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;

117 118 119 120 121 122 123 124 125 126 127 128 129 130 131
	put_uint32_t_by_index(msg, 0, 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
	put_uint32_t_by_index(msg, 4, 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
	put_uint32_t_by_index(msg, 8, 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
	put_uint16_t_by_index(msg, 12, load); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
	put_uint16_t_by_index(msg, 14, voltage_battery); // Battery voltage, in millivolts (1 = 1 millivolt)
	put_int16_t_by_index(msg, 16, current_battery); // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
	put_uint16_t_by_index(msg, 18, watt); // Watts consumed from this battery since startup
	put_uint16_t_by_index(msg, 20, errors_comm); // Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
	put_uint16_t_by_index(msg, 22, errors_count1); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 24, errors_count2); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 26, errors_count3); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 28, errors_count4); // Autopilot-specific errors
	put_int8_t_by_index(msg, 30, battery_remaining); // Remaining battery energy: (0%: 0, 100%: 200%), -1: autopilot estimate the remaining battery

	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 31, 236);
lm's avatar
lm committed
132 133
}

James Goppert's avatar
James Goppert committed
134 135 136 137 138 139 140 141 142 143
/**
 * @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)
{
144
	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->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
145 146 147 148 149 150
}

/**
 * @brief Send a sys_status message
 * @param chan MAVLink channel to send the message
 *
151 152 153
 * @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
154
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
155
 * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
156
 * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
157
 * @param watt Watts consumed from this battery since startup
158 159 160 161 162 163
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 200%), -1: autopilot estimate the remaining battery
 * @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
164
 */
lm's avatar
lm committed
165 166
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

167
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 errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4)
lm's avatar
lm committed
168
{
169
	MAVLINK_ALIGNED_MESSAGE(msg, 31);
LM's avatar
LM committed
170 171
	msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;

172 173 174 175 176 177 178 179 180 181 182 183 184 185 186
	put_uint32_t_by_index(msg, 0, 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
	put_uint32_t_by_index(msg, 4, 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
	put_uint32_t_by_index(msg, 8, 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
	put_uint16_t_by_index(msg, 12, load); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 10'000) should be always below 10'000
	put_uint16_t_by_index(msg, 14, voltage_battery); // Battery voltage, in millivolts (1 = 1 millivolt)
	put_int16_t_by_index(msg, 16, current_battery); // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
	put_uint16_t_by_index(msg, 18, watt); // Watts consumed from this battery since startup
	put_uint16_t_by_index(msg, 20, errors_comm); // Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
	put_uint16_t_by_index(msg, 22, errors_count1); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 24, errors_count2); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 26, errors_count3); // Autopilot-specific errors
	put_uint16_t_by_index(msg, 28, errors_count4); // Autopilot-specific errors
	put_int8_t_by_index(msg, 30, battery_remaining); // Remaining battery energy: (0%: 0, 100%: 200%), -1: autopilot estimate the remaining battery

	mavlink_finalize_message_chan_send(msg, chan, 31, 236);
James Goppert's avatar
James Goppert committed
187 188 189
}

#endif
lm's avatar
lm committed
190

James Goppert's avatar
James Goppert committed
191 192
// MESSAGE SYS_STATUS UNPACKING

lm's avatar
lm committed
193

James Goppert's avatar
James Goppert committed
194
/**
195
 * @brief Get field onboard_control_sensors_present from sys_status message
James Goppert's avatar
James Goppert committed
196
 *
197
 * @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
198
 */
199
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
200
{
201
	return MAVLINK_MSG_RETURN_uint32_t(msg,  0);
James Goppert's avatar
James Goppert committed
202 203 204
}

/**
205
 * @brief Get field onboard_control_sensors_enabled from sys_status message
James Goppert's avatar
James Goppert committed
206
 *
207
 * @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
208
 */
209
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
210
{
211
	return MAVLINK_MSG_RETURN_uint32_t(msg,  4);
James Goppert's avatar
James Goppert committed
212 213 214
}

/**
215
 * @brief Get field onboard_control_sensors_health from sys_status message
James Goppert's avatar
James Goppert committed
216
 *
217
 * @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
218
 */
219
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
220
{
221
	return MAVLINK_MSG_RETURN_uint32_t(msg,  8);
James Goppert's avatar
James Goppert committed
222 223 224 225 226
}

/**
 * @brief Get field load from sys_status message
 *
227
 * @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
228 229 230
 */
static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg)
{
231
	return MAVLINK_MSG_RETURN_uint16_t(msg,  12);
James Goppert's avatar
James Goppert committed
232 233 234
}

/**
235
 * @brief Get field voltage_battery from sys_status message
James Goppert's avatar
James Goppert committed
236 237 238
 *
 * @return Battery voltage, in millivolts (1 = 1 millivolt)
 */
239
static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
240
{
241
	return MAVLINK_MSG_RETURN_uint16_t(msg,  14);
James Goppert's avatar
James Goppert committed
242 243 244
}

/**
245
 * @brief Get field current_battery from sys_status message
James Goppert's avatar
James Goppert committed
246
 *
247
 * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
James Goppert's avatar
James Goppert committed
248
 */
249
static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
250
{
251
	return MAVLINK_MSG_RETURN_int16_t(msg,  16);
James Goppert's avatar
James Goppert committed
252 253 254
}

/**
255
 * @brief Get field watt from sys_status message
James Goppert's avatar
James Goppert committed
256
 *
257
 * @return Watts consumed from this battery since startup
James Goppert's avatar
James Goppert committed
258
 */
259
static inline uint16_t mavlink_msg_sys_status_get_watt(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
260
{
261
	return MAVLINK_MSG_RETURN_uint16_t(msg,  18);
262 263 264
}

/**
265
 * @brief Get field battery_remaining from sys_status message
266
 *
267
 * @return Remaining battery energy: (0%: 0, 100%: 200%), -1: autopilot estimate the remaining battery
268
 */
269
static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
270
{
271
	return MAVLINK_MSG_RETURN_int8_t(msg,  30);
272 273 274
}

/**
275
 * @brief Get field errors_comm from sys_status message
276
 *
277
 * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
278
 */
279
static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg)
280
{
281
	return MAVLINK_MSG_RETURN_uint16_t(msg,  20);
282 283 284
}

/**
285
 * @brief Get field errors_count1 from sys_status message
286
 *
287
 * @return Autopilot-specific errors
288
 */
289
static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg)
290
{
291
	return MAVLINK_MSG_RETURN_uint16_t(msg,  22);
292 293 294
}

/**
295
 * @brief Get field errors_count2 from sys_status message
296
 *
297
 * @return Autopilot-specific errors
298
 */
299
static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg)
300
{
301
	return MAVLINK_MSG_RETURN_uint16_t(msg,  24);
302 303 304
}

/**
305
 * @brief Get field errors_count3 from sys_status message
306
 *
307
 * @return Autopilot-specific errors
308
 */
309
static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg)
310
{
311 312 313 314 315 316 317 318 319 320 321
	return MAVLINK_MSG_RETURN_uint16_t(msg,  26);
}

/**
 * @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)
{
	return MAVLINK_MSG_RETURN_uint16_t(msg,  28);
James Goppert's avatar
James Goppert committed
322 323 324 325 326 327 328 329 330 331
}

/**
 * @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
332 333 334 335 336 337 338 339
#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);
340 341 342 343 344 345
	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
346
#else
347
	memcpy(sys_status, MAVLINK_PAYLOAD(msg), 31);
lm's avatar
lm committed
348
#endif
James Goppert's avatar
James Goppert committed
349
}