Skip to main content

File

Struct File 

Source
pub struct File { /* private fields */ }
Expand description

High-level wrapper for reading a DataFlash BIN file from disk.

use ardupilot_binlog::File;

let file = File::open("flight.bin").unwrap();
for result in file.entries().unwrap() {
    let entry = result.unwrap();
    println!("{}", entry.name);
}

Implementations§

Source§

impl File

Source

pub fn open(path: impl AsRef<Path>) -> Result<Self, BinlogError>

Open a BIN file. Validates the path exists.

Source

pub fn entries(&self) -> Result<Reader<File>, BinlogError>

Return a fresh reader over the file’s entries.

Source

pub fn time_range(&self) -> Result<Option<(u64, u64)>, BinlogError>

Scan the file and return the time range (first_usec, last_usec).

Optimized: reads the head to find FMTs and the first timestamped message, then scans the tail for the last timestamp. Returns None for empty files or files with no timestamped entries.

Timestamps are boot-relative, not Unix epoch.

Precondition: assumes all FMT definitions appear before the first timestamped message, which is the standard ArduPilot file layout. The tail scan reuses formats discovered during the head scan.

Auto Trait Implementations§

§

impl Freeze for File

§

impl RefUnwindSafe for File

§

impl Send for File

§

impl Sync for File

§

impl Unpin for File

§

impl UnsafeUnpin for File

§

impl UnwindSafe for File

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.