Class: MAVLink::Log::Messages::ParamValue
Instance Method Summary
collapse
#crc, #id, #initialize
Instance Method Details
#param_count ⇒ Object
9
10
11
|
# File 'lib/mavlink/log/messages/param_value.rb', line 9
def param_count
@param_count ||= uint16_t(4..5)
end
|
#param_id ⇒ Object
17
18
19
|
# File 'lib/mavlink/log/messages/param_value.rb', line 17
def param_id
@param_id ||= string(8..23)
end
|
#param_index ⇒ Object
13
14
15
|
# File 'lib/mavlink/log/messages/param_value.rb', line 13
def param_index
@param_index ||= uint16_t(6..7)
end
|
#param_type ⇒ Object
21
22
23
|
# File 'lib/mavlink/log/messages/param_value.rb', line 21
def param_type
@param_type ||= uint8_t(24)
end
|
#param_value ⇒ Object
5
6
7
|
# File 'lib/mavlink/log/messages/param_value.rb', line 5
def param_value
@param_value ||= float(0..3)
end
|