class MAVLink::Log::Messages::VfrHud

Public Instance Methods

airspeed(unit = :mps) click to toggle source

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

# File lib/mavlink/log/messages/vfr_hud.rb, line 9
def airspeed(unit = :mps)
  @airspeed ||= float(0..3)
  speed_convert(@airspeed, unit)
end
alt() click to toggle source

meters (MSL)

# File lib/mavlink/log/messages/vfr_hud.rb, line 34
def alt
  @alt ||= float(12..15)
end
climb(unit = :mps) click to toggle source

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

# File lib/mavlink/log/messages/vfr_hud.rb, line 42
def climb(unit = :mps)
  @climb ||= float(16..19)
  speed_convert(@climb, unit)
end
groundspeed(unit = :mps) click to toggle source

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

# File lib/mavlink/log/messages/vfr_hud.rb, line 18
def groundspeed(unit = :mps)
  @groundspeed ||= float(4..7)
  speed_convert(@groundspeed, unit)
end
heading() click to toggle source

0..360

# File lib/mavlink/log/messages/vfr_hud.rb, line 24
def heading
  @heading ||= int16_t(8..9)
end
throttle() click to toggle source

0..100%

# File lib/mavlink/log/messages/vfr_hud.rb, line 29
def throttle
  @throttle ||= uint16_t(10..11)
end

Private Instance Methods

speed_convert(value, unit = :mps) click to toggle source
# File lib/mavlink/log/messages/vfr_hud.rb, line 49
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