Class: MAVLink::Log::Messages::ServoOutputRaw
Instance Method Summary
collapse
#time_usec
#crc, #id, #initialize
Instance Method Details
#port ⇒ Object
37
38
39
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 37
def port
@port ||= uint8_t(20)
end
|
#servo1_raw ⇒ Object
5
6
7
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 5
def servo1_raw
@servo1_raw ||= uint16_t(4..5)
end
|
#servo2_raw ⇒ Object
9
10
11
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 9
def servo2_raw
@servo2_raw ||= uint16_t(6..7)
end
|
#servo3_raw ⇒ Object
13
14
15
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 13
def servo3_raw
@servo3_raw ||= uint16_t(8..9)
end
|
#servo4_raw ⇒ Object
17
18
19
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 17
def servo4_raw
@servo4_raw ||= uint16_t(10..11)
end
|
#servo5_raw ⇒ Object
21
22
23
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 21
def servo5_raw
@servo5_raw ||= uint16_t(12..13)
end
|
#servo6_raw ⇒ Object
25
26
27
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 25
def servo6_raw
@servo6_raw ||= uint16_t(14..15)
end
|
#servo7_raw ⇒ Object
29
30
31
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 29
def servo7_raw
@servo7_raw ||= uint16_t(16..17)
end
|
#servo8_raw ⇒ Object
33
34
35
|
# File 'lib/mavlink/log/messages/servo_output_raw.rb', line 33
def servo8_raw
@servo8_raw ||= uint16_t(18..19)
end
|