2021-01-28 18:36:37 -04:00
|
|
|
-- This script is an example of reading a analog pin, PWM in and GPIO
|
|
|
|
|
|
|
|
-- for these examples BRD_PWM_COUNT must be 0
|
|
|
|
|
|
|
|
-- load the analog pin, there are only 16 of these available
|
|
|
|
-- some are used by the main AP code, ie battery monitors
|
|
|
|
-- assign them like this in the init, not in the main loop
|
2021-03-17 19:50:32 -03:00
|
|
|
local analog_in = analog:channel()
|
2021-09-25 22:16:21 -03:00
|
|
|
if not analog_in:set_pin(13) then -- typically 13 is the battery input
|
|
|
|
gcs:send_text(0, "Invalid analog pin")
|
|
|
|
end
|
2021-01-28 18:36:37 -04:00
|
|
|
|
|
|
|
-- load a input pwm pin
|
|
|
|
local pwm_in = PWMSource()
|
|
|
|
local pwm_in_fail = PWMSource()
|
|
|
|
|
|
|
|
if not pwm_in:set_pin(50) then -- AUX 1
|
|
|
|
gcs:send_text(0, "Failed to setup PWM in on pin 50")
|
|
|
|
end
|
|
|
|
|
|
|
|
-- there are a few combinations of PWM in that will not work
|
|
|
|
-- this is due to the way interrupts are handled, AUX 1 and 6 cannot both
|
|
|
|
-- be PWM at once because they use the same interrupt (on Cubes), this should fail
|
|
|
|
if not pwm_in_fail:set_pin(55) then -- AUX 6
|
|
|
|
gcs:send_text(0, "Failed to setup PWM in on pin 55")
|
|
|
|
end
|
|
|
|
|
2021-03-17 19:50:32 -03:00
|
|
|
gpio:pinMode(51,1) -- set AUX 2 to output, gpio:pinMode(51,0) would be input
|
2021-01-28 18:36:37 -04:00
|
|
|
|
|
|
|
function update()
|
2021-03-17 19:50:32 -03:00
|
|
|
gcs:send_text(0, string.format("voltage: %0.2f, PWM: %i, input: ", analog_in:voltage_average(), pwm_in:get_pwm_us()) .. tostring(gpio:read(51)))
|
2021-01-28 18:36:37 -04:00
|
|
|
|
2021-03-17 19:50:32 -03:00
|
|
|
-- analog_in:voltage_average() the average voltage since the last call
|
|
|
|
-- analog_in:voltage_latest() the latest voltage reading
|
|
|
|
-- analog_in:voltage_average_ratiometric() the average ratiometric voltage (relative to the board 5v)
|
2021-01-28 18:36:37 -04:00
|
|
|
|
|
|
|
-- pwm_in:get_pwm_us() the latest pwm value in us
|
|
|
|
-- pwm_in:get_pwm_avg_us() the average pwm value in us since the last call
|
|
|
|
|
2021-03-17 19:50:32 -03:00
|
|
|
-- gpio:read(pin)
|
|
|
|
-- gpio:write(pin, state)
|
|
|
|
-- gpio:toggle(pin)
|
2021-01-28 18:36:37 -04:00
|
|
|
|
2021-03-17 19:50:32 -03:00
|
|
|
gpio:toggle(51)
|
2021-01-28 18:36:37 -04:00
|
|
|
|
|
|
|
return update, 1000
|
|
|
|
end
|
|
|
|
|
|
|
|
return update() -- run immediately before starting to reschedule
|