Class: MAVLink::Log::Messages::VfrHud

Inherits:
MAVLink::Log::Message show all
Defined in:
lib/mavlink/log/messages/vfr_hud.rb

Instance Method Summary collapse

Methods inherited from MAVLink::Log::Message

#crc, #id, #initialize

Constructor Details

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

Instance Method Details

#airspeed(unit = :mps) ⇒ Object

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



9
10
11
12
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 9

def airspeed(unit = :mps)
  @airspeed ||= float(0..3)
  speed_convert(@airspeed, unit)
end

#altObject

meters (MSL)



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

def alt
  @alt ||= float(12..15)
end

#climb(unit = :mps) ⇒ Object

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



42
43
44
45
# 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) ⇒ Object

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



18
19
20
21
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 18

def groundspeed(unit = :mps)
  @groundspeed ||= float(4..7)
  speed_convert(@groundspeed, unit)
end

#headingObject

0..360



24
25
26
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 24

def heading
  @heading ||= int16_t(8..9)
end

#throttleObject

0..100%



29
30
31
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 29

def throttle
  @throttle ||= uint16_t(10..11)
end