class MAVLink::Log::File
Attributes
entries[R]
messages[R]
Public Class Methods
mavlink?(uri)
click to toggle source
new(uri)
click to toggle source
# File lib/mavlink/log/file.rb, line 18 def initialize(uri) @entries = [] @messages = [] open(uri, 'rb') do |file| loop do raw_time = file.read(8) break if raw_time.nil? header = Header.new(file.read(6)) raise "Unexpected magic number (#{header.magic})" unless header.magic == 0xFE payload = file.read(header.length) raw_crc = file.read(2) @entries << Entry.new(raw_time, header, payload, raw_crc) @messages << Messages::Factory.build(@entries.last) end end if @entries.empty? raise 'No entries found in file' end rescue => e unless @entries.length >= 2 # bad ending message, give the file benefit of the doubt... raise ArgumentError, "File does not appear to be an MAVLink log (#{e})" end end
Public Instance Methods
duration()
click to toggle source
Gets the duration of the session, in seconds.
@return [Float] duration of the session, in seconds
# File lib/mavlink/log/file.rb, line 49 def duration return 0 if @entries.empty? ended_at - started_at end
ended_at()
click to toggle source
Gets the ending time as a Unix Epoch time stamp in seconds.
@return [Float] unix epoch time the log ended
# File lib/mavlink/log/file.rb, line 64 def ended_at time_in_seconds(@entries.last.time) end
started_at()
click to toggle source
Gets the starting time as a Unix Epoch time stamp in seconds.
@return [Float] unix epoch time the log began
# File lib/mavlink/log/file.rb, line 57 def started_at time_in_seconds(@entries.first.time) end
Private Instance Methods
time_in_seconds(stamp)
click to toggle source
# File lib/mavlink/log/file.rb, line 70 def time_in_seconds(stamp) stamp / 1000000.0 end