Class: MAVLink::Log::Messages::GlobalPositionInt
- Inherits:
-
TimedMessageMilli
- Object
- MAVLink::Log::Message
- TimedMessageMilli
- MAVLink::Log::Messages::GlobalPositionInt
- Defined in:
- lib/mavlink/log/messages/global_position_int.rb
Instance Method Summary collapse
-
#alt ⇒ Object
meters.
-
#hdg ⇒ Object
degrees (0.0..359.99) (0xFFFF if unknown).
-
#lat ⇒ Object
dec.
-
#lon ⇒ Object
dec.
-
#relative_alt ⇒ Object
meters.
-
#vx ⇒ Object
m/s.
-
#vy ⇒ Object
m/s.
-
#vz ⇒ Object
m/s.
Methods inherited from TimedMessageMilli
Methods inherited from MAVLink::Log::Message
Constructor Details
This class inherits a constructor from MAVLink::Log::Message
Instance Method Details
#alt ⇒ Object
meters
16 17 18 |
# File 'lib/mavlink/log/messages/global_position_int.rb', line 16 def alt @alt ||= (int32_t(12..15) / 1000.0) end |
#hdg ⇒ Object
degrees (0.0..359.99) (0xFFFF if unknown)
41 42 43 |
# File 'lib/mavlink/log/messages/global_position_int.rb', line 41 def hdg @hdg ||= (uint16_t(26..27) / 100.0) end |
#lat ⇒ Object
dec. degrees
6 7 8 |
# File 'lib/mavlink/log/messages/global_position_int.rb', line 6 def lat @lat ||= (int32_t(4..7) / 10000000.0) end |
#lon ⇒ Object
dec. degrees
11 12 13 |
# File 'lib/mavlink/log/messages/global_position_int.rb', line 11 def lon @lon ||= (int32_t(8..11) / 10000000.0) end |
#relative_alt ⇒ Object
meters
21 22 23 |
# File 'lib/mavlink/log/messages/global_position_int.rb', line 21 def relative_alt @relative_alt ||= (int32_t(16..19) / 1000.0) end |
#vx ⇒ Object
m/s
26 27 28 |
# File 'lib/mavlink/log/messages/global_position_int.rb', line 26 def vx @vx ||= (int16_t(20..21) / 100.0) end |
#vy ⇒ Object
m/s
31 32 33 |
# File 'lib/mavlink/log/messages/global_position_int.rb', line 31 def vy @vy ||= (int16_t(22..23) / 100.0) end |
#vz ⇒ Object
m/s
36 37 38 |
# File 'lib/mavlink/log/messages/global_position_int.rb', line 36 def vz @vz ||= (int16_t(24..25) / 100.0) end |