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.
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):
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.