mavlink_msg_vkfly_edu_status.h 34 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792
  1. #pragma once
  2. // MESSAGE VKFLY_EDU_STATUS PACKING
  3. #define MAVLINK_MSG_ID_VKFLY_EDU_STATUS 53025
  4. typedef struct __mavlink_vkfly_edu_status_t {
  5. uint64_t unix_timestamp; /*< [ms] Unix timestamp in ms, from 1 Jan 1970.*/
  6. uint32_t boot_timestamp; /*< [ms] Timestamp in ms from system boot.*/
  7. uint32_t seq; /*< Sequence number for this package.*/
  8. uint32_t dev_sn; /*< Device SN number.*/
  9. int32_t longitude; /*< [degE7] wgs84 longitude*/
  10. int32_t latitude; /*< [degE7] wgs84 latitude*/
  11. float amsl; /*< [m] altitude amsl*/
  12. float alt_relative; /*< [m] altitude above takeoff*/
  13. int16_t ve; /*< [cm/s] */
  14. int16_t vn; /*< [cm/s] */
  15. int16_t vu; /*< [cm/s] */
  16. int16_t yaw; /*< [cdeg] */
  17. int16_t pitch; /*< [cdeg] */
  18. int16_t roll; /*< [cdeg] */
  19. int16_t yaw_rate; /*< [cdeg/s] */
  20. uint8_t dev_type; /*< 0 for flight controller. 1 for elec-stake*/
  21. uint8_t retry_cnt; /*< Retry send this message count.*/
  22. uint8_t fix_type; /*< 0 no fix, 1 single, 2 RTK*/
  23. uint8_t reserve; /*< */
  24. uint8_t flight_mode; /*< */
  25. } mavlink_vkfly_edu_status_t;
  26. #define MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN 55
  27. #define MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN 55
  28. #define MAVLINK_MSG_ID_53025_LEN 55
  29. #define MAVLINK_MSG_ID_53025_MIN_LEN 55
  30. #define MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC 24
  31. #define MAVLINK_MSG_ID_53025_CRC 24
  32. #if MAVLINK_COMMAND_24BIT
  33. #define MAVLINK_MESSAGE_INFO_VKFLY_EDU_STATUS { \
  34. 53025, \
  35. "VKFLY_EDU_STATUS", \
  36. 20, \
  37. { { "unix_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vkfly_edu_status_t, unix_timestamp) }, \
  38. { "boot_timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vkfly_edu_status_t, boot_timestamp) }, \
  39. { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_vkfly_edu_status_t, seq) }, \
  40. { "dev_sn", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_vkfly_edu_status_t, dev_sn) }, \
  41. { "dev_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_vkfly_edu_status_t, dev_type) }, \
  42. { "retry_cnt", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_vkfly_edu_status_t, retry_cnt) }, \
  43. { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_vkfly_edu_status_t, fix_type) }, \
  44. { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_vkfly_edu_status_t, reserve) }, \
  45. { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_vkfly_edu_status_t, longitude) }, \
  46. { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_vkfly_edu_status_t, latitude) }, \
  47. { "amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vkfly_edu_status_t, amsl) }, \
  48. { "alt_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vkfly_edu_status_t, alt_relative) }, \
  49. { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_vkfly_edu_status_t, ve) }, \
  50. { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_vkfly_edu_status_t, vn) }, \
  51. { "vu", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_vkfly_edu_status_t, vu) }, \
  52. { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 42, offsetof(mavlink_vkfly_edu_status_t, yaw) }, \
  53. { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_vkfly_edu_status_t, pitch) }, \
  54. { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_vkfly_edu_status_t, roll) }, \
  55. { "yaw_rate", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_vkfly_edu_status_t, yaw_rate) }, \
  56. { "flight_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_vkfly_edu_status_t, flight_mode) }, \
  57. } \
  58. }
  59. #else
  60. #define MAVLINK_MESSAGE_INFO_VKFLY_EDU_STATUS { \
  61. "VKFLY_EDU_STATUS", \
  62. 20, \
  63. { { "unix_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vkfly_edu_status_t, unix_timestamp) }, \
  64. { "boot_timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vkfly_edu_status_t, boot_timestamp) }, \
  65. { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_vkfly_edu_status_t, seq) }, \
  66. { "dev_sn", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_vkfly_edu_status_t, dev_sn) }, \
  67. { "dev_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_vkfly_edu_status_t, dev_type) }, \
  68. { "retry_cnt", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_vkfly_edu_status_t, retry_cnt) }, \
  69. { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_vkfly_edu_status_t, fix_type) }, \
  70. { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_vkfly_edu_status_t, reserve) }, \
  71. { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_vkfly_edu_status_t, longitude) }, \
  72. { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_vkfly_edu_status_t, latitude) }, \
  73. { "amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vkfly_edu_status_t, amsl) }, \
  74. { "alt_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vkfly_edu_status_t, alt_relative) }, \
  75. { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_vkfly_edu_status_t, ve) }, \
  76. { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_vkfly_edu_status_t, vn) }, \
  77. { "vu", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_vkfly_edu_status_t, vu) }, \
  78. { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 42, offsetof(mavlink_vkfly_edu_status_t, yaw) }, \
  79. { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_vkfly_edu_status_t, pitch) }, \
  80. { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_vkfly_edu_status_t, roll) }, \
  81. { "yaw_rate", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_vkfly_edu_status_t, yaw_rate) }, \
  82. { "flight_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_vkfly_edu_status_t, flight_mode) }, \
  83. } \
  84. }
  85. #endif
  86. /**
  87. * @brief Pack a vkfly_edu_status message
  88. * @param system_id ID of this system
  89. * @param component_id ID of this component (e.g. 200 for IMU)
  90. * @param msg The MAVLink message to compress the data into
  91. *
  92. * @param unix_timestamp [ms] Unix timestamp in ms, from 1 Jan 1970.
  93. * @param boot_timestamp [ms] Timestamp in ms from system boot.
  94. * @param seq Sequence number for this package.
  95. * @param dev_sn Device SN number.
  96. * @param dev_type 0 for flight controller. 1 for elec-stake
  97. * @param retry_cnt Retry send this message count.
  98. * @param fix_type 0 no fix, 1 single, 2 RTK
  99. * @param reserve
  100. * @param longitude [degE7] wgs84 longitude
  101. * @param latitude [degE7] wgs84 latitude
  102. * @param amsl [m] altitude amsl
  103. * @param alt_relative [m] altitude above takeoff
  104. * @param ve [cm/s]
  105. * @param vn [cm/s]
  106. * @param vu [cm/s]
  107. * @param yaw [cdeg]
  108. * @param pitch [cdeg]
  109. * @param roll [cdeg]
  110. * @param yaw_rate [cdeg/s]
  111. * @param flight_mode
  112. * @return length of the message in bytes (excluding serial stream start sign)
  113. */
  114. static inline uint16_t mavlink_msg_vkfly_edu_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  115. uint64_t unix_timestamp, uint32_t boot_timestamp, uint32_t seq, uint32_t dev_sn, uint8_t dev_type, uint8_t retry_cnt, uint8_t fix_type, uint8_t reserve, int32_t longitude, int32_t latitude, float amsl, float alt_relative, int16_t ve, int16_t vn, int16_t vu, int16_t yaw, int16_t pitch, int16_t roll, int16_t yaw_rate, uint8_t flight_mode)
  116. {
  117. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  118. char buf[MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN];
  119. _mav_put_uint64_t(buf, 0, unix_timestamp);
  120. _mav_put_uint32_t(buf, 8, boot_timestamp);
  121. _mav_put_uint32_t(buf, 12, seq);
  122. _mav_put_uint32_t(buf, 16, dev_sn);
  123. _mav_put_int32_t(buf, 20, longitude);
  124. _mav_put_int32_t(buf, 24, latitude);
  125. _mav_put_float(buf, 28, amsl);
  126. _mav_put_float(buf, 32, alt_relative);
  127. _mav_put_int16_t(buf, 36, ve);
  128. _mav_put_int16_t(buf, 38, vn);
  129. _mav_put_int16_t(buf, 40, vu);
  130. _mav_put_int16_t(buf, 42, yaw);
  131. _mav_put_int16_t(buf, 44, pitch);
  132. _mav_put_int16_t(buf, 46, roll);
  133. _mav_put_int16_t(buf, 48, yaw_rate);
  134. _mav_put_uint8_t(buf, 50, dev_type);
  135. _mav_put_uint8_t(buf, 51, retry_cnt);
  136. _mav_put_uint8_t(buf, 52, fix_type);
  137. _mav_put_uint8_t(buf, 53, reserve);
  138. _mav_put_uint8_t(buf, 54, flight_mode);
  139. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN);
  140. #else
  141. mavlink_vkfly_edu_status_t packet;
  142. packet.unix_timestamp = unix_timestamp;
  143. packet.boot_timestamp = boot_timestamp;
  144. packet.seq = seq;
  145. packet.dev_sn = dev_sn;
  146. packet.longitude = longitude;
  147. packet.latitude = latitude;
  148. packet.amsl = amsl;
  149. packet.alt_relative = alt_relative;
  150. packet.ve = ve;
  151. packet.vn = vn;
  152. packet.vu = vu;
  153. packet.yaw = yaw;
  154. packet.pitch = pitch;
  155. packet.roll = roll;
  156. packet.yaw_rate = yaw_rate;
  157. packet.dev_type = dev_type;
  158. packet.retry_cnt = retry_cnt;
  159. packet.fix_type = fix_type;
  160. packet.reserve = reserve;
  161. packet.flight_mode = flight_mode;
  162. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN);
  163. #endif
  164. msg->msgid = MAVLINK_MSG_ID_VKFLY_EDU_STATUS;
  165. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC);
  166. }
  167. /**
  168. * @brief Pack a vkfly_edu_status message
  169. * @param system_id ID of this system
  170. * @param component_id ID of this component (e.g. 200 for IMU)
  171. * @param status MAVLink status structure
  172. * @param msg The MAVLink message to compress the data into
  173. *
  174. * @param unix_timestamp [ms] Unix timestamp in ms, from 1 Jan 1970.
  175. * @param boot_timestamp [ms] Timestamp in ms from system boot.
  176. * @param seq Sequence number for this package.
  177. * @param dev_sn Device SN number.
  178. * @param dev_type 0 for flight controller. 1 for elec-stake
  179. * @param retry_cnt Retry send this message count.
  180. * @param fix_type 0 no fix, 1 single, 2 RTK
  181. * @param reserve
  182. * @param longitude [degE7] wgs84 longitude
  183. * @param latitude [degE7] wgs84 latitude
  184. * @param amsl [m] altitude amsl
  185. * @param alt_relative [m] altitude above takeoff
  186. * @param ve [cm/s]
  187. * @param vn [cm/s]
  188. * @param vu [cm/s]
  189. * @param yaw [cdeg]
  190. * @param pitch [cdeg]
  191. * @param roll [cdeg]
  192. * @param yaw_rate [cdeg/s]
  193. * @param flight_mode
  194. * @return length of the message in bytes (excluding serial stream start sign)
  195. */
  196. static inline uint16_t mavlink_msg_vkfly_edu_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  197. uint64_t unix_timestamp, uint32_t boot_timestamp, uint32_t seq, uint32_t dev_sn, uint8_t dev_type, uint8_t retry_cnt, uint8_t fix_type, uint8_t reserve, int32_t longitude, int32_t latitude, float amsl, float alt_relative, int16_t ve, int16_t vn, int16_t vu, int16_t yaw, int16_t pitch, int16_t roll, int16_t yaw_rate, uint8_t flight_mode)
  198. {
  199. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  200. char buf[MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN];
  201. _mav_put_uint64_t(buf, 0, unix_timestamp);
  202. _mav_put_uint32_t(buf, 8, boot_timestamp);
  203. _mav_put_uint32_t(buf, 12, seq);
  204. _mav_put_uint32_t(buf, 16, dev_sn);
  205. _mav_put_int32_t(buf, 20, longitude);
  206. _mav_put_int32_t(buf, 24, latitude);
  207. _mav_put_float(buf, 28, amsl);
  208. _mav_put_float(buf, 32, alt_relative);
  209. _mav_put_int16_t(buf, 36, ve);
  210. _mav_put_int16_t(buf, 38, vn);
  211. _mav_put_int16_t(buf, 40, vu);
  212. _mav_put_int16_t(buf, 42, yaw);
  213. _mav_put_int16_t(buf, 44, pitch);
  214. _mav_put_int16_t(buf, 46, roll);
  215. _mav_put_int16_t(buf, 48, yaw_rate);
  216. _mav_put_uint8_t(buf, 50, dev_type);
  217. _mav_put_uint8_t(buf, 51, retry_cnt);
  218. _mav_put_uint8_t(buf, 52, fix_type);
  219. _mav_put_uint8_t(buf, 53, reserve);
  220. _mav_put_uint8_t(buf, 54, flight_mode);
  221. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN);
  222. #else
  223. mavlink_vkfly_edu_status_t packet;
  224. packet.unix_timestamp = unix_timestamp;
  225. packet.boot_timestamp = boot_timestamp;
  226. packet.seq = seq;
  227. packet.dev_sn = dev_sn;
  228. packet.longitude = longitude;
  229. packet.latitude = latitude;
  230. packet.amsl = amsl;
  231. packet.alt_relative = alt_relative;
  232. packet.ve = ve;
  233. packet.vn = vn;
  234. packet.vu = vu;
  235. packet.yaw = yaw;
  236. packet.pitch = pitch;
  237. packet.roll = roll;
  238. packet.yaw_rate = yaw_rate;
  239. packet.dev_type = dev_type;
  240. packet.retry_cnt = retry_cnt;
  241. packet.fix_type = fix_type;
  242. packet.reserve = reserve;
  243. packet.flight_mode = flight_mode;
  244. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN);
  245. #endif
  246. msg->msgid = MAVLINK_MSG_ID_VKFLY_EDU_STATUS;
  247. #if MAVLINK_CRC_EXTRA
  248. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC);
  249. #else
  250. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN);
  251. #endif
  252. }
  253. /**
  254. * @brief Pack a vkfly_edu_status message on a channel
  255. * @param system_id ID of this system
  256. * @param component_id ID of this component (e.g. 200 for IMU)
  257. * @param chan The MAVLink channel this message will be sent over
  258. * @param msg The MAVLink message to compress the data into
  259. * @param unix_timestamp [ms] Unix timestamp in ms, from 1 Jan 1970.
  260. * @param boot_timestamp [ms] Timestamp in ms from system boot.
  261. * @param seq Sequence number for this package.
  262. * @param dev_sn Device SN number.
  263. * @param dev_type 0 for flight controller. 1 for elec-stake
  264. * @param retry_cnt Retry send this message count.
  265. * @param fix_type 0 no fix, 1 single, 2 RTK
  266. * @param reserve
  267. * @param longitude [degE7] wgs84 longitude
  268. * @param latitude [degE7] wgs84 latitude
  269. * @param amsl [m] altitude amsl
  270. * @param alt_relative [m] altitude above takeoff
  271. * @param ve [cm/s]
  272. * @param vn [cm/s]
  273. * @param vu [cm/s]
  274. * @param yaw [cdeg]
  275. * @param pitch [cdeg]
  276. * @param roll [cdeg]
  277. * @param yaw_rate [cdeg/s]
  278. * @param flight_mode
  279. * @return length of the message in bytes (excluding serial stream start sign)
  280. */
  281. static inline uint16_t mavlink_msg_vkfly_edu_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  282. mavlink_message_t* msg,
  283. uint64_t unix_timestamp,uint32_t boot_timestamp,uint32_t seq,uint32_t dev_sn,uint8_t dev_type,uint8_t retry_cnt,uint8_t fix_type,uint8_t reserve,int32_t longitude,int32_t latitude,float amsl,float alt_relative,int16_t ve,int16_t vn,int16_t vu,int16_t yaw,int16_t pitch,int16_t roll,int16_t yaw_rate,uint8_t flight_mode)
  284. {
  285. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  286. char buf[MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN];
  287. _mav_put_uint64_t(buf, 0, unix_timestamp);
  288. _mav_put_uint32_t(buf, 8, boot_timestamp);
  289. _mav_put_uint32_t(buf, 12, seq);
  290. _mav_put_uint32_t(buf, 16, dev_sn);
  291. _mav_put_int32_t(buf, 20, longitude);
  292. _mav_put_int32_t(buf, 24, latitude);
  293. _mav_put_float(buf, 28, amsl);
  294. _mav_put_float(buf, 32, alt_relative);
  295. _mav_put_int16_t(buf, 36, ve);
  296. _mav_put_int16_t(buf, 38, vn);
  297. _mav_put_int16_t(buf, 40, vu);
  298. _mav_put_int16_t(buf, 42, yaw);
  299. _mav_put_int16_t(buf, 44, pitch);
  300. _mav_put_int16_t(buf, 46, roll);
  301. _mav_put_int16_t(buf, 48, yaw_rate);
  302. _mav_put_uint8_t(buf, 50, dev_type);
  303. _mav_put_uint8_t(buf, 51, retry_cnt);
  304. _mav_put_uint8_t(buf, 52, fix_type);
  305. _mav_put_uint8_t(buf, 53, reserve);
  306. _mav_put_uint8_t(buf, 54, flight_mode);
  307. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN);
  308. #else
  309. mavlink_vkfly_edu_status_t packet;
  310. packet.unix_timestamp = unix_timestamp;
  311. packet.boot_timestamp = boot_timestamp;
  312. packet.seq = seq;
  313. packet.dev_sn = dev_sn;
  314. packet.longitude = longitude;
  315. packet.latitude = latitude;
  316. packet.amsl = amsl;
  317. packet.alt_relative = alt_relative;
  318. packet.ve = ve;
  319. packet.vn = vn;
  320. packet.vu = vu;
  321. packet.yaw = yaw;
  322. packet.pitch = pitch;
  323. packet.roll = roll;
  324. packet.yaw_rate = yaw_rate;
  325. packet.dev_type = dev_type;
  326. packet.retry_cnt = retry_cnt;
  327. packet.fix_type = fix_type;
  328. packet.reserve = reserve;
  329. packet.flight_mode = flight_mode;
  330. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN);
  331. #endif
  332. msg->msgid = MAVLINK_MSG_ID_VKFLY_EDU_STATUS;
  333. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC);
  334. }
  335. /**
  336. * @brief Encode a vkfly_edu_status struct
  337. *
  338. * @param system_id ID of this system
  339. * @param component_id ID of this component (e.g. 200 for IMU)
  340. * @param msg The MAVLink message to compress the data into
  341. * @param vkfly_edu_status C-struct to read the message contents from
  342. */
  343. static inline uint16_t mavlink_msg_vkfly_edu_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vkfly_edu_status_t* vkfly_edu_status)
  344. {
  345. return mavlink_msg_vkfly_edu_status_pack(system_id, component_id, msg, vkfly_edu_status->unix_timestamp, vkfly_edu_status->boot_timestamp, vkfly_edu_status->seq, vkfly_edu_status->dev_sn, vkfly_edu_status->dev_type, vkfly_edu_status->retry_cnt, vkfly_edu_status->fix_type, vkfly_edu_status->reserve, vkfly_edu_status->longitude, vkfly_edu_status->latitude, vkfly_edu_status->amsl, vkfly_edu_status->alt_relative, vkfly_edu_status->ve, vkfly_edu_status->vn, vkfly_edu_status->vu, vkfly_edu_status->yaw, vkfly_edu_status->pitch, vkfly_edu_status->roll, vkfly_edu_status->yaw_rate, vkfly_edu_status->flight_mode);
  346. }
  347. /**
  348. * @brief Encode a vkfly_edu_status struct on a channel
  349. *
  350. * @param system_id ID of this system
  351. * @param component_id ID of this component (e.g. 200 for IMU)
  352. * @param chan The MAVLink channel this message will be sent over
  353. * @param msg The MAVLink message to compress the data into
  354. * @param vkfly_edu_status C-struct to read the message contents from
  355. */
  356. static inline uint16_t mavlink_msg_vkfly_edu_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vkfly_edu_status_t* vkfly_edu_status)
  357. {
  358. return mavlink_msg_vkfly_edu_status_pack_chan(system_id, component_id, chan, msg, vkfly_edu_status->unix_timestamp, vkfly_edu_status->boot_timestamp, vkfly_edu_status->seq, vkfly_edu_status->dev_sn, vkfly_edu_status->dev_type, vkfly_edu_status->retry_cnt, vkfly_edu_status->fix_type, vkfly_edu_status->reserve, vkfly_edu_status->longitude, vkfly_edu_status->latitude, vkfly_edu_status->amsl, vkfly_edu_status->alt_relative, vkfly_edu_status->ve, vkfly_edu_status->vn, vkfly_edu_status->vu, vkfly_edu_status->yaw, vkfly_edu_status->pitch, vkfly_edu_status->roll, vkfly_edu_status->yaw_rate, vkfly_edu_status->flight_mode);
  359. }
  360. /**
  361. * @brief Encode a vkfly_edu_status struct with provided status structure
  362. *
  363. * @param system_id ID of this system
  364. * @param component_id ID of this component (e.g. 200 for IMU)
  365. * @param status MAVLink status structure
  366. * @param msg The MAVLink message to compress the data into
  367. * @param vkfly_edu_status C-struct to read the message contents from
  368. */
  369. static inline uint16_t mavlink_msg_vkfly_edu_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vkfly_edu_status_t* vkfly_edu_status)
  370. {
  371. return mavlink_msg_vkfly_edu_status_pack_status(system_id, component_id, _status, msg, vkfly_edu_status->unix_timestamp, vkfly_edu_status->boot_timestamp, vkfly_edu_status->seq, vkfly_edu_status->dev_sn, vkfly_edu_status->dev_type, vkfly_edu_status->retry_cnt, vkfly_edu_status->fix_type, vkfly_edu_status->reserve, vkfly_edu_status->longitude, vkfly_edu_status->latitude, vkfly_edu_status->amsl, vkfly_edu_status->alt_relative, vkfly_edu_status->ve, vkfly_edu_status->vn, vkfly_edu_status->vu, vkfly_edu_status->yaw, vkfly_edu_status->pitch, vkfly_edu_status->roll, vkfly_edu_status->yaw_rate, vkfly_edu_status->flight_mode);
  372. }
  373. /**
  374. * @brief Send a vkfly_edu_status message
  375. * @param chan MAVLink channel to send the message
  376. *
  377. * @param unix_timestamp [ms] Unix timestamp in ms, from 1 Jan 1970.
  378. * @param boot_timestamp [ms] Timestamp in ms from system boot.
  379. * @param seq Sequence number for this package.
  380. * @param dev_sn Device SN number.
  381. * @param dev_type 0 for flight controller. 1 for elec-stake
  382. * @param retry_cnt Retry send this message count.
  383. * @param fix_type 0 no fix, 1 single, 2 RTK
  384. * @param reserve
  385. * @param longitude [degE7] wgs84 longitude
  386. * @param latitude [degE7] wgs84 latitude
  387. * @param amsl [m] altitude amsl
  388. * @param alt_relative [m] altitude above takeoff
  389. * @param ve [cm/s]
  390. * @param vn [cm/s]
  391. * @param vu [cm/s]
  392. * @param yaw [cdeg]
  393. * @param pitch [cdeg]
  394. * @param roll [cdeg]
  395. * @param yaw_rate [cdeg/s]
  396. * @param flight_mode
  397. */
  398. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  399. static inline void mavlink_msg_vkfly_edu_status_send(mavlink_channel_t chan, uint64_t unix_timestamp, uint32_t boot_timestamp, uint32_t seq, uint32_t dev_sn, uint8_t dev_type, uint8_t retry_cnt, uint8_t fix_type, uint8_t reserve, int32_t longitude, int32_t latitude, float amsl, float alt_relative, int16_t ve, int16_t vn, int16_t vu, int16_t yaw, int16_t pitch, int16_t roll, int16_t yaw_rate, uint8_t flight_mode)
  400. {
  401. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  402. char buf[MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN];
  403. _mav_put_uint64_t(buf, 0, unix_timestamp);
  404. _mav_put_uint32_t(buf, 8, boot_timestamp);
  405. _mav_put_uint32_t(buf, 12, seq);
  406. _mav_put_uint32_t(buf, 16, dev_sn);
  407. _mav_put_int32_t(buf, 20, longitude);
  408. _mav_put_int32_t(buf, 24, latitude);
  409. _mav_put_float(buf, 28, amsl);
  410. _mav_put_float(buf, 32, alt_relative);
  411. _mav_put_int16_t(buf, 36, ve);
  412. _mav_put_int16_t(buf, 38, vn);
  413. _mav_put_int16_t(buf, 40, vu);
  414. _mav_put_int16_t(buf, 42, yaw);
  415. _mav_put_int16_t(buf, 44, pitch);
  416. _mav_put_int16_t(buf, 46, roll);
  417. _mav_put_int16_t(buf, 48, yaw_rate);
  418. _mav_put_uint8_t(buf, 50, dev_type);
  419. _mav_put_uint8_t(buf, 51, retry_cnt);
  420. _mav_put_uint8_t(buf, 52, fix_type);
  421. _mav_put_uint8_t(buf, 53, reserve);
  422. _mav_put_uint8_t(buf, 54, flight_mode);
  423. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFLY_EDU_STATUS, buf, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC);
  424. #else
  425. mavlink_vkfly_edu_status_t packet;
  426. packet.unix_timestamp = unix_timestamp;
  427. packet.boot_timestamp = boot_timestamp;
  428. packet.seq = seq;
  429. packet.dev_sn = dev_sn;
  430. packet.longitude = longitude;
  431. packet.latitude = latitude;
  432. packet.amsl = amsl;
  433. packet.alt_relative = alt_relative;
  434. packet.ve = ve;
  435. packet.vn = vn;
  436. packet.vu = vu;
  437. packet.yaw = yaw;
  438. packet.pitch = pitch;
  439. packet.roll = roll;
  440. packet.yaw_rate = yaw_rate;
  441. packet.dev_type = dev_type;
  442. packet.retry_cnt = retry_cnt;
  443. packet.fix_type = fix_type;
  444. packet.reserve = reserve;
  445. packet.flight_mode = flight_mode;
  446. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFLY_EDU_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC);
  447. #endif
  448. }
  449. /**
  450. * @brief Send a vkfly_edu_status message
  451. * @param chan MAVLink channel to send the message
  452. * @param struct The MAVLink struct to serialize
  453. */
  454. static inline void mavlink_msg_vkfly_edu_status_send_struct(mavlink_channel_t chan, const mavlink_vkfly_edu_status_t* vkfly_edu_status)
  455. {
  456. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  457. mavlink_msg_vkfly_edu_status_send(chan, vkfly_edu_status->unix_timestamp, vkfly_edu_status->boot_timestamp, vkfly_edu_status->seq, vkfly_edu_status->dev_sn, vkfly_edu_status->dev_type, vkfly_edu_status->retry_cnt, vkfly_edu_status->fix_type, vkfly_edu_status->reserve, vkfly_edu_status->longitude, vkfly_edu_status->latitude, vkfly_edu_status->amsl, vkfly_edu_status->alt_relative, vkfly_edu_status->ve, vkfly_edu_status->vn, vkfly_edu_status->vu, vkfly_edu_status->yaw, vkfly_edu_status->pitch, vkfly_edu_status->roll, vkfly_edu_status->yaw_rate, vkfly_edu_status->flight_mode);
  458. #else
  459. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFLY_EDU_STATUS, (const char *)vkfly_edu_status, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC);
  460. #endif
  461. }
  462. #if MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  463. /*
  464. This variant of _send() can be used to save stack space by re-using
  465. memory from the receive buffer. The caller provides a
  466. mavlink_message_t which is the size of a full mavlink message. This
  467. is usually the receive buffer for the channel, and allows a reply to an
  468. incoming message with minimum stack space usage.
  469. */
  470. static inline void mavlink_msg_vkfly_edu_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t unix_timestamp, uint32_t boot_timestamp, uint32_t seq, uint32_t dev_sn, uint8_t dev_type, uint8_t retry_cnt, uint8_t fix_type, uint8_t reserve, int32_t longitude, int32_t latitude, float amsl, float alt_relative, int16_t ve, int16_t vn, int16_t vu, int16_t yaw, int16_t pitch, int16_t roll, int16_t yaw_rate, uint8_t flight_mode)
  471. {
  472. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  473. char *buf = (char *)msgbuf;
  474. _mav_put_uint64_t(buf, 0, unix_timestamp);
  475. _mav_put_uint32_t(buf, 8, boot_timestamp);
  476. _mav_put_uint32_t(buf, 12, seq);
  477. _mav_put_uint32_t(buf, 16, dev_sn);
  478. _mav_put_int32_t(buf, 20, longitude);
  479. _mav_put_int32_t(buf, 24, latitude);
  480. _mav_put_float(buf, 28, amsl);
  481. _mav_put_float(buf, 32, alt_relative);
  482. _mav_put_int16_t(buf, 36, ve);
  483. _mav_put_int16_t(buf, 38, vn);
  484. _mav_put_int16_t(buf, 40, vu);
  485. _mav_put_int16_t(buf, 42, yaw);
  486. _mav_put_int16_t(buf, 44, pitch);
  487. _mav_put_int16_t(buf, 46, roll);
  488. _mav_put_int16_t(buf, 48, yaw_rate);
  489. _mav_put_uint8_t(buf, 50, dev_type);
  490. _mav_put_uint8_t(buf, 51, retry_cnt);
  491. _mav_put_uint8_t(buf, 52, fix_type);
  492. _mav_put_uint8_t(buf, 53, reserve);
  493. _mav_put_uint8_t(buf, 54, flight_mode);
  494. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFLY_EDU_STATUS, buf, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC);
  495. #else
  496. mavlink_vkfly_edu_status_t *packet = (mavlink_vkfly_edu_status_t *)msgbuf;
  497. packet->unix_timestamp = unix_timestamp;
  498. packet->boot_timestamp = boot_timestamp;
  499. packet->seq = seq;
  500. packet->dev_sn = dev_sn;
  501. packet->longitude = longitude;
  502. packet->latitude = latitude;
  503. packet->amsl = amsl;
  504. packet->alt_relative = alt_relative;
  505. packet->ve = ve;
  506. packet->vn = vn;
  507. packet->vu = vu;
  508. packet->yaw = yaw;
  509. packet->pitch = pitch;
  510. packet->roll = roll;
  511. packet->yaw_rate = yaw_rate;
  512. packet->dev_type = dev_type;
  513. packet->retry_cnt = retry_cnt;
  514. packet->fix_type = fix_type;
  515. packet->reserve = reserve;
  516. packet->flight_mode = flight_mode;
  517. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFLY_EDU_STATUS, (const char *)packet, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_CRC);
  518. #endif
  519. }
  520. #endif
  521. #endif
  522. // MESSAGE VKFLY_EDU_STATUS UNPACKING
  523. /**
  524. * @brief Get field unix_timestamp from vkfly_edu_status message
  525. *
  526. * @return [ms] Unix timestamp in ms, from 1 Jan 1970.
  527. */
  528. static inline uint64_t mavlink_msg_vkfly_edu_status_get_unix_timestamp(const mavlink_message_t* msg)
  529. {
  530. return _MAV_RETURN_uint64_t(msg, 0);
  531. }
  532. /**
  533. * @brief Get field boot_timestamp from vkfly_edu_status message
  534. *
  535. * @return [ms] Timestamp in ms from system boot.
  536. */
  537. static inline uint32_t mavlink_msg_vkfly_edu_status_get_boot_timestamp(const mavlink_message_t* msg)
  538. {
  539. return _MAV_RETURN_uint32_t(msg, 8);
  540. }
  541. /**
  542. * @brief Get field seq from vkfly_edu_status message
  543. *
  544. * @return Sequence number for this package.
  545. */
  546. static inline uint32_t mavlink_msg_vkfly_edu_status_get_seq(const mavlink_message_t* msg)
  547. {
  548. return _MAV_RETURN_uint32_t(msg, 12);
  549. }
  550. /**
  551. * @brief Get field dev_sn from vkfly_edu_status message
  552. *
  553. * @return Device SN number.
  554. */
  555. static inline uint32_t mavlink_msg_vkfly_edu_status_get_dev_sn(const mavlink_message_t* msg)
  556. {
  557. return _MAV_RETURN_uint32_t(msg, 16);
  558. }
  559. /**
  560. * @brief Get field dev_type from vkfly_edu_status message
  561. *
  562. * @return 0 for flight controller. 1 for elec-stake
  563. */
  564. static inline uint8_t mavlink_msg_vkfly_edu_status_get_dev_type(const mavlink_message_t* msg)
  565. {
  566. return _MAV_RETURN_uint8_t(msg, 50);
  567. }
  568. /**
  569. * @brief Get field retry_cnt from vkfly_edu_status message
  570. *
  571. * @return Retry send this message count.
  572. */
  573. static inline uint8_t mavlink_msg_vkfly_edu_status_get_retry_cnt(const mavlink_message_t* msg)
  574. {
  575. return _MAV_RETURN_uint8_t(msg, 51);
  576. }
  577. /**
  578. * @brief Get field fix_type from vkfly_edu_status message
  579. *
  580. * @return 0 no fix, 1 single, 2 RTK
  581. */
  582. static inline uint8_t mavlink_msg_vkfly_edu_status_get_fix_type(const mavlink_message_t* msg)
  583. {
  584. return _MAV_RETURN_uint8_t(msg, 52);
  585. }
  586. /**
  587. * @brief Get field reserve from vkfly_edu_status message
  588. *
  589. * @return
  590. */
  591. static inline uint8_t mavlink_msg_vkfly_edu_status_get_reserve(const mavlink_message_t* msg)
  592. {
  593. return _MAV_RETURN_uint8_t(msg, 53);
  594. }
  595. /**
  596. * @brief Get field longitude from vkfly_edu_status message
  597. *
  598. * @return [degE7] wgs84 longitude
  599. */
  600. static inline int32_t mavlink_msg_vkfly_edu_status_get_longitude(const mavlink_message_t* msg)
  601. {
  602. return _MAV_RETURN_int32_t(msg, 20);
  603. }
  604. /**
  605. * @brief Get field latitude from vkfly_edu_status message
  606. *
  607. * @return [degE7] wgs84 latitude
  608. */
  609. static inline int32_t mavlink_msg_vkfly_edu_status_get_latitude(const mavlink_message_t* msg)
  610. {
  611. return _MAV_RETURN_int32_t(msg, 24);
  612. }
  613. /**
  614. * @brief Get field amsl from vkfly_edu_status message
  615. *
  616. * @return [m] altitude amsl
  617. */
  618. static inline float mavlink_msg_vkfly_edu_status_get_amsl(const mavlink_message_t* msg)
  619. {
  620. return _MAV_RETURN_float(msg, 28);
  621. }
  622. /**
  623. * @brief Get field alt_relative from vkfly_edu_status message
  624. *
  625. * @return [m] altitude above takeoff
  626. */
  627. static inline float mavlink_msg_vkfly_edu_status_get_alt_relative(const mavlink_message_t* msg)
  628. {
  629. return _MAV_RETURN_float(msg, 32);
  630. }
  631. /**
  632. * @brief Get field ve from vkfly_edu_status message
  633. *
  634. * @return [cm/s]
  635. */
  636. static inline int16_t mavlink_msg_vkfly_edu_status_get_ve(const mavlink_message_t* msg)
  637. {
  638. return _MAV_RETURN_int16_t(msg, 36);
  639. }
  640. /**
  641. * @brief Get field vn from vkfly_edu_status message
  642. *
  643. * @return [cm/s]
  644. */
  645. static inline int16_t mavlink_msg_vkfly_edu_status_get_vn(const mavlink_message_t* msg)
  646. {
  647. return _MAV_RETURN_int16_t(msg, 38);
  648. }
  649. /**
  650. * @brief Get field vu from vkfly_edu_status message
  651. *
  652. * @return [cm/s]
  653. */
  654. static inline int16_t mavlink_msg_vkfly_edu_status_get_vu(const mavlink_message_t* msg)
  655. {
  656. return _MAV_RETURN_int16_t(msg, 40);
  657. }
  658. /**
  659. * @brief Get field yaw from vkfly_edu_status message
  660. *
  661. * @return [cdeg]
  662. */
  663. static inline int16_t mavlink_msg_vkfly_edu_status_get_yaw(const mavlink_message_t* msg)
  664. {
  665. return _MAV_RETURN_int16_t(msg, 42);
  666. }
  667. /**
  668. * @brief Get field pitch from vkfly_edu_status message
  669. *
  670. * @return [cdeg]
  671. */
  672. static inline int16_t mavlink_msg_vkfly_edu_status_get_pitch(const mavlink_message_t* msg)
  673. {
  674. return _MAV_RETURN_int16_t(msg, 44);
  675. }
  676. /**
  677. * @brief Get field roll from vkfly_edu_status message
  678. *
  679. * @return [cdeg]
  680. */
  681. static inline int16_t mavlink_msg_vkfly_edu_status_get_roll(const mavlink_message_t* msg)
  682. {
  683. return _MAV_RETURN_int16_t(msg, 46);
  684. }
  685. /**
  686. * @brief Get field yaw_rate from vkfly_edu_status message
  687. *
  688. * @return [cdeg/s]
  689. */
  690. static inline int16_t mavlink_msg_vkfly_edu_status_get_yaw_rate(const mavlink_message_t* msg)
  691. {
  692. return _MAV_RETURN_int16_t(msg, 48);
  693. }
  694. /**
  695. * @brief Get field flight_mode from vkfly_edu_status message
  696. *
  697. * @return
  698. */
  699. static inline uint8_t mavlink_msg_vkfly_edu_status_get_flight_mode(const mavlink_message_t* msg)
  700. {
  701. return _MAV_RETURN_uint8_t(msg, 54);
  702. }
  703. /**
  704. * @brief Decode a vkfly_edu_status message into a struct
  705. *
  706. * @param msg The message to decode
  707. * @param vkfly_edu_status C-struct to decode the message contents into
  708. */
  709. static inline void mavlink_msg_vkfly_edu_status_decode(const mavlink_message_t* msg, mavlink_vkfly_edu_status_t* vkfly_edu_status)
  710. {
  711. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  712. vkfly_edu_status->unix_timestamp = mavlink_msg_vkfly_edu_status_get_unix_timestamp(msg);
  713. vkfly_edu_status->boot_timestamp = mavlink_msg_vkfly_edu_status_get_boot_timestamp(msg);
  714. vkfly_edu_status->seq = mavlink_msg_vkfly_edu_status_get_seq(msg);
  715. vkfly_edu_status->dev_sn = mavlink_msg_vkfly_edu_status_get_dev_sn(msg);
  716. vkfly_edu_status->longitude = mavlink_msg_vkfly_edu_status_get_longitude(msg);
  717. vkfly_edu_status->latitude = mavlink_msg_vkfly_edu_status_get_latitude(msg);
  718. vkfly_edu_status->amsl = mavlink_msg_vkfly_edu_status_get_amsl(msg);
  719. vkfly_edu_status->alt_relative = mavlink_msg_vkfly_edu_status_get_alt_relative(msg);
  720. vkfly_edu_status->ve = mavlink_msg_vkfly_edu_status_get_ve(msg);
  721. vkfly_edu_status->vn = mavlink_msg_vkfly_edu_status_get_vn(msg);
  722. vkfly_edu_status->vu = mavlink_msg_vkfly_edu_status_get_vu(msg);
  723. vkfly_edu_status->yaw = mavlink_msg_vkfly_edu_status_get_yaw(msg);
  724. vkfly_edu_status->pitch = mavlink_msg_vkfly_edu_status_get_pitch(msg);
  725. vkfly_edu_status->roll = mavlink_msg_vkfly_edu_status_get_roll(msg);
  726. vkfly_edu_status->yaw_rate = mavlink_msg_vkfly_edu_status_get_yaw_rate(msg);
  727. vkfly_edu_status->dev_type = mavlink_msg_vkfly_edu_status_get_dev_type(msg);
  728. vkfly_edu_status->retry_cnt = mavlink_msg_vkfly_edu_status_get_retry_cnt(msg);
  729. vkfly_edu_status->fix_type = mavlink_msg_vkfly_edu_status_get_fix_type(msg);
  730. vkfly_edu_status->reserve = mavlink_msg_vkfly_edu_status_get_reserve(msg);
  731. vkfly_edu_status->flight_mode = mavlink_msg_vkfly_edu_status_get_flight_mode(msg);
  732. #else
  733. uint8_t len = msg->len < MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN;
  734. memset(vkfly_edu_status, 0, MAVLINK_MSG_ID_VKFLY_EDU_STATUS_LEN);
  735. memcpy(vkfly_edu_status, _MAV_PAYLOAD(msg), len);
  736. #endif
  737. }