2 // MESSAGE OPEN_DRONE_ID_SYSTEM PACKING
4 #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM 12904
7 typedef struct __mavlink_open_drone_id_system_t
{
8 int32_t operator_latitude
; /*< [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).*/
9 int32_t operator_longitude
; /*< [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).*/
10 float area_ceiling
; /*< [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.*/
11 float area_floor
; /*< [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.*/
12 uint16_t area_count
; /*< Number of aircraft in the area, group or formation (default 1).*/
13 uint16_t area_radius
; /*< [m] Radius of the cylindrical area of the group or formation (default 0).*/
14 uint8_t target_system
; /*< System ID (0 for broadcast).*/
15 uint8_t target_component
; /*< Component ID (0 for broadcast).*/
16 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. */
17 uint8_t operator_location_type
; /*< Specifies the operator location type.*/
18 uint8_t classification_type
; /*< Specifies the classification type of the UA.*/
19 uint8_t category_eu
; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.*/
20 uint8_t class_eu
; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.*/
21 } mavlink_open_drone_id_system_t
;
23 #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN 46
24 #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN 46
25 #define MAVLINK_MSG_ID_12904_LEN 46
26 #define MAVLINK_MSG_ID_12904_MIN_LEN 46
28 #define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC 203
29 #define MAVLINK_MSG_ID_12904_CRC 203
31 #define MAVLINK_MSG_OPEN_DRONE_ID_SYSTEM_FIELD_ID_OR_MAC_LEN 20
33 #if MAVLINK_COMMAND_24BIT
34 #define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM { \
36 "OPEN_DRONE_ID_SYSTEM", \
38 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_open_drone_id_system_t, target_system) }, \
39 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_open_drone_id_system_t, target_component) }, \
40 { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 22, offsetof(mavlink_open_drone_id_system_t, id_or_mac) }, \
41 { "operator_location_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_open_drone_id_system_t, operator_location_type) }, \
42 { "classification_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_open_drone_id_system_t, classification_type) }, \
43 { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_t, operator_latitude) }, \
44 { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_t, operator_longitude) }, \
45 { "area_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_open_drone_id_system_t, area_count) }, \
46 { "area_radius", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_open_drone_id_system_t, area_radius) }, \
47 { "area_ceiling", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_t, area_ceiling) }, \
48 { "area_floor", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_system_t, area_floor) }, \
49 { "category_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_open_drone_id_system_t, category_eu) }, \
50 { "class_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_open_drone_id_system_t, class_eu) }, \
54 #define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM { \
55 "OPEN_DRONE_ID_SYSTEM", \
57 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_open_drone_id_system_t, target_system) }, \
58 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_open_drone_id_system_t, target_component) }, \
59 { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 22, offsetof(mavlink_open_drone_id_system_t, id_or_mac) }, \
60 { "operator_location_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_open_drone_id_system_t, operator_location_type) }, \
61 { "classification_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_open_drone_id_system_t, classification_type) }, \
62 { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_t, operator_latitude) }, \
63 { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_t, operator_longitude) }, \
64 { "area_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_open_drone_id_system_t, area_count) }, \
65 { "area_radius", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_open_drone_id_system_t, area_radius) }, \
66 { "area_ceiling", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_t, area_ceiling) }, \
67 { "area_floor", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_system_t, area_floor) }, \
68 { "category_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_open_drone_id_system_t, category_eu) }, \
69 { "class_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_open_drone_id_system_t, class_eu) }, \
75 * @brief Pack a open_drone_id_system message
76 * @param system_id ID of this system
77 * @param component_id ID of this component (e.g. 200 for IMU)
78 * @param msg The MAVLink message to compress the data into
80 * @param target_system System ID (0 for broadcast).
81 * @param target_component Component ID (0 for broadcast).
82 * @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.
83 * @param operator_location_type Specifies the operator location type.
84 * @param classification_type Specifies the classification type of the UA.
85 * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
86 * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
87 * @param area_count Number of aircraft in the area, group or formation (default 1).
88 * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
89 * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
90 * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
91 * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
92 * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
93 * @return length of the message in bytes (excluding serial stream start sign)
95 static inline uint16_t mavlink_msg_open_drone_id_system_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
96 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
)
98 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
99 char buf
[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
];
100 _mav_put_int32_t(buf
, 0, operator_latitude
);
101 _mav_put_int32_t(buf
, 4, operator_longitude
);
102 _mav_put_float(buf
, 8, area_ceiling
);
103 _mav_put_float(buf
, 12, area_floor
);
104 _mav_put_uint16_t(buf
, 16, area_count
);
105 _mav_put_uint16_t(buf
, 18, area_radius
);
106 _mav_put_uint8_t(buf
, 20, target_system
);
107 _mav_put_uint8_t(buf
, 21, target_component
);
108 _mav_put_uint8_t(buf
, 42, operator_location_type
);
109 _mav_put_uint8_t(buf
, 43, classification_type
);
110 _mav_put_uint8_t(buf
, 44, category_eu
);
111 _mav_put_uint8_t(buf
, 45, class_eu
);
112 _mav_put_uint8_t_array(buf
, 22, id_or_mac
, 20);
113 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
);
115 mavlink_open_drone_id_system_t packet
;
116 packet
.operator_latitude
= operator_latitude
;
117 packet
.operator_longitude
= operator_longitude
;
118 packet
.area_ceiling
= area_ceiling
;
119 packet
.area_floor
= area_floor
;
120 packet
.area_count
= area_count
;
121 packet
.area_radius
= area_radius
;
122 packet
.target_system
= target_system
;
123 packet
.target_component
= target_component
;
124 packet
.operator_location_type
= operator_location_type
;
125 packet
.classification_type
= classification_type
;
126 packet
.category_eu
= category_eu
;
127 packet
.class_eu
= class_eu
;
128 mav_array_memcpy(packet
.id_or_mac
, id_or_mac
, sizeof(uint8_t)*20);
129 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
);
132 msg
->msgid
= MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM
;
133 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
);
137 * @brief Pack a open_drone_id_system message on a channel
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 target_system System ID (0 for broadcast).
143 * @param target_component Component ID (0 for broadcast).
144 * @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.
145 * @param operator_location_type Specifies the operator location type.
146 * @param classification_type Specifies the classification type of the UA.
147 * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
148 * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
149 * @param area_count Number of aircraft in the area, group or formation (default 1).
150 * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
151 * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
152 * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
153 * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
154 * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
155 * @return length of the message in bytes (excluding serial stream start sign)
157 static inline uint16_t mavlink_msg_open_drone_id_system_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
158 mavlink_message_t
* msg
,
159 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
)
161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
162 char buf
[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
];
163 _mav_put_int32_t(buf
, 0, operator_latitude
);
164 _mav_put_int32_t(buf
, 4, operator_longitude
);
165 _mav_put_float(buf
, 8, area_ceiling
);
166 _mav_put_float(buf
, 12, area_floor
);
167 _mav_put_uint16_t(buf
, 16, area_count
);
168 _mav_put_uint16_t(buf
, 18, area_radius
);
169 _mav_put_uint8_t(buf
, 20, target_system
);
170 _mav_put_uint8_t(buf
, 21, target_component
);
171 _mav_put_uint8_t(buf
, 42, operator_location_type
);
172 _mav_put_uint8_t(buf
, 43, classification_type
);
173 _mav_put_uint8_t(buf
, 44, category_eu
);
174 _mav_put_uint8_t(buf
, 45, class_eu
);
175 _mav_put_uint8_t_array(buf
, 22, id_or_mac
, 20);
176 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
);
178 mavlink_open_drone_id_system_t packet
;
179 packet
.operator_latitude
= operator_latitude
;
180 packet
.operator_longitude
= operator_longitude
;
181 packet
.area_ceiling
= area_ceiling
;
182 packet
.area_floor
= area_floor
;
183 packet
.area_count
= area_count
;
184 packet
.area_radius
= area_radius
;
185 packet
.target_system
= target_system
;
186 packet
.target_component
= target_component
;
187 packet
.operator_location_type
= operator_location_type
;
188 packet
.classification_type
= classification_type
;
189 packet
.category_eu
= category_eu
;
190 packet
.class_eu
= class_eu
;
191 mav_array_memcpy(packet
.id_or_mac
, id_or_mac
, sizeof(uint8_t)*20);
192 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
);
195 msg
->msgid
= MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM
;
196 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
);
200 * @brief Encode a open_drone_id_system struct
202 * @param system_id ID of this system
203 * @param component_id ID of this component (e.g. 200 for IMU)
204 * @param msg The MAVLink message to compress the data into
205 * @param open_drone_id_system C-struct to read the message contents from
207 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
)
209 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
);
213 * @brief Encode a open_drone_id_system struct on a channel
215 * @param system_id ID of this system
216 * @param component_id ID of this component (e.g. 200 for IMU)
217 * @param chan The MAVLink channel this message will be sent over
218 * @param msg The MAVLink message to compress the data into
219 * @param open_drone_id_system C-struct to read the message contents from
221 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
)
223 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
);
227 * @brief Send a open_drone_id_system message
228 * @param chan MAVLink channel to send the message
230 * @param target_system System ID (0 for broadcast).
231 * @param target_component Component ID (0 for broadcast).
232 * @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.
233 * @param operator_location_type Specifies the operator location type.
234 * @param classification_type Specifies the classification type of the UA.
235 * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
236 * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
237 * @param area_count Number of aircraft in the area, group or formation (default 1).
238 * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
239 * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
240 * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
241 * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
242 * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
244 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
246 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
)
248 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
249 char buf
[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
];
250 _mav_put_int32_t(buf
, 0, operator_latitude
);
251 _mav_put_int32_t(buf
, 4, operator_longitude
);
252 _mav_put_float(buf
, 8, area_ceiling
);
253 _mav_put_float(buf
, 12, area_floor
);
254 _mav_put_uint16_t(buf
, 16, area_count
);
255 _mav_put_uint16_t(buf
, 18, area_radius
);
256 _mav_put_uint8_t(buf
, 20, target_system
);
257 _mav_put_uint8_t(buf
, 21, target_component
);
258 _mav_put_uint8_t(buf
, 42, operator_location_type
);
259 _mav_put_uint8_t(buf
, 43, classification_type
);
260 _mav_put_uint8_t(buf
, 44, category_eu
);
261 _mav_put_uint8_t(buf
, 45, class_eu
);
262 _mav_put_uint8_t_array(buf
, 22, id_or_mac
, 20);
263 _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
);
265 mavlink_open_drone_id_system_t packet
;
266 packet
.operator_latitude
= operator_latitude
;
267 packet
.operator_longitude
= operator_longitude
;
268 packet
.area_ceiling
= area_ceiling
;
269 packet
.area_floor
= area_floor
;
270 packet
.area_count
= area_count
;
271 packet
.area_radius
= area_radius
;
272 packet
.target_system
= target_system
;
273 packet
.target_component
= target_component
;
274 packet
.operator_location_type
= operator_location_type
;
275 packet
.classification_type
= classification_type
;
276 packet
.category_eu
= category_eu
;
277 packet
.class_eu
= class_eu
;
278 mav_array_memcpy(packet
.id_or_mac
, id_or_mac
, sizeof(uint8_t)*20);
279 _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
);
284 * @brief Send a open_drone_id_system message
285 * @param chan MAVLink channel to send the message
286 * @param struct The MAVLink struct to serialize
288 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
)
290 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
291 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
);
293 _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
);
297 #if MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
299 This varient of _send() can be used to save stack space by re-using
300 memory from the receive buffer. The caller provides a
301 mavlink_message_t which is the size of a full mavlink message. This
302 is usually the receive buffer for the channel, and allows a reply to an
303 incoming message with minimum stack space usage.
305 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
)
307 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
308 char *buf
= (char *)msgbuf
;
309 _mav_put_int32_t(buf
, 0, operator_latitude
);
310 _mav_put_int32_t(buf
, 4, operator_longitude
);
311 _mav_put_float(buf
, 8, area_ceiling
);
312 _mav_put_float(buf
, 12, area_floor
);
313 _mav_put_uint16_t(buf
, 16, area_count
);
314 _mav_put_uint16_t(buf
, 18, area_radius
);
315 _mav_put_uint8_t(buf
, 20, target_system
);
316 _mav_put_uint8_t(buf
, 21, target_component
);
317 _mav_put_uint8_t(buf
, 42, operator_location_type
);
318 _mav_put_uint8_t(buf
, 43, classification_type
);
319 _mav_put_uint8_t(buf
, 44, category_eu
);
320 _mav_put_uint8_t(buf
, 45, class_eu
);
321 _mav_put_uint8_t_array(buf
, 22, id_or_mac
, 20);
322 _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
);
324 mavlink_open_drone_id_system_t
*packet
= (mavlink_open_drone_id_system_t
*)msgbuf
;
325 packet
->operator_latitude
= operator_latitude
;
326 packet
->operator_longitude
= operator_longitude
;
327 packet
->area_ceiling
= area_ceiling
;
328 packet
->area_floor
= area_floor
;
329 packet
->area_count
= area_count
;
330 packet
->area_radius
= area_radius
;
331 packet
->target_system
= target_system
;
332 packet
->target_component
= target_component
;
333 packet
->operator_location_type
= operator_location_type
;
334 packet
->classification_type
= classification_type
;
335 packet
->category_eu
= category_eu
;
336 packet
->class_eu
= class_eu
;
337 mav_array_memcpy(packet
->id_or_mac
, id_or_mac
, sizeof(uint8_t)*20);
338 _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
);
345 // MESSAGE OPEN_DRONE_ID_SYSTEM UNPACKING
349 * @brief Get field target_system from open_drone_id_system message
351 * @return System ID (0 for broadcast).
353 static inline uint8_t mavlink_msg_open_drone_id_system_get_target_system(const mavlink_message_t
* msg
)
355 return _MAV_RETURN_uint8_t(msg
, 20);
359 * @brief Get field target_component from open_drone_id_system message
361 * @return Component ID (0 for broadcast).
363 static inline uint8_t mavlink_msg_open_drone_id_system_get_target_component(const mavlink_message_t
* msg
)
365 return _MAV_RETURN_uint8_t(msg
, 21);
369 * @brief Get field id_or_mac from open_drone_id_system message
371 * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
373 static inline uint16_t mavlink_msg_open_drone_id_system_get_id_or_mac(const mavlink_message_t
* msg
, uint8_t *id_or_mac
)
375 return _MAV_RETURN_uint8_t_array(msg
, id_or_mac
, 20, 22);
379 * @brief Get field operator_location_type from open_drone_id_system message
381 * @return Specifies the operator location type.
383 static inline uint8_t mavlink_msg_open_drone_id_system_get_operator_location_type(const mavlink_message_t
* msg
)
385 return _MAV_RETURN_uint8_t(msg
, 42);
389 * @brief Get field classification_type from open_drone_id_system message
391 * @return Specifies the classification type of the UA.
393 static inline uint8_t mavlink_msg_open_drone_id_system_get_classification_type(const mavlink_message_t
* msg
)
395 return _MAV_RETURN_uint8_t(msg
, 43);
399 * @brief Get field operator_latitude from open_drone_id_system message
401 * @return [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
403 static inline int32_t mavlink_msg_open_drone_id_system_get_operator_latitude(const mavlink_message_t
* msg
)
405 return _MAV_RETURN_int32_t(msg
, 0);
409 * @brief Get field operator_longitude from open_drone_id_system message
411 * @return [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
413 static inline int32_t mavlink_msg_open_drone_id_system_get_operator_longitude(const mavlink_message_t
* msg
)
415 return _MAV_RETURN_int32_t(msg
, 4);
419 * @brief Get field area_count from open_drone_id_system message
421 * @return Number of aircraft in the area, group or formation (default 1).
423 static inline uint16_t mavlink_msg_open_drone_id_system_get_area_count(const mavlink_message_t
* msg
)
425 return _MAV_RETURN_uint16_t(msg
, 16);
429 * @brief Get field area_radius from open_drone_id_system message
431 * @return [m] Radius of the cylindrical area of the group or formation (default 0).
433 static inline uint16_t mavlink_msg_open_drone_id_system_get_area_radius(const mavlink_message_t
* msg
)
435 return _MAV_RETURN_uint16_t(msg
, 18);
439 * @brief Get field area_ceiling from open_drone_id_system message
441 * @return [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
443 static inline float mavlink_msg_open_drone_id_system_get_area_ceiling(const mavlink_message_t
* msg
)
445 return _MAV_RETURN_float(msg
, 8);
449 * @brief Get field area_floor from open_drone_id_system message
451 * @return [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
453 static inline float mavlink_msg_open_drone_id_system_get_area_floor(const mavlink_message_t
* msg
)
455 return _MAV_RETURN_float(msg
, 12);
459 * @brief Get field category_eu from open_drone_id_system message
461 * @return When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
463 static inline uint8_t mavlink_msg_open_drone_id_system_get_category_eu(const mavlink_message_t
* msg
)
465 return _MAV_RETURN_uint8_t(msg
, 44);
469 * @brief Get field class_eu from open_drone_id_system message
471 * @return When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
473 static inline uint8_t mavlink_msg_open_drone_id_system_get_class_eu(const mavlink_message_t
* msg
)
475 return _MAV_RETURN_uint8_t(msg
, 45);
479 * @brief Decode a open_drone_id_system message into a struct
481 * @param msg The message to decode
482 * @param open_drone_id_system C-struct to decode the message contents into
484 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
)
486 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
487 open_drone_id_system
->operator_latitude
= mavlink_msg_open_drone_id_system_get_operator_latitude(msg
);
488 open_drone_id_system
->operator_longitude
= mavlink_msg_open_drone_id_system_get_operator_longitude(msg
);
489 open_drone_id_system
->area_ceiling
= mavlink_msg_open_drone_id_system_get_area_ceiling(msg
);
490 open_drone_id_system
->area_floor
= mavlink_msg_open_drone_id_system_get_area_floor(msg
);
491 open_drone_id_system
->area_count
= mavlink_msg_open_drone_id_system_get_area_count(msg
);
492 open_drone_id_system
->area_radius
= mavlink_msg_open_drone_id_system_get_area_radius(msg
);
493 open_drone_id_system
->target_system
= mavlink_msg_open_drone_id_system_get_target_system(msg
);
494 open_drone_id_system
->target_component
= mavlink_msg_open_drone_id_system_get_target_component(msg
);
495 mavlink_msg_open_drone_id_system_get_id_or_mac(msg
, open_drone_id_system
->id_or_mac
);
496 open_drone_id_system
->operator_location_type
= mavlink_msg_open_drone_id_system_get_operator_location_type(msg
);
497 open_drone_id_system
->classification_type
= mavlink_msg_open_drone_id_system_get_classification_type(msg
);
498 open_drone_id_system
->category_eu
= mavlink_msg_open_drone_id_system_get_category_eu(msg
);
499 open_drone_id_system
->class_eu
= mavlink_msg_open_drone_id_system_get_class_eu(msg
);
501 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
? msg
->len
: MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
;
502 memset(open_drone_id_system
, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN
);
503 memcpy(open_drone_id_system
, _MAV_PAYLOAD(msg
), len
);