First, you must configure the outputs as GPIO by setting these parameters:
SERVO10_FUNCTION,-1
SERVO11_FUNCTION,-1
Then this (untested) script should work:
local AUX2 = 51
local AUX3 = 52
local NUM_PINS = 2
local RUN_INTERVAL_MS = 5000
local BOOL_TO_UINT = { [true] = 1, [false] = 0 }
local MAV_SEVERITY = {
EMERGENCY = 0,
ALERT = 1,
CRITICAL = 2,
ERROR = 3,
WARNING = 4,
NOTICE = 5,
INFO = 6,
DEBUG = 7
}
gpio:pinMode(AUX2, 1) -- must be output for write to work
gpio:pinMode(AUX3, 1)
local state = 0
function update()
gpio:write(AUX2, state & 0x01)
gpio:write(AUX3, (state >> 1) & 0x01)
local aux2_state = BOOL_TO_UINT[gpio:read(AUX2)]
local aux3_state = BOOL_TO_UINT[gpio:read(AUX3)]
gcs:send_text(MAV_SEVERITY.INFO, ('AUX3, AUX2: %d%d'):format(aux3_state, aux2_state))
state = (state + 1) % (NUM_PINS ^ 2)
return update, RUN_INTERVAL_MS
end
return update()