pub struct Entry {
pub name: String,
pub msg_type: u8,
pub timestamp_usec: Option<u64>,
/* private fields */
}Expand description
A single parsed message from a DataFlash BIN log.
use ardupilot_binlog::Reader;
use std::io::Cursor;
let reader = Reader::new(Cursor::new(Vec::new()));
for result in reader {
let entry = result.unwrap();
println!("{} ({} fields)", entry.name, entry.len());
for (label, value) in entry.fields() {
println!(" {label} = {value}");
}
}Fields§
§name: StringMessage type name (e.g. “ATT”, “GPS”, “BARO”)
msg_type: u8Message type ID (0–255)
timestamp_usec: Option<u64>Timestamp in microseconds since boot (from the first Q-typed field). None for FMT messages and messages without a Q-typed first field.
Implementations§
Source§impl Entry
impl Entry
Sourcepub fn get(&self, field: &str) -> Option<&FieldValue>
pub fn get(&self, field: &str) -> Option<&FieldValue>
Look up a field by name.
Sourcepub fn get_f64(&self, field: &str) -> Option<f64>
pub fn get_f64(&self, field: &str) -> Option<f64>
Look up a field and convert to f64 (convenience for charting).
Sourcepub fn get_str(&self, field: &str) -> Option<&str>
pub fn get_str(&self, field: &str) -> Option<&str>
Look up a field and convert to string reference.
Sourcepub fn fields(&self) -> impl Iterator<Item = (&str, &FieldValue)>
pub fn fields(&self) -> impl Iterator<Item = (&str, &FieldValue)>
Iterate over (label, value) pairs in definition order.
Sourcepub fn values(&self) -> &[FieldValue]
pub fn values(&self) -> &[FieldValue]
Return field values in definition order.
Trait Implementations§
Auto Trait Implementations§
impl Freeze for Entry
impl RefUnwindSafe for Entry
impl Send for Entry
impl Sync for Entry
impl Unpin for Entry
impl UnsafeUnpin for Entry
impl UnwindSafe for Entry
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more