Turn off sprayer pump when tank gets empty using lua scripting

Hey, I’m building an agricultural drone (hexacopter). But unfortunately the current ardupilot codebase doesnt offer all functionalities I need. For example: During spraying, whenever the tank gets empty (flow meter rate becomes zero), the pump should turn off.
My task is to build a new firmware by making some necessary changes in the source code for this purpose. Any suggestion on where and how to make the changes would be appreciated.

Look up LUA scripting for Ardupilot. Almost everything can be done with it.
https://ardupilot.org/copter/docs/common-lua-scripts.html

Hey thanks…but how can i create new firmware by making some changes in lua script

that’s the point of LUA scripting, you don’t need to build a custom firmware to run scripts that perform tasks the original fw wasn’t capable of.

2 Likes
-- Lua script for ArduPilot Copter

-- Check if BATT_MONITOR parameter is 11
local batt_monitor = param:get("BATT_MONITOR")
if batt_monitor ~= 11 then
    return -- Exit the script if BATT_MONITOR is not 11
end

-- Define the RC channel for the pump
local pump_channel = 6

-- Define the threshold for battery current
local current_threshold = 100

-- Function to turn the pump off
local function turn_off_pump()
    rc:set_output_pwm(pump_channel, 1051) -- Set RC channel to minimum to turn off the pump
end

-- Function to monitor battery current and control the pump
local function monitor_battery_and_control_pump()
    -- Check if the pump is turned on (RC channel value is above 1500)
    if rc:get_pwm(pump_channel) > 1200 then
        -- Wait for 2 seconds
        local wait_time = 500
        local start_time = millis()
        while millis() - start_time < wait_time do
            -- Wait loop
        end
        
        -- Monitor battery current
        while true do
            local current_amps = battery:current_amps(0) -- Get the current from battery 0
            if current_amps < current_threshold then
                turn_off_pump() -- Turn off the pump if current is below threshold
                gcs:send_text(0,"Pumps will be turned off")
                return -- Exit the function to keep the pump off
            end
            
        end
    end
end

-- Main loop to periodically check the pump status and monitor battery
function update()
    monitor_battery_and_control_pump()
    return update, 1000 -- Run the update function every second
end

return update()

Hey @Eosbandi this is the script i have written to turn off my pump whenever my pump rate goes below certain value. But I dont think this is working. Any modifications to the script that you would like to suggest?

Do not do wait loop in a script, is must return within a certain time (set via a param) or it will be terminated.
Use the update loop and some variables to implement waiting within doe not hold up the script.

1 Like

hey, thanks man. I got it working by making some changes in the script

1 Like

Publish it here for other users to see.

1 Like