Servo Out Read PWM

Hi team

This might be simple, but struggling with reading a servo/relay PWM from mission planner in Lua

im trying to set up a parameter that will listen for the PWM signal on a channel 9, i have 9 set up as RC passthrough

image

and i am sending a signal via the servo/relay section of mission planner
image

but i can’t seem to find the right parameter for reading that output? I’d like to monitor when i toggle it from 1100 to 1900 in Lua, ive tried


local RC9 = SRV_Channels:get_output_pwm(58)


function update()

    gcs:send_text(0, "RC9: " .. tostring(RC9))
  
    return update, 100
  end
  
  return update()

but i just get nil, how should i be trying to read the output pwm on this channel for rc passthru?

im assuming that 58 for the channel is correct as per

image

The binding you are using does not use pin number, but rather output function number. Additionally, your script does not continuously update the desired variable. Try this:

local RCIN9_FN = 59

function update()
    local srv_pwm = SRV_Channels:get_output_pwm(RCIN9_FN)
    gcs:send_named_float('RCIN9', srv_pwm)
    return update, 100
  end
  
  return update()

And monitor the script on Mission Planner’s Quick tab by selecting MAV_RCIN9 as one of the values.

Using the servo/relay page will be ineffective for testing. Those are not RC overrides. You will need to supply actual RC input. If you are more clear on your goal, I can help further.

Hi Yuri, thanks so much for the reply, as always so quick!

no luck on that either, I have a PWM to analog converter and im giving a high PWM output on a channel that equates to a on or off in DC (led lights for POC) and want to test and monitor the PWM output (im going to set up a timer that once its 1900, after 10 seconds, switch back to 1100, or OFF)

But i think the RC in is the issue, i will need an actual RC IN to monitor it looks like, as there doesn’t seem to be a way of monitoring the PWM out just from the servo/relay page (which is what i was going to use as the control buttons) but i shall use some real RC input instead i think

I think this is more like what you want. No RC required. Testable in SITL and should work on any scripting compatible autopilot.

local SCRIPTING_FN = 94
local AUX_FN = 300
local PWM_HIGH = 1900
local PWM_LOW = 1100
local TIMEOUT_MS = 10000
local RUN_INTERVAL_MS = 100

SRV_Channels:set_output_pwm(SCRIPTING_FN, PWM_LOW)

local last_aux_pos = nil
local timeout = 0

function update()
    local aux_pos = rc:get_aux_cached(AUX_FN)
    local now = millis()

    if aux_pos ~= last_aux_pos then
        last_aux_pos = aux_pos

        if aux_pos > 0  and timeout < now then
            SRV_Channels:set_output_pwm(SCRIPTING_FN, PWM_HIGH)
            timeout = now + TIMEOUT_MS
            return update, RUN_INTERVAL_MS
        end

        -- this cancels the timeout when the aux switch goes low
        -- remove this if condition if you always want to let the timeout control the off position
        if aux_pos == 0 then
            timeout = 0
            SRV_Channels:set_output_pwm(SCRIPTING_FN, PWM_LOW)
        end
    end

    if timeout > 0 and timeout < now then
        timeout = 0
        SRV_Channels:set_output_pwm(SCRIPTING_FN, PWM_LOW)
    end

    return update, RUN_INTERVAL_MS
end

return update()

To use it, set a SERVOx_FUNCTION parameter to 94 and control it with the Aux Function page on Mission Planner. It will also trigger on RC input by setting any 2 or 3 position switch RCx_OPTION parameter to 300.

image

Monitor output on the Quick Tab by choosing chXout for the channel you’re using as one of the monitored values (or on the Setup/Servo page):

image

Hi Yuri
Thanks so much for this, once again super useful help this will work well!

Out of curiosity, is there a way of listening for the servo/replay page’s toggles? Or will a lua script always need an RCIn to bind a parameter to?

It’s an awkward approach and not really worth exploring. You’d have to poll for MAVLink commands, and I don’t think the outcome would be exactly what you’re envisioning.

There are better mechanisms for gathering input…like the one I just showed you.

Thanks Yuri, load and clear!

With the example above, i take it that it would be 1 servo per script?

Or would i be able to monitor and control multiple servos for a single script?

One script can do a lot more than you probably realize…

1 Like

You are once again correct!! Have got what i need working thank you!

As an aesthetic aside, i don’t suppose there’s a way of changing the text on these buttons?
image

similar to how you can on the servo page?

