class MAVLink::Log::Messages::GlobalPositionInt
Public Instance Methods
alt()
click to toggle source
meters
# File lib/mavlink/log/messages/global_position_int.rb, line 16 def alt @alt ||= (int32_t(12..15) / 1000.0) end
hdg()
click to toggle source
degrees (0.0..359.99) (0xFFFF if unknown)
# File lib/mavlink/log/messages/global_position_int.rb, line 41 def hdg @hdg ||= (uint16_t(26..27) / 100.0) end
lat()
click to toggle source
dec. degrees
# File lib/mavlink/log/messages/global_position_int.rb, line 6 def lat @lat ||= (int32_t(4..7) / 10000000.0) end
lon()
click to toggle source
dec. degrees
# File lib/mavlink/log/messages/global_position_int.rb, line 11 def lon @lon ||= (int32_t(8..11) / 10000000.0) end
relative_alt()
click to toggle source
meters
# File lib/mavlink/log/messages/global_position_int.rb, line 21 def relative_alt @relative_alt ||= (int32_t(16..19) / 1000.0) end
vx()
click to toggle source
m/s
# File lib/mavlink/log/messages/global_position_int.rb, line 26 def vx @vx ||= (int16_t(20..21) / 100.0) end
vy()
click to toggle source
m/s
# File lib/mavlink/log/messages/global_position_int.rb, line 31 def vy @vy ||= (int16_t(22..23) / 100.0) end
vz()
click to toggle source
m/s
# File lib/mavlink/log/messages/global_position_int.rb, line 36 def vz @vz ||= (int16_t(24..25) / 100.0) end