GPIO AUX and Lua script

Hi there,
I thought it would be easy to get information through GPIO AUX ports !
I’m currently using Mission Planner 1.3.81 build 1.3.87, ArduPlane V4.4.0 Cube Orange; SCR_ENABLE = 1

In that version BRD_PWM_COUNT doesn’t exist anymore.
My Code tries to affect Pin 2 and 3, and to read it, but unfortunatly nothing happens when I put it to HIGH (3-5V). On the screen I have always “Blue Green = 10” with or without avtivating the pins. (Im using rangefinder on 5-6 and it’s working nicely )

Blockquote
gpio:pinMode(51,0) – AUX 2
gpio:pinMode(52,0) – set AUX 3 to input, gpio:pinMode(51,1) would be output

local Blue = false
local Green = false

function update()

Green = gpio:read(51)
Blue = gpio:read(52)

if not Blue and not Green then
	gcs:send_text(0, "Blue Green = 00 OK")
elseif Blue and not Green then
	gcs:send_text(0, "Blue Green = 10")
elseif not Blue and Green then
	gcs:send_text(0, "Blue Green = 01")
elseif Blue and Green then
	gcs:send_text(0, "Blue Green = 11 STOP")
else
	gcs:send_text(0, "Aucune correspondace")

end

return update, 5000 – boucle 5 secondes

end

return update()

Blockquote

Thanks for help or Advice

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()

Hi Yuri, Thanks a lot ! Yes your code is working : the states are changing one by one !

In my case I had some difficulties linked to the fact that I discovered that if you dont force the Signal Pin to “LOW” by linking to “GND”, the state will be “HIGH”. If you leave it alone it’s HIGH… initially I thought that if no Signal it would be LOW but NO.

In my case to be abble to read the signal sent to the GPIO I have set

@Yuri_Rage I was planning to use 51 & 52 (see picture)

You asked me to put
SERVO10_FUNCTION,-1
SERVO11_FUNCTION,-1

If I wanted to use 50, should I’ve put SERVO9_FUNCTION,-1 ?

Thanks

Correct. Glad you’re on track now.

Thanks Yuri, I wish you would be my neighbour ! :slight_smile: :rofl: