ardupilot/libraries/AP_Scripting/examples/rangefinder_test.lua

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

32 lines
1.2 KiB
Lua
Raw Permalink Normal View History

2020-07-29 10:54:25 -03:00
-- This script checks RangeFinder
local rotation_downward = 25
local rotation_forward = 0
function update()
local sensor_count = rangefinder:num_sensors()
gcs:send_text(0, string.format("%d rangefinder sensors found.", sensor_count))
for _ = 0, rangefinder:num_sensors() do
2020-07-29 10:54:25 -03:00
if rangefinder:has_data_orient(rotation_downward) then
info(rotation_downward)
elseif rangefinder:has_data_orient(rotation_forward) then
info(rotation_forward)
end
end
return update, 1000 -- check again in 1Hz
end
function info(rotation)
local ground_clearance = rangefinder:ground_clearance_cm_orient(rotation)
local distance_min = rangefinder:min_distance_cm_orient(rotation)
local distance_max = rangefinder:max_distance_cm_orient(rotation)
local offset = rangefinder:get_pos_offset_orient(rotation)
local distance_cm = rangefinder:distance_cm_orient(rotation)
gcs:send_text(0, string.format("Rotation %d %.0f cm range %d - %d offset %.0f %.0f %.0f ground clearance %.0f", rotation, distance_cm, distance_min, distance_max, offset:x(), offset:y(), offset:z(), ground_clearance))
2020-07-29 10:54:25 -03:00
end
return update(), 1000 -- first message may be displayed 1 seconds after start-up