Class: MAVLink::Log::Messages::GpsRawInt

Inherits:
TimedMessageMicro show all
Defined in:
lib/mavlink/log/messages/gps_raw_int.rb

Instance Method Summary collapse

Methods inherited from TimedMessageMicro

#time_usec

Methods inherited from MAVLink::Log::Message

#crc, #id, #initialize

Constructor Details

This class inherits a constructor from MAVLink::Log::Message

Instance Method Details

#altObject

meters



16
17
18
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 16

def alt
  @alt ||= (int32_t(16..19) / 1000.0)
end

#cogObject

degrees 0..359.99



40
41
42
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 40

def cog
  @cog ||= (uint16_t(26..27) / 100.0)
end

#ephObject

meters



21
22
23
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 21

def eph
  @eph ||= (uint16_t(20..21) / 100.0)
end

#epvObject

meters



26
27
28
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 26

def epv
  @epv ||= (uint16_t(22..23) / 100.0)
end

#fix_typeObject

0-1: no fix, 2: 2D fix, 3: 3D fix



45
46
47
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 45

def fix_type
  @fix_type ||= uint8_t(28)
end

#latObject

WGS84 dec. degrees



6
7
8
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 6

def lat
  @lat ||= (int32_t(8..11) / 10000000.0)
end

#lonObject

WGS84 dec. degrees



11
12
13
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 11

def lon
  @lon ||= (int32_t(12..15) / 10000000.0)
end

#satellites_visibleObject



49
50
51
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 49

def satellites_visible
  @satellites_visible ||= uint8_t(29)
end

#vel(unit = :mps) ⇒ Object

:mps (m/s) :knots :mph :kph



34
35
36
37
# File 'lib/mavlink/log/messages/gps_raw_int.rb', line 34

def vel(unit = :mps)
  @vel ||= (uint16_t(24..25) / 100.0)
  speed_convert(@vel, unit)
end