Class: MAVLink::Log::File
- Inherits:
-
Object
- Object
- MAVLink::Log::File
- Defined in:
- lib/mavlink/log/file.rb
Instance Attribute Summary collapse
-
#entries ⇒ Object
Returns the value of attribute entries.
-
#messages ⇒ Object
Returns the value of attribute messages.
Class Method Summary collapse
-
.mavlink?(uri) ⇒ MAVLink::Log::File
Determines if the file at the given URI is a MAVLink telemetry log file.
Instance Method Summary collapse
-
#duration ⇒ Float
Gets the duration of the session, in seconds.
- #ended_at ⇒ Object
-
#initialize(uri) ⇒ File
constructor
A new instance of File.
- #started_at ⇒ Object
-
#to_kml? ⇒ Boolean
Determines if KML methods can be called for this file.
Constructor Details
#initialize(uri) ⇒ File
Returns a new instance of File.
24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 |
# File 'lib/mavlink/log/file.rb', line 24 def initialize(uri) @entries = [] = [] open(uri, 'rb') do |file| loop do raw_time = file.read(8) break if raw_time.nil? time = to_time(raw_time) header = to_header(file.read(6)) payload = file.read(header.length) crc = file.read(2).unpack('S>')[0] @entries << Entry.new(time, header, payload, crc) << MessageFactory.build(@entries.last) end end #@messages.each do |e| # puts e.inspect #end rescue => e raise ArgumentError, "File does not appear to be an MAVLink log (#{e})" end |
Instance Attribute Details
#entries ⇒ Object
Returns the value of attribute entries.
14 15 16 |
# File 'lib/mavlink/log/file.rb', line 14 def entries @entries end |
#messages ⇒ Object
Returns the value of attribute messages.
14 15 16 |
# File 'lib/mavlink/log/file.rb', line 14 def end |
Class Method Details
.mavlink?(uri) ⇒ MAVLink::Log::File
Determines if the file at the given URI is a MAVLink telemetry log file.
20 21 22 |
# File 'lib/mavlink/log/file.rb', line 20 def self.mavlink?(uri) File.new(uri) rescue nil end |
Instance Method Details
#duration ⇒ Float
Gets the duration of the session, in seconds.
50 51 52 53 |
# File 'lib/mavlink/log/file.rb', line 50 def duration return 0 if @entries.empty? (@entries.last.time - @entries.first.time) / USEC_PER_SEC end |
#ended_at ⇒ Object
59 60 61 |
# File 'lib/mavlink/log/file.rb', line 59 def ended_at Time.at(@entries.last.time / USEC_PER_SEC) end |
#started_at ⇒ Object
55 56 57 |
# File 'lib/mavlink/log/file.rb', line 55 def started_at Time.at(@entries.first.time / USEC_PER_SEC) end |
#to_kml? ⇒ Boolean
Determines if KML methods can be called for this file.
66 67 68 |
# File 'lib/mavlink/log/file.rb', line 66 def to_kml? @entries.any? { |e| e.header.id == GlobalPositionInt::ID } end |