mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Scripting: add proximity bindings
This commit is contained in:
parent
e2eed88ca3
commit
67ad05609f
27
libraries/AP_Scripting/examples/proximity_test.lua
Normal file
27
libraries/AP_Scripting/examples/proximity_test.lua
Normal file
@ -0,0 +1,27 @@
|
|||||||
|
-- This script checks Proximity
|
||||||
|
|
||||||
|
function update()
|
||||||
|
sensor_count = proximity:num_sensors()
|
||||||
|
gcs:send_text(0, string.format("%d proximity sensors found.", sensor_count))
|
||||||
|
|
||||||
|
if sensor_count > 0 then
|
||||||
|
object_count = proximity:get_object_count()
|
||||||
|
gcs:send_text(0, string.format("%d objects found.", object_count))
|
||||||
|
|
||||||
|
closest_angle, closest_distance = proximity:get_closest_object()
|
||||||
|
if closest_angle and closest_distance then
|
||||||
|
gcs:send_text(0, "Closest object at angle "..closest_angle.." distance "..closest_distance)
|
||||||
|
end
|
||||||
|
|
||||||
|
for i = 0, object_count do
|
||||||
|
angle, distance = proximity:get_object_angle_and_distance(i)
|
||||||
|
if angle and distance then
|
||||||
|
gcs:send_text(0, "Object "..i.." at angle "..angle.." distance "..distance)
|
||||||
|
end
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
return update, 2000 -- check again in 0.5Hz
|
||||||
|
end
|
||||||
|
|
||||||
|
return update(), 2000 -- first message may be displayed 2 seconds after start-up
|
@ -124,6 +124,14 @@ singleton AP_Notify alias notify
|
|||||||
singleton AP_Notify method play_tune void string
|
singleton AP_Notify method play_tune void string
|
||||||
singleton AP_Notify method handle_rgb void uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX
|
singleton AP_Notify method handle_rgb void uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX
|
||||||
|
|
||||||
|
include AP_Proximity/AP_Proximity.h
|
||||||
|
|
||||||
|
singleton AP_Proximity alias proximity
|
||||||
|
singleton AP_Proximity method num_sensors uint8_t
|
||||||
|
singleton AP_Proximity method get_object_count uint8_t
|
||||||
|
singleton AP_Proximity method get_closest_object boolean float'Null float'Null
|
||||||
|
singleton AP_Proximity method get_object_angle_and_distance boolean uint8_t 0 UINT8_MAX float'Null float'Null
|
||||||
|
|
||||||
include AP_RangeFinder/AP_RangeFinder.h
|
include AP_RangeFinder/AP_RangeFinder.h
|
||||||
|
|
||||||
singleton RangeFinder alias rangefinder
|
singleton RangeFinder alias rangefinder
|
||||||
|
Loading…
Reference in New Issue
Block a user