mavlink_msg_vkins_status.h 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648
  1. #pragma once
  2. // MESSAGE VKINS_STATUS PACKING
  3. #define MAVLINK_MSG_ID_VKINS_STATUS 53000
  4. typedef struct __mavlink_vkins_status_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp in ms from system boot.*/
  6. float g0; /*< [m/s/s] vkins initial calibrated gravitation acceleration.*/
  7. int32_t raw_latitude; /*< [degE7] raw longitude for data fusion*/
  8. int32_t raw_longitude; /*< [degE7] raw latitidue for data fusion*/
  9. float baro_alt; /*< [m] raw baromoter altitude for data fusion*/
  10. float raw_gps_alt; /*< [m] gps amsl altitude for data fusion*/
  11. int16_t temperature; /*< [cdegC] temperature*/
  12. uint8_t nav_status; /*< VKINS
  13. navigation status flag.*/
  14. uint8_t s_flag1; /*< vinks flag1*/
  15. uint8_t s_flag2; /*< vinks flag2.*/
  16. uint8_t s_flag3; /*< vinks flag3.*/
  17. uint8_t s_flag4; /*< vinks flag4.*/
  18. uint8_t s_flag5; /*< vinks flag5.*/
  19. uint8_t s_flag6; /*< vinks flag6.*/
  20. uint8_t mag_calib_stage; /*< vkins mag calib
  21. stage.*/
  22. uint8_t solv_psat_num; /*< satelites number for position*/
  23. uint8_t solv_hsat_num; /*< satelites number for heading*/
  24. uint8_t vibe_coe; /*< */
  25. } mavlink_vkins_status_t;
  26. #define MAVLINK_MSG_ID_VKINS_STATUS_LEN 37
  27. #define MAVLINK_MSG_ID_VKINS_STATUS_MIN_LEN 37
  28. #define MAVLINK_MSG_ID_53000_LEN 37
  29. #define MAVLINK_MSG_ID_53000_MIN_LEN 37
  30. #define MAVLINK_MSG_ID_VKINS_STATUS_CRC 22
  31. #define MAVLINK_MSG_ID_53000_CRC 22
  32. #if MAVLINK_COMMAND_24BIT
  33. #define MAVLINK_MESSAGE_INFO_VKINS_STATUS { \
  34. 53000, \
  35. "VKINS_STATUS", \
  36. 18, \
  37. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkins_status_t, time_boot_ms) }, \
  38. { "nav_status", "0x%02x", MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_vkins_status_t, nav_status) }, \
  39. { "s_flag1", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_vkins_status_t, s_flag1) }, \
  40. { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_vkins_status_t, s_flag2) }, \
  41. { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_vkins_status_t, s_flag3) }, \
  42. { "s_flag4", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_vkins_status_t, s_flag4) }, \
  43. { "s_flag5", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_vkins_status_t, s_flag5) }, \
  44. { "s_flag6", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_vkins_status_t, s_flag6) }, \
  45. { "mag_calib_stage", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_vkins_status_t, mag_calib_stage) }, \
  46. { "g0", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vkins_status_t, g0) }, \
  47. { "raw_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vkins_status_t, raw_latitude) }, \
  48. { "raw_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_vkins_status_t, raw_longitude) }, \
  49. { "baro_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vkins_status_t, baro_alt) }, \
  50. { "raw_gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vkins_status_t, raw_gps_alt) }, \
  51. { "solv_psat_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_vkins_status_t, solv_psat_num) }, \
  52. { "solv_hsat_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_vkins_status_t, solv_hsat_num) }, \
  53. { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_vkins_status_t, temperature) }, \
  54. { "vibe_coe", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_vkins_status_t, vibe_coe) }, \
  55. } \
  56. }
  57. #else
  58. #define MAVLINK_MESSAGE_INFO_VKINS_STATUS { \
  59. "VKINS_STATUS", \
  60. 18, \
  61. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkins_status_t, time_boot_ms) }, \
  62. { "nav_status", "0x%02x", MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_vkins_status_t, nav_status) }, \
  63. { "s_flag1", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_vkins_status_t, s_flag1) }, \
  64. { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_vkins_status_t, s_flag2) }, \
  65. { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_vkins_status_t, s_flag3) }, \
  66. { "s_flag4", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_vkins_status_t, s_flag4) }, \
  67. { "s_flag5", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_vkins_status_t, s_flag5) }, \
  68. { "s_flag6", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_vkins_status_t, s_flag6) }, \
  69. { "mag_calib_stage", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_vkins_status_t, mag_calib_stage) }, \
  70. { "g0", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vkins_status_t, g0) }, \
  71. { "raw_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vkins_status_t, raw_latitude) }, \
  72. { "raw_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_vkins_status_t, raw_longitude) }, \
  73. { "baro_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vkins_status_t, baro_alt) }, \
  74. { "raw_gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vkins_status_t, raw_gps_alt) }, \
  75. { "solv_psat_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_vkins_status_t, solv_psat_num) }, \
  76. { "solv_hsat_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_vkins_status_t, solv_hsat_num) }, \
  77. { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_vkins_status_t, temperature) }, \
  78. { "vibe_coe", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_vkins_status_t, vibe_coe) }, \
  79. } \
  80. }
  81. #endif
  82. /**
  83. * @brief Pack a vkins_status message
  84. * @param system_id ID of this system
  85. * @param component_id ID of this component (e.g. 200 for IMU)
  86. * @param msg The MAVLink message to compress the data into
  87. *
  88. * @param time_boot_ms [ms] Timestamp in ms from system boot.
  89. * @param nav_status VKINS
  90. navigation status flag.
  91. * @param s_flag1 vinks flag1
  92. * @param s_flag2 vinks flag2.
  93. * @param s_flag3 vinks flag3.
  94. * @param s_flag4 vinks flag4.
  95. * @param s_flag5 vinks flag5.
  96. * @param s_flag6 vinks flag6.
  97. * @param mag_calib_stage vkins mag calib
  98. stage.
  99. * @param g0 [m/s/s] vkins initial calibrated gravitation acceleration.
  100. * @param raw_latitude [degE7] raw longitude for data fusion
  101. * @param raw_longitude [degE7] raw latitidue for data fusion
  102. * @param baro_alt [m] raw baromoter altitude for data fusion
  103. * @param raw_gps_alt [m] gps amsl altitude for data fusion
  104. * @param solv_psat_num satelites number for position
  105. * @param solv_hsat_num satelites number for heading
  106. * @param temperature [cdegC] temperature
  107. * @param vibe_coe
  108. * @return length of the message in bytes (excluding serial stream start sign)
  109. */
  110. static inline uint16_t mavlink_msg_vkins_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  111. uint32_t time_boot_ms, uint8_t nav_status, uint8_t s_flag1, uint8_t s_flag2, uint8_t s_flag3, uint8_t s_flag4, uint8_t s_flag5, uint8_t s_flag6, uint8_t mag_calib_stage, float g0, int32_t raw_latitude, int32_t raw_longitude, float baro_alt, float raw_gps_alt, uint8_t solv_psat_num, uint8_t solv_hsat_num, int16_t temperature, uint8_t vibe_coe)
  112. {
  113. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  114. char buf[MAVLINK_MSG_ID_VKINS_STATUS_LEN];
  115. _mav_put_uint32_t(buf, 0, time_boot_ms);
  116. _mav_put_float(buf, 4, g0);
  117. _mav_put_int32_t(buf, 8, raw_latitude);
  118. _mav_put_int32_t(buf, 12, raw_longitude);
  119. _mav_put_float(buf, 16, baro_alt);
  120. _mav_put_float(buf, 20, raw_gps_alt);
  121. _mav_put_int16_t(buf, 24, temperature);
  122. _mav_put_uint8_t(buf, 26, nav_status);
  123. _mav_put_uint8_t(buf, 27, s_flag1);
  124. _mav_put_uint8_t(buf, 28, s_flag2);
  125. _mav_put_uint8_t(buf, 29, s_flag3);
  126. _mav_put_uint8_t(buf, 30, s_flag4);
  127. _mav_put_uint8_t(buf, 31, s_flag5);
  128. _mav_put_uint8_t(buf, 32, s_flag6);
  129. _mav_put_uint8_t(buf, 33, mag_calib_stage);
  130. _mav_put_uint8_t(buf, 34, solv_psat_num);
  131. _mav_put_uint8_t(buf, 35, solv_hsat_num);
  132. _mav_put_uint8_t(buf, 36, vibe_coe);
  133. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKINS_STATUS_LEN);
  134. #else
  135. mavlink_vkins_status_t packet;
  136. packet.time_boot_ms = time_boot_ms;
  137. packet.g0 = g0;
  138. packet.raw_latitude = raw_latitude;
  139. packet.raw_longitude = raw_longitude;
  140. packet.baro_alt = baro_alt;
  141. packet.raw_gps_alt = raw_gps_alt;
  142. packet.temperature = temperature;
  143. packet.nav_status = nav_status;
  144. packet.s_flag1 = s_flag1;
  145. packet.s_flag2 = s_flag2;
  146. packet.s_flag3 = s_flag3;
  147. packet.s_flag4 = s_flag4;
  148. packet.s_flag5 = s_flag5;
  149. packet.s_flag6 = s_flag6;
  150. packet.mag_calib_stage = mag_calib_stage;
  151. packet.solv_psat_num = solv_psat_num;
  152. packet.solv_hsat_num = solv_hsat_num;
  153. packet.vibe_coe = vibe_coe;
  154. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKINS_STATUS_LEN);
  155. #endif
  156. msg->msgid = MAVLINK_MSG_ID_VKINS_STATUS;
  157. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VKINS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKINS_STATUS_LEN, MAVLINK_MSG_ID_VKINS_STATUS_CRC);
  158. }
  159. /**
  160. * @brief Pack a vkins_status message on a channel
  161. * @param system_id ID of this system
  162. * @param component_id ID of this component (e.g. 200 for IMU)
  163. * @param chan The MAVLink channel this message will be sent over
  164. * @param msg The MAVLink message to compress the data into
  165. * @param time_boot_ms [ms] Timestamp in ms from system boot.
  166. * @param nav_status VKINS
  167. navigation status flag.
  168. * @param s_flag1 vinks flag1
  169. * @param s_flag2 vinks flag2.
  170. * @param s_flag3 vinks flag3.
  171. * @param s_flag4 vinks flag4.
  172. * @param s_flag5 vinks flag5.
  173. * @param s_flag6 vinks flag6.
  174. * @param mag_calib_stage vkins mag calib
  175. stage.
  176. * @param g0 [m/s/s] vkins initial calibrated gravitation acceleration.
  177. * @param raw_latitude [degE7] raw longitude for data fusion
  178. * @param raw_longitude [degE7] raw latitidue for data fusion
  179. * @param baro_alt [m] raw baromoter altitude for data fusion
  180. * @param raw_gps_alt [m] gps amsl altitude for data fusion
  181. * @param solv_psat_num satelites number for position
  182. * @param solv_hsat_num satelites number for heading
  183. * @param temperature [cdegC] temperature
  184. * @param vibe_coe
  185. * @return length of the message in bytes (excluding serial stream start sign)
  186. */
  187. static inline uint16_t mavlink_msg_vkins_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  188. mavlink_message_t* msg,
  189. uint32_t time_boot_ms,uint8_t nav_status,uint8_t s_flag1,uint8_t s_flag2,uint8_t s_flag3,uint8_t s_flag4,uint8_t s_flag5,uint8_t s_flag6,uint8_t mag_calib_stage,float g0,int32_t raw_latitude,int32_t raw_longitude,float baro_alt,float raw_gps_alt,uint8_t solv_psat_num,uint8_t solv_hsat_num,int16_t temperature,uint8_t vibe_coe)
  190. {
  191. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  192. char buf[MAVLINK_MSG_ID_VKINS_STATUS_LEN];
  193. _mav_put_uint32_t(buf, 0, time_boot_ms);
  194. _mav_put_float(buf, 4, g0);
  195. _mav_put_int32_t(buf, 8, raw_latitude);
  196. _mav_put_int32_t(buf, 12, raw_longitude);
  197. _mav_put_float(buf, 16, baro_alt);
  198. _mav_put_float(buf, 20, raw_gps_alt);
  199. _mav_put_int16_t(buf, 24, temperature);
  200. _mav_put_uint8_t(buf, 26, nav_status);
  201. _mav_put_uint8_t(buf, 27, s_flag1);
  202. _mav_put_uint8_t(buf, 28, s_flag2);
  203. _mav_put_uint8_t(buf, 29, s_flag3);
  204. _mav_put_uint8_t(buf, 30, s_flag4);
  205. _mav_put_uint8_t(buf, 31, s_flag5);
  206. _mav_put_uint8_t(buf, 32, s_flag6);
  207. _mav_put_uint8_t(buf, 33, mag_calib_stage);
  208. _mav_put_uint8_t(buf, 34, solv_psat_num);
  209. _mav_put_uint8_t(buf, 35, solv_hsat_num);
  210. _mav_put_uint8_t(buf, 36, vibe_coe);
  211. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKINS_STATUS_LEN);
  212. #else
  213. mavlink_vkins_status_t packet;
  214. packet.time_boot_ms = time_boot_ms;
  215. packet.g0 = g0;
  216. packet.raw_latitude = raw_latitude;
  217. packet.raw_longitude = raw_longitude;
  218. packet.baro_alt = baro_alt;
  219. packet.raw_gps_alt = raw_gps_alt;
  220. packet.temperature = temperature;
  221. packet.nav_status = nav_status;
  222. packet.s_flag1 = s_flag1;
  223. packet.s_flag2 = s_flag2;
  224. packet.s_flag3 = s_flag3;
  225. packet.s_flag4 = s_flag4;
  226. packet.s_flag5 = s_flag5;
  227. packet.s_flag6 = s_flag6;
  228. packet.mag_calib_stage = mag_calib_stage;
  229. packet.solv_psat_num = solv_psat_num;
  230. packet.solv_hsat_num = solv_hsat_num;
  231. packet.vibe_coe = vibe_coe;
  232. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKINS_STATUS_LEN);
  233. #endif
  234. msg->msgid = MAVLINK_MSG_ID_VKINS_STATUS;
  235. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VKINS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKINS_STATUS_LEN, MAVLINK_MSG_ID_VKINS_STATUS_CRC);
  236. }
  237. /**
  238. * @brief Encode a vkins_status struct
  239. *
  240. * @param system_id ID of this system
  241. * @param component_id ID of this component (e.g. 200 for IMU)
  242. * @param msg The MAVLink message to compress the data into
  243. * @param vkins_status C-struct to read the message contents from
  244. */
  245. static inline uint16_t mavlink_msg_vkins_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vkins_status_t* vkins_status)
  246. {
  247. return mavlink_msg_vkins_status_pack(system_id, component_id, msg, vkins_status->time_boot_ms, vkins_status->nav_status, vkins_status->s_flag1, vkins_status->s_flag2, vkins_status->s_flag3, vkins_status->s_flag4, vkins_status->s_flag5, vkins_status->s_flag6, vkins_status->mag_calib_stage, vkins_status->g0, vkins_status->raw_latitude, vkins_status->raw_longitude, vkins_status->baro_alt, vkins_status->raw_gps_alt, vkins_status->solv_psat_num, vkins_status->solv_hsat_num, vkins_status->temperature, vkins_status->vibe_coe);
  248. }
  249. /**
  250. * @brief Encode a vkins_status struct on a channel
  251. *
  252. * @param system_id ID of this system
  253. * @param component_id ID of this component (e.g. 200 for IMU)
  254. * @param chan The MAVLink channel this message will be sent over
  255. * @param msg The MAVLink message to compress the data into
  256. * @param vkins_status C-struct to read the message contents from
  257. */
  258. static inline uint16_t mavlink_msg_vkins_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vkins_status_t* vkins_status)
  259. {
  260. return mavlink_msg_vkins_status_pack_chan(system_id, component_id, chan, msg, vkins_status->time_boot_ms, vkins_status->nav_status, vkins_status->s_flag1, vkins_status->s_flag2, vkins_status->s_flag3, vkins_status->s_flag4, vkins_status->s_flag5, vkins_status->s_flag6, vkins_status->mag_calib_stage, vkins_status->g0, vkins_status->raw_latitude, vkins_status->raw_longitude, vkins_status->baro_alt, vkins_status->raw_gps_alt, vkins_status->solv_psat_num, vkins_status->solv_hsat_num, vkins_status->temperature, vkins_status->vibe_coe);
  261. }
  262. /**
  263. * @brief Send a vkins_status message
  264. * @param chan MAVLink channel to send the message
  265. *
  266. * @param time_boot_ms [ms] Timestamp in ms from system boot.
  267. * @param nav_status VKINS
  268. navigation status flag.
  269. * @param s_flag1 vinks flag1
  270. * @param s_flag2 vinks flag2.
  271. * @param s_flag3 vinks flag3.
  272. * @param s_flag4 vinks flag4.
  273. * @param s_flag5 vinks flag5.
  274. * @param s_flag6 vinks flag6.
  275. * @param mag_calib_stage vkins mag calib
  276. stage.
  277. * @param g0 [m/s/s] vkins initial calibrated gravitation acceleration.
  278. * @param raw_latitude [degE7] raw longitude for data fusion
  279. * @param raw_longitude [degE7] raw latitidue for data fusion
  280. * @param baro_alt [m] raw baromoter altitude for data fusion
  281. * @param raw_gps_alt [m] gps amsl altitude for data fusion
  282. * @param solv_psat_num satelites number for position
  283. * @param solv_hsat_num satelites number for heading
  284. * @param temperature [cdegC] temperature
  285. * @param vibe_coe
  286. */
  287. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  288. static inline void mavlink_msg_vkins_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t nav_status, uint8_t s_flag1, uint8_t s_flag2, uint8_t s_flag3, uint8_t s_flag4, uint8_t s_flag5, uint8_t s_flag6, uint8_t mag_calib_stage, float g0, int32_t raw_latitude, int32_t raw_longitude, float baro_alt, float raw_gps_alt, uint8_t solv_psat_num, uint8_t solv_hsat_num, int16_t temperature, uint8_t vibe_coe)
  289. {
  290. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  291. char buf[MAVLINK_MSG_ID_VKINS_STATUS_LEN];
  292. _mav_put_uint32_t(buf, 0, time_boot_ms);
  293. _mav_put_float(buf, 4, g0);
  294. _mav_put_int32_t(buf, 8, raw_latitude);
  295. _mav_put_int32_t(buf, 12, raw_longitude);
  296. _mav_put_float(buf, 16, baro_alt);
  297. _mav_put_float(buf, 20, raw_gps_alt);
  298. _mav_put_int16_t(buf, 24, temperature);
  299. _mav_put_uint8_t(buf, 26, nav_status);
  300. _mav_put_uint8_t(buf, 27, s_flag1);
  301. _mav_put_uint8_t(buf, 28, s_flag2);
  302. _mav_put_uint8_t(buf, 29, s_flag3);
  303. _mav_put_uint8_t(buf, 30, s_flag4);
  304. _mav_put_uint8_t(buf, 31, s_flag5);
  305. _mav_put_uint8_t(buf, 32, s_flag6);
  306. _mav_put_uint8_t(buf, 33, mag_calib_stage);
  307. _mav_put_uint8_t(buf, 34, solv_psat_num);
  308. _mav_put_uint8_t(buf, 35, solv_hsat_num);
  309. _mav_put_uint8_t(buf, 36, vibe_coe);
  310. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKINS_STATUS, buf, MAVLINK_MSG_ID_VKINS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKINS_STATUS_LEN, MAVLINK_MSG_ID_VKINS_STATUS_CRC);
  311. #else
  312. mavlink_vkins_status_t packet;
  313. packet.time_boot_ms = time_boot_ms;
  314. packet.g0 = g0;
  315. packet.raw_latitude = raw_latitude;
  316. packet.raw_longitude = raw_longitude;
  317. packet.baro_alt = baro_alt;
  318. packet.raw_gps_alt = raw_gps_alt;
  319. packet.temperature = temperature;
  320. packet.nav_status = nav_status;
  321. packet.s_flag1 = s_flag1;
  322. packet.s_flag2 = s_flag2;
  323. packet.s_flag3 = s_flag3;
  324. packet.s_flag4 = s_flag4;
  325. packet.s_flag5 = s_flag5;
  326. packet.s_flag6 = s_flag6;
  327. packet.mag_calib_stage = mag_calib_stage;
  328. packet.solv_psat_num = solv_psat_num;
  329. packet.solv_hsat_num = solv_hsat_num;
  330. packet.vibe_coe = vibe_coe;
  331. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKINS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VKINS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKINS_STATUS_LEN, MAVLINK_MSG_ID_VKINS_STATUS_CRC);
  332. #endif
  333. }
  334. /**
  335. * @brief Send a vkins_status message
  336. * @param chan MAVLink channel to send the message
  337. * @param struct The MAVLink struct to serialize
  338. */
  339. static inline void mavlink_msg_vkins_status_send_struct(mavlink_channel_t chan, const mavlink_vkins_status_t* vkins_status)
  340. {
  341. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  342. mavlink_msg_vkins_status_send(chan, vkins_status->time_boot_ms, vkins_status->nav_status, vkins_status->s_flag1, vkins_status->s_flag2, vkins_status->s_flag3, vkins_status->s_flag4, vkins_status->s_flag5, vkins_status->s_flag6, vkins_status->mag_calib_stage, vkins_status->g0, vkins_status->raw_latitude, vkins_status->raw_longitude, vkins_status->baro_alt, vkins_status->raw_gps_alt, vkins_status->solv_psat_num, vkins_status->solv_hsat_num, vkins_status->temperature, vkins_status->vibe_coe);
  343. #else
  344. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKINS_STATUS, (const char *)vkins_status, MAVLINK_MSG_ID_VKINS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKINS_STATUS_LEN, MAVLINK_MSG_ID_VKINS_STATUS_CRC);
  345. #endif
  346. }
  347. #if MAVLINK_MSG_ID_VKINS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  348. /*
  349. This variant of _send() can be used to save stack space by re-using
  350. memory from the receive buffer. The caller provides a
  351. mavlink_message_t which is the size of a full mavlink message. This
  352. is usually the receive buffer for the channel, and allows a reply to an
  353. incoming message with minimum stack space usage.
  354. */
  355. static inline void mavlink_msg_vkins_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t nav_status, uint8_t s_flag1, uint8_t s_flag2, uint8_t s_flag3, uint8_t s_flag4, uint8_t s_flag5, uint8_t s_flag6, uint8_t mag_calib_stage, float g0, int32_t raw_latitude, int32_t raw_longitude, float baro_alt, float raw_gps_alt, uint8_t solv_psat_num, uint8_t solv_hsat_num, int16_t temperature, uint8_t vibe_coe)
  356. {
  357. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  358. char *buf = (char *)msgbuf;
  359. _mav_put_uint32_t(buf, 0, time_boot_ms);
  360. _mav_put_float(buf, 4, g0);
  361. _mav_put_int32_t(buf, 8, raw_latitude);
  362. _mav_put_int32_t(buf, 12, raw_longitude);
  363. _mav_put_float(buf, 16, baro_alt);
  364. _mav_put_float(buf, 20, raw_gps_alt);
  365. _mav_put_int16_t(buf, 24, temperature);
  366. _mav_put_uint8_t(buf, 26, nav_status);
  367. _mav_put_uint8_t(buf, 27, s_flag1);
  368. _mav_put_uint8_t(buf, 28, s_flag2);
  369. _mav_put_uint8_t(buf, 29, s_flag3);
  370. _mav_put_uint8_t(buf, 30, s_flag4);
  371. _mav_put_uint8_t(buf, 31, s_flag5);
  372. _mav_put_uint8_t(buf, 32, s_flag6);
  373. _mav_put_uint8_t(buf, 33, mag_calib_stage);
  374. _mav_put_uint8_t(buf, 34, solv_psat_num);
  375. _mav_put_uint8_t(buf, 35, solv_hsat_num);
  376. _mav_put_uint8_t(buf, 36, vibe_coe);
  377. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKINS_STATUS, buf, MAVLINK_MSG_ID_VKINS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKINS_STATUS_LEN, MAVLINK_MSG_ID_VKINS_STATUS_CRC);
  378. #else
  379. mavlink_vkins_status_t *packet = (mavlink_vkins_status_t *)msgbuf;
  380. packet->time_boot_ms = time_boot_ms;
  381. packet->g0 = g0;
  382. packet->raw_latitude = raw_latitude;
  383. packet->raw_longitude = raw_longitude;
  384. packet->baro_alt = baro_alt;
  385. packet->raw_gps_alt = raw_gps_alt;
  386. packet->temperature = temperature;
  387. packet->nav_status = nav_status;
  388. packet->s_flag1 = s_flag1;
  389. packet->s_flag2 = s_flag2;
  390. packet->s_flag3 = s_flag3;
  391. packet->s_flag4 = s_flag4;
  392. packet->s_flag5 = s_flag5;
  393. packet->s_flag6 = s_flag6;
  394. packet->mag_calib_stage = mag_calib_stage;
  395. packet->solv_psat_num = solv_psat_num;
  396. packet->solv_hsat_num = solv_hsat_num;
  397. packet->vibe_coe = vibe_coe;
  398. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKINS_STATUS, (const char *)packet, MAVLINK_MSG_ID_VKINS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKINS_STATUS_LEN, MAVLINK_MSG_ID_VKINS_STATUS_CRC);
  399. #endif
  400. }
  401. #endif
  402. #endif
  403. // MESSAGE VKINS_STATUS UNPACKING
  404. /**
  405. * @brief Get field time_boot_ms from vkins_status message
  406. *
  407. * @return [ms] Timestamp in ms from system boot.
  408. */
  409. static inline uint32_t mavlink_msg_vkins_status_get_time_boot_ms(const mavlink_message_t* msg)
  410. {
  411. return _MAV_RETURN_uint32_t(msg, 0);
  412. }
  413. /**
  414. * @brief Get field nav_status from vkins_status message
  415. *
  416. * @return VKINS
  417. navigation status flag.
  418. */
  419. static inline uint8_t mavlink_msg_vkins_status_get_nav_status(const mavlink_message_t* msg)
  420. {
  421. return _MAV_RETURN_uint8_t(msg, 26);
  422. }
  423. /**
  424. * @brief Get field s_flag1 from vkins_status message
  425. *
  426. * @return vinks flag1
  427. */
  428. static inline uint8_t mavlink_msg_vkins_status_get_s_flag1(const mavlink_message_t* msg)
  429. {
  430. return _MAV_RETURN_uint8_t(msg, 27);
  431. }
  432. /**
  433. * @brief Get field s_flag2 from vkins_status message
  434. *
  435. * @return vinks flag2.
  436. */
  437. static inline uint8_t mavlink_msg_vkins_status_get_s_flag2(const mavlink_message_t* msg)
  438. {
  439. return _MAV_RETURN_uint8_t(msg, 28);
  440. }
  441. /**
  442. * @brief Get field s_flag3 from vkins_status message
  443. *
  444. * @return vinks flag3.
  445. */
  446. static inline uint8_t mavlink_msg_vkins_status_get_s_flag3(const mavlink_message_t* msg)
  447. {
  448. return _MAV_RETURN_uint8_t(msg, 29);
  449. }
  450. /**
  451. * @brief Get field s_flag4 from vkins_status message
  452. *
  453. * @return vinks flag4.
  454. */
  455. static inline uint8_t mavlink_msg_vkins_status_get_s_flag4(const mavlink_message_t* msg)
  456. {
  457. return _MAV_RETURN_uint8_t(msg, 30);
  458. }
  459. /**
  460. * @brief Get field s_flag5 from vkins_status message
  461. *
  462. * @return vinks flag5.
  463. */
  464. static inline uint8_t mavlink_msg_vkins_status_get_s_flag5(const mavlink_message_t* msg)
  465. {
  466. return _MAV_RETURN_uint8_t(msg, 31);
  467. }
  468. /**
  469. * @brief Get field s_flag6 from vkins_status message
  470. *
  471. * @return vinks flag6.
  472. */
  473. static inline uint8_t mavlink_msg_vkins_status_get_s_flag6(const mavlink_message_t* msg)
  474. {
  475. return _MAV_RETURN_uint8_t(msg, 32);
  476. }
  477. /**
  478. * @brief Get field mag_calib_stage from vkins_status message
  479. *
  480. * @return vkins mag calib
  481. stage.
  482. */
  483. static inline uint8_t mavlink_msg_vkins_status_get_mag_calib_stage(const mavlink_message_t* msg)
  484. {
  485. return _MAV_RETURN_uint8_t(msg, 33);
  486. }
  487. /**
  488. * @brief Get field g0 from vkins_status message
  489. *
  490. * @return [m/s/s] vkins initial calibrated gravitation acceleration.
  491. */
  492. static inline float mavlink_msg_vkins_status_get_g0(const mavlink_message_t* msg)
  493. {
  494. return _MAV_RETURN_float(msg, 4);
  495. }
  496. /**
  497. * @brief Get field raw_latitude from vkins_status message
  498. *
  499. * @return [degE7] raw longitude for data fusion
  500. */
  501. static inline int32_t mavlink_msg_vkins_status_get_raw_latitude(const mavlink_message_t* msg)
  502. {
  503. return _MAV_RETURN_int32_t(msg, 8);
  504. }
  505. /**
  506. * @brief Get field raw_longitude from vkins_status message
  507. *
  508. * @return [degE7] raw latitidue for data fusion
  509. */
  510. static inline int32_t mavlink_msg_vkins_status_get_raw_longitude(const mavlink_message_t* msg)
  511. {
  512. return _MAV_RETURN_int32_t(msg, 12);
  513. }
  514. /**
  515. * @brief Get field baro_alt from vkins_status message
  516. *
  517. * @return [m] raw baromoter altitude for data fusion
  518. */
  519. static inline float mavlink_msg_vkins_status_get_baro_alt(const mavlink_message_t* msg)
  520. {
  521. return _MAV_RETURN_float(msg, 16);
  522. }
  523. /**
  524. * @brief Get field raw_gps_alt from vkins_status message
  525. *
  526. * @return [m] gps amsl altitude for data fusion
  527. */
  528. static inline float mavlink_msg_vkins_status_get_raw_gps_alt(const mavlink_message_t* msg)
  529. {
  530. return _MAV_RETURN_float(msg, 20);
  531. }
  532. /**
  533. * @brief Get field solv_psat_num from vkins_status message
  534. *
  535. * @return satelites number for position
  536. */
  537. static inline uint8_t mavlink_msg_vkins_status_get_solv_psat_num(const mavlink_message_t* msg)
  538. {
  539. return _MAV_RETURN_uint8_t(msg, 34);
  540. }
  541. /**
  542. * @brief Get field solv_hsat_num from vkins_status message
  543. *
  544. * @return satelites number for heading
  545. */
  546. static inline uint8_t mavlink_msg_vkins_status_get_solv_hsat_num(const mavlink_message_t* msg)
  547. {
  548. return _MAV_RETURN_uint8_t(msg, 35);
  549. }
  550. /**
  551. * @brief Get field temperature from vkins_status message
  552. *
  553. * @return [cdegC] temperature
  554. */
  555. static inline int16_t mavlink_msg_vkins_status_get_temperature(const mavlink_message_t* msg)
  556. {
  557. return _MAV_RETURN_int16_t(msg, 24);
  558. }
  559. /**
  560. * @brief Get field vibe_coe from vkins_status message
  561. *
  562. * @return
  563. */
  564. static inline uint8_t mavlink_msg_vkins_status_get_vibe_coe(const mavlink_message_t* msg)
  565. {
  566. return _MAV_RETURN_uint8_t(msg, 36);
  567. }
  568. /**
  569. * @brief Decode a vkins_status message into a struct
  570. *
  571. * @param msg The message to decode
  572. * @param vkins_status C-struct to decode the message contents into
  573. */
  574. static inline void mavlink_msg_vkins_status_decode(const mavlink_message_t* msg, mavlink_vkins_status_t* vkins_status)
  575. {
  576. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  577. vkins_status->time_boot_ms = mavlink_msg_vkins_status_get_time_boot_ms(msg);
  578. vkins_status->g0 = mavlink_msg_vkins_status_get_g0(msg);
  579. vkins_status->raw_latitude = mavlink_msg_vkins_status_get_raw_latitude(msg);
  580. vkins_status->raw_longitude = mavlink_msg_vkins_status_get_raw_longitude(msg);
  581. vkins_status->baro_alt = mavlink_msg_vkins_status_get_baro_alt(msg);
  582. vkins_status->raw_gps_alt = mavlink_msg_vkins_status_get_raw_gps_alt(msg);
  583. vkins_status->temperature = mavlink_msg_vkins_status_get_temperature(msg);
  584. vkins_status->nav_status = mavlink_msg_vkins_status_get_nav_status(msg);
  585. vkins_status->s_flag1 = mavlink_msg_vkins_status_get_s_flag1(msg);
  586. vkins_status->s_flag2 = mavlink_msg_vkins_status_get_s_flag2(msg);
  587. vkins_status->s_flag3 = mavlink_msg_vkins_status_get_s_flag3(msg);
  588. vkins_status->s_flag4 = mavlink_msg_vkins_status_get_s_flag4(msg);
  589. vkins_status->s_flag5 = mavlink_msg_vkins_status_get_s_flag5(msg);
  590. vkins_status->s_flag6 = mavlink_msg_vkins_status_get_s_flag6(msg);
  591. vkins_status->mag_calib_stage = mavlink_msg_vkins_status_get_mag_calib_stage(msg);
  592. vkins_status->solv_psat_num = mavlink_msg_vkins_status_get_solv_psat_num(msg);
  593. vkins_status->solv_hsat_num = mavlink_msg_vkins_status_get_solv_hsat_num(msg);
  594. vkins_status->vibe_coe = mavlink_msg_vkins_status_get_vibe_coe(msg);
  595. #else
  596. uint8_t len = msg->len < MAVLINK_MSG_ID_VKINS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VKINS_STATUS_LEN;
  597. memset(vkins_status, 0, MAVLINK_MSG_ID_VKINS_STATUS_LEN);
  598. memcpy(vkins_status, _MAV_PAYLOAD(msg), len);
  599. #endif
  600. }