This is not my favorite script, but it will do what you want if you connect your single RC channel output to main out 12 of the ZealotH743. I chose output 12 because it is somewhat unlikely to overlap timer groups in use for other functions.
The script is fairly well commented so you can see what’s happening. I considered trying to override all the prearm checks, but that became a parameter control nightmare, and there are some failsafes that almost always preclude throttle output - a situation you are likely to encounter indoors without the primary RC system involved.
While you can leave it as is, that’s probably unwise. You should set up your radio failsafe actions and values and then monitor for valid RC input within the update loop. Use valid RC input as a means to set the enable_jog_control
variable to false, which should preclude jog control when the primary RC handset is in use.
If you have to reverse one of the throttle channels, this script will make your robot spin in circles. You’ll need to do some math in the script to get reversed output. I did not account for that. I’m also assuming that you’re using a skid steer setup. It’s easy enough to modify the script for a single throttle output if you need to do that.
You might also consider limiting the min and max output PWM values, since the script will allow a pretty wide range of output (essentially all the way up to full forward and reverse throttle).
I can confirm that this script will move the Rover forward and backward with nearly every failsafe imaginable active, since I tested it on a live, disarmed ZealotH743 with no GPS, no RC system, and wildly out of calibration.
As written, there is a deadband of +/- 50µs around 1500µs, which is the usual neutral point of an RC channel. You can modify the values to suit your RC remote as needed. If the jog channel remains within the deadband for a half second or more, normal throttle function is returned.
PLEASE test this thoroughly with the engine off and/or vehicle wheels off the ground before you trust it to move your big, expensive toy!
You would be safer and better off using one of my recommendations above rather than this script. Using an autopilot with an IOMCU and a true second RC system would provide a ton more flexibility than this simple, hacky forward/reverse scheme.
--[[----------------------------------------------------------------------------
rover-jog-disarmed ArduPilot Lua script
Extremely hacky script to allow moving a rover by directly influencing
servo output while disarmed via PWM input.
CAUTION: This script is capable of engaging and disengaging autonomous control
of a vehicle. Use this script AT YOUR OWN RISK.
------------------------------------------------------------------------------]]
local RUN_INTERVAL_MS = 25
local DEADBAND = 50
local IDLE_TIMEOUT = 500
local pwm_in = PWMSource()
local throttle_left_ch = assert(SRV_Channels:find_channel(73), 'ThrottleLeft not configured')
local throttle_right_ch = assert(SRV_Channels:find_channel(74), 'ThrottleRight not configured')
local servo_left_fn = Parameter(('SERVO%d_FUNCTION'):format(throttle_left_ch + 1))
local servo_right_fn = Parameter(('SERVO%d_FUNCTION'):format(throttle_right_ch + 1))
local timeout = uint32_t(0)
local is_active = false
if not pwm_in:set_pin(61) then -- Pin 12
gcs:send_text(0, 'Failed to configure input on PWM 12')
return
end
-- temporarily use scripted servo functions to allow movement regardless of arming state
local function take_control()
servo_left_fn:set(300)
servo_right_fn:set(301)
is_active = true
gcs:send_text(5, 'Jog active')
end
-- return servo functions to throttle left/right
local function release_control()
servo_left_fn:set(73)
servo_right_fn:set(74)
is_active = false
gcs:send_text(5, 'Released jog control')
end
function update()
-- TODO: user should implement a way to set enable_jog_control based on radio failsafe indications
local enable_jog_control = true
-- if jog control is disabled, release control and immediately return
if not enable_jog_control then
if is_active then
release_control()
end
return update, RUN_INTERVAL_MS
end
local pwm_value = pwm_in:get_pwm_us()
local is_pwm_valid = pwm_value > 900 and pwm_value < 2100
-- if pwm value is out of range, release control and immediately return
if not is_pwm_valid then
if is_active then
release_control()
end
return update, RUN_INTERVAL_MS
end
-- if pwm value is in range and outside deadband, take jog control
if pwm_value < (1500 - DEADBAND) or pwm_value > (1500 + DEADBAND) then
if not is_active then
take_control()
end
SRV_Channels:set_output_pwm_chan(throttle_left_ch, pwm_value)
SRV_Channels:set_output_pwm_chan(throttle_right_ch, pwm_value)
timeout = millis()
end
-- if pwm value is in range and within deadband, release control
if is_active and millis() - timeout > IDLE_TIMEOUT then
release_control()
end
gcs:send_named_float('JOG', pwm_value)
return update, RUN_INTERVAL_MS
end
gcs:send_text(6, 'Jog script loaded')
return update()