mavlink_msg_open_drone_id_system.h 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505
  1. #pragma once
  2. // MESSAGE OPEN_DRONE_ID_SYSTEM PACKING
  3. #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM 12904
  4. typedef struct __mavlink_open_drone_id_system_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 area_ceiling; /*< [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.*/
  8. float area_floor; /*< [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.*/
  9. uint16_t area_count; /*< Number of aircraft in the area, group or formation (default 1).*/
  10. uint16_t area_radius; /*< [m] Radius of the cylindrical area of the group or formation (default 0).*/
  11. uint8_t target_system; /*< System ID (0 for broadcast).*/
  12. uint8_t target_component; /*< Component ID (0 for broadcast).*/
  13. uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */
  14. uint8_t operator_location_type; /*< Specifies the operator location type.*/
  15. uint8_t classification_type; /*< Specifies the classification type of the UA.*/
  16. uint8_t category_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.*/
  17. uint8_t class_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.*/
  18. } mavlink_open_drone_id_system_t;
  19. #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN 46
  20. #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN 46
  21. #define MAVLINK_MSG_ID_12904_LEN 46
  22. #define MAVLINK_MSG_ID_12904_MIN_LEN 46
  23. #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC 203
  24. #define MAVLINK_MSG_ID_12904_CRC 203
  25. #define MAVLINK_MSG_OPEN_DRONE_ID_SYSTEM_FIELD_ID_OR_MAC_LEN 20
  26. #if MAVLINK_COMMAND_24BIT
  27. #define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM { \
  28. 12904, \
  29. "OPEN_DRONE_ID_SYSTEM", \
  30. 13, \
  31. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_open_drone_id_system_t, target_system) }, \
  32. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_open_drone_id_system_t, target_component) }, \
  33. { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 22, offsetof(mavlink_open_drone_id_system_t, id_or_mac) }, \
  34. { "operator_location_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_open_drone_id_system_t, operator_location_type) }, \
  35. { "classification_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_open_drone_id_system_t, classification_type) }, \
  36. { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_t, operator_latitude) }, \
  37. { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_t, operator_longitude) }, \
  38. { "area_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_open_drone_id_system_t, area_count) }, \
  39. { "area_radius", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_open_drone_id_system_t, area_radius) }, \
  40. { "area_ceiling", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_t, area_ceiling) }, \
  41. { "area_floor", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_system_t, area_floor) }, \
  42. { "category_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_open_drone_id_system_t, category_eu) }, \
  43. { "class_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_open_drone_id_system_t, class_eu) }, \
  44. } \
  45. }
  46. #else
  47. #define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM { \
  48. "OPEN_DRONE_ID_SYSTEM", \
  49. 13, \
  50. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_open_drone_id_system_t, target_system) }, \
  51. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_open_drone_id_system_t, target_component) }, \
  52. { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 22, offsetof(mavlink_open_drone_id_system_t, id_or_mac) }, \
  53. { "operator_location_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_open_drone_id_system_t, operator_location_type) }, \
  54. { "classification_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_open_drone_id_system_t, classification_type) }, \
  55. { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_t, operator_latitude) }, \
  56. { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_t, operator_longitude) }, \
  57. { "area_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_open_drone_id_system_t, area_count) }, \
  58. { "area_radius", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_open_drone_id_system_t, area_radius) }, \
  59. { "area_ceiling", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_t, area_ceiling) }, \
  60. { "area_floor", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_system_t, area_floor) }, \
  61. { "category_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_open_drone_id_system_t, category_eu) }, \
  62. { "class_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_open_drone_id_system_t, class_eu) }, \
  63. } \
  64. }
  65. #endif
  66. /**
  67. * @brief Pack a open_drone_id_system message
  68. * @param system_id ID of this system
  69. * @param component_id ID of this component (e.g. 200 for IMU)
  70. * @param msg The MAVLink message to compress the data into
  71. *
  72. * @param target_system System ID (0 for broadcast).
  73. * @param target_component Component ID (0 for broadcast).
  74. * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
  75. * @param operator_location_type Specifies the operator location type.
  76. * @param classification_type Specifies the classification type of the UA.
  77. * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
  78. * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
  79. * @param area_count Number of aircraft in the area, group or formation (default 1).
  80. * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
  81. * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
  82. * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
  83. * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
  84. * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
  85. * @return length of the message in bytes (excluding serial stream start sign)
  86. */
  87. static inline uint16_t mavlink_msg_open_drone_id_system_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  88. uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu)
  89. {
  90. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  91. char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN];
  92. _mav_put_int32_t(buf, 0, operator_latitude);
  93. _mav_put_int32_t(buf, 4, operator_longitude);
  94. _mav_put_float(buf, 8, area_ceiling);
  95. _mav_put_float(buf, 12, area_floor);
  96. _mav_put_uint16_t(buf, 16, area_count);
  97. _mav_put_uint16_t(buf, 18, area_radius);
  98. _mav_put_uint8_t(buf, 20, target_system);
  99. _mav_put_uint8_t(buf, 21, target_component);
  100. _mav_put_uint8_t(buf, 42, operator_location_type);
  101. _mav_put_uint8_t(buf, 43, classification_type);
  102. _mav_put_uint8_t(buf, 44, category_eu);
  103. _mav_put_uint8_t(buf, 45, class_eu);
  104. _mav_put_uint8_t_array(buf, 22, id_or_mac, 20);
  105. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
  106. #else
  107. mavlink_open_drone_id_system_t packet;
  108. packet.operator_latitude = operator_latitude;
  109. packet.operator_longitude = operator_longitude;
  110. packet.area_ceiling = area_ceiling;
  111. packet.area_floor = area_floor;
  112. packet.area_count = area_count;
  113. packet.area_radius = area_radius;
  114. packet.target_system = target_system;
  115. packet.target_component = target_component;
  116. packet.operator_location_type = operator_location_type;
  117. packet.classification_type = classification_type;
  118. packet.category_eu = category_eu;
  119. packet.class_eu = class_eu;
  120. mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
  121. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
  122. #endif
  123. msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM;
  124. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
  125. }
  126. /**
  127. * @brief Pack a open_drone_id_system message on a channel
  128. * @param system_id ID of this system
  129. * @param component_id ID of this component (e.g. 200 for IMU)
  130. * @param chan The MAVLink channel this message will be sent over
  131. * @param msg The MAVLink message to compress the data into
  132. * @param target_system System ID (0 for broadcast).
  133. * @param target_component Component ID (0 for broadcast).
  134. * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
  135. * @param operator_location_type Specifies the operator location type.
  136. * @param classification_type Specifies the classification type of the UA.
  137. * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
  138. * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
  139. * @param area_count Number of aircraft in the area, group or formation (default 1).
  140. * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
  141. * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
  142. * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
  143. * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
  144. * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
  145. * @return length of the message in bytes (excluding serial stream start sign)
  146. */
  147. static inline uint16_t mavlink_msg_open_drone_id_system_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  148. mavlink_message_t* msg,
  149. uint8_t target_system,uint8_t target_component,const uint8_t *id_or_mac,uint8_t operator_location_type,uint8_t classification_type,int32_t operator_latitude,int32_t operator_longitude,uint16_t area_count,uint16_t area_radius,float area_ceiling,float area_floor,uint8_t category_eu,uint8_t class_eu)
  150. {
  151. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  152. char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN];
  153. _mav_put_int32_t(buf, 0, operator_latitude);
  154. _mav_put_int32_t(buf, 4, operator_longitude);
  155. _mav_put_float(buf, 8, area_ceiling);
  156. _mav_put_float(buf, 12, area_floor);
  157. _mav_put_uint16_t(buf, 16, area_count);
  158. _mav_put_uint16_t(buf, 18, area_radius);
  159. _mav_put_uint8_t(buf, 20, target_system);
  160. _mav_put_uint8_t(buf, 21, target_component);
  161. _mav_put_uint8_t(buf, 42, operator_location_type);
  162. _mav_put_uint8_t(buf, 43, classification_type);
  163. _mav_put_uint8_t(buf, 44, category_eu);
  164. _mav_put_uint8_t(buf, 45, class_eu);
  165. _mav_put_uint8_t_array(buf, 22, id_or_mac, 20);
  166. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
  167. #else
  168. mavlink_open_drone_id_system_t packet;
  169. packet.operator_latitude = operator_latitude;
  170. packet.operator_longitude = operator_longitude;
  171. packet.area_ceiling = area_ceiling;
  172. packet.area_floor = area_floor;
  173. packet.area_count = area_count;
  174. packet.area_radius = area_radius;
  175. packet.target_system = target_system;
  176. packet.target_component = target_component;
  177. packet.operator_location_type = operator_location_type;
  178. packet.classification_type = classification_type;
  179. packet.category_eu = category_eu;
  180. packet.class_eu = class_eu;
  181. mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
  182. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
  183. #endif
  184. msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM;
  185. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
  186. }
  187. /**
  188. * @brief Encode a open_drone_id_system struct
  189. *
  190. * @param system_id ID of this system
  191. * @param component_id ID of this component (e.g. 200 for IMU)
  192. * @param msg The MAVLink message to compress the data into
  193. * @param open_drone_id_system C-struct to read the message contents from
  194. */
  195. static inline uint16_t mavlink_msg_open_drone_id_system_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_system_t* open_drone_id_system)
  196. {
  197. return mavlink_msg_open_drone_id_system_pack(system_id, component_id, msg, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu);
  198. }
  199. /**
  200. * @brief Encode a open_drone_id_system struct on a channel
  201. *
  202. * @param system_id ID of this system
  203. * @param component_id ID of this component (e.g. 200 for IMU)
  204. * @param chan The MAVLink channel this message will be sent over
  205. * @param msg The MAVLink message to compress the data into
  206. * @param open_drone_id_system C-struct to read the message contents from
  207. */
  208. static inline uint16_t mavlink_msg_open_drone_id_system_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_system_t* open_drone_id_system)
  209. {
  210. return mavlink_msg_open_drone_id_system_pack_chan(system_id, component_id, chan, msg, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu);
  211. }
  212. /**
  213. * @brief Send a open_drone_id_system message
  214. * @param chan MAVLink channel to send the message
  215. *
  216. * @param target_system System ID (0 for broadcast).
  217. * @param target_component Component ID (0 for broadcast).
  218. * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
  219. * @param operator_location_type Specifies the operator location type.
  220. * @param classification_type Specifies the classification type of the UA.
  221. * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
  222. * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
  223. * @param area_count Number of aircraft in the area, group or formation (default 1).
  224. * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
  225. * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
  226. * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
  227. * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
  228. * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
  229. */
  230. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  231. static inline void mavlink_msg_open_drone_id_system_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu)
  232. {
  233. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  234. char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN];
  235. _mav_put_int32_t(buf, 0, operator_latitude);
  236. _mav_put_int32_t(buf, 4, operator_longitude);
  237. _mav_put_float(buf, 8, area_ceiling);
  238. _mav_put_float(buf, 12, area_floor);
  239. _mav_put_uint16_t(buf, 16, area_count);
  240. _mav_put_uint16_t(buf, 18, area_radius);
  241. _mav_put_uint8_t(buf, 20, target_system);
  242. _mav_put_uint8_t(buf, 21, target_component);
  243. _mav_put_uint8_t(buf, 42, operator_location_type);
  244. _mav_put_uint8_t(buf, 43, classification_type);
  245. _mav_put_uint8_t(buf, 44, category_eu);
  246. _mav_put_uint8_t(buf, 45, class_eu);
  247. _mav_put_uint8_t_array(buf, 22, id_or_mac, 20);
  248. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
  249. #else
  250. mavlink_open_drone_id_system_t packet;
  251. packet.operator_latitude = operator_latitude;
  252. packet.operator_longitude = operator_longitude;
  253. packet.area_ceiling = area_ceiling;
  254. packet.area_floor = area_floor;
  255. packet.area_count = area_count;
  256. packet.area_radius = area_radius;
  257. packet.target_system = target_system;
  258. packet.target_component = target_component;
  259. packet.operator_location_type = operator_location_type;
  260. packet.classification_type = classification_type;
  261. packet.category_eu = category_eu;
  262. packet.class_eu = class_eu;
  263. mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
  264. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
  265. #endif
  266. }
  267. /**
  268. * @brief Send a open_drone_id_system message
  269. * @param chan MAVLink channel to send the message
  270. * @param struct The MAVLink struct to serialize
  271. */
  272. static inline void mavlink_msg_open_drone_id_system_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_system_t* open_drone_id_system)
  273. {
  274. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  275. mavlink_msg_open_drone_id_system_send(chan, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu);
  276. #else
  277. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)open_drone_id_system, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
  278. #endif
  279. }
  280. #if MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  281. /*
  282. This varient of _send() can be used to save stack space by re-using
  283. memory from the receive buffer. The caller provides a
  284. mavlink_message_t which is the size of a full mavlink message. This
  285. is usually the receive buffer for the channel, and allows a reply to an
  286. incoming message with minimum stack space usage.
  287. */
  288. static inline void mavlink_msg_open_drone_id_system_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu)
  289. {
  290. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  291. char *buf = (char *)msgbuf;
  292. _mav_put_int32_t(buf, 0, operator_latitude);
  293. _mav_put_int32_t(buf, 4, operator_longitude);
  294. _mav_put_float(buf, 8, area_ceiling);
  295. _mav_put_float(buf, 12, area_floor);
  296. _mav_put_uint16_t(buf, 16, area_count);
  297. _mav_put_uint16_t(buf, 18, area_radius);
  298. _mav_put_uint8_t(buf, 20, target_system);
  299. _mav_put_uint8_t(buf, 21, target_component);
  300. _mav_put_uint8_t(buf, 42, operator_location_type);
  301. _mav_put_uint8_t(buf, 43, classification_type);
  302. _mav_put_uint8_t(buf, 44, category_eu);
  303. _mav_put_uint8_t(buf, 45, class_eu);
  304. _mav_put_uint8_t_array(buf, 22, id_or_mac, 20);
  305. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
  306. #else
  307. mavlink_open_drone_id_system_t *packet = (mavlink_open_drone_id_system_t *)msgbuf;
  308. packet->operator_latitude = operator_latitude;
  309. packet->operator_longitude = operator_longitude;
  310. packet->area_ceiling = area_ceiling;
  311. packet->area_floor = area_floor;
  312. packet->area_count = area_count;
  313. packet->area_radius = area_radius;
  314. packet->target_system = target_system;
  315. packet->target_component = target_component;
  316. packet->operator_location_type = operator_location_type;
  317. packet->classification_type = classification_type;
  318. packet->category_eu = category_eu;
  319. packet->class_eu = class_eu;
  320. mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20);
  321. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
  322. #endif
  323. }
  324. #endif
  325. #endif
  326. // MESSAGE OPEN_DRONE_ID_SYSTEM UNPACKING
  327. /**
  328. * @brief Get field target_system from open_drone_id_system message
  329. *
  330. * @return System ID (0 for broadcast).
  331. */
  332. static inline uint8_t mavlink_msg_open_drone_id_system_get_target_system(const mavlink_message_t* msg)
  333. {
  334. return _MAV_RETURN_uint8_t(msg, 20);
  335. }
  336. /**
  337. * @brief Get field target_component from open_drone_id_system message
  338. *
  339. * @return Component ID (0 for broadcast).
  340. */
  341. static inline uint8_t mavlink_msg_open_drone_id_system_get_target_component(const mavlink_message_t* msg)
  342. {
  343. return _MAV_RETURN_uint8_t(msg, 21);
  344. }
  345. /**
  346. * @brief Get field id_or_mac from open_drone_id_system message
  347. *
  348. * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
  349. */
  350. static inline uint16_t mavlink_msg_open_drone_id_system_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac)
  351. {
  352. return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 22);
  353. }
  354. /**
  355. * @brief Get field operator_location_type from open_drone_id_system message
  356. *
  357. * @return Specifies the operator location type.
  358. */
  359. static inline uint8_t mavlink_msg_open_drone_id_system_get_operator_location_type(const mavlink_message_t* msg)
  360. {
  361. return _MAV_RETURN_uint8_t(msg, 42);
  362. }
  363. /**
  364. * @brief Get field classification_type from open_drone_id_system message
  365. *
  366. * @return Specifies the classification type of the UA.
  367. */
  368. static inline uint8_t mavlink_msg_open_drone_id_system_get_classification_type(const mavlink_message_t* msg)
  369. {
  370. return _MAV_RETURN_uint8_t(msg, 43);
  371. }
  372. /**
  373. * @brief Get field operator_latitude from open_drone_id_system message
  374. *
  375. * @return [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
  376. */
  377. static inline int32_t mavlink_msg_open_drone_id_system_get_operator_latitude(const mavlink_message_t* msg)
  378. {
  379. return _MAV_RETURN_int32_t(msg, 0);
  380. }
  381. /**
  382. * @brief Get field operator_longitude from open_drone_id_system message
  383. *
  384. * @return [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
  385. */
  386. static inline int32_t mavlink_msg_open_drone_id_system_get_operator_longitude(const mavlink_message_t* msg)
  387. {
  388. return _MAV_RETURN_int32_t(msg, 4);
  389. }
  390. /**
  391. * @brief Get field area_count from open_drone_id_system message
  392. *
  393. * @return Number of aircraft in the area, group or formation (default 1).
  394. */
  395. static inline uint16_t mavlink_msg_open_drone_id_system_get_area_count(const mavlink_message_t* msg)
  396. {
  397. return _MAV_RETURN_uint16_t(msg, 16);
  398. }
  399. /**
  400. * @brief Get field area_radius from open_drone_id_system message
  401. *
  402. * @return [m] Radius of the cylindrical area of the group or formation (default 0).
  403. */
  404. static inline uint16_t mavlink_msg_open_drone_id_system_get_area_radius(const mavlink_message_t* msg)
  405. {
  406. return _MAV_RETURN_uint16_t(msg, 18);
  407. }
  408. /**
  409. * @brief Get field area_ceiling from open_drone_id_system message
  410. *
  411. * @return [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
  412. */
  413. static inline float mavlink_msg_open_drone_id_system_get_area_ceiling(const mavlink_message_t* msg)
  414. {
  415. return _MAV_RETURN_float(msg, 8);
  416. }
  417. /**
  418. * @brief Get field area_floor from open_drone_id_system message
  419. *
  420. * @return [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
  421. */
  422. static inline float mavlink_msg_open_drone_id_system_get_area_floor(const mavlink_message_t* msg)
  423. {
  424. return _MAV_RETURN_float(msg, 12);
  425. }
  426. /**
  427. * @brief Get field category_eu from open_drone_id_system message
  428. *
  429. * @return When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
  430. */
  431. static inline uint8_t mavlink_msg_open_drone_id_system_get_category_eu(const mavlink_message_t* msg)
  432. {
  433. return _MAV_RETURN_uint8_t(msg, 44);
  434. }
  435. /**
  436. * @brief Get field class_eu from open_drone_id_system message
  437. *
  438. * @return When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
  439. */
  440. static inline uint8_t mavlink_msg_open_drone_id_system_get_class_eu(const mavlink_message_t* msg)
  441. {
  442. return _MAV_RETURN_uint8_t(msg, 45);
  443. }
  444. /**
  445. * @brief Decode a open_drone_id_system message into a struct
  446. *
  447. * @param msg The message to decode
  448. * @param open_drone_id_system C-struct to decode the message contents into
  449. */
  450. static inline void mavlink_msg_open_drone_id_system_decode(const mavlink_message_t* msg, mavlink_open_drone_id_system_t* open_drone_id_system)
  451. {
  452. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  453. open_drone_id_system->operator_latitude = mavlink_msg_open_drone_id_system_get_operator_latitude(msg);
  454. open_drone_id_system->operator_longitude = mavlink_msg_open_drone_id_system_get_operator_longitude(msg);
  455. open_drone_id_system->area_ceiling = mavlink_msg_open_drone_id_system_get_area_ceiling(msg);
  456. open_drone_id_system->area_floor = mavlink_msg_open_drone_id_system_get_area_floor(msg);
  457. open_drone_id_system->area_count = mavlink_msg_open_drone_id_system_get_area_count(msg);
  458. open_drone_id_system->area_radius = mavlink_msg_open_drone_id_system_get_area_radius(msg);
  459. open_drone_id_system->target_system = mavlink_msg_open_drone_id_system_get_target_system(msg);
  460. open_drone_id_system->target_component = mavlink_msg_open_drone_id_system_get_target_component(msg);
  461. mavlink_msg_open_drone_id_system_get_id_or_mac(msg, open_drone_id_system->id_or_mac);
  462. open_drone_id_system->operator_location_type = mavlink_msg_open_drone_id_system_get_operator_location_type(msg);
  463. open_drone_id_system->classification_type = mavlink_msg_open_drone_id_system_get_classification_type(msg);
  464. open_drone_id_system->category_eu = mavlink_msg_open_drone_id_system_get_category_eu(msg);
  465. open_drone_id_system->class_eu = mavlink_msg_open_drone_id_system_get_class_eu(msg);
  466. #else
  467. uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN;
  468. memset(open_drone_id_system, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
  469. memcpy(open_drone_id_system, _MAV_PAYLOAD(msg), len);
  470. #endif
  471. }