Not without a custom build of Mission Planner, I think.

Hello @Yuri_Rage

I wanted to ask you because i’m trying to modify the min_pwm position of a channel with a switch.

I used this post as base to do this code but i’m getting an error saying “attemp to call a nil value (method ‘set_output_min’)” so seems the method don’t exits, maybe was deprecated or something

Do you know what will be the current way to do this?

local AUX_FN = 300
local RUN_INTERVAL_MS = 100
local SERVO_N = 94
local DISARMED_PWM = 1000
local ARMED_PWM = 1250

function update()
    local aux_pos = rc:get_aux_cached(AUX_FN)
    local now = millis()
    
    if aux_pos ~= nil then
        if aux_pos > 0 then
            SRV_Channels:set_output_min(SERVO_N, ARMED_PWM)
        else
            SRV_Channels:set_output_min(SERVO_N, DISARMED_PWM)
        end
    end
    
    return update, RUN_INTERVAL_MS
end

return update()

Regards

set_output_min is not and has never been a Lua binding. You can’t just arbitrarily choose methods from the C++ headers and attempt to access them via scripting. See here for valid, bound methods.

I think what you’re looking for is: SRV_Channels:set_output_scaled(function_num, value), where you’d use a value of -1 to set the minimum output value.

Ah ok, seems i got confused then as i tought it was a lua method!!, my mistake.

But if i understand correctly this one will set the current value i choose, -1 to set a channel to the lower range it has specified

SRV_Channels:set_output_scaled(function_num, value)

What i want to do is to set the low possible position, for example: in one switch position range will be 1000-2000 and in other one 1250-2000

Thanks!

It sounds like you want to set SERVOx_MIN via scripting. The param bindings do that.

Ok, thanks.

What i’m doing wrong here please? Sintax of the param setter seems wrong but i cant figure…

--- https://discuss.ardupilot.org/t/servo-out-read-pwm/121911/4
--- https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Scripting/applets/leds_on_a_switch.lua

-- constants
local DISARMED_PWM = 1000
local ARMED_PWM = 1250
local AuxSwitchPos = {LOW=0, MIDDLE=1, HIGH=2}
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local SCR_ENABLE = Parameter()
local prev_pos = -1

-- state
if not SCR_ENABLE:init('SCR_ENABLE') then
    gcs:send_text(MAV_SEVERITY.INFO, 'init SCR_ENABLE failed')
else
    gcs:send_text(MAV_SEVERITY.INFO, "Turbine script loaded")
end

function update()
    local sw_pos = rc:get_aux_cached(300)
    local parameter = SCR_ENABLE:get()

    if sw_pos ~= prev_pos then
        if sw_pos == AuxSwitchPos.LOW then
            gcs:send_text(MAV_SEVERITY.INFO, "Turbine disarmed")
            parameter:set('SERVO3_MIN', DISARMED_PWM)
        else
            parameter:set('SERVO3_MIN', ARMED_PWM)
            gcs:send_text(MAV_SEVERITY.INFO, "Turbine armed")
        end
        prev_pos = sw_pos
    end

    return update, 1000
end

return update()
--- https://discuss.ardupilot.org/t/servo-out-read-pwm/121911/4
--- https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Scripting/applets/leds_on_a_switch.lua

-- constants
local DISARMED_PWM = 1000
local ARMED_PWM = 1250
local AuxSwitchPos = {LOW=0, MIDDLE=1, HIGH=2}
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local prev_pos = nil

-- bind a parameter to a variable
-- see: https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Scripting/applets/rover-quicktune.lua
local function bind_param(name)
    local p = Parameter()
    assert(p:init(name), string.format("Could not find %s parameter", name))
    return p
end

local SERVO3_MIN = bind_param('SERVO3_MIN')

function update()
    local sw_pos = rc:get_aux_cached(300)

    if sw_pos ~= prev_pos then
        if sw_pos == AuxSwitchPos.LOW then
            gcs:send_text(MAV_SEVERITY.INFO, "Turbine disarmed")
            SERVO3_MIN:set(DISARMED_PWM)
        else
            SERVO3_MIN:set(ARMED_PWM)
            gcs:send_text(MAV_SEVERITY.INFO, "Turbine armed")
        end
        prev_pos = sw_pos
    end

    return update, 1000  -- consider a faster polling rate unless you want a ~1s delay upon switch change
end

gcs:send_text(MAV_SEVERITY.INFO, "Turbine script loaded")

return update()
1 Like