Class: MAVLink::Log::Messages::RcChannelsRaw
Instance Method Summary
collapse
#time_boot_ms
#crc, #id, #initialize
Instance Method Details
#chan1_raw ⇒ Object
5
6
7
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 5
def chan1_raw
@chan1_raw ||= uint16_t(4..5)
end
|
#chan2_raw ⇒ Object
9
10
11
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 9
def chan2_raw
@chan2_raw ||= uint16_t(6..7)
end
|
#chan3_raw ⇒ Object
13
14
15
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 13
def chan3_raw
@chan3_raw ||= uint16_t(8..9)
end
|
#chan4_raw ⇒ Object
17
18
19
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 17
def chan4_raw
@chan4_raw ||= uint16_t(10..11)
end
|
#chan5_raw ⇒ Object
21
22
23
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 21
def chan5_raw
@chan5_raw ||= uint16_t(12..13)
end
|
#chan6_raw ⇒ Object
25
26
27
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 25
def chan6_raw
@chan6_raw ||= uint16_t(14..15)
end
|
#chan7_raw ⇒ Object
29
30
31
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 29
def chan7_raw
@chan7_raw ||= uint16_t(16..17)
end
|
#chan8_raw ⇒ Object
33
34
35
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 33
def chan8_raw
@chan8_raw ||= uint16_t(18..19)
end
|
#port ⇒ Object
37
38
39
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 37
def port
@port ||= uint8_t(20)
end
|
41
42
43
|
# File 'lib/mavlink/log/messages/rc_channels_raw.rb', line 41
def
@rssi ||= uint8_t(21)
end
|