Class: MAVLink::Log::GlobalPositionInt
- Inherits:
-
TimedMessage
- Object
- Message
- TimedMessage
- MAVLink::Log::GlobalPositionInt
- Defined in:
- lib/mavlink/log/messages.rb
Constant Summary collapse
- ID =
33
Instance Attribute Summary collapse
-
#alt ⇒ Object
Returns the value of attribute alt.
-
#hdg ⇒ Object
Returns the value of attribute hdg.
-
#lat ⇒ Object
Returns the value of attribute lat.
-
#lon ⇒ Object
Returns the value of attribute lon.
-
#relative_alt ⇒ Object
Returns the value of attribute relative_alt.
-
#vx ⇒ Object
Returns the value of attribute vx.
-
#vy ⇒ Object
Returns the value of attribute vy.
-
#vz ⇒ Object
Returns the value of attribute vz.
Attributes inherited from TimedMessage
Instance Method Summary collapse
-
#initialize(raw_payload) ⇒ GlobalPositionInt
constructor
A new instance of GlobalPositionInt.
Constructor Details
#initialize(raw_payload) ⇒ GlobalPositionInt
Returns a new instance of GlobalPositionInt.
89 90 91 92 93 94 95 96 97 98 99 |
# File 'lib/mavlink/log/messages.rb', line 89 def initialize(raw_payload) super @lat = raw_payload[4..7].unpack('l<')[0] / 10000000.0 # dec. degrees @lon = raw_payload[8..11].unpack('l<')[0] / 10000000.0 # dec. degrees @alt = raw_payload[12..15].unpack('l<')[0] / 1000.0 # meters @relative_alt = raw_payload[16..19].unpack('l<')[0] / 1000.0 # meters @vx = raw_payload[20..21].unpack('s<')[0] / 100.0 # m/s @vy = raw_payload[22..23].unpack('s<')[0] / 100.0 # m/s @vz = raw_payload[24..25].unpack('s<')[0] / 100.0 # m/s @hdg = raw_payload[26..27].unpack('S<')[0] / 100.0 # degrees (0.0..359.99) (0xFFFF if unknown) end |
Instance Attribute Details
#alt ⇒ Object
Returns the value of attribute alt.
87 88 89 |
# File 'lib/mavlink/log/messages.rb', line 87 def alt @alt end |
#hdg ⇒ Object
Returns the value of attribute hdg.
87 88 89 |
# File 'lib/mavlink/log/messages.rb', line 87 def hdg @hdg end |
#lat ⇒ Object
Returns the value of attribute lat.
87 88 89 |
# File 'lib/mavlink/log/messages.rb', line 87 def lat @lat end |
#lon ⇒ Object
Returns the value of attribute lon.
87 88 89 |
# File 'lib/mavlink/log/messages.rb', line 87 def lon @lon end |
#relative_alt ⇒ Object
Returns the value of attribute relative_alt.
87 88 89 |
# File 'lib/mavlink/log/messages.rb', line 87 def relative_alt @relative_alt end |
#vx ⇒ Object
Returns the value of attribute vx.
87 88 89 |
# File 'lib/mavlink/log/messages.rb', line 87 def vx @vx end |
#vy ⇒ Object
Returns the value of attribute vy.
87 88 89 |
# File 'lib/mavlink/log/messages.rb', line 87 def vy @vy end |
#vz ⇒ Object
Returns the value of attribute vz.
87 88 89 |
# File 'lib/mavlink/log/messages.rb', line 87 def vz @vz end |