Problem: Your Drone Can't Make Decisions Without a Ground Station
Your drone follows a pre-planned mission just fine — until something changes. Wind shifts. A sensor triggers. A waypoint needs to be skipped conditionally. Without custom logic running onboard, your options are: abort, or babysit the mission from a laptop.
You'll learn:
- How to enable and deploy Lua scripts on ArduPilot flight controllers
- How to write scripts that react to sensor data and modify flight behavior in real time
- How to structure a complete onboard mission automation script with safe fallbacks
Time: 25 min | Level: Intermediate
Why This Happens
ArduPilot's standard mission planner is static — waypoints, speeds, and altitudes are fixed at upload time. If you need conditional behavior (fly to waypoint B only if rangefinder reads > 5m, or loiter until a GPIO pin goes high), you either need a companion computer running MAVLink, or you need Lua.
ArduPilot's scripting engine runs Lua directly on the flight controller's CPU, with access to the full parameter tree, sensor data, servo outputs, and mission commands. No extra hardware. No latency from an external computer.
Common situations where this matters:
- Precision agriculture: spray only when flying over crop rows, not headlands
- Inspection drones: loiter and capture when a sensor threshold is crossed
- Racing/acrobatics: custom arming sequences or mode switches based on telemetry
- Research: rapid prototyping of flight behaviors without recompiling firmware
Lua scripts run in a sandboxed environment on the flight controller, with direct API access to sensors and the mission engine
Solution
Step 1: Enable Scripting on Your Flight Controller
Lua scripting requires ArduPilot 4.1 or later. It's disabled by default to preserve CPU headroom.
# Via MAVProxy or Mission Planner parameter editor
# Set these parameters:
SCR_ENABLE = 1 # Enable scripting engine
SCR_HEAP_SIZE = 65536 # Memory allocated to scripts (bytes) — 64KB is a safe start
SCR_VM_I_COUNT = 10000 # Instructions per 10ms tick — lower = safer CPU usage
Reboot the flight controller after setting SCR_ENABLE. The scripting engine initializes at boot.
Expected: MAVProxy will show Scripting: Running in the boot log. Check with:
param show SCR_ENABLE
# Should return: SCR_ENABLE 1
If it fails:
- No SCR_ENABLE parameter visible: Your firmware build doesn't include scripting. Flash the standard "with scripting" build from firmware.ardupilot.org — look for builds labeled
-scripting. - Scripting: FAILED on boot: Heap too small. Increase
SCR_HEAP_SIZEto 131072 (128KB).
Step 2: Upload Your First Script
Scripts live in the APM/scripts/ directory on the SD card. Use Mission Planner's MAVFtp, QGroundControl, or a direct SD card connection.
-- hello_world.lua
-- Runs once per second, logs a message to the GCS
local function update()
gcs:send_text(6, "Script alive: " .. tostring(millis()))
return update, 1000 -- reschedule in 1000ms
end
return update()
Upload this as APM/scripts/hello_world.lua, then reboot. In Mission Planner's Messages tab you should see Script alive: <timestamp> appearing every second.
The GCS messages tab confirms your script is running — message level 6 = INFO
Step 3: Read Sensor Data
The ArduPilot Lua API exposes the full sensor suite. Here's how to read the most common sources:
-- sensor_reader.lua
-- Reads GPS, rangefinder, and battery — the core of most automation logic
local function update()
-- GPS position
local loc = ahrs:get_location()
if loc then
-- loc:lat() and loc:lng() return integers (1e7 degrees)
local lat = loc:lat() / 1e7
local lng = loc:lng() / 1e7
gcs:send_text(6, string.format("Pos: %.6f, %.6f", lat, lng))
end
-- Rangefinder (first sensor, index 0)
local rng = rangefinder:distance_cm_orient(0) -- returns cm as integer
if rng then
gcs:send_text(6, "Range: " .. tostring(rng) .. "cm")
end
-- Battery voltage
local voltage = battery:voltage(0) -- battery instance 0
if voltage then
gcs:send_text(6, string.format("Batt: %.2fV", voltage))
end
return update, 500 -- poll every 500ms
end
return update()
Why the nil checks matter: Sensors can be unavailable at boot, during GPS acquisition, or on hardware without that sensor. Calling methods on nil crashes the script. Always guard sensor reads.
Step 4: Write a Complete Mission Automation Script
This script implements a real use case: automatically trigger a camera servo when the drone reaches within 10m horizontal of each waypoint, then confirm capture before advancing.
-- waypoint_camera_trigger.lua
-- Fires camera servo at waypoint proximity, waits for confirmation
local CAMERA_SERVO_CHANNEL = 8 -- RC output channel for camera trigger
local TRIGGER_RADIUS_M = 10 -- meters from waypoint to trigger
local TRIGGER_PULSE_MS = 200 -- servo pulse duration
local CONFIRM_WAIT_MS = 1500 -- wait before advancing to next waypoint
local triggered = false
local trigger_time = 0
local function distance_to_waypoint_m()
-- Get current mission target waypoint location
local wp_loc = mission:get_current_nav_cmd()
if not wp_loc then return nil end
local current_loc = ahrs:get_location()
if not current_loc then return nil end
-- get_distance returns meters as a float
return current_loc:get_distance(wp_loc:get_location())
end
local function fire_camera()
-- Set servo to trigger position (1800us = full deflection)
SRV_Channels:set_output_pwm_chan(CAMERA_SERVO_CHANNEL - 1, 1800)
trigger_time = millis()
triggered = true
gcs:send_text(5, "Camera triggered at waypoint") -- level 5 = NOTICE
end
local function release_camera()
-- Return servo to neutral (1500us)
SRV_Channels:set_output_pwm_chan(CAMERA_SERVO_CHANNEL - 1, 1500)
end
local function update()
-- Only run logic in AUTO mode
if vehicle:get_mode() ~= 10 then -- 10 = AUTO for Copter
triggered = false
return update, 200
end
local dist = distance_to_waypoint_m()
if dist and dist < TRIGGER_RADIUS_M and not triggered then
fire_camera()
end
if triggered then
local elapsed = millis() - trigger_time
if elapsed >= TRIGGER_PULSE_MS then
release_camera()
end
if elapsed >= CONFIRM_WAIT_MS then
triggered = false
-- Advance to next waypoint
mission:set_current_cmd(mission:get_current_nav_index() + 1)
gcs:send_text(6, "Advancing to next waypoint")
end
end
return update, 100 -- 100ms loop for responsive triggering
end
return update()
Key patterns used:
- Mode check first — script is a no-op in LOITER or STABILIZE, preventing accidental triggers on the ground
- Non-blocking timing with
millis()— never usesleep()in ArduPilot scripts, it blocks the flight controller - Explicit servo channel indexing starts at 0, not 1
If it fails:
- Servo not moving: Verify the channel is configured as
RCx_OPTION = 0(passthrough), not assigned to a flight function - Script crashes on
mission:get_current_nav_cmd(): Not in a mission yet. The nil guard onwp_lochandles this — confirm it's in place - Mode number wrong: Mode numbers differ between Copter, Plane, and Rover. Check
vehicle:get_mode()against your vehicle type's mode table in the ArduPilot docs
Step 5: Add a Safe Fallback
Scripts that crash leave hardware in whatever state it was when the crash happened. Add a protected call wrapper for production scripts:
-- Wrap your update function with error handling
local function protected_update()
local ok, err = pcall(update)
if not ok then
gcs:send_text(3, "Script error: " .. tostring(err)) -- level 3 = ERROR
-- Return to safe servo state
SRV_Channels:set_output_pwm_chan(CAMERA_SERVO_CHANNEL - 1, 1500)
end
return protected_update, 100
end
return protected_update()
This logs the error to the GCS and ensures the servo returns to neutral rather than staying at the trigger position indefinitely.
Verification
Check that your script loaded and is running cleanly:
# In MAVProxy
script list # Lists all loaded scripts
script stats # Shows CPU usage per script and error counts
On Mission Planner, go to Config → MAVFtp → APM/scripts/ and confirm your .lua files are present. Boot logs under Messages will show Loaded script: your_script.lua for each successfully loaded script.
You should see: Zero error count in script stats, and your GCS messages appearing at the expected interval.
Script stats shows CPU usage and error count — a clean run shows 0 errors
What You Learned
- ArduPilot Lua scripts run onboard the FC with direct sensor and mission API access — no companion computer needed
- Scripts are event-loop based: your
update()function reschedules itself, never blocks - Always nil-check sensor reads and wrap production scripts in
pcallfor safe failure handling - Mode checks prevent accidental actuation when the vehicle isn't in the expected flight mode
Limitations to know:
- Script CPU budget is shared with flight control — keep loops above 50ms and avoid heavy string formatting in tight loops
- The Lua API is ArduPilot-version-specific. Scripts written for 4.3 may use APIs not present in 4.1. Check the ArduPilot scripting API docs for your firmware version.
- Scripts cannot directly control throttle or attitude — they interact through the mission and parameter system, not the inner control loops. For that level of control you need a full AP_ExternalControl integration.
When NOT to use Lua scripting:
- Hard realtime requirements (< 10ms response) — use a companion computer with MAVLink instead
- Complex computer vision or ML inference — the FC doesn't have the CPU for it
- Cross-vehicle portability — mode numbers and some API calls differ between Copter, Plane, and Rover
Tested on ArduPilot Copter 4.5.x, CubeOrange and MatekH743 flight controllers, Mission Planner 1.3.82