ardupilot/libraries/AP_Scripting/examples/get-target-location-mount-backend.lua
neo-0007 16a79f5554 AP_Scripting: add example script to test target location
Script to test location for all 7 modes of mount using the
AP_Scripting_Backend.

Signed-off-by: neo-0007 <hrishikeshgohain123@gmail.com>
2025-11-27 10:14:20 +11:00

31 lines
770 B
Lua

-- Test mount scripting backend
local UPDATE_MS = 100
local REPORT_INTERVAL_MS = 2000
local last_report_ms = millis()
function update()
-- Keep mount healthy
mount:set_attitude_euler(0, 0, -30, 0)
-- Test get_location_target every 2 seconds
local now_ms = millis()
if now_ms - last_report_ms >= REPORT_INTERVAL_MS then
last_report_ms = now_ms
local mode = mount:get_mode(0)
local target = mount:get_location_target(0)
if target then
gcs:send_text(6, string.format("Mode %d: %.6f,%.6f",
mode, target:lat()/1e7, target:lng()/1e7))
else
gcs:send_text(6, string.format("Mode %d: No target", mode))
end
end
return update, UPDATE_MS
end
return update()