mavlink_msg_sys_status.h 42 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680
  1. #pragma once
  2. // MESSAGE SYS_STATUS PACKING
  3. #define MAVLINK_MSG_ID_SYS_STATUS 1
  4. MAVPACKED(
  5. typedef struct __mavlink_sys_status_t {
  6. uint32_t onboard_control_sensors_present; /*< Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.*/
  7. uint32_t onboard_control_sensors_enabled; /*< Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.*/
  8. uint32_t onboard_control_sensors_health; /*< Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.*/
  9. uint16_t load; /*< [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000*/
  10. uint16_t voltage_battery; /*< [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot*/
  11. int16_t current_battery; /*< [cA] Battery current, -1: Current not sent by autopilot*/
  12. uint16_t drop_rate_comm; /*< [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/
  13. uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/
  14. uint16_t errors_count1; /*< Autopilot-specific errors*/
  15. uint16_t errors_count2; /*< Autopilot-specific errors*/
  16. uint16_t errors_count3; /*< Autopilot-specific errors*/
  17. uint16_t errors_count4; /*< Autopilot-specific errors*/
  18. int8_t battery_remaining; /*< [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot*/
  19. uint32_t onboard_control_sensors_present_extended; /*< Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.*/
  20. uint32_t onboard_control_sensors_enabled_extended; /*< Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.*/
  21. uint32_t onboard_control_sensors_health_extended; /*< Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.*/
  22. }) mavlink_sys_status_t;
  23. #define MAVLINK_MSG_ID_SYS_STATUS_LEN 43
  24. #define MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN 31
  25. #define MAVLINK_MSG_ID_1_LEN 43
  26. #define MAVLINK_MSG_ID_1_MIN_LEN 31
  27. #define MAVLINK_MSG_ID_SYS_STATUS_CRC 124
  28. #define MAVLINK_MSG_ID_1_CRC 124
  29. #if MAVLINK_COMMAND_24BIT
  30. #define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
  31. 1, \
  32. "SYS_STATUS", \
  33. 16, \
  34. { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \
  35. { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \
  36. { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \
  37. { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \
  38. { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \
  39. { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \
  40. { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \
  41. { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \
  42. { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \
  43. { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \
  44. { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \
  45. { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \
  46. { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \
  47. { "onboard_control_sensors_present_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 31, offsetof(mavlink_sys_status_t, onboard_control_sensors_present_extended) }, \
  48. { "onboard_control_sensors_enabled_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 35, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled_extended) }, \
  49. { "onboard_control_sensors_health_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 39, offsetof(mavlink_sys_status_t, onboard_control_sensors_health_extended) }, \
  50. } \
  51. }
  52. #else
  53. #define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
  54. "SYS_STATUS", \
  55. 16, \
  56. { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \
  57. { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \
  58. { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \
  59. { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \
  60. { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \
  61. { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \
  62. { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \
  63. { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \
  64. { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \
  65. { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \
  66. { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \
  67. { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \
  68. { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \
  69. { "onboard_control_sensors_present_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 31, offsetof(mavlink_sys_status_t, onboard_control_sensors_present_extended) }, \
  70. { "onboard_control_sensors_enabled_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 35, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled_extended) }, \
  71. { "onboard_control_sensors_health_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 39, offsetof(mavlink_sys_status_t, onboard_control_sensors_health_extended) }, \
  72. } \
  73. }
  74. #endif
  75. /**
  76. * @brief Pack a sys_status message
  77. * @param system_id ID of this system
  78. * @param component_id ID of this component (e.g. 200 for IMU)
  79. * @param msg The MAVLink message to compress the data into
  80. *
  81. * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  82. * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  83. * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  84. * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000
  85. * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot
  86. * @param current_battery [cA] Battery current, -1: Current not sent by autopilot
  87. * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot
  88. * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  89. * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  90. * @param errors_count1 Autopilot-specific errors
  91. * @param errors_count2 Autopilot-specific errors
  92. * @param errors_count3 Autopilot-specific errors
  93. * @param errors_count4 Autopilot-specific errors
  94. * @param onboard_control_sensors_present_extended Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  95. * @param onboard_control_sensors_enabled_extended Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  96. * @param onboard_control_sensors_health_extended Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  97. * @return length of the message in bytes (excluding serial stream start sign)
  98. */
  99. static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  100. 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, uint32_t onboard_control_sensors_present_extended, uint32_t onboard_control_sensors_enabled_extended, uint32_t onboard_control_sensors_health_extended)
  101. {
  102. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  103. char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN];
  104. _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
  105. _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
  106. _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
  107. _mav_put_uint16_t(buf, 12, load);
  108. _mav_put_uint16_t(buf, 14, voltage_battery);
  109. _mav_put_int16_t(buf, 16, current_battery);
  110. _mav_put_uint16_t(buf, 18, drop_rate_comm);
  111. _mav_put_uint16_t(buf, 20, errors_comm);
  112. _mav_put_uint16_t(buf, 22, errors_count1);
  113. _mav_put_uint16_t(buf, 24, errors_count2);
  114. _mav_put_uint16_t(buf, 26, errors_count3);
  115. _mav_put_uint16_t(buf, 28, errors_count4);
  116. _mav_put_int8_t(buf, 30, battery_remaining);
  117. _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended);
  118. _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended);
  119. _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended);
  120. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN);
  121. #else
  122. mavlink_sys_status_t packet;
  123. packet.onboard_control_sensors_present = onboard_control_sensors_present;
  124. packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
  125. packet.onboard_control_sensors_health = onboard_control_sensors_health;
  126. packet.load = load;
  127. packet.voltage_battery = voltage_battery;
  128. packet.current_battery = current_battery;
  129. packet.drop_rate_comm = drop_rate_comm;
  130. packet.errors_comm = errors_comm;
  131. packet.errors_count1 = errors_count1;
  132. packet.errors_count2 = errors_count2;
  133. packet.errors_count3 = errors_count3;
  134. packet.errors_count4 = errors_count4;
  135. packet.battery_remaining = battery_remaining;
  136. packet.onboard_control_sensors_present_extended = onboard_control_sensors_present_extended;
  137. packet.onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended;
  138. packet.onboard_control_sensors_health_extended = onboard_control_sensors_health_extended;
  139. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN);
  140. #endif
  141. msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
  142. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
  143. }
  144. /**
  145. * @brief Pack a sys_status message
  146. * @param system_id ID of this system
  147. * @param component_id ID of this component (e.g. 200 for IMU)
  148. * @param status MAVLink status structure
  149. * @param msg The MAVLink message to compress the data into
  150. *
  151. * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  152. * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  153. * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  154. * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000
  155. * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot
  156. * @param current_battery [cA] Battery current, -1: Current not sent by autopilot
  157. * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot
  158. * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  159. * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  160. * @param errors_count1 Autopilot-specific errors
  161. * @param errors_count2 Autopilot-specific errors
  162. * @param errors_count3 Autopilot-specific errors
  163. * @param errors_count4 Autopilot-specific errors
  164. * @param onboard_control_sensors_present_extended Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  165. * @param onboard_control_sensors_enabled_extended Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  166. * @param onboard_control_sensors_health_extended Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  167. * @return length of the message in bytes (excluding serial stream start sign)
  168. */
  169. static inline uint16_t mavlink_msg_sys_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  170. 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, uint32_t onboard_control_sensors_present_extended, uint32_t onboard_control_sensors_enabled_extended, uint32_t onboard_control_sensors_health_extended)
  171. {
  172. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  173. char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN];
  174. _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
  175. _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
  176. _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
  177. _mav_put_uint16_t(buf, 12, load);
  178. _mav_put_uint16_t(buf, 14, voltage_battery);
  179. _mav_put_int16_t(buf, 16, current_battery);
  180. _mav_put_uint16_t(buf, 18, drop_rate_comm);
  181. _mav_put_uint16_t(buf, 20, errors_comm);
  182. _mav_put_uint16_t(buf, 22, errors_count1);
  183. _mav_put_uint16_t(buf, 24, errors_count2);
  184. _mav_put_uint16_t(buf, 26, errors_count3);
  185. _mav_put_uint16_t(buf, 28, errors_count4);
  186. _mav_put_int8_t(buf, 30, battery_remaining);
  187. _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended);
  188. _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended);
  189. _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended);
  190. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN);
  191. #else
  192. mavlink_sys_status_t packet;
  193. packet.onboard_control_sensors_present = onboard_control_sensors_present;
  194. packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
  195. packet.onboard_control_sensors_health = onboard_control_sensors_health;
  196. packet.load = load;
  197. packet.voltage_battery = voltage_battery;
  198. packet.current_battery = current_battery;
  199. packet.drop_rate_comm = drop_rate_comm;
  200. packet.errors_comm = errors_comm;
  201. packet.errors_count1 = errors_count1;
  202. packet.errors_count2 = errors_count2;
  203. packet.errors_count3 = errors_count3;
  204. packet.errors_count4 = errors_count4;
  205. packet.battery_remaining = battery_remaining;
  206. packet.onboard_control_sensors_present_extended = onboard_control_sensors_present_extended;
  207. packet.onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended;
  208. packet.onboard_control_sensors_health_extended = onboard_control_sensors_health_extended;
  209. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN);
  210. #endif
  211. msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
  212. #if MAVLINK_CRC_EXTRA
  213. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
  214. #else
  215. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN);
  216. #endif
  217. }
  218. /**
  219. * @brief Pack a sys_status message on a channel
  220. * @param system_id ID of this system
  221. * @param component_id ID of this component (e.g. 200 for IMU)
  222. * @param chan The MAVLink channel this message will be sent over
  223. * @param msg The MAVLink message to compress the data into
  224. * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  225. * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  226. * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  227. * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000
  228. * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot
  229. * @param current_battery [cA] Battery current, -1: Current not sent by autopilot
  230. * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot
  231. * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  232. * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  233. * @param errors_count1 Autopilot-specific errors
  234. * @param errors_count2 Autopilot-specific errors
  235. * @param errors_count3 Autopilot-specific errors
  236. * @param errors_count4 Autopilot-specific errors
  237. * @param onboard_control_sensors_present_extended Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  238. * @param onboard_control_sensors_enabled_extended Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  239. * @param onboard_control_sensors_health_extended Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  240. * @return length of the message in bytes (excluding serial stream start sign)
  241. */
  242. static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  243. mavlink_message_t* msg,
  244. 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,uint32_t onboard_control_sensors_present_extended,uint32_t onboard_control_sensors_enabled_extended,uint32_t onboard_control_sensors_health_extended)
  245. {
  246. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  247. char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN];
  248. _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
  249. _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
  250. _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
  251. _mav_put_uint16_t(buf, 12, load);
  252. _mav_put_uint16_t(buf, 14, voltage_battery);
  253. _mav_put_int16_t(buf, 16, current_battery);
  254. _mav_put_uint16_t(buf, 18, drop_rate_comm);
  255. _mav_put_uint16_t(buf, 20, errors_comm);
  256. _mav_put_uint16_t(buf, 22, errors_count1);
  257. _mav_put_uint16_t(buf, 24, errors_count2);
  258. _mav_put_uint16_t(buf, 26, errors_count3);
  259. _mav_put_uint16_t(buf, 28, errors_count4);
  260. _mav_put_int8_t(buf, 30, battery_remaining);
  261. _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended);
  262. _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended);
  263. _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended);
  264. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN);
  265. #else
  266. mavlink_sys_status_t packet;
  267. packet.onboard_control_sensors_present = onboard_control_sensors_present;
  268. packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
  269. packet.onboard_control_sensors_health = onboard_control_sensors_health;
  270. packet.load = load;
  271. packet.voltage_battery = voltage_battery;
  272. packet.current_battery = current_battery;
  273. packet.drop_rate_comm = drop_rate_comm;
  274. packet.errors_comm = errors_comm;
  275. packet.errors_count1 = errors_count1;
  276. packet.errors_count2 = errors_count2;
  277. packet.errors_count3 = errors_count3;
  278. packet.errors_count4 = errors_count4;
  279. packet.battery_remaining = battery_remaining;
  280. packet.onboard_control_sensors_present_extended = onboard_control_sensors_present_extended;
  281. packet.onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended;
  282. packet.onboard_control_sensors_health_extended = onboard_control_sensors_health_extended;
  283. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN);
  284. #endif
  285. msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
  286. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
  287. }
  288. /**
  289. * @brief Encode a sys_status struct
  290. *
  291. * @param system_id ID of this system
  292. * @param component_id ID of this component (e.g. 200 for IMU)
  293. * @param msg The MAVLink message to compress the data into
  294. * @param sys_status C-struct to read the message contents from
  295. */
  296. 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)
  297. {
  298. 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, sys_status->onboard_control_sensors_present_extended, sys_status->onboard_control_sensors_enabled_extended, sys_status->onboard_control_sensors_health_extended);
  299. }
  300. /**
  301. * @brief Encode a sys_status struct on a channel
  302. *
  303. * @param system_id ID of this system
  304. * @param component_id ID of this component (e.g. 200 for IMU)
  305. * @param chan The MAVLink channel this message will be sent over
  306. * @param msg The MAVLink message to compress the data into
  307. * @param sys_status C-struct to read the message contents from
  308. */
  309. static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
  310. {
  311. return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4, sys_status->onboard_control_sensors_present_extended, sys_status->onboard_control_sensors_enabled_extended, sys_status->onboard_control_sensors_health_extended);
  312. }
  313. /**
  314. * @brief Encode a sys_status struct with provided status structure
  315. *
  316. * @param system_id ID of this system
  317. * @param component_id ID of this component (e.g. 200 for IMU)
  318. * @param status MAVLink status structure
  319. * @param msg The MAVLink message to compress the data into
  320. * @param sys_status C-struct to read the message contents from
  321. */
  322. static inline uint16_t mavlink_msg_sys_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
  323. {
  324. return mavlink_msg_sys_status_pack_status(system_id, component_id, _status, 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, sys_status->onboard_control_sensors_present_extended, sys_status->onboard_control_sensors_enabled_extended, sys_status->onboard_control_sensors_health_extended);
  325. }
  326. /**
  327. * @brief Send a sys_status message
  328. * @param chan MAVLink channel to send the message
  329. *
  330. * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  331. * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  332. * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  333. * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000
  334. * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot
  335. * @param current_battery [cA] Battery current, -1: Current not sent by autopilot
  336. * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot
  337. * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  338. * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  339. * @param errors_count1 Autopilot-specific errors
  340. * @param errors_count2 Autopilot-specific errors
  341. * @param errors_count3 Autopilot-specific errors
  342. * @param errors_count4 Autopilot-specific errors
  343. * @param onboard_control_sensors_present_extended Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  344. * @param onboard_control_sensors_enabled_extended Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  345. * @param onboard_control_sensors_health_extended Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  346. */
  347. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  348. 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, uint32_t onboard_control_sensors_present_extended, uint32_t onboard_control_sensors_enabled_extended, uint32_t onboard_control_sensors_health_extended)
  349. {
  350. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  351. char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN];
  352. _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
  353. _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
  354. _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
  355. _mav_put_uint16_t(buf, 12, load);
  356. _mav_put_uint16_t(buf, 14, voltage_battery);
  357. _mav_put_int16_t(buf, 16, current_battery);
  358. _mav_put_uint16_t(buf, 18, drop_rate_comm);
  359. _mav_put_uint16_t(buf, 20, errors_comm);
  360. _mav_put_uint16_t(buf, 22, errors_count1);
  361. _mav_put_uint16_t(buf, 24, errors_count2);
  362. _mav_put_uint16_t(buf, 26, errors_count3);
  363. _mav_put_uint16_t(buf, 28, errors_count4);
  364. _mav_put_int8_t(buf, 30, battery_remaining);
  365. _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended);
  366. _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended);
  367. _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended);
  368. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
  369. #else
  370. mavlink_sys_status_t packet;
  371. packet.onboard_control_sensors_present = onboard_control_sensors_present;
  372. packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
  373. packet.onboard_control_sensors_health = onboard_control_sensors_health;
  374. packet.load = load;
  375. packet.voltage_battery = voltage_battery;
  376. packet.current_battery = current_battery;
  377. packet.drop_rate_comm = drop_rate_comm;
  378. packet.errors_comm = errors_comm;
  379. packet.errors_count1 = errors_count1;
  380. packet.errors_count2 = errors_count2;
  381. packet.errors_count3 = errors_count3;
  382. packet.errors_count4 = errors_count4;
  383. packet.battery_remaining = battery_remaining;
  384. packet.onboard_control_sensors_present_extended = onboard_control_sensors_present_extended;
  385. packet.onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended;
  386. packet.onboard_control_sensors_health_extended = onboard_control_sensors_health_extended;
  387. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
  388. #endif
  389. }
  390. /**
  391. * @brief Send a sys_status message
  392. * @param chan MAVLink channel to send the message
  393. * @param struct The MAVLink struct to serialize
  394. */
  395. static inline void mavlink_msg_sys_status_send_struct(mavlink_channel_t chan, const mavlink_sys_status_t* sys_status)
  396. {
  397. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  398. mavlink_msg_sys_status_send(chan, 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, sys_status->onboard_control_sensors_present_extended, sys_status->onboard_control_sensors_enabled_extended, sys_status->onboard_control_sensors_health_extended);
  399. #else
  400. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)sys_status, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
  401. #endif
  402. }
  403. #if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  404. /*
  405. This variant of _send() can be used to save stack space by re-using
  406. memory from the receive buffer. The caller provides a
  407. mavlink_message_t which is the size of a full mavlink message. This
  408. is usually the receive buffer for the channel, and allows a reply to an
  409. incoming message with minimum stack space usage.
  410. */
  411. static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4, uint32_t onboard_control_sensors_present_extended, uint32_t onboard_control_sensors_enabled_extended, uint32_t onboard_control_sensors_health_extended)
  412. {
  413. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  414. char *buf = (char *)msgbuf;
  415. _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
  416. _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
  417. _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
  418. _mav_put_uint16_t(buf, 12, load);
  419. _mav_put_uint16_t(buf, 14, voltage_battery);
  420. _mav_put_int16_t(buf, 16, current_battery);
  421. _mav_put_uint16_t(buf, 18, drop_rate_comm);
  422. _mav_put_uint16_t(buf, 20, errors_comm);
  423. _mav_put_uint16_t(buf, 22, errors_count1);
  424. _mav_put_uint16_t(buf, 24, errors_count2);
  425. _mav_put_uint16_t(buf, 26, errors_count3);
  426. _mav_put_uint16_t(buf, 28, errors_count4);
  427. _mav_put_int8_t(buf, 30, battery_remaining);
  428. _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended);
  429. _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended);
  430. _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended);
  431. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
  432. #else
  433. mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf;
  434. packet->onboard_control_sensors_present = onboard_control_sensors_present;
  435. packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled;
  436. packet->onboard_control_sensors_health = onboard_control_sensors_health;
  437. packet->load = load;
  438. packet->voltage_battery = voltage_battery;
  439. packet->current_battery = current_battery;
  440. packet->drop_rate_comm = drop_rate_comm;
  441. packet->errors_comm = errors_comm;
  442. packet->errors_count1 = errors_count1;
  443. packet->errors_count2 = errors_count2;
  444. packet->errors_count3 = errors_count3;
  445. packet->errors_count4 = errors_count4;
  446. packet->battery_remaining = battery_remaining;
  447. packet->onboard_control_sensors_present_extended = onboard_control_sensors_present_extended;
  448. packet->onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended;
  449. packet->onboard_control_sensors_health_extended = onboard_control_sensors_health_extended;
  450. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
  451. #endif
  452. }
  453. #endif
  454. #endif
  455. // MESSAGE SYS_STATUS UNPACKING
  456. /**
  457. * @brief Get field onboard_control_sensors_present from sys_status message
  458. *
  459. * @return Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  460. */
  461. static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg)
  462. {
  463. return _MAV_RETURN_uint32_t(msg, 0);
  464. }
  465. /**
  466. * @brief Get field onboard_control_sensors_enabled from sys_status message
  467. *
  468. * @return Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  469. */
  470. static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg)
  471. {
  472. return _MAV_RETURN_uint32_t(msg, 4);
  473. }
  474. /**
  475. * @brief Get field onboard_control_sensors_health from sys_status message
  476. *
  477. * @return Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  478. */
  479. static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg)
  480. {
  481. return _MAV_RETURN_uint32_t(msg, 8);
  482. }
  483. /**
  484. * @brief Get field load from sys_status message
  485. *
  486. * @return [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000
  487. */
  488. static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg)
  489. {
  490. return _MAV_RETURN_uint16_t(msg, 12);
  491. }
  492. /**
  493. * @brief Get field voltage_battery from sys_status message
  494. *
  495. * @return [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot
  496. */
  497. static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg)
  498. {
  499. return _MAV_RETURN_uint16_t(msg, 14);
  500. }
  501. /**
  502. * @brief Get field current_battery from sys_status message
  503. *
  504. * @return [cA] Battery current, -1: Current not sent by autopilot
  505. */
  506. static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg)
  507. {
  508. return _MAV_RETURN_int16_t(msg, 16);
  509. }
  510. /**
  511. * @brief Get field battery_remaining from sys_status message
  512. *
  513. * @return [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot
  514. */
  515. static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
  516. {
  517. return _MAV_RETURN_int8_t(msg, 30);
  518. }
  519. /**
  520. * @brief Get field drop_rate_comm from sys_status message
  521. *
  522. * @return [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  523. */
  524. static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg)
  525. {
  526. return _MAV_RETURN_uint16_t(msg, 18);
  527. }
  528. /**
  529. * @brief Get field errors_comm from sys_status message
  530. *
  531. * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
  532. */
  533. static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg)
  534. {
  535. return _MAV_RETURN_uint16_t(msg, 20);
  536. }
  537. /**
  538. * @brief Get field errors_count1 from sys_status message
  539. *
  540. * @return Autopilot-specific errors
  541. */
  542. static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg)
  543. {
  544. return _MAV_RETURN_uint16_t(msg, 22);
  545. }
  546. /**
  547. * @brief Get field errors_count2 from sys_status message
  548. *
  549. * @return Autopilot-specific errors
  550. */
  551. static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg)
  552. {
  553. return _MAV_RETURN_uint16_t(msg, 24);
  554. }
  555. /**
  556. * @brief Get field errors_count3 from sys_status message
  557. *
  558. * @return Autopilot-specific errors
  559. */
  560. static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg)
  561. {
  562. return _MAV_RETURN_uint16_t(msg, 26);
  563. }
  564. /**
  565. * @brief Get field errors_count4 from sys_status message
  566. *
  567. * @return Autopilot-specific errors
  568. */
  569. static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg)
  570. {
  571. return _MAV_RETURN_uint16_t(msg, 28);
  572. }
  573. /**
  574. * @brief Get field onboard_control_sensors_present_extended from sys_status message
  575. *
  576. * @return Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
  577. */
  578. static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present_extended(const mavlink_message_t* msg)
  579. {
  580. return _MAV_RETURN_uint32_t(msg, 31);
  581. }
  582. /**
  583. * @brief Get field onboard_control_sensors_enabled_extended from sys_status message
  584. *
  585. * @return Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
  586. */
  587. static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled_extended(const mavlink_message_t* msg)
  588. {
  589. return _MAV_RETURN_uint32_t(msg, 35);
  590. }
  591. /**
  592. * @brief Get field onboard_control_sensors_health_extended from sys_status message
  593. *
  594. * @return Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
  595. */
  596. static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health_extended(const mavlink_message_t* msg)
  597. {
  598. return _MAV_RETURN_uint32_t(msg, 39);
  599. }
  600. /**
  601. * @brief Decode a sys_status message into a struct
  602. *
  603. * @param msg The message to decode
  604. * @param sys_status C-struct to decode the message contents into
  605. */
  606. static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
  607. {
  608. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  609. sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg);
  610. sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg);
  611. sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg);
  612. sys_status->load = mavlink_msg_sys_status_get_load(msg);
  613. sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg);
  614. sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg);
  615. sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg);
  616. sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg);
  617. sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg);
  618. sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg);
  619. sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg);
  620. sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg);
  621. sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg);
  622. sys_status->onboard_control_sensors_present_extended = mavlink_msg_sys_status_get_onboard_control_sensors_present_extended(msg);
  623. sys_status->onboard_control_sensors_enabled_extended = mavlink_msg_sys_status_get_onboard_control_sensors_enabled_extended(msg);
  624. sys_status->onboard_control_sensors_health_extended = mavlink_msg_sys_status_get_onboard_control_sensors_health_extended(msg);
  625. #else
  626. uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_SYS_STATUS_LEN;
  627. memset(sys_status, 0, MAVLINK_MSG_ID_SYS_STATUS_LEN);
  628. memcpy(sys_status, _MAV_PAYLOAD(msg), len);
  629. #endif
  630. }