mavlink_msg_open_drone_id_system_update.h 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338
  1. #pragma once
  2. // MESSAGE OPEN_DRONE_ID_SYSTEM_UPDATE PACKING
  3. #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE 12919
  4. typedef struct __mavlink_open_drone_id_system_update_t {
  5. int32_t operator_latitude; /*< [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).*/
  6. int32_t operator_longitude; /*< [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).*/
  7. float operator_altitude_geo; /*< [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.*/
  8. uint32_t timestamp; /*< [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.*/
  9. uint8_t target_system; /*< System ID (0 for broadcast).*/
  10. uint8_t target_component; /*< Component ID (0 for broadcast).*/
  11. } mavlink_open_drone_id_system_update_t;
  12. #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN 18
  13. #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN 18
  14. #define MAVLINK_MSG_ID_12919_LEN 18
  15. #define MAVLINK_MSG_ID_12919_MIN_LEN 18
  16. #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC 7
  17. #define MAVLINK_MSG_ID_12919_CRC 7
  18. #if MAVLINK_COMMAND_24BIT
  19. #define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE { \
  20. 12919, \
  21. "OPEN_DRONE_ID_SYSTEM_UPDATE", \
  22. 6, \
  23. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_open_drone_id_system_update_t, target_system) }, \
  24. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_open_drone_id_system_update_t, target_component) }, \
  25. { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_update_t, operator_latitude) }, \
  26. { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_update_t, operator_longitude) }, \
  27. { "operator_altitude_geo", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_update_t, operator_altitude_geo) }, \
  28. { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_open_drone_id_system_update_t, timestamp) }, \
  29. } \
  30. }
  31. #else
  32. #define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE { \
  33. "OPEN_DRONE_ID_SYSTEM_UPDATE", \
  34. 6, \
  35. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_open_drone_id_system_update_t, target_system) }, \
  36. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_open_drone_id_system_update_t, target_component) }, \
  37. { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_update_t, operator_latitude) }, \
  38. { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_update_t, operator_longitude) }, \
  39. { "operator_altitude_geo", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_update_t, operator_altitude_geo) }, \
  40. { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_open_drone_id_system_update_t, timestamp) }, \
  41. } \
  42. }
  43. #endif
  44. /**
  45. * @brief Pack a open_drone_id_system_update message
  46. * @param system_id ID of this system
  47. * @param component_id ID of this component (e.g. 200 for IMU)
  48. * @param msg The MAVLink message to compress the data into
  49. *
  50. * @param target_system System ID (0 for broadcast).
  51. * @param target_component Component ID (0 for broadcast).
  52. * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
  53. * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
  54. * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.
  55. * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
  56. * @return length of the message in bytes (excluding serial stream start sign)
  57. */
  58. static inline uint16_t mavlink_msg_open_drone_id_system_update_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  59. uint8_t target_system, uint8_t target_component, int32_t operator_latitude, int32_t operator_longitude, float operator_altitude_geo, uint32_t timestamp)
  60. {
  61. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  62. char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN];
  63. _mav_put_int32_t(buf, 0, operator_latitude);
  64. _mav_put_int32_t(buf, 4, operator_longitude);
  65. _mav_put_float(buf, 8, operator_altitude_geo);
  66. _mav_put_uint32_t(buf, 12, timestamp);
  67. _mav_put_uint8_t(buf, 16, target_system);
  68. _mav_put_uint8_t(buf, 17, target_component);
  69. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN);
  70. #else
  71. mavlink_open_drone_id_system_update_t packet;
  72. packet.operator_latitude = operator_latitude;
  73. packet.operator_longitude = operator_longitude;
  74. packet.operator_altitude_geo = operator_altitude_geo;
  75. packet.timestamp = timestamp;
  76. packet.target_system = target_system;
  77. packet.target_component = target_component;
  78. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN);
  79. #endif
  80. msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE;
  81. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC);
  82. }
  83. /**
  84. * @brief Pack a open_drone_id_system_update message on a channel
  85. * @param system_id ID of this system
  86. * @param component_id ID of this component (e.g. 200 for IMU)
  87. * @param chan The MAVLink channel this message will be sent over
  88. * @param msg The MAVLink message to compress the data into
  89. * @param target_system System ID (0 for broadcast).
  90. * @param target_component Component ID (0 for broadcast).
  91. * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
  92. * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
  93. * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.
  94. * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
  95. * @return length of the message in bytes (excluding serial stream start sign)
  96. */
  97. static inline uint16_t mavlink_msg_open_drone_id_system_update_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  98. mavlink_message_t* msg,
  99. uint8_t target_system,uint8_t target_component,int32_t operator_latitude,int32_t operator_longitude,float operator_altitude_geo,uint32_t timestamp)
  100. {
  101. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  102. char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN];
  103. _mav_put_int32_t(buf, 0, operator_latitude);
  104. _mav_put_int32_t(buf, 4, operator_longitude);
  105. _mav_put_float(buf, 8, operator_altitude_geo);
  106. _mav_put_uint32_t(buf, 12, timestamp);
  107. _mav_put_uint8_t(buf, 16, target_system);
  108. _mav_put_uint8_t(buf, 17, target_component);
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN);
  110. #else
  111. mavlink_open_drone_id_system_update_t packet;
  112. packet.operator_latitude = operator_latitude;
  113. packet.operator_longitude = operator_longitude;
  114. packet.operator_altitude_geo = operator_altitude_geo;
  115. packet.timestamp = timestamp;
  116. packet.target_system = target_system;
  117. packet.target_component = target_component;
  118. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN);
  119. #endif
  120. msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE;
  121. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC);
  122. }
  123. /**
  124. * @brief Encode a open_drone_id_system_update struct
  125. *
  126. * @param system_id ID of this system
  127. * @param component_id ID of this component (e.g. 200 for IMU)
  128. * @param msg The MAVLink message to compress the data into
  129. * @param open_drone_id_system_update C-struct to read the message contents from
  130. */
  131. static inline uint16_t mavlink_msg_open_drone_id_system_update_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_system_update_t* open_drone_id_system_update)
  132. {
  133. return mavlink_msg_open_drone_id_system_update_pack(system_id, component_id, msg, open_drone_id_system_update->target_system, open_drone_id_system_update->target_component, open_drone_id_system_update->operator_latitude, open_drone_id_system_update->operator_longitude, open_drone_id_system_update->operator_altitude_geo, open_drone_id_system_update->timestamp);
  134. }
  135. /**
  136. * @brief Encode a open_drone_id_system_update struct on a channel
  137. *
  138. * @param system_id ID of this system
  139. * @param component_id ID of this component (e.g. 200 for IMU)
  140. * @param chan The MAVLink channel this message will be sent over
  141. * @param msg The MAVLink message to compress the data into
  142. * @param open_drone_id_system_update C-struct to read the message contents from
  143. */
  144. static inline uint16_t mavlink_msg_open_drone_id_system_update_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_system_update_t* open_drone_id_system_update)
  145. {
  146. return mavlink_msg_open_drone_id_system_update_pack_chan(system_id, component_id, chan, msg, open_drone_id_system_update->target_system, open_drone_id_system_update->target_component, open_drone_id_system_update->operator_latitude, open_drone_id_system_update->operator_longitude, open_drone_id_system_update->operator_altitude_geo, open_drone_id_system_update->timestamp);
  147. }
  148. /**
  149. * @brief Send a open_drone_id_system_update message
  150. * @param chan MAVLink channel to send the message
  151. *
  152. * @param target_system System ID (0 for broadcast).
  153. * @param target_component Component ID (0 for broadcast).
  154. * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
  155. * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
  156. * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.
  157. * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
  158. */
  159. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  160. static inline void mavlink_msg_open_drone_id_system_update_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t operator_latitude, int32_t operator_longitude, float operator_altitude_geo, uint32_t timestamp)
  161. {
  162. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  163. char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN];
  164. _mav_put_int32_t(buf, 0, operator_latitude);
  165. _mav_put_int32_t(buf, 4, operator_longitude);
  166. _mav_put_float(buf, 8, operator_altitude_geo);
  167. _mav_put_uint32_t(buf, 12, timestamp);
  168. _mav_put_uint8_t(buf, 16, target_system);
  169. _mav_put_uint8_t(buf, 17, target_component);
  170. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC);
  171. #else
  172. mavlink_open_drone_id_system_update_t packet;
  173. packet.operator_latitude = operator_latitude;
  174. packet.operator_longitude = operator_longitude;
  175. packet.operator_altitude_geo = operator_altitude_geo;
  176. packet.timestamp = timestamp;
  177. packet.target_system = target_system;
  178. packet.target_component = target_component;
  179. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC);
  180. #endif
  181. }
  182. /**
  183. * @brief Send a open_drone_id_system_update message
  184. * @param chan MAVLink channel to send the message
  185. * @param struct The MAVLink struct to serialize
  186. */
  187. static inline void mavlink_msg_open_drone_id_system_update_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_system_update_t* open_drone_id_system_update)
  188. {
  189. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  190. mavlink_msg_open_drone_id_system_update_send(chan, open_drone_id_system_update->target_system, open_drone_id_system_update->target_component, open_drone_id_system_update->operator_latitude, open_drone_id_system_update->operator_longitude, open_drone_id_system_update->operator_altitude_geo, open_drone_id_system_update->timestamp);
  191. #else
  192. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, (const char *)open_drone_id_system_update, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC);
  193. #endif
  194. }
  195. #if MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  196. /*
  197. This variant of _send() can be used to save stack space by re-using
  198. memory from the receive buffer. The caller provides a
  199. mavlink_message_t which is the size of a full mavlink message. This
  200. is usually the receive buffer for the channel, and allows a reply to an
  201. incoming message with minimum stack space usage.
  202. */
  203. static inline void mavlink_msg_open_drone_id_system_update_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t operator_latitude, int32_t operator_longitude, float operator_altitude_geo, uint32_t timestamp)
  204. {
  205. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  206. char *buf = (char *)msgbuf;
  207. _mav_put_int32_t(buf, 0, operator_latitude);
  208. _mav_put_int32_t(buf, 4, operator_longitude);
  209. _mav_put_float(buf, 8, operator_altitude_geo);
  210. _mav_put_uint32_t(buf, 12, timestamp);
  211. _mav_put_uint8_t(buf, 16, target_system);
  212. _mav_put_uint8_t(buf, 17, target_component);
  213. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC);
  214. #else
  215. mavlink_open_drone_id_system_update_t *packet = (mavlink_open_drone_id_system_update_t *)msgbuf;
  216. packet->operator_latitude = operator_latitude;
  217. packet->operator_longitude = operator_longitude;
  218. packet->operator_altitude_geo = operator_altitude_geo;
  219. packet->timestamp = timestamp;
  220. packet->target_system = target_system;
  221. packet->target_component = target_component;
  222. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC);
  223. #endif
  224. }
  225. #endif
  226. #endif
  227. // MESSAGE OPEN_DRONE_ID_SYSTEM_UPDATE UNPACKING
  228. /**
  229. * @brief Get field target_system from open_drone_id_system_update message
  230. *
  231. * @return System ID (0 for broadcast).
  232. */
  233. static inline uint8_t mavlink_msg_open_drone_id_system_update_get_target_system(const mavlink_message_t* msg)
  234. {
  235. return _MAV_RETURN_uint8_t(msg, 16);
  236. }
  237. /**
  238. * @brief Get field target_component from open_drone_id_system_update message
  239. *
  240. * @return Component ID (0 for broadcast).
  241. */
  242. static inline uint8_t mavlink_msg_open_drone_id_system_update_get_target_component(const mavlink_message_t* msg)
  243. {
  244. return _MAV_RETURN_uint8_t(msg, 17);
  245. }
  246. /**
  247. * @brief Get field operator_latitude from open_drone_id_system_update message
  248. *
  249. * @return [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
  250. */
  251. static inline int32_t mavlink_msg_open_drone_id_system_update_get_operator_latitude(const mavlink_message_t* msg)
  252. {
  253. return _MAV_RETURN_int32_t(msg, 0);
  254. }
  255. /**
  256. * @brief Get field operator_longitude from open_drone_id_system_update message
  257. *
  258. * @return [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
  259. */
  260. static inline int32_t mavlink_msg_open_drone_id_system_update_get_operator_longitude(const mavlink_message_t* msg)
  261. {
  262. return _MAV_RETURN_int32_t(msg, 4);
  263. }
  264. /**
  265. * @brief Get field operator_altitude_geo from open_drone_id_system_update message
  266. *
  267. * @return [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.
  268. */
  269. static inline float mavlink_msg_open_drone_id_system_update_get_operator_altitude_geo(const mavlink_message_t* msg)
  270. {
  271. return _MAV_RETURN_float(msg, 8);
  272. }
  273. /**
  274. * @brief Get field timestamp from open_drone_id_system_update message
  275. *
  276. * @return [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
  277. */
  278. static inline uint32_t mavlink_msg_open_drone_id_system_update_get_timestamp(const mavlink_message_t* msg)
  279. {
  280. return _MAV_RETURN_uint32_t(msg, 12);
  281. }
  282. /**
  283. * @brief Decode a open_drone_id_system_update message into a struct
  284. *
  285. * @param msg The message to decode
  286. * @param open_drone_id_system_update C-struct to decode the message contents into
  287. */
  288. static inline void mavlink_msg_open_drone_id_system_update_decode(const mavlink_message_t* msg, mavlink_open_drone_id_system_update_t* open_drone_id_system_update)
  289. {
  290. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  291. open_drone_id_system_update->operator_latitude = mavlink_msg_open_drone_id_system_update_get_operator_latitude(msg);
  292. open_drone_id_system_update->operator_longitude = mavlink_msg_open_drone_id_system_update_get_operator_longitude(msg);
  293. open_drone_id_system_update->operator_altitude_geo = mavlink_msg_open_drone_id_system_update_get_operator_altitude_geo(msg);
  294. open_drone_id_system_update->timestamp = mavlink_msg_open_drone_id_system_update_get_timestamp(msg);
  295. open_drone_id_system_update->target_system = mavlink_msg_open_drone_id_system_update_get_target_system(msg);
  296. open_drone_id_system_update->target_component = mavlink_msg_open_drone_id_system_update_get_target_component(msg);
  297. #else
  298. uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN;
  299. memset(open_drone_id_system_update, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN);
  300. memcpy(open_drone_id_system_update, _MAV_PAYLOAD(msg), len);
  301. #endif
  302. }