ardupilot-binlog 0.2.0

Parser for ArduPilot DataFlash BIN log files
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
use std::collections::HashMap;
use std::io::{BufReader, Read};
use std::sync::Arc;

use crate::entry::Entry;
use crate::error::BinlogError;
use crate::format::{parse_fmt_payload, MessageFormat};
use crate::{FMT_TYPE, HEADER_MAGIC};

const MAX_CONSECUTIVE_ERRORS: u32 = 256;

/// Streaming parser for DataFlash BIN data.
///
/// Reads from any `Read` source, discovers message schemas via FMT
/// messages, and yields parsed [`Entry`] values via the [`Iterator`] trait.
///
/// ```
/// use ardupilot_binlog::Reader;
/// use std::io::Cursor;
///
/// let data: Vec<u8> = vec![];
/// let reader = Reader::new(Cursor::new(data));
/// for result in reader {
///     let entry = result.unwrap();
///     println!("{}: {} fields", entry.name, entry.len());
/// }
/// ```
pub struct Reader<R: Read> {
    reader: BufReader<R>,
    formats: HashMap<u8, Arc<MessageFormat>>,
    consecutive_errors: u32,
}

impl<R: Read> Reader<R> {
    /// Create a new reader wrapping a byte source.
    pub fn new(reader: R) -> Self {
        let mut formats = HashMap::new();
        // Bootstrap: hardcode the FMT definition so we can parse the first FMT message
        formats.insert(
            FMT_TYPE,
            Arc::new(MessageFormat {
                msg_type: FMT_TYPE,
                msg_len: 89,
                name: "FMT".into(),
                format: "BBnNZ".into(),
                labels: Arc::from([
                    "Type".into(),
                    "Length".into(),
                    "Name".into(),
                    "Format".into(),
                    "Labels".into(),
                ]),
            }),
        );

        Reader {
            reader: BufReader::new(reader),
            formats,
            consecutive_errors: 0,
        }
    }

    fn next_inner(&mut self) -> Result<Option<Entry>, BinlogError> {
        if self.consecutive_errors >= MAX_CONSECUTIVE_ERRORS {
            return Ok(None);
        }

        // Read the 3-byte header
        let mut header = [0u8; 3];
        match self.read_exact_or_eof(&mut header) {
            Ok(true) => {}
            Ok(false) => return Ok(None), // EOF
            Err(_) => return Ok(None),
        }

        // Validate magic bytes
        if header[0] != HEADER_MAGIC[0] || header[1] != HEADER_MAGIC[1] {
            self.consecutive_errors += 1;
            return self.recover_and_retry();
        }

        let msg_type = header[2];
        self.parse_message(msg_type)
    }

    /// Return all message format definitions discovered so far.
    #[must_use]
    pub fn formats(&self) -> &HashMap<u8, Arc<MessageFormat>> {
        &self.formats
    }

    /// Parse a message given its type byte (header already consumed).
    fn parse_message(&mut self, msg_type: u8) -> Result<Option<Entry>, BinlogError> {
        // Clone the Arc so we own a handle and don't borrow self.formats
        let format = match self.formats.get(&msg_type) {
            Some(f) => Arc::clone(f),
            None => {
                self.consecutive_errors += 1;
                return self.recover_and_retry();
            }
        };

        // Read payload (no borrow on self.formats)
        let payload = match self.read_payload(&format) {
            Ok(p) => p,
            Err(_) => {
                self.consecutive_errors += 1;
                return self.recover_and_retry();
            }
        };

        let result = if msg_type == FMT_TYPE {
            build_fmt_entry(&format, &payload)
        } else {
            build_data_entry(&format, msg_type, &payload)
        };

        match result {
            Ok((entry, new_fmt)) => {
                if let Some(new_fmt) = new_fmt {
                    self.formats.insert(new_fmt.msg_type, Arc::new(new_fmt));
                }
                self.consecutive_errors = 0;
                Ok(Some(entry))
            }
            Err(_) => {
                self.consecutive_errors += 1;
                self.recover_and_retry()
            }
        }
    }

    /// Read the payload bytes for a message (everything after the 3-byte header).
    fn read_payload(&mut self, format: &MessageFormat) -> Result<Vec<u8>, BinlogError> {
        let payload_len = format.msg_len as usize - 3;
        let mut payload = vec![0u8; payload_len];
        match self.read_exact_or_eof(&mut payload) {
            Ok(true) => Ok(payload),
            Ok(false) => Err(BinlogError::UnexpectedEof),
            Err(e) => Err(e),
        }
    }

