Class: MAVLink::Log::Messages::VfrHud
- Inherits:
-
MAVLink::Log::Message
- Object
- MAVLink::Log::Message
- MAVLink::Log::Messages::VfrHud
- Defined in:
- lib/mavlink/log/messages/vfr_hud.rb
Instance Method Summary collapse
-
#airspeed ⇒ Object
m/s.
-
#alt ⇒ Object
meters (MSL).
-
#climb ⇒ Object
m/s.
-
#groundspeed ⇒ Object
m/s.
-
#heading ⇒ Object
0..360.
-
#throttle ⇒ Object
0..100%.
Methods inherited from MAVLink::Log::Message
Constructor Details
This class inherits a constructor from MAVLink::Log::Message
Instance Method Details
#airspeed ⇒ Object
m/s
6 7 8 |
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 6 def airspeed @airspeed ||= float(0..3) end |
#alt ⇒ Object
meters (MSL)
26 27 28 |
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 26 def alt @alt ||= float(12..15) end |
#climb ⇒ Object
m/s
31 32 33 |
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 31 def climb @climb ||= float(16..19) end |
#groundspeed ⇒ Object
m/s
11 12 13 |
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 11 def groundspeed @groundspeed ||= float(4..7) end |
#heading ⇒ Object
0..360
16 17 18 |
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 16 def heading @heading ||= int16_t(8..9) end |
#throttle ⇒ Object
0..100%
21 22 23 |
# File 'lib/mavlink/log/messages/vfr_hud.rb', line 21 def throttle @throttle ||= uint16_t(10..11) end |