class MAVLink::Log::Messages::GpsRawInt
Public Instance Methods
alt()
click to toggle source
meters
# File lib/mavlink/log/messages/gps_raw_int.rb, line 16 def alt @alt ||= (int32_t(16..19) / 1000.0) end
cog()
click to toggle source
degrees 0..359.99
# File lib/mavlink/log/messages/gps_raw_int.rb, line 40 def cog @cog ||= (uint16_t(26..27) / 100.0) end
eph()
click to toggle source
meters
# File lib/mavlink/log/messages/gps_raw_int.rb, line 21 def eph @eph ||= (uint16_t(20..21) / 100.0) end
epv()
click to toggle source
meters
# File lib/mavlink/log/messages/gps_raw_int.rb, line 26 def epv @epv ||= (uint16_t(22..23) / 100.0) end
fix_type()
click to toggle source
0-1: no fix, 2: 2D fix, 3: 3D fix
# File lib/mavlink/log/messages/gps_raw_int.rb, line 45 def fix_type @fix_type ||= uint8_t(28) end
lat()
click to toggle source
WGS84 dec. degrees
# File lib/mavlink/log/messages/gps_raw_int.rb, line 6 def lat @lat ||= (int32_t(8..11) / 10000000.0) end
lon()
click to toggle source
WGS84 dec. degrees
# File lib/mavlink/log/messages/gps_raw_int.rb, line 11 def lon @lon ||= (int32_t(12..15) / 10000000.0) end
satellites_visible()
click to toggle source
# File lib/mavlink/log/messages/gps_raw_int.rb, line 49 def satellites_visible @satellites_visible ||= uint8_t(29) end
vel(unit = :mps)
click to toggle source
:mps (m/s) :knots :mph :kph
# 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
Private Instance Methods
speed_convert(value, unit = :mps)
click to toggle source
# File lib/mavlink/log/messages/gps_raw_int.rb, line 55 def speed_convert(value, unit = :mps) case unit when :knots; value * 1.9438444924406 when :mph; value * 2.2369362920544025 when :kph; value * 3.6 else; value end end