This repository was archived by the owner on Dec 17, 2025. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathrng_simulate_offset.lua
More file actions
54 lines (47 loc) · 2.01 KB
/
Copy pathrng_simulate_offset.lua
File metadata and controls
54 lines (47 loc) · 2.01 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
-- This script simulate a rangefinder consuming the barometric altitude and adding an offset.
-- Used to test the surface_tracking reset
local INIT_MILLIS = 3000
local OFFSET = 2
-- Global variables (DO NOT CHANGE)
local MAV_SEVERITY = {EMERGENCY = 0, ALERT = 1, CRITICAL = 2, ERROR = 3, WARNING = 4, NOTICE = 5, INFO = 6, DEBUG = 7}
local PARAM_LUA_RFND = 36 -- parameter number for lua rangefinder
local lua_rfnd_backend -- store lua backend here
local lua_rfnd_driver_found = false -- true if user has configured lua backend
local UPDATE_MILLIS = 100 -- update rate (in ms) of the driver
-- -------------------------------- RFND DRIVER --------------------------------
function init()
local sensor_count = rangefinder:num_sensors() -- number of sensors connected
for j = 0, sensor_count - 1 do
local device = rangefinder:get_backend(j)
if ((not lua_rfnd_driver_found) and device and (device:type() == PARAM_LUA_RFND)) then
-- this is a lua driver
lua_rfnd_driver_found = true
lua_rfnd_backend = device
end
end
if not lua_rfnd_driver_found then
-- We can't use this script if user hasn't setup a lua backend
gcs:send_text(0, string.format("RFND: Configure RNGFNDx_TYPE = " .. PARAM_LUA_RFND))
else
gcs:send_text(MAV_SEVERITY.INFO, "RFND: started")
end
end
function send_distance()
dist = baro:get_altitude() + OFFSET
local sent_successfully = lua_rfnd_backend:handle_script_msg(dist)
if not sent_successfully then
-- This should never happen as we already checked for a valid configured lua backend above
gcs:send_text(MAV_SEVERITY.EMERGENCY, string.format("RFND: Lua Script Error"))
end
return send_distance, UPDATE_MILLIS
end
-- -------------------------------- MAIN --------------------------------
function update()
if not lua_rfnd_driver_found then
init()
return update, INIT_MILLIS
end
return send_distance, UPDATE_MILLIS
end
-- start running update loop
return update()