AP_scripting: add bindings and example for analog inputs
This commit is contained in:
parent
e5de148ad1
commit
9d739cfa42
18
libraries/AP_Scripting/examples/analog_input.lua
Normal file
18
libraries/AP_Scripting/examples/analog_input.lua
Normal file
@ -0,0 +1,18 @@
|
||||
-- This script is an example of reading a analog pin
|
||||
|
||||
-- load the analog pin
|
||||
local analog = hal.analog_pin()
|
||||
|
||||
analog:set_pin(13) -- typically 13 is the battery input
|
||||
|
||||
function update()
|
||||
gcs:send_text(0, string.format("voltage: %0.2f", analog:voltage_average()))
|
||||
|
||||
-- analog:voltage_average() the average voltage since the last call
|
||||
-- analog:voltage_latest() the latest voltage reading
|
||||
-- analog:voltage_average_ratiometric() the average ratiometric voltage (relative to the board 5v)
|
||||
|
||||
return update, 1000
|
||||
end
|
||||
|
||||
return update() -- run immediately before starting to reschedule
|
@ -339,3 +339,9 @@ ap_object AP_HAL::I2CDevice method set_retries void uint8_t 0 20
|
||||
ap_object AP_HAL::I2CDevice method write_register boolean uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX
|
||||
ap_object AP_HAL::I2CDevice method read_registers boolean uint8_t 0 UINT8_MAX &uint8_t'Null 1'literal
|
||||
ap_object AP_HAL::I2CDevice method set_address void uint8_t 0 UINT8_MAX
|
||||
|
||||
|
||||
ap_object AP_HAL::AnalogSource method set_pin void uint8_t 0 UINT8_MAX
|
||||
ap_object AP_HAL::AnalogSource method voltage_average float
|
||||
ap_object AP_HAL::AnalogSource method voltage_latest float
|
||||
ap_object AP_HAL::AnalogSource method voltage_average_ratiometric float
|
||||
|
Loading…
Reference in New Issue
Block a user