Class: MAVLink::Log::Messages::Attitude

Inherits:
TimedMessageMilli show all
Defined in:
lib/mavlink/log/messages/attitude.rb

Instance Method Summary collapse

Methods inherited from TimedMessageMilli

#time_boot_ms

Methods inherited from MAVLink::Log::Message

#crc, #id, #initialize

Constructor Details

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

Instance Method Details

#pitchObject

radians (-pi..pi)



11
12
13
# File 'lib/mavlink/log/messages/attitude.rb', line 11

def pitch
  @pitch ||= float(4..7)
end

#pitchspeedObject

rad/s



26
27
28
# File 'lib/mavlink/log/messages/attitude.rb', line 26

def pitchspeed
  @pitchspeed ||= float(16..19)
end

#rollObject

radians (-pi..pi)



6
7
8
# File 'lib/mavlink/log/messages/attitude.rb', line 6

def roll
  @roll ||= float(0..3)
end

#rollspeedObject

rad/s



21
22
23
# File 'lib/mavlink/log/messages/attitude.rb', line 21

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

#yawObject

radians (-pi..pi)



16
17
18
# File 'lib/mavlink/log/messages/attitude.rb', line 16

def yaw
  @yaw ||= float(8..11)
end

#yawspeedObject

rad/s



31
32
33
# File 'lib/mavlink/log/messages/attitude.rb', line 31

def yawspeed
  @yawspeed ||= float(20..23)
end