Class: MAVLink::Log::File

Inherits:
Object
  • Object
show all
Defined in:
lib/mavlink/log/file.rb

Instance Attribute Summary collapse

Class Method Summary collapse

Instance Method Summary collapse

Constructor Details

#initialize(uri) ⇒ File

Returns a new instance of File.



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
# 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

  #puts @messages.inspect
rescue => e
  raise ArgumentError, "File does not appear to be an MAVLink log (#{e})"
end

Instance Attribute Details

#entriesObject (readonly)

Returns the value of attribute entries.



8
9
10
# File 'lib/mavlink/log/file.rb', line 8

def entries
  @entries
end

#messagesObject (readonly)

Returns the value of attribute messages.



8
9
10
# File 'lib/mavlink/log/file.rb', line 8

def messages
  @messages
end

Class Method Details

.mavlink?(uri) ⇒ MAVLink::Log::File

Determines if the file at the given URI is a MAVLink telemetry log file.

Parameters:

  • uri

    URI to file to read

Returns:



14
15
16
# File 'lib/mavlink/log/file.rb', line 14

def self.mavlink?(uri)
  File.new(uri) rescue nil
end

Instance Method Details

#durationFloat

Gets the duration of the session, in seconds.

Returns:

  • (Float)

    duration of the session, in seconds



48
49
50
51
# File 'lib/mavlink/log/file.rb', line 48

def duration
  return 0 if @entries.empty?
  (@entries.last.time - @entries.first.time) / 1000000.0
end

#ended_atObject



57
58
59
# File 'lib/mavlink/log/file.rb', line 57

def ended_at
  Time.at(@entries.last.time / 1000000.0)
end

#started_atObject



53
54
55
# File 'lib/mavlink/log/file.rb', line 53

def started_at
  Time.at(@entries.first.time / 1000000.0)
end