    /// Scan forward byte-by-byte looking for the magic header, then retry parsing.
    fn recover_and_retry(&mut self) -> Result<Option<Entry>, BinlogError> {
        if self.consecutive_errors >= MAX_CONSECUTIVE_ERRORS {
            return Ok(None);
        }
        match self.scan_for_header()? {
            Some(msg_type) => self.parse_message(msg_type),
            None => Ok(None),
        }
    }

    /// Scan byte-by-byte for the next 0xA3 0x95 sequence.
    /// Returns the msg_type byte that follows the magic, or None at EOF.
    fn scan_for_header(&mut self) -> Result<Option<u8>, BinlogError> {
        let mut prev = 0u8;
        loop {
            let mut byte = [0u8; 1];
            match self.reader.read(&mut byte) {
                Ok(0) => return Ok(None), // EOF
                Ok(_) => {
                    if prev == HEADER_MAGIC[0] && byte[0] == HEADER_MAGIC[1] {
                        // Found magic, read msg_type
                        let mut msg_type = [0u8; 1];
                        match self.reader.read(&mut msg_type) {
                            Ok(0) => return Ok(None),
                            Ok(_) => return Ok(Some(msg_type[0])),
                            Err(_) => return Ok(None),
                        }
                    }
                    prev = byte[0];
                }
                Err(_) => return Ok(None),
            }
        }
    }

    /// Read exactly `buf.len()` bytes. Returns Ok(true) on success, Ok(false) on EOF
    /// (zero bytes available), Err on partial read / IO error.
    fn read_exact_or_eof(&mut self, buf: &mut [u8]) -> Result<bool, BinlogError> {
        let mut total = 0;
        while total < buf.len() {
            match self.reader.read(&mut buf[total..]) {
                Ok(0) => {
                    if total == 0 {
                        return Ok(false); // Clean EOF
                    }
                    return Err(BinlogError::UnexpectedEof);
                }
                Ok(n) => total += n,
                Err(e) => return Err(BinlogError::Io(e)),
            }
        }
        Ok(true)
    }
}

fn build_fmt_entry(
    format: &MessageFormat,
    payload: &[u8],
) -> Result<(Entry, Option<MessageFormat>), BinlogError> {
    let new_fmt = parse_fmt_payload(payload)?;
    let values = format.decode_fields(payload)?;
    let entry = Entry {
        name: "FMT".into(),
        msg_type: FMT_TYPE,
        timestamp_usec: None,
        labels: format.labels.clone(),
        values,
    };
    Ok((entry, Some(new_fmt)))
}

fn build_data_entry(
    format: &MessageFormat,
    msg_type: u8,
    payload: &[u8],
) -> Result<(Entry, Option<MessageFormat>), BinlogError> {
    let values = format.decode_fields(payload)?;
    let timestamp_usec = format.extract_timestamp(payload);
    let entry = Entry {
        name: format.name.clone(),
        msg_type,
        timestamp_usec,
        labels: format.labels.clone(),
        values,
    };
    Ok((entry, None))
}

impl<R: Read> Iterator for Reader<R> {
    type Item = Result<Entry, BinlogError>;

    fn next(&mut self) -> Option<Self::Item> {
        self.next_inner().transpose()
    }
}

#[cfg(test)]
mod tests {
    use super::*;
    use crate::value::FieldValue;

    /// Build a valid FMT message (89 bytes) that defines the FMT type itself.
    fn build_fmt_bootstrap() -> Vec<u8> {
        let mut msg = Vec::new();
        msg.extend_from_slice(&HEADER_MAGIC);
        msg.push(FMT_TYPE);
        // 86-byte payload
        let mut payload = [0u8; 86];
        payload[0] = FMT_TYPE; // type
        payload[1] = 89; // length
        payload[2..6].copy_from_slice(b"FMT\0"); // name
        payload[6..11].copy_from_slice(b"BBnNZ"); // format
        let labels = b"Type,Length,Name,Format,Labels";
        payload[22..22 + labels.len()].copy_from_slice(labels);
        msg.extend_from_slice(&payload);
        msg
    }

