remote_id/codec/
decode.rs

1use core::time::Duration;
2
3use basic_id::{BasicId, IdType, UAType};
4use chrono::DateTime;
5use location::{
6    HeightType, HorizontalAccuracy, Location, OperationalStatus, SpeedAccuracy, VerticalAccuracy,
7};
8use operator_id::{OperatorId, OperatorIdType};
9use system::{ClassificationType, OperatorLocationType, System};
10
11extern crate std;
12use crate::data::system::{UaCategory, UaClass, UaClassification};
13use crate::{data::*, get_bits, get_bytes};
14use crate::{MAX_ID_BYTE_SIZE, OPEN_DRONE_ID_AD_CODE};
15
16use super::{copy_to_id, MessageType};
17
18pub fn from_service_data(data: &[u8]) -> Option<RemoteIDMessage> {
19    let first_byte = data[0];
20    if first_byte != OPEN_DRONE_ID_AD_CODE {
21        // all RemoteID Messages start with this byte?
22        return None;
23    }
24
25    let _message_counter = data[1];
26
27    from_message_buffer(&data[2..])
28}
29
30pub fn from_message_buffer(data: &[u8]) -> Option<RemoteIDMessage> {
31    // protocol version, reserved for private use
32    let _version = get_bits!(data[0], 3..0);
33
34    match MessageType::from(get_bits!(data[0], 7..4)) {
35        MessageType::BasicId => parse_basic_id(data),
36        MessageType::Location => parse_location(data),
37        MessageType::OperatorId => parse_operator_id(data),
38        MessageType::System => parse_system(data),
39
40        // we have no examples for these yet
41        MessageType::Selfid => todo!(),
42        MessageType::Auth => todo!(),
43        MessageType::MessagePack => todo!(),
44
45        MessageType::Invalid => None,
46    }
47}
48
49fn parse_basic_id(buffer: &[u8]) -> Option<RemoteIDMessage> {
50    let id_type = IdType::from(get_bits!(buffer[1], 7..4));
51    let ua_type = UAType::from(get_bits!(buffer[1], 3..0));
52
53    let uas_id = copy_to_id(get_bytes!(buffer, 2, crate::MAX_ID_BYTE_SIZE));
54
55    Some(RemoteIDMessage::BasicID(BasicId {
56        id_type,
57        ua_type,
58        uas_id,
59    }))
60}
61
62fn parse_operator_id(buffer: &[u8]) -> Option<RemoteIDMessage> {
63    // Operator ID Type
64    let id_type = OperatorIdType::from(buffer[1]);
65
66    // Operator ID
67    let operator_id = copy_to_id(get_bytes!(buffer, 2, MAX_ID_BYTE_SIZE));
68
69    let _reserved = get_bytes!(buffer, MAX_ID_BYTE_SIZE + 2, 3);
70
71    Some(RemoteIDMessage::OperatorId(OperatorId {
72        id_type,
73        operator_id,
74    }))
75}
76
77fn parse_system(buffer: &[u8]) -> Option<RemoteIDMessage> {
78    let flags = buffer[1];
79    // Reserved: Bits [7..5]
80    let _reserved = get_bits!(flags, 7..5);
81    // Classification Type: Bits [4..2]
82    let classification_type = ClassificationType::from(get_bits!(flags, 4..2));
83    // Operator Location/Altitude source type: Bits [1–0]
84    let operator_location_type = OperatorLocationType::from(get_bits!(flags, 1..0));
85
86    // Operator Latitude
87    //    Latitude of Remote Pilot
88    let operator_latidute =
89        u32::from_le_bytes(get_bytes!(buffer, 2, 4)) as f32 / f32::powf(10., 7.);
90
91    // Operator Longitude
92    //   Longitude of Remote Pilot
93    let operator_longitude =
94        u32::from_le_bytes(get_bytes!(buffer, 6, 4)) as f32 / f32::powf(10., 7.);
95
96    // Area Count
97    //   Number of aircraft in Area, group or formation (default 1)
98    let area_count = u16::from_le_bytes(get_bytes!(buffer, 10, 2));
99
100    // Area Radius
101    //   Radius of cylindrical area of group or formation * 10 m (default 0)
102    //   centered on Location/Vector Message position
103    let area_radius = get_bytes!(buffer, 12, 1) as f32 * 10.;
104
105    // Area Ceiling
106    //   Group operations ceiling WGS-84 HAE (Altitude + 1000 m)/0.5
107    let area_ceiling = u16::from_le_bytes(get_bytes!(buffer, 13, 2)) as f32 / 2. - 1000.;
108
109    // Area Floor
110    //   Group operations floor WGS-84 HAE (Altitude + 1000 m)/0.5
111    let area_floor = u16::from_le_bytes(get_bytes!(buffer, 15, 2)) as f32 / 2. - 1000.;
112
113    // TODO UA Classification
114    let ua_classification = if classification_type == ClassificationType::EuropeanUnion {
115        UaClassification {
116            category: UaCategory::from(buffer[17] >> 3),
117            class: UaClass::from(get_bits!(buffer[17], 0..3)),
118        }
119    } else {
120        UaClassification::undefined()
121    };
122
123    // Operator Altitude
124    let operator_altitude = u16::from_le_bytes(get_bytes!(buffer, 18, 2)) as f32 / 2. - 1000.;
125
126    // Timestamp
127    let unix_secs = u32::from_le_bytes(get_bytes!(buffer, 20, 4));
128    let timestamp = DateTime::from_timestamp(unix_secs as i64 + 1546300800, 0)?;
129
130    // Reserved
131    let _reserved = get_bytes!(buffer, 24, 1);
132
133    Some(RemoteIDMessage::System(System {
134        classification_type,
135        operator_location_type,
136        operator_latidute,
137        operator_longitude,
138        operator_altitude,
139        area_count,
140        area_radius,
141        area_floor,
142        area_ceiling,
143        ua_classification,
144        timestamp,
145    }))
146}
147
148fn parse_location(buffer: &[u8]) -> Option<RemoteIDMessage> {
149    // Status, Flags
150    let status_flags = get_bytes!(buffer, 1, 1);
151
152    let operational_status = OperationalStatus::from(get_bits!(status_flags, 7..4));
153    let _reserved = get_bits!(status_flags, 3..3);
154    let height_type = HeightType::from(get_bits!(status_flags, 2..2));
155    let ew_direction_segment = get_bits!(status_flags, 1..1);
156    let speed_multiplier = get_bits!(status_flags, 0..0);
157
158    // Track Direction
159    let track_direction = get_bytes!(buffer, 2, 1);
160    let track_direction = if ew_direction_segment > 0 {
161        track_direction as u16 + 180
162    } else {
163        track_direction as u16
164    };
165
166    // Speed
167    let speed = get_bytes!(buffer, 3, 1);
168    let speed = if speed_multiplier == 0 {
169        speed as f32 * 0.25
170    } else {
171        (speed as f32 + 255. * 0.25) * 0.75
172    };
173
174    // Vertical Speed
175    let vertical_speed = get_bytes!(buffer, 4, 1);
176    let vertical_speed = vertical_speed as f32 * 0.5;
177
178    // Latitude
179    let latidute = u32::from_le_bytes(get_bytes!(buffer, 5, 4)) as f32 / f32::powf(10., 7.);
180
181    // Longitude
182    let longitude = u32::from_le_bytes(get_bytes!(buffer, 9, 4)) as f32 / f32::powf(10., 7.);
183
184    // Pressure Altitude
185    let pressure_altitude = u16::from_le_bytes(get_bytes!(buffer, 13, 2)) as f32 / 2.0 - 1000.;
186
187    // Geodetic Altitude
188    let geodetic_altitude = u16::from_le_bytes(get_bytes!(buffer, 15, 2)) as f32 / 2.0 - 1000.;
189
190    // Geodetic Altitude
191    let height = u16::from_le_bytes(get_bytes!(buffer, 17, 2)) as f32 / 2.0 - 1000.;
192
193    // Vertical / Horizontal Accuracy
194    let accuracy = get_bytes!(buffer, 19, 1);
195    let vertical_accuracy = VerticalAccuracy::from(get_bits!(accuracy, 7..4));
196    let horizontal_accuracy = HorizontalAccuracy::from(get_bits!(accuracy, 3..0));
197
198    let accuracy = get_bytes!(buffer, 20, 1);
199    let baro_altitude_accuracy = VerticalAccuracy::from(get_bits!(accuracy, 7..4));
200    let speed_accuracy = SpeedAccuracy::from(get_bits!(accuracy, 3..0));
201
202    let timestamp = u16::from_le_bytes(get_bytes!(buffer, 21, 2)) as f32 / 10.;
203
204    let timestamp_accuracy = get_bits!(get_bytes!(buffer, 23, 1), 3..0);
205    let timestamp_accuracy = if timestamp_accuracy == 0 {
206        None
207    } else {
208        Some(Duration::from_secs_f32(timestamp_accuracy as f32 * 0.1))
209    };
210
211    Some(RemoteIDMessage::Location(Location {
212        height_type,
213        operational_status,
214        latidute,
215        longitude,
216        height,
217        pressure_altitude,
218        geodetic_altitude,
219        track_direction,
220        speed,
221        vertical_speed,
222        horizontal_accuracy,
223        vertical_accuracy,
224        baro_altitude_accuracy,
225        speed_accuracy,
226        timestamp,
227        timestamp_accuracy,
228    }))
229}
230
231#[cfg(test)]
232mod test {
233    extern crate std;
234
235    use operator_id::{OperatorId, OperatorIdType};
236
237    use super::*;
238
239    #[test]
240    fn decode_basic_id_1() {
241        // DroneTag Mini
242        let expected = RemoteIDMessage::BasicID(BasicId {
243            id_type: IdType::SerialNumber,
244            ua_type: UAType::None,
245            uas_id: copy_to_id("10000000000000000009".as_bytes()),
246        });
247
248        let service_data = [
249            13, 1, 2, 16, 49, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48,
250            48, 57, 0, 0, 0,
251        ];
252
253        assert_eq!(expected, from_service_data(&service_data).unwrap());
254    }
255
256    #[test]
257    fn decode_basic_id_2() {
258        // DroneTag BS
259        let expected = RemoteIDMessage::BasicID(BasicId {
260            id_type: IdType::SerialNumber,
261            ua_type: UAType::None,
262            uas_id: copy_to_id("10000000000000000009".as_bytes()),
263        });
264
265        let service_data = [
266            13, 1, 2, 16, 49, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48, 48,
267            48, 57, 0, 0, 0,
268        ];
269
270        assert_eq!(expected, from_service_data(&service_data).unwrap());
271    }
272
273    #[test]
274    fn decode_location_1() {
275        let expected = RemoteIDMessage::Location(Location {
276            height_type: HeightType::AboveTakeoff,
277            operational_status: OperationalStatus::Airborne,
278            speed: 0.,
279            pressure_altitude: 190.5,
280            geodetic_altitude: 210.0,
281            vertical_speed: 0.,
282            latidute: 49.874855,
283            longitude: 8.912173,
284            height: 0.,
285            track_direction: 337,
286            horizontal_accuracy: location::HorizontalAccuracy::LessThan_3_m,
287            vertical_accuracy: location::VerticalAccuracy::LessThan_3_m,
288            baro_altitude_accuracy: location::VerticalAccuracy::Unknown,
289            speed_accuracy: location::SpeedAccuracy::LessThan_third_mps,
290            timestamp: 361.0,
291            timestamp_accuracy: None,
292        });
293
294        let service_data = [
295            13, 72, 18, 34, 157, 0, 0, 143, 76, 186, 29, 192, 227, 79, 5, 77, 9, 116, 9, 208, 7,
296            91, 4, 26, 14, 0, 0,
297        ];
298        assert_eq!(expected, from_service_data(&service_data).unwrap());
299    }
300
301    #[test]
302    fn decode_location_2() {
303        let expected = RemoteIDMessage::Location(Location {
304            height_type: HeightType::AboveTakeoff,
305            operational_status: OperationalStatus::Airborne,
306            speed: 5.25,
307            pressure_altitude: 201.5,
308            geodetic_altitude: 218.0,
309            vertical_speed: 0.,
310            latidute: 49.875015,
311            longitude: 8.912442,
312            height: 11.0,
313            track_direction: 52,
314            horizontal_accuracy: location::HorizontalAccuracy::LessThan_3_m,
315            vertical_accuracy: location::VerticalAccuracy::LessThan_3_m,
316            baro_altitude_accuracy: location::VerticalAccuracy::Unknown,
317            speed_accuracy: location::SpeedAccuracy::LessThan_third_mps,
318            timestamp: 886.0,
319            timestamp_accuracy: None,
320        });
321
322        let service_data = [
323            13, 85, 18, 32, 52, 21, 0, 188, 82, 186, 29, 69, 238, 79, 5, 99, 9, 132, 9, 230, 7, 91,
324            4, 156, 34, 0, 0,
325        ];
326        assert_eq!(expected, from_service_data(&service_data).unwrap());
327    }
328
329    #[test]
330    fn decode_location_3() {
331        let service_data = [
332            13, 1, 18, 32, 77, 2, 20, 128, 76, 186, 29, 200, 227, 79, 5, 77, 9, 116, 9, 208, 7, 91,
333            4, 26, 14, 0, 0,
334        ];
335        std::dbg!(from_service_data(&service_data).unwrap());
336    }
337
338    #[test]
339    fn decode_operator_id() {
340        let expected = RemoteIDMessage::OperatorId(OperatorId {
341            id_type: OperatorIdType::OperatorId,
342            operator_id: copy_to_id("NULL".as_bytes()),
343        });
344
345        let service_data = [
346            13, 3, 82, 0, 78, 85, 76, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
347        ];
348        assert_eq!(expected, from_service_data(&service_data).unwrap());
349    }
350
351    #[test]
352    fn decode_operator_id_2() {
353        let expected = RemoteIDMessage::OperatorId(OperatorId {
354            id_type: OperatorIdType::OperatorId,
355            operator_id: copy_to_id("FIN87astrdge12k8".as_bytes()),
356        });
357
358        let service_data = [
359            13, 3, 82, 0, 70, 73, 78, 56, 55, 97, 115, 116, 114, 100, 103, 101, 49, 50, 107, 56, 0,
360            0, 0, 0, 0, 0, 0,
361        ];
362        assert_eq!(expected, from_service_data(&service_data).unwrap());
363    }
364
365    #[test]
366    fn decode_system_1() {
367        let expected = RemoteIDMessage::System(System {
368            classification_type: ClassificationType::EuropeanUnion,
369            operator_location_type: OperatorLocationType::TakeOff,
370            operator_latidute: 49.874855,
371            operator_longitude: 8.912173,
372            operator_altitude: 210.,
373            area_ceiling: -1000.,
374            area_count: 1,
375            area_floor: -1000.,
376            area_radius: 250.,
377            ua_classification: UaClassification {
378                category: UaCategory::Specific,
379                class: UaClass::Undefined,
380            },
381            timestamp: DateTime::parse_from_rfc3339(&"2024-07-04T14:05:54Z")
382                .unwrap()
383                .to_utc(),
384        });
385
386        let service_data = [
387            13, 3, 66, 4, 131, 76, 186, 29, 188, 227, 79, 5, 1, 0, 25, 0, 0, 0, 0, 16, 116, 9, 194,
388            254, 91, 10, 0,
389        ];
390        assert_eq!(expected, from_service_data(&service_data).unwrap());
391    }
392}