mavlink_msg_vkfmu_status.h 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540
  1. #pragma once
  2. // MESSAGE VKFMU_STATUS PACKING
  3. #define MAVLINK_MSG_ID_VKFMU_STATUS 53001
  4. MAVPACKED(
  5. typedef struct __mavlink_vkfmu_status_t {
  6. uint32_t time_boot_ms; /*< [ms] Timestamp in ms from system boot.*/
  7. uint32_t flight_time; /*< [s] flight time in seconds*/
  8. uint32_t dist_to_tar; /*< [cm] distance to target position in cm*/
  9. float flight_dist; /*< [m] flight distance since this power up*/
  10. uint16_t ups_volt; /*< ups voltage in 0.1V*/
  11. uint16_t adc_volt; /*< adc voltage in 0.1V*/
  12. uint16_t servo_state; /*< bitmap for servo state*/
  13. uint8_t rtl_reason; /*< return to launch reason.*/
  14. uint8_t loiter_reason; /*< Loiter reason */
  15. uint8_t s_flag3; /*< fmu sflag3*/
  16. uint16_t servo_state2; /*< bitmap for servo state2*/
  17. }) mavlink_vkfmu_status_t;
  18. #define MAVLINK_MSG_ID_VKFMU_STATUS_LEN 27
  19. #define MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN 25
  20. #define MAVLINK_MSG_ID_53001_LEN 27
  21. #define MAVLINK_MSG_ID_53001_MIN_LEN 25
  22. #define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 136
  23. #define MAVLINK_MSG_ID_53001_CRC 136
  24. #if MAVLINK_COMMAND_24BIT
  25. #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
  26. 53001, \
  27. "VKFMU_STATUS", \
  28. 11, \
  29. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfmu_status_t, time_boot_ms) }, \
  30. { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
  31. { "loiter_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_vkfmu_status_t, loiter_reason) }, \
  32. { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
  33. { "ups_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vkfmu_status_t, ups_volt) }, \
  34. { "adc_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vkfmu_status_t, adc_volt) }, \
  35. { "flight_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vkfmu_status_t, flight_time) }, \
  36. { "dist_to_tar", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vkfmu_status_t, dist_to_tar) }, \
  37. { "servo_state", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_vkfmu_status_t, servo_state) }, \
  38. { "flight_dist", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vkfmu_status_t, flight_dist) }, \
  39. { "servo_state2", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_vkfmu_status_t, servo_state2) }, \
  40. } \
  41. }
  42. #else
  43. #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
  44. "VKFMU_STATUS", \
  45. 11, \
  46. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfmu_status_t, time_boot_ms) }, \
  47. { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
  48. { "loiter_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_vkfmu_status_t, loiter_reason) }, \
  49. { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
  50. { "ups_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vkfmu_status_t, ups_volt) }, \
  51. { "adc_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vkfmu_status_t, adc_volt) }, \
  52. { "flight_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vkfmu_status_t, flight_time) }, \
  53. { "dist_to_tar", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vkfmu_status_t, dist_to_tar) }, \
  54. { "servo_state", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_vkfmu_status_t, servo_state) }, \
  55. { "flight_dist", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vkfmu_status_t, flight_dist) }, \
  56. { "servo_state2", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_vkfmu_status_t, servo_state2) }, \
  57. } \
  58. }
  59. #endif
  60. /**
  61. * @brief Pack a vkfmu_status message
  62. * @param system_id ID of this system
  63. * @param component_id ID of this component (e.g. 200 for IMU)
  64. * @param msg The MAVLink message to compress the data into
  65. *
  66. * @param time_boot_ms [ms] Timestamp in ms from system boot.
  67. * @param rtl_reason return to launch reason.
  68. * @param loiter_reason Loiter reason
  69. * @param s_flag3 fmu sflag3
  70. * @param ups_volt ups voltage in 0.1V
  71. * @param adc_volt adc voltage in 0.1V
  72. * @param flight_time [s] flight time in seconds
  73. * @param dist_to_tar [cm] distance to target position in cm
  74. * @param servo_state bitmap for servo state
  75. * @param flight_dist [m] flight distance since this power up
  76. * @param servo_state2 bitmap for servo state2
  77. * @return length of the message in bytes (excluding serial stream start sign)
  78. */
  79. static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  80. uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist, uint16_t servo_state2)
  81. {
  82. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  83. char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
  84. _mav_put_uint32_t(buf, 0, time_boot_ms);
  85. _mav_put_uint32_t(buf, 4, flight_time);
  86. _mav_put_uint32_t(buf, 8, dist_to_tar);
  87. _mav_put_float(buf, 12, flight_dist);
  88. _mav_put_uint16_t(buf, 16, ups_volt);
  89. _mav_put_uint16_t(buf, 18, adc_volt);
  90. _mav_put_uint16_t(buf, 20, servo_state);
  91. _mav_put_uint8_t(buf, 22, rtl_reason);
  92. _mav_put_uint8_t(buf, 23, loiter_reason);
  93. _mav_put_uint8_t(buf, 24, s_flag3);
  94. _mav_put_uint16_t(buf, 25, servo_state2);
  95. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
  96. #else
  97. mavlink_vkfmu_status_t packet;
  98. packet.time_boot_ms = time_boot_ms;
  99. packet.flight_time = flight_time;
  100. packet.dist_to_tar = dist_to_tar;
  101. packet.flight_dist = flight_dist;
  102. packet.ups_volt = ups_volt;
  103. packet.adc_volt = adc_volt;
  104. packet.servo_state = servo_state;
  105. packet.rtl_reason = rtl_reason;
  106. packet.loiter_reason = loiter_reason;
  107. packet.s_flag3 = s_flag3;
  108. packet.servo_state2 = servo_state2;
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
  110. #endif
  111. msg->msgid = MAVLINK_MSG_ID_VKFMU_STATUS;
  112. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
  113. }
  114. /**
  115. * @brief Pack a vkfmu_status message
  116. * @param system_id ID of this system
  117. * @param component_id ID of this component (e.g. 200 for IMU)
  118. * @param status MAVLink status structure
  119. * @param msg The MAVLink message to compress the data into
  120. *
  121. * @param time_boot_ms [ms] Timestamp in ms from system boot.
  122. * @param rtl_reason return to launch reason.
  123. * @param loiter_reason Loiter reason
  124. * @param s_flag3 fmu sflag3
  125. * @param ups_volt ups voltage in 0.1V
  126. * @param adc_volt adc voltage in 0.1V
  127. * @param flight_time [s] flight time in seconds
  128. * @param dist_to_tar [cm] distance to target position in cm
  129. * @param servo_state bitmap for servo state
  130. * @param flight_dist [m] flight distance since this power up
  131. * @param servo_state2 bitmap for servo state2
  132. * @return length of the message in bytes (excluding serial stream start sign)
  133. */
  134. static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  135. uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist, uint16_t servo_state2)
  136. {
  137. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  138. char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
  139. _mav_put_uint32_t(buf, 0, time_boot_ms);
  140. _mav_put_uint32_t(buf, 4, flight_time);
  141. _mav_put_uint32_t(buf, 8, dist_to_tar);
  142. _mav_put_float(buf, 12, flight_dist);
  143. _mav_put_uint16_t(buf, 16, ups_volt);
  144. _mav_put_uint16_t(buf, 18, adc_volt);
  145. _mav_put_uint16_t(buf, 20, servo_state);
  146. _mav_put_uint8_t(buf, 22, rtl_reason);
  147. _mav_put_uint8_t(buf, 23, loiter_reason);
  148. _mav_put_uint8_t(buf, 24, s_flag3);
  149. _mav_put_uint16_t(buf, 25, servo_state2);
  150. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
  151. #else
  152. mavlink_vkfmu_status_t packet;
  153. packet.time_boot_ms = time_boot_ms;
  154. packet.flight_time = flight_time;
  155. packet.dist_to_tar = dist_to_tar;
  156. packet.flight_dist = flight_dist;
  157. packet.ups_volt = ups_volt;
  158. packet.adc_volt = adc_volt;
  159. packet.servo_state = servo_state;
  160. packet.rtl_reason = rtl_reason;
  161. packet.loiter_reason = loiter_reason;
  162. packet.s_flag3 = s_flag3;
  163. packet.servo_state2 = servo_state2;
  164. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
  165. #endif
  166. msg->msgid = MAVLINK_MSG_ID_VKFMU_STATUS;
  167. #if MAVLINK_CRC_EXTRA
  168. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
  169. #else
  170. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
  171. #endif
  172. }
  173. /**
  174. * @brief Pack a vkfmu_status message on a channel
  175. * @param system_id ID of this system
  176. * @param component_id ID of this component (e.g. 200 for IMU)
  177. * @param chan The MAVLink channel this message will be sent over
  178. * @param msg The MAVLink message to compress the data into
  179. * @param time_boot_ms [ms] Timestamp in ms from system boot.
  180. * @param rtl_reason return to launch reason.
  181. * @param loiter_reason Loiter reason
  182. * @param s_flag3 fmu sflag3
  183. * @param ups_volt ups voltage in 0.1V
  184. * @param adc_volt adc voltage in 0.1V
  185. * @param flight_time [s] flight time in seconds
  186. * @param dist_to_tar [cm] distance to target position in cm
  187. * @param servo_state bitmap for servo state
  188. * @param flight_dist [m] flight distance since this power up
  189. * @param servo_state2 bitmap for servo state2
  190. * @return length of the message in bytes (excluding serial stream start sign)
  191. */
  192. static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  193. mavlink_message_t* msg,
  194. uint32_t time_boot_ms,uint8_t rtl_reason,uint8_t loiter_reason,uint8_t s_flag3,uint16_t ups_volt,uint16_t adc_volt,uint32_t flight_time,uint32_t dist_to_tar,uint16_t servo_state,float flight_dist,uint16_t servo_state2)
  195. {
  196. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  197. char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
  198. _mav_put_uint32_t(buf, 0, time_boot_ms);
  199. _mav_put_uint32_t(buf, 4, flight_time);
  200. _mav_put_uint32_t(buf, 8, dist_to_tar);
  201. _mav_put_float(buf, 12, flight_dist);
  202. _mav_put_uint16_t(buf, 16, ups_volt);
  203. _mav_put_uint16_t(buf, 18, adc_volt);
  204. _mav_put_uint16_t(buf, 20, servo_state);
  205. _mav_put_uint8_t(buf, 22, rtl_reason);
  206. _mav_put_uint8_t(buf, 23, loiter_reason);
  207. _mav_put_uint8_t(buf, 24, s_flag3);
  208. _mav_put_uint16_t(buf, 25, servo_state2);
  209. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
  210. #else
  211. mavlink_vkfmu_status_t packet;
  212. packet.time_boot_ms = time_boot_ms;
  213. packet.flight_time = flight_time;
  214. packet.dist_to_tar = dist_to_tar;
  215. packet.flight_dist = flight_dist;
  216. packet.ups_volt = ups_volt;
  217. packet.adc_volt = adc_volt;
  218. packet.servo_state = servo_state;
  219. packet.rtl_reason = rtl_reason;
  220. packet.loiter_reason = loiter_reason;
  221. packet.s_flag3 = s_flag3;
  222. packet.servo_state2 = servo_state2;
  223. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
  224. #endif
  225. msg->msgid = MAVLINK_MSG_ID_VKFMU_STATUS;
  226. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
  227. }
  228. /**
  229. * @brief Encode a vkfmu_status struct
  230. *
  231. * @param system_id ID of this system
  232. * @param component_id ID of this component (e.g. 200 for IMU)
  233. * @param msg The MAVLink message to compress the data into
  234. * @param vkfmu_status C-struct to read the message contents from
  235. */
  236. static inline uint16_t mavlink_msg_vkfmu_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
  237. {
  238. return mavlink_msg_vkfmu_status_pack(system_id, component_id, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist, vkfmu_status->servo_state2);
  239. }
  240. /**
  241. * @brief Encode a vkfmu_status struct on a channel
  242. *
  243. * @param system_id ID of this system
  244. * @param component_id ID of this component (e.g. 200 for IMU)
  245. * @param chan The MAVLink channel this message will be sent over
  246. * @param msg The MAVLink message to compress the data into
  247. * @param vkfmu_status C-struct to read the message contents from
  248. */
  249. static inline uint16_t mavlink_msg_vkfmu_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
  250. {
  251. return mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, chan, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist, vkfmu_status->servo_state2);
  252. }
  253. /**
  254. * @brief Encode a vkfmu_status struct with provided status structure
  255. *
  256. * @param system_id ID of this system
  257. * @param component_id ID of this component (e.g. 200 for IMU)
  258. * @param status MAVLink status structure
  259. * @param msg The MAVLink message to compress the data into
  260. * @param vkfmu_status C-struct to read the message contents from
  261. */
  262. static inline uint16_t mavlink_msg_vkfmu_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
  263. {
  264. return mavlink_msg_vkfmu_status_pack_status(system_id, component_id, _status, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist, vkfmu_status->servo_state2);
  265. }
  266. /**
  267. * @brief Send a vkfmu_status message
  268. * @param chan MAVLink channel to send the message
  269. *
  270. * @param time_boot_ms [ms] Timestamp in ms from system boot.
  271. * @param rtl_reason return to launch reason.
  272. * @param loiter_reason Loiter reason
  273. * @param s_flag3 fmu sflag3
  274. * @param ups_volt ups voltage in 0.1V
  275. * @param adc_volt adc voltage in 0.1V
  276. * @param flight_time [s] flight time in seconds
  277. * @param dist_to_tar [cm] distance to target position in cm
  278. * @param servo_state bitmap for servo state
  279. * @param flight_dist [m] flight distance since this power up
  280. * @param servo_state2 bitmap for servo state2
  281. */
  282. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  283. static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist, uint16_t servo_state2)
  284. {
  285. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  286. char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
  287. _mav_put_uint32_t(buf, 0, time_boot_ms);
  288. _mav_put_uint32_t(buf, 4, flight_time);
  289. _mav_put_uint32_t(buf, 8, dist_to_tar);
  290. _mav_put_float(buf, 12, flight_dist);
  291. _mav_put_uint16_t(buf, 16, ups_volt);
  292. _mav_put_uint16_t(buf, 18, adc_volt);
  293. _mav_put_uint16_t(buf, 20, servo_state);
  294. _mav_put_uint8_t(buf, 22, rtl_reason);
  295. _mav_put_uint8_t(buf, 23, loiter_reason);
  296. _mav_put_uint8_t(buf, 24, s_flag3);
  297. _mav_put_uint16_t(buf, 25, servo_state2);
  298. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, buf, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
  299. #else
  300. mavlink_vkfmu_status_t packet;
  301. packet.time_boot_ms = time_boot_ms;
  302. packet.flight_time = flight_time;
  303. packet.dist_to_tar = dist_to_tar;
  304. packet.flight_dist = flight_dist;
  305. packet.ups_volt = ups_volt;
  306. packet.adc_volt = adc_volt;
  307. packet.servo_state = servo_state;
  308. packet.rtl_reason = rtl_reason;
  309. packet.loiter_reason = loiter_reason;
  310. packet.s_flag3 = s_flag3;
  311. packet.servo_state2 = servo_state2;
  312. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
  313. #endif
  314. }
  315. /**
  316. * @brief Send a vkfmu_status message
  317. * @param chan MAVLink channel to send the message
  318. * @param struct The MAVLink struct to serialize
  319. */
  320. static inline void mavlink_msg_vkfmu_status_send_struct(mavlink_channel_t chan, const mavlink_vkfmu_status_t* vkfmu_status)
  321. {
  322. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  323. mavlink_msg_vkfmu_status_send(chan, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist, vkfmu_status->servo_state2);
  324. #else
  325. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, (const char *)vkfmu_status, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
  326. #endif
  327. }
  328. #if MAVLINK_MSG_ID_VKFMU_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  329. /*
  330. This variant of _send() can be used to save stack space by re-using
  331. memory from the receive buffer. The caller provides a
  332. mavlink_message_t which is the size of a full mavlink message. This
  333. is usually the receive buffer for the channel, and allows a reply to an
  334. incoming message with minimum stack space usage.
  335. */
  336. static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist, uint16_t servo_state2)
  337. {
  338. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  339. char *buf = (char *)msgbuf;
  340. _mav_put_uint32_t(buf, 0, time_boot_ms);
  341. _mav_put_uint32_t(buf, 4, flight_time);
  342. _mav_put_uint32_t(buf, 8, dist_to_tar);
  343. _mav_put_float(buf, 12, flight_dist);
  344. _mav_put_uint16_t(buf, 16, ups_volt);
  345. _mav_put_uint16_t(buf, 18, adc_volt);
  346. _mav_put_uint16_t(buf, 20, servo_state);
  347. _mav_put_uint8_t(buf, 22, rtl_reason);
  348. _mav_put_uint8_t(buf, 23, loiter_reason);
  349. _mav_put_uint8_t(buf, 24, s_flag3);
  350. _mav_put_uint16_t(buf, 25, servo_state2);
  351. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, buf, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
  352. #else
  353. mavlink_vkfmu_status_t *packet = (mavlink_vkfmu_status_t *)msgbuf;
  354. packet->time_boot_ms = time_boot_ms;
  355. packet->flight_time = flight_time;
  356. packet->dist_to_tar = dist_to_tar;
  357. packet->flight_dist = flight_dist;
  358. packet->ups_volt = ups_volt;
  359. packet->adc_volt = adc_volt;
  360. packet->servo_state = servo_state;
  361. packet->rtl_reason = rtl_reason;
  362. packet->loiter_reason = loiter_reason;
  363. packet->s_flag3 = s_flag3;
  364. packet->servo_state2 = servo_state2;
  365. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, (const char *)packet, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
  366. #endif
  367. }
  368. #endif
  369. #endif
  370. // MESSAGE VKFMU_STATUS UNPACKING
  371. /**
  372. * @brief Get field time_boot_ms from vkfmu_status message
  373. *
  374. * @return [ms] Timestamp in ms from system boot.
  375. */
  376. static inline uint32_t mavlink_msg_vkfmu_status_get_time_boot_ms(const mavlink_message_t* msg)
  377. {
  378. return _MAV_RETURN_uint32_t(msg, 0);
  379. }
  380. /**
  381. * @brief Get field rtl_reason from vkfmu_status message
  382. *
  383. * @return return to launch reason.
  384. */
  385. static inline uint8_t mavlink_msg_vkfmu_status_get_rtl_reason(const mavlink_message_t* msg)
  386. {
  387. return _MAV_RETURN_uint8_t(msg, 22);
  388. }
  389. /**
  390. * @brief Get field loiter_reason from vkfmu_status message
  391. *
  392. * @return Loiter reason
  393. */
  394. static inline uint8_t mavlink_msg_vkfmu_status_get_loiter_reason(const mavlink_message_t* msg)
  395. {
  396. return _MAV_RETURN_uint8_t(msg, 23);
  397. }
  398. /**
  399. * @brief Get field s_flag3 from vkfmu_status message
  400. *
  401. * @return fmu sflag3
  402. */
  403. static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag3(const mavlink_message_t* msg)
  404. {
  405. return _MAV_RETURN_uint8_t(msg, 24);
  406. }
  407. /**
  408. * @brief Get field ups_volt from vkfmu_status message
  409. *
  410. * @return ups voltage in 0.1V
  411. */
  412. static inline uint16_t mavlink_msg_vkfmu_status_get_ups_volt(const mavlink_message_t* msg)
  413. {
  414. return _MAV_RETURN_uint16_t(msg, 16);
  415. }
  416. /**
  417. * @brief Get field adc_volt from vkfmu_status message
  418. *
  419. * @return adc voltage in 0.1V
  420. */
  421. static inline uint16_t mavlink_msg_vkfmu_status_get_adc_volt(const mavlink_message_t* msg)
  422. {
  423. return _MAV_RETURN_uint16_t(msg, 18);
  424. }
  425. /**
  426. * @brief Get field flight_time from vkfmu_status message
  427. *
  428. * @return [s] flight time in seconds
  429. */
  430. static inline uint32_t mavlink_msg_vkfmu_status_get_flight_time(const mavlink_message_t* msg)
  431. {
  432. return _MAV_RETURN_uint32_t(msg, 4);
  433. }
  434. /**
  435. * @brief Get field dist_to_tar from vkfmu_status message
  436. *
  437. * @return [cm] distance to target position in cm
  438. */
  439. static inline uint32_t mavlink_msg_vkfmu_status_get_dist_to_tar(const mavlink_message_t* msg)
  440. {
  441. return _MAV_RETURN_uint32_t(msg, 8);
  442. }
  443. /**
  444. * @brief Get field servo_state from vkfmu_status message
  445. *
  446. * @return bitmap for servo state
  447. */
  448. static inline uint16_t mavlink_msg_vkfmu_status_get_servo_state(const mavlink_message_t* msg)
  449. {
  450. return _MAV_RETURN_uint16_t(msg, 20);
  451. }
  452. /**
  453. * @brief Get field flight_dist from vkfmu_status message
  454. *
  455. * @return [m] flight distance since this power up
  456. */
  457. static inline float mavlink_msg_vkfmu_status_get_flight_dist(const mavlink_message_t* msg)
  458. {
  459. return _MAV_RETURN_float(msg, 12);
  460. }
  461. /**
  462. * @brief Get field servo_state2 from vkfmu_status message
  463. *
  464. * @return bitmap for servo state2
  465. */
  466. static inline uint16_t mavlink_msg_vkfmu_status_get_servo_state2(const mavlink_message_t* msg)
  467. {
  468. return _MAV_RETURN_uint16_t(msg, 25);
  469. }
  470. /**
  471. * @brief Decode a vkfmu_status message into a struct
  472. *
  473. * @param msg The message to decode
  474. * @param vkfmu_status C-struct to decode the message contents into
  475. */
  476. static inline void mavlink_msg_vkfmu_status_decode(const mavlink_message_t* msg, mavlink_vkfmu_status_t* vkfmu_status)
  477. {
  478. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  479. vkfmu_status->time_boot_ms = mavlink_msg_vkfmu_status_get_time_boot_ms(msg);
  480. vkfmu_status->flight_time = mavlink_msg_vkfmu_status_get_flight_time(msg);
  481. vkfmu_status->dist_to_tar = mavlink_msg_vkfmu_status_get_dist_to_tar(msg);
  482. vkfmu_status->flight_dist = mavlink_msg_vkfmu_status_get_flight_dist(msg);
  483. vkfmu_status->ups_volt = mavlink_msg_vkfmu_status_get_ups_volt(msg);
  484. vkfmu_status->adc_volt = mavlink_msg_vkfmu_status_get_adc_volt(msg);
  485. vkfmu_status->servo_state = mavlink_msg_vkfmu_status_get_servo_state(msg);
  486. vkfmu_status->rtl_reason = mavlink_msg_vkfmu_status_get_rtl_reason(msg);
  487. vkfmu_status->loiter_reason = mavlink_msg_vkfmu_status_get_loiter_reason(msg);
  488. vkfmu_status->s_flag3 = mavlink_msg_vkfmu_status_get_s_flag3(msg);
  489. vkfmu_status->servo_state2 = mavlink_msg_vkfmu_status_get_servo_state2(msg);
  490. #else
  491. uint8_t len = msg->len < MAVLINK_MSG_ID_VKFMU_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VKFMU_STATUS_LEN;
  492. memset(vkfmu_status, 0, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
  493. memcpy(vkfmu_status, _MAV_PAYLOAD(msg), len);
  494. #endif
  495. }