    /// Build a FMT message that defines a custom message type.
    fn build_fmt_for_type(
        msg_type: u8,
        msg_len: u8,
        name: &[u8; 4],
        format: &str,
        labels: &str,
    ) -> Vec<u8> {
        let mut msg = Vec::new();
        msg.extend_from_slice(&HEADER_MAGIC);
        msg.push(FMT_TYPE);
        let mut payload = [0u8; 86];
        payload[0] = msg_type;
        payload[1] = msg_len;
        payload[2..6].copy_from_slice(name);
        let fmt_bytes = format.as_bytes();
        payload[6..6 + fmt_bytes.len()].copy_from_slice(fmt_bytes);
        let lbl_bytes = labels.as_bytes();
        payload[22..22 + lbl_bytes.len()].copy_from_slice(lbl_bytes);
        msg.extend_from_slice(&payload);
        msg
    }

    /// Build a data message with a given type and raw payload.
    fn build_data_message(msg_type: u8, payload: &[u8]) -> Vec<u8> {
        let mut msg = Vec::new();
        msg.extend_from_slice(&HEADER_MAGIC);
        msg.push(msg_type);
        msg.extend_from_slice(payload);
        msg
    }

    #[test]
    fn parse_empty_input() {
        let reader = Reader::new(std::io::Cursor::new(Vec::new()));
        let entries: Vec<_> = reader.collect::<Result<Vec<_>, _>>().unwrap();
        assert!(entries.is_empty());
    }

    #[test]
    fn parse_fmt_bootstrap_only() {
        let data = build_fmt_bootstrap();
        let reader = Reader::new(std::io::Cursor::new(data));
        let entries: Vec<_> = reader.collect::<Result<Vec<_>, _>>().unwrap();
        assert_eq!(entries.len(), 1);
        assert_eq!(entries[0].name, "FMT");
        assert_eq!(entries[0].msg_type, FMT_TYPE);
        assert!(entries[0].timestamp_usec.is_none());
    }

    #[test]
    fn parse_data_message() {
        let mut data = Vec::new();
        // Bootstrap FMT
        data.extend(build_fmt_bootstrap());
        // payload size: 8 + 2 + 2 = 12, total = 15
        data.extend(build_fmt_for_type(
            0x81,
            15,
            b"ATT\0",
            "Qhh",
            "TimeUS,Roll,Pitch",
        ));
        let mut payload = Vec::new();
        payload.extend_from_slice(&1_000_000u64.to_le_bytes());
        payload.extend_from_slice(&4500i16.to_le_bytes()); // Roll
        payload.extend_from_slice(&(-200i16).to_le_bytes()); // Pitch
        data.extend(build_data_message(0x81, &payload));

        let reader = Reader::new(std::io::Cursor::new(data));
        let entries: Vec<_> = reader.collect::<Result<Vec<_>, _>>().unwrap();
        assert_eq!(entries.len(), 3); // FMT(FMT), FMT(ATT), ATT

        let att = &entries[2];
        assert_eq!(att.name, "ATT");
        assert_eq!(att.msg_type, 0x81);
        assert_eq!(att.timestamp_usec, Some(1_000_000));
        assert_eq!(att.get("Roll"), Some(&FieldValue::Int(4500)));
        assert_eq!(att.get("Pitch"), Some(&FieldValue::Int(-200)));
    }

    #[test]
    fn error_recovery_with_garbage() {
        let mut data = Vec::new();
        data.extend(build_fmt_bootstrap());
        // Define a simple type
        data.extend(build_fmt_for_type(
            0x81, 11, // 3 + 8
            b"TST\0", "Q", "TimeUS",
        ));
        // First valid data message
        data.extend(build_data_message(0x81, &100u64.to_le_bytes()));
        // Garbage bytes
        data.extend_from_slice(&[0xFF; 50]);
        // Second valid data message
        data.extend(build_data_message(0x81, &200u64.to_le_bytes()));

        let reader = Reader::new(std::io::Cursor::new(data));
        let entries: Vec<_> = reader.collect::<Result<Vec<_>, _>>().unwrap();

        // Should have: FMT(FMT), FMT(TST), TST(100), TST(200)
        let tst_entries: Vec<_> = entries.iter().filter(|e| e.name == "TST").collect();
        assert_eq!(tst_entries.len(), 2);
        assert_eq!(tst_entries[0].timestamp_usec, Some(100));
        assert_eq!(tst_entries[1].timestamp_usec, Some(200));
    }

