mavlink_msg_vk_formation_leader.h 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624
  1. #pragma once
  2. // MESSAGE VK_FORMATION_LEADER PACKING
  3. #define MAVLINK_MSG_ID_VK_FORMATION_LEADER 53004
  4. typedef struct __mavlink_vk_formation_leader_t {
  5. uint32_t timestamp; /*< [ms] Timestamp in ms from system boot.*/
  6. uint32_t state; /*< formation leader drone state bitmap*/
  7. int32_t lat; /*< [degE7] formation leader latitude in 1e-7deg */
  8. int32_t lon; /*< [degE7] formation leader longitude in 1e-7deg*/
  9. float msl; /*< [m] formation leader msl altitude in meter*/
  10. float ve; /*< [m/s] formation leader east speed*/
  11. float vn; /*< [m/s] formation leader north speed*/
  12. float vu; /*< [m/s] formation leader up speed*/
  13. float yaw; /*< [deg] formation leader yaw*/
  14. int16_t x_dist; /*< [cm] distance between drones in x axis*/
  15. int16_t y_dist; /*< [cm] distance between drones in y axis*/
  16. int16_t z_dist; /*< [cm] distance between drones in z axis*/
  17. uint16_t rect_col_num; /*< columns number of rectangle formation*/
  18. uint8_t formation_type; /*< formation type*/
  19. } mavlink_vk_formation_leader_t;
  20. #define MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN 45
  21. #define MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN 45
  22. #define MAVLINK_MSG_ID_53004_LEN 45
  23. #define MAVLINK_MSG_ID_53004_MIN_LEN 45
  24. #define MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC 219
  25. #define MAVLINK_MSG_ID_53004_CRC 219
  26. #if MAVLINK_COMMAND_24BIT
  27. #define MAVLINK_MESSAGE_INFO_VK_FORMATION_LEADER { \
  28. 53004, \
  29. "VK_FORMATION_LEADER", \
  30. 14, \
  31. { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_formation_leader_t, timestamp) }, \
  32. { "state", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_formation_leader_t, state) }, \
  33. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vk_formation_leader_t, lat) }, \
  34. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_vk_formation_leader_t, lon) }, \
  35. { "msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vk_formation_leader_t, msl) }, \
  36. { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vk_formation_leader_t, ve) }, \
  37. { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vk_formation_leader_t, vn) }, \
  38. { "vu", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vk_formation_leader_t, vu) }, \
  39. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vk_formation_leader_t, yaw) }, \
  40. { "formation_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_vk_formation_leader_t, formation_type) }, \
  41. { "x_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_vk_formation_leader_t, x_dist) }, \
  42. { "y_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_vk_formation_leader_t, y_dist) }, \
  43. { "z_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_vk_formation_leader_t, z_dist) }, \
  44. { "rect_col_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_vk_formation_leader_t, rect_col_num) }, \
  45. } \
  46. }
  47. #else
  48. #define MAVLINK_MESSAGE_INFO_VK_FORMATION_LEADER { \
  49. "VK_FORMATION_LEADER", \
  50. 14, \
  51. { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_formation_leader_t, timestamp) }, \
  52. { "state", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_formation_leader_t, state) }, \
  53. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vk_formation_leader_t, lat) }, \
  54. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_vk_formation_leader_t, lon) }, \
  55. { "msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vk_formation_leader_t, msl) }, \
  56. { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vk_formation_leader_t, ve) }, \
  57. { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vk_formation_leader_t, vn) }, \
  58. { "vu", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vk_formation_leader_t, vu) }, \
  59. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vk_formation_leader_t, yaw) }, \
  60. { "formation_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_vk_formation_leader_t, formation_type) }, \
  61. { "x_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_vk_formation_leader_t, x_dist) }, \
  62. { "y_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_vk_formation_leader_t, y_dist) }, \
  63. { "z_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_vk_formation_leader_t, z_dist) }, \
  64. { "rect_col_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_vk_formation_leader_t, rect_col_num) }, \
  65. } \
  66. }
  67. #endif
  68. /**
  69. * @brief Pack a vk_formation_leader message
  70. * @param system_id ID of this system
  71. * @param component_id ID of this component (e.g. 200 for IMU)
  72. * @param msg The MAVLink message to compress the data into
  73. *
  74. * @param timestamp [ms] Timestamp in ms from system boot.
  75. * @param state formation leader drone state bitmap
  76. * @param lat [degE7] formation leader latitude in 1e-7deg
  77. * @param lon [degE7] formation leader longitude in 1e-7deg
  78. * @param msl [m] formation leader msl altitude in meter
  79. * @param ve [m/s] formation leader east speed
  80. * @param vn [m/s] formation leader north speed
  81. * @param vu [m/s] formation leader up speed
  82. * @param yaw [deg] formation leader yaw
  83. * @param formation_type formation type
  84. * @param x_dist [cm] distance between drones in x axis
  85. * @param y_dist [cm] distance between drones in y axis
  86. * @param z_dist [cm] distance between drones in z axis
  87. * @param rect_col_num columns number of rectangle formation
  88. * @return length of the message in bytes (excluding serial stream start sign)
  89. */
  90. static inline uint16_t mavlink_msg_vk_formation_leader_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  91. uint32_t timestamp, uint32_t state, int32_t lat, int32_t lon, float msl, float ve, float vn, float vu, float yaw, uint8_t formation_type, int16_t x_dist, int16_t y_dist, int16_t z_dist, uint16_t rect_col_num)
  92. {
  93. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  94. char buf[MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN];
  95. _mav_put_uint32_t(buf, 0, timestamp);
  96. _mav_put_uint32_t(buf, 4, state);
  97. _mav_put_int32_t(buf, 8, lat);
  98. _mav_put_int32_t(buf, 12, lon);
  99. _mav_put_float(buf, 16, msl);
  100. _mav_put_float(buf, 20, ve);
  101. _mav_put_float(buf, 24, vn);
  102. _mav_put_float(buf, 28, vu);
  103. _mav_put_float(buf, 32, yaw);
  104. _mav_put_int16_t(buf, 36, x_dist);
  105. _mav_put_int16_t(buf, 38, y_dist);
  106. _mav_put_int16_t(buf, 40, z_dist);
  107. _mav_put_uint16_t(buf, 42, rect_col_num);
  108. _mav_put_uint8_t(buf, 44, formation_type);
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
  110. #else
  111. mavlink_vk_formation_leader_t packet;
  112. packet.timestamp = timestamp;
  113. packet.state = state;
  114. packet.lat = lat;
  115. packet.lon = lon;
  116. packet.msl = msl;
  117. packet.ve = ve;
  118. packet.vn = vn;
  119. packet.vu = vu;
  120. packet.yaw = yaw;
  121. packet.x_dist = x_dist;
  122. packet.y_dist = y_dist;
  123. packet.z_dist = z_dist;
  124. packet.rect_col_num = rect_col_num;
  125. packet.formation_type = formation_type;
  126. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
  127. #endif
  128. msg->msgid = MAVLINK_MSG_ID_VK_FORMATION_LEADER;
  129. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
  130. }
  131. /**
  132. * @brief Pack a vk_formation_leader message
  133. * @param system_id ID of this system
  134. * @param component_id ID of this component (e.g. 200 for IMU)
  135. * @param status MAVLink status structure
  136. * @param msg The MAVLink message to compress the data into
  137. *
  138. * @param timestamp [ms] Timestamp in ms from system boot.
  139. * @param state formation leader drone state bitmap
  140. * @param lat [degE7] formation leader latitude in 1e-7deg
  141. * @param lon [degE7] formation leader longitude in 1e-7deg
  142. * @param msl [m] formation leader msl altitude in meter
  143. * @param ve [m/s] formation leader east speed
  144. * @param vn [m/s] formation leader north speed
  145. * @param vu [m/s] formation leader up speed
  146. * @param yaw [deg] formation leader yaw
  147. * @param formation_type formation type
  148. * @param x_dist [cm] distance between drones in x axis
  149. * @param y_dist [cm] distance between drones in y axis
  150. * @param z_dist [cm] distance between drones in z axis
  151. * @param rect_col_num columns number of rectangle formation
  152. * @return length of the message in bytes (excluding serial stream start sign)
  153. */
  154. static inline uint16_t mavlink_msg_vk_formation_leader_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  155. uint32_t timestamp, uint32_t state, int32_t lat, int32_t lon, float msl, float ve, float vn, float vu, float yaw, uint8_t formation_type, int16_t x_dist, int16_t y_dist, int16_t z_dist, uint16_t rect_col_num)
  156. {
  157. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  158. char buf[MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN];
  159. _mav_put_uint32_t(buf, 0, timestamp);
  160. _mav_put_uint32_t(buf, 4, state);
  161. _mav_put_int32_t(buf, 8, lat);
  162. _mav_put_int32_t(buf, 12, lon);
  163. _mav_put_float(buf, 16, msl);
  164. _mav_put_float(buf, 20, ve);
  165. _mav_put_float(buf, 24, vn);
  166. _mav_put_float(buf, 28, vu);
  167. _mav_put_float(buf, 32, yaw);
  168. _mav_put_int16_t(buf, 36, x_dist);
  169. _mav_put_int16_t(buf, 38, y_dist);
  170. _mav_put_int16_t(buf, 40, z_dist);
  171. _mav_put_uint16_t(buf, 42, rect_col_num);
  172. _mav_put_uint8_t(buf, 44, formation_type);
  173. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
  174. #else
  175. mavlink_vk_formation_leader_t packet;
  176. packet.timestamp = timestamp;
  177. packet.state = state;
  178. packet.lat = lat;
  179. packet.lon = lon;
  180. packet.msl = msl;
  181. packet.ve = ve;
  182. packet.vn = vn;
  183. packet.vu = vu;
  184. packet.yaw = yaw;
  185. packet.x_dist = x_dist;
  186. packet.y_dist = y_dist;
  187. packet.z_dist = z_dist;
  188. packet.rect_col_num = rect_col_num;
  189. packet.formation_type = formation_type;
  190. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
  191. #endif
  192. msg->msgid = MAVLINK_MSG_ID_VK_FORMATION_LEADER;
  193. #if MAVLINK_CRC_EXTRA
  194. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
  195. #else
  196. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
  197. #endif
  198. }
  199. /**
  200. * @brief Pack a vk_formation_leader message on a channel
  201. * @param system_id ID of this system
  202. * @param component_id ID of this component (e.g. 200 for IMU)
  203. * @param chan The MAVLink channel this message will be sent over
  204. * @param msg The MAVLink message to compress the data into
  205. * @param timestamp [ms] Timestamp in ms from system boot.
  206. * @param state formation leader drone state bitmap
  207. * @param lat [degE7] formation leader latitude in 1e-7deg
  208. * @param lon [degE7] formation leader longitude in 1e-7deg
  209. * @param msl [m] formation leader msl altitude in meter
  210. * @param ve [m/s] formation leader east speed
  211. * @param vn [m/s] formation leader north speed
  212. * @param vu [m/s] formation leader up speed
  213. * @param yaw [deg] formation leader yaw
  214. * @param formation_type formation type
  215. * @param x_dist [cm] distance between drones in x axis
  216. * @param y_dist [cm] distance between drones in y axis
  217. * @param z_dist [cm] distance between drones in z axis
  218. * @param rect_col_num columns number of rectangle formation
  219. * @return length of the message in bytes (excluding serial stream start sign)
  220. */
  221. static inline uint16_t mavlink_msg_vk_formation_leader_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  222. mavlink_message_t* msg,
  223. uint32_t timestamp,uint32_t state,int32_t lat,int32_t lon,float msl,float ve,float vn,float vu,float yaw,uint8_t formation_type,int16_t x_dist,int16_t y_dist,int16_t z_dist,uint16_t rect_col_num)
  224. {
  225. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  226. char buf[MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN];
  227. _mav_put_uint32_t(buf, 0, timestamp);
  228. _mav_put_uint32_t(buf, 4, state);
  229. _mav_put_int32_t(buf, 8, lat);
  230. _mav_put_int32_t(buf, 12, lon);
  231. _mav_put_float(buf, 16, msl);
  232. _mav_put_float(buf, 20, ve);
  233. _mav_put_float(buf, 24, vn);
  234. _mav_put_float(buf, 28, vu);
  235. _mav_put_float(buf, 32, yaw);
  236. _mav_put_int16_t(buf, 36, x_dist);
  237. _mav_put_int16_t(buf, 38, y_dist);
  238. _mav_put_int16_t(buf, 40, z_dist);
  239. _mav_put_uint16_t(buf, 42, rect_col_num);
  240. _mav_put_uint8_t(buf, 44, formation_type);
  241. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
  242. #else
  243. mavlink_vk_formation_leader_t packet;
  244. packet.timestamp = timestamp;
  245. packet.state = state;
  246. packet.lat = lat;
  247. packet.lon = lon;
  248. packet.msl = msl;
  249. packet.ve = ve;
  250. packet.vn = vn;
  251. packet.vu = vu;
  252. packet.yaw = yaw;
  253. packet.x_dist = x_dist;
  254. packet.y_dist = y_dist;
  255. packet.z_dist = z_dist;
  256. packet.rect_col_num = rect_col_num;
  257. packet.formation_type = formation_type;
  258. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
  259. #endif
  260. msg->msgid = MAVLINK_MSG_ID_VK_FORMATION_LEADER;
  261. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
  262. }
  263. /**
  264. * @brief Encode a vk_formation_leader struct
  265. *
  266. * @param system_id ID of this system
  267. * @param component_id ID of this component (e.g. 200 for IMU)
  268. * @param msg The MAVLink message to compress the data into
  269. * @param vk_formation_leader C-struct to read the message contents from
  270. */
  271. static inline uint16_t mavlink_msg_vk_formation_leader_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_formation_leader_t* vk_formation_leader)
  272. {
  273. return mavlink_msg_vk_formation_leader_pack(system_id, component_id, msg, vk_formation_leader->timestamp, vk_formation_leader->state, vk_formation_leader->lat, vk_formation_leader->lon, vk_formation_leader->msl, vk_formation_leader->ve, vk_formation_leader->vn, vk_formation_leader->vu, vk_formation_leader->yaw, vk_formation_leader->formation_type, vk_formation_leader->x_dist, vk_formation_leader->y_dist, vk_formation_leader->z_dist, vk_formation_leader->rect_col_num);
  274. }
  275. /**
  276. * @brief Encode a vk_formation_leader struct on a channel
  277. *
  278. * @param system_id ID of this system
  279. * @param component_id ID of this component (e.g. 200 for IMU)
  280. * @param chan The MAVLink channel this message will be sent over
  281. * @param msg The MAVLink message to compress the data into
  282. * @param vk_formation_leader C-struct to read the message contents from
  283. */
  284. static inline uint16_t mavlink_msg_vk_formation_leader_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_formation_leader_t* vk_formation_leader)
  285. {
  286. return mavlink_msg_vk_formation_leader_pack_chan(system_id, component_id, chan, msg, vk_formation_leader->timestamp, vk_formation_leader->state, vk_formation_leader->lat, vk_formation_leader->lon, vk_formation_leader->msl, vk_formation_leader->ve, vk_formation_leader->vn, vk_formation_leader->vu, vk_formation_leader->yaw, vk_formation_leader->formation_type, vk_formation_leader->x_dist, vk_formation_leader->y_dist, vk_formation_leader->z_dist, vk_formation_leader->rect_col_num);
  287. }
  288. /**
  289. * @brief Encode a vk_formation_leader struct with provided status structure
  290. *
  291. * @param system_id ID of this system
  292. * @param component_id ID of this component (e.g. 200 for IMU)
  293. * @param status MAVLink status structure
  294. * @param msg The MAVLink message to compress the data into
  295. * @param vk_formation_leader C-struct to read the message contents from
  296. */
  297. static inline uint16_t mavlink_msg_vk_formation_leader_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_formation_leader_t* vk_formation_leader)
  298. {
  299. return mavlink_msg_vk_formation_leader_pack_status(system_id, component_id, _status, msg, vk_formation_leader->timestamp, vk_formation_leader->state, vk_formation_leader->lat, vk_formation_leader->lon, vk_formation_leader->msl, vk_formation_leader->ve, vk_formation_leader->vn, vk_formation_leader->vu, vk_formation_leader->yaw, vk_formation_leader->formation_type, vk_formation_leader->x_dist, vk_formation_leader->y_dist, vk_formation_leader->z_dist, vk_formation_leader->rect_col_num);
  300. }
  301. /**
  302. * @brief Send a vk_formation_leader message
  303. * @param chan MAVLink channel to send the message
  304. *
  305. * @param timestamp [ms] Timestamp in ms from system boot.
  306. * @param state formation leader drone state bitmap
  307. * @param lat [degE7] formation leader latitude in 1e-7deg
  308. * @param lon [degE7] formation leader longitude in 1e-7deg
  309. * @param msl [m] formation leader msl altitude in meter
  310. * @param ve [m/s] formation leader east speed
  311. * @param vn [m/s] formation leader north speed
  312. * @param vu [m/s] formation leader up speed
  313. * @param yaw [deg] formation leader yaw
  314. * @param formation_type formation type
  315. * @param x_dist [cm] distance between drones in x axis
  316. * @param y_dist [cm] distance between drones in y axis
  317. * @param z_dist [cm] distance between drones in z axis
  318. * @param rect_col_num columns number of rectangle formation
  319. */
  320. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  321. static inline void mavlink_msg_vk_formation_leader_send(mavlink_channel_t chan, uint32_t timestamp, uint32_t state, int32_t lat, int32_t lon, float msl, float ve, float vn, float vu, float yaw, uint8_t formation_type, int16_t x_dist, int16_t y_dist, int16_t z_dist, uint16_t rect_col_num)
  322. {
  323. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  324. char buf[MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN];
  325. _mav_put_uint32_t(buf, 0, timestamp);
  326. _mav_put_uint32_t(buf, 4, state);
  327. _mav_put_int32_t(buf, 8, lat);
  328. _mav_put_int32_t(buf, 12, lon);
  329. _mav_put_float(buf, 16, msl);
  330. _mav_put_float(buf, 20, ve);
  331. _mav_put_float(buf, 24, vn);
  332. _mav_put_float(buf, 28, vu);
  333. _mav_put_float(buf, 32, yaw);
  334. _mav_put_int16_t(buf, 36, x_dist);
  335. _mav_put_int16_t(buf, 38, y_dist);
  336. _mav_put_int16_t(buf, 40, z_dist);
  337. _mav_put_uint16_t(buf, 42, rect_col_num);
  338. _mav_put_uint8_t(buf, 44, formation_type);
  339. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
  340. #else
  341. mavlink_vk_formation_leader_t packet;
  342. packet.timestamp = timestamp;
  343. packet.state = state;
  344. packet.lat = lat;
  345. packet.lon = lon;
  346. packet.msl = msl;
  347. packet.ve = ve;
  348. packet.vn = vn;
  349. packet.vu = vu;
  350. packet.yaw = yaw;
  351. packet.x_dist = x_dist;
  352. packet.y_dist = y_dist;
  353. packet.z_dist = z_dist;
  354. packet.rect_col_num = rect_col_num;
  355. packet.formation_type = formation_type;
  356. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, (const char *)&packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
  357. #endif
  358. }
  359. /**
  360. * @brief Send a vk_formation_leader message
  361. * @param chan MAVLink channel to send the message
  362. * @param struct The MAVLink struct to serialize
  363. */
  364. static inline void mavlink_msg_vk_formation_leader_send_struct(mavlink_channel_t chan, const mavlink_vk_formation_leader_t* vk_formation_leader)
  365. {
  366. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  367. mavlink_msg_vk_formation_leader_send(chan, vk_formation_leader->timestamp, vk_formation_leader->state, vk_formation_leader->lat, vk_formation_leader->lon, vk_formation_leader->msl, vk_formation_leader->ve, vk_formation_leader->vn, vk_formation_leader->vu, vk_formation_leader->yaw, vk_formation_leader->formation_type, vk_formation_leader->x_dist, vk_formation_leader->y_dist, vk_formation_leader->z_dist, vk_formation_leader->rect_col_num);
  368. #else
  369. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, (const char *)vk_formation_leader, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
  370. #endif
  371. }
  372. #if MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  373. /*
  374. This variant of _send() can be used to save stack space by re-using
  375. memory from the receive buffer. The caller provides a
  376. mavlink_message_t which is the size of a full mavlink message. This
  377. is usually the receive buffer for the channel, and allows a reply to an
  378. incoming message with minimum stack space usage.
  379. */
  380. static inline void mavlink_msg_vk_formation_leader_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timestamp, uint32_t state, int32_t lat, int32_t lon, float msl, float ve, float vn, float vu, float yaw, uint8_t formation_type, int16_t x_dist, int16_t y_dist, int16_t z_dist, uint16_t rect_col_num)
  381. {
  382. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  383. char *buf = (char *)msgbuf;
  384. _mav_put_uint32_t(buf, 0, timestamp);
  385. _mav_put_uint32_t(buf, 4, state);
  386. _mav_put_int32_t(buf, 8, lat);
  387. _mav_put_int32_t(buf, 12, lon);
  388. _mav_put_float(buf, 16, msl);
  389. _mav_put_float(buf, 20, ve);
  390. _mav_put_float(buf, 24, vn);
  391. _mav_put_float(buf, 28, vu);
  392. _mav_put_float(buf, 32, yaw);
  393. _mav_put_int16_t(buf, 36, x_dist);
  394. _mav_put_int16_t(buf, 38, y_dist);
  395. _mav_put_int16_t(buf, 40, z_dist);
  396. _mav_put_uint16_t(buf, 42, rect_col_num);
  397. _mav_put_uint8_t(buf, 44, formation_type);
  398. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
  399. #else
  400. mavlink_vk_formation_leader_t *packet = (mavlink_vk_formation_leader_t *)msgbuf;
  401. packet->timestamp = timestamp;
  402. packet->state = state;
  403. packet->lat = lat;
  404. packet->lon = lon;
  405. packet->msl = msl;
  406. packet->ve = ve;
  407. packet->vn = vn;
  408. packet->vu = vu;
  409. packet->yaw = yaw;
  410. packet->x_dist = x_dist;
  411. packet->y_dist = y_dist;
  412. packet->z_dist = z_dist;
  413. packet->rect_col_num = rect_col_num;
  414. packet->formation_type = formation_type;
  415. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, (const char *)packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
  416. #endif
  417. }
  418. #endif
  419. #endif
  420. // MESSAGE VK_FORMATION_LEADER UNPACKING
  421. /**
  422. * @brief Get field timestamp from vk_formation_leader message
  423. *
  424. * @return [ms] Timestamp in ms from system boot.
  425. */
  426. static inline uint32_t mavlink_msg_vk_formation_leader_get_timestamp(const mavlink_message_t* msg)
  427. {
  428. return _MAV_RETURN_uint32_t(msg, 0);
  429. }
  430. /**
  431. * @brief Get field state from vk_formation_leader message
  432. *
  433. * @return formation leader drone state bitmap
  434. */
  435. static inline uint32_t mavlink_msg_vk_formation_leader_get_state(const mavlink_message_t* msg)
  436. {
  437. return _MAV_RETURN_uint32_t(msg, 4);
  438. }
  439. /**
  440. * @brief Get field lat from vk_formation_leader message
  441. *
  442. * @return [degE7] formation leader latitude in 1e-7deg
  443. */
  444. static inline int32_t mavlink_msg_vk_formation_leader_get_lat(const mavlink_message_t* msg)
  445. {
  446. return _MAV_RETURN_int32_t(msg, 8);
  447. }
  448. /**
  449. * @brief Get field lon from vk_formation_leader message
  450. *
  451. * @return [degE7] formation leader longitude in 1e-7deg
  452. */
  453. static inline int32_t mavlink_msg_vk_formation_leader_get_lon(const mavlink_message_t* msg)
  454. {
  455. return _MAV_RETURN_int32_t(msg, 12);
  456. }
  457. /**
  458. * @brief Get field msl from vk_formation_leader message
  459. *
  460. * @return [m] formation leader msl altitude in meter
  461. */
  462. static inline float mavlink_msg_vk_formation_leader_get_msl(const mavlink_message_t* msg)
  463. {
  464. return _MAV_RETURN_float(msg, 16);
  465. }
  466. /**
  467. * @brief Get field ve from vk_formation_leader message
  468. *
  469. * @return [m/s] formation leader east speed
  470. */
  471. static inline float mavlink_msg_vk_formation_leader_get_ve(const mavlink_message_t* msg)
  472. {
  473. return _MAV_RETURN_float(msg, 20);
  474. }
  475. /**
  476. * @brief Get field vn from vk_formation_leader message
  477. *
  478. * @return [m/s] formation leader north speed
  479. */
  480. static inline float mavlink_msg_vk_formation_leader_get_vn(const mavlink_message_t* msg)
  481. {
  482. return _MAV_RETURN_float(msg, 24);
  483. }
  484. /**
  485. * @brief Get field vu from vk_formation_leader message
  486. *
  487. * @return [m/s] formation leader up speed
  488. */
  489. static inline float mavlink_msg_vk_formation_leader_get_vu(const mavlink_message_t* msg)
  490. {
  491. return _MAV_RETURN_float(msg, 28);
  492. }
  493. /**
  494. * @brief Get field yaw from vk_formation_leader message
  495. *
  496. * @return [deg] formation leader yaw
  497. */
  498. static inline float mavlink_msg_vk_formation_leader_get_yaw(const mavlink_message_t* msg)
  499. {
  500. return _MAV_RETURN_float(msg, 32);
  501. }
  502. /**
  503. * @brief Get field formation_type from vk_formation_leader message
  504. *
  505. * @return formation type
  506. */
  507. static inline uint8_t mavlink_msg_vk_formation_leader_get_formation_type(const mavlink_message_t* msg)
  508. {
  509. return _MAV_RETURN_uint8_t(msg, 44);
  510. }
  511. /**
  512. * @brief Get field x_dist from vk_formation_leader message
  513. *
  514. * @return [cm] distance between drones in x axis
  515. */
  516. static inline int16_t mavlink_msg_vk_formation_leader_get_x_dist(const mavlink_message_t* msg)
  517. {
  518. return _MAV_RETURN_int16_t(msg, 36);
  519. }
  520. /**
  521. * @brief Get field y_dist from vk_formation_leader message
  522. *
  523. * @return [cm] distance between drones in y axis
  524. */
  525. static inline int16_t mavlink_msg_vk_formation_leader_get_y_dist(const mavlink_message_t* msg)
  526. {
  527. return _MAV_RETURN_int16_t(msg, 38);
  528. }
  529. /**
  530. * @brief Get field z_dist from vk_formation_leader message
  531. *
  532. * @return [cm] distance between drones in z axis
  533. */
  534. static inline int16_t mavlink_msg_vk_formation_leader_get_z_dist(const mavlink_message_t* msg)
  535. {
  536. return _MAV_RETURN_int16_t(msg, 40);
  537. }
  538. /**
  539. * @brief Get field rect_col_num from vk_formation_leader message
  540. *
  541. * @return columns number of rectangle formation
  542. */
  543. static inline uint16_t mavlink_msg_vk_formation_leader_get_rect_col_num(const mavlink_message_t* msg)
  544. {
  545. return _MAV_RETURN_uint16_t(msg, 42);
  546. }
  547. /**
  548. * @brief Decode a vk_formation_leader message into a struct
  549. *
  550. * @param msg The message to decode
  551. * @param vk_formation_leader C-struct to decode the message contents into
  552. */
  553. static inline void mavlink_msg_vk_formation_leader_decode(const mavlink_message_t* msg, mavlink_vk_formation_leader_t* vk_formation_leader)
  554. {
  555. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  556. vk_formation_leader->timestamp = mavlink_msg_vk_formation_leader_get_timestamp(msg);
  557. vk_formation_leader->state = mavlink_msg_vk_formation_leader_get_state(msg);
  558. vk_formation_leader->lat = mavlink_msg_vk_formation_leader_get_lat(msg);
  559. vk_formation_leader->lon = mavlink_msg_vk_formation_leader_get_lon(msg);
  560. vk_formation_leader->msl = mavlink_msg_vk_formation_leader_get_msl(msg);
  561. vk_formation_leader->ve = mavlink_msg_vk_formation_leader_get_ve(msg);
  562. vk_formation_leader->vn = mavlink_msg_vk_formation_leader_get_vn(msg);
  563. vk_formation_leader->vu = mavlink_msg_vk_formation_leader_get_vu(msg);
  564. vk_formation_leader->yaw = mavlink_msg_vk_formation_leader_get_yaw(msg);
  565. vk_formation_leader->x_dist = mavlink_msg_vk_formation_leader_get_x_dist(msg);
  566. vk_formation_leader->y_dist = mavlink_msg_vk_formation_leader_get_y_dist(msg);
  567. vk_formation_leader->z_dist = mavlink_msg_vk_formation_leader_get_z_dist(msg);
  568. vk_formation_leader->rect_col_num = mavlink_msg_vk_formation_leader_get_rect_col_num(msg);
  569. vk_formation_leader->formation_type = mavlink_msg_vk_formation_leader_get_formation_type(msg);
  570. #else
  571. uint8_t len = msg->len < MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN? msg->len : MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN;
  572. memset(vk_formation_leader, 0, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
  573. memcpy(vk_formation_leader, _MAV_PAYLOAD(msg), len);
  574. #endif
  575. }