    #[test]
    fn truncated_final_message() {
        let mut data = Vec::new();
        data.extend(build_fmt_bootstrap());
        data.extend(build_fmt_for_type(0x81, 11, b"TST\0", "Q", "TimeUS"));
        // Valid message
        data.extend(build_data_message(0x81, &100u64.to_le_bytes()));
        // Truncated message: header + partial payload
        data.extend_from_slice(&HEADER_MAGIC);
        data.push(0x81);
        data.extend_from_slice(&[0; 3]); // only 3 of 8 payload bytes

        let reader = Reader::new(std::io::Cursor::new(data));
        let entries: Vec<_> = reader.collect::<Result<Vec<_>, _>>().unwrap();

        let tst_entries: Vec<_> = entries.iter().filter(|e| e.name == "TST").collect();
        assert_eq!(tst_entries.len(), 1);
        assert_eq!(tst_entries[0].timestamp_usec, Some(100));
    }

    #[test]
    fn unknown_type_recovery() {
        let mut data = Vec::new();
        data.extend(build_fmt_bootstrap());
        data.extend(build_fmt_for_type(0x81, 11, b"TST\0", "Q", "TimeUS"));
        // Message with unknown type 0x99
        data.extend_from_slice(&HEADER_MAGIC);
        data.push(0x99);
        data.extend_from_slice(&[0; 20]); // some bytes
                                          // Valid message after
        data.extend(build_data_message(0x81, &300u64.to_le_bytes()));

        let reader = Reader::new(std::io::Cursor::new(data));
        let entries: Vec<_> = reader.collect::<Result<Vec<_>, _>>().unwrap();

        let tst_entries: Vec<_> = entries.iter().filter(|e| e.name == "TST").collect();
        assert_eq!(tst_entries.len(), 1);
        assert_eq!(tst_entries[0].timestamp_usec, Some(300));
    }

    #[test]
    fn max_consecutive_errors_boundary() {
        let mut data = Vec::new();
        data.extend(build_fmt_bootstrap());
        data.extend(build_fmt_for_type(0x81, 11, b"TST\0", "Q", "TimeUS"));

        // Each unknown-type header chains: parse_message → recover_and_retry →
        // scan_for_header → parse_message, incrementing consecutive_errors each time.
        let error_count = MAX_CONSECUTIVE_ERRORS + 10;
        for _ in 0..error_count {
            data.extend_from_slice(&HEADER_MAGIC);
            data.push(0x99);
        }

        data.extend(build_data_message(0x81, &999u64.to_le_bytes()));

        let reader = Reader::new(std::io::Cursor::new(data));
        let entries: Vec<_> = reader.collect::<Result<Vec<_>, _>>().unwrap();

        let tst_entries: Vec<_> = entries.iter().filter(|e| e.name == "TST").collect();
        assert!(
            tst_entries.is_empty(),
            "reader should stop before reaching the valid message after {} errors",
            MAX_CONSECUTIVE_ERRORS
        );
    }

    #[test]
    fn recovery_just_below_max_errors() {
        let mut data = Vec::new();
        data.extend(build_fmt_bootstrap());
        data.extend(build_fmt_for_type(0x81, 11, b"TST\0", "Q", "TimeUS"));

        // 255 unknown-type headers: one below the limit, so the final
        // recover_and_retry still scans forward and finds the valid message.
        for _ in 0..(MAX_CONSECUTIVE_ERRORS - 1) {
            data.extend_from_slice(&HEADER_MAGIC);
            data.push(0x99);
        }

        data.extend(build_data_message(0x81, &777u64.to_le_bytes()));

        let reader = Reader::new(std::io::Cursor::new(data));
        let entries: Vec<_> = reader.collect::<Result<Vec<_>, _>>().unwrap();

        let tst_entries: Vec<_> = entries.iter().filter(|e| e.name == "TST").collect();
        assert_eq!(
            tst_entries.len(),
            1,
            "recovery should still work at {} consecutive errors",
            MAX_CONSECUTIVE_ERRORS - 1
        );
        assert_eq!(tst_entries[0].timestamp_usec, Some(777));
    }

    #[test]
    fn formats_accessible() {
        let data = build_fmt_bootstrap();
        let mut reader = Reader::new(std::io::Cursor::new(data));
        let _ = reader.next(); // parse the FMT
        assert!(reader.formats().contains_key(&FMT_TYPE));
        assert_eq!(reader.formats().get(&FMT_TYPE).unwrap().name, "FMT");
    }
}