mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 10:13:57 -04:00
AP_Scripting: added avoidance bindings
This commit is contained in:
parent
b4102322b7
commit
94fbb7aec2
libraries/AP_Scripting
@ -4013,3 +4013,24 @@ function visual_odom:healthy() end
|
||||
-- visual odometry quality as a percentage from 1 to 100 or 0 if unknown
|
||||
---@return integer
|
||||
function visual_odom:quality() end
|
||||
|
||||
-- Returns the number of detected obstacles via ADS-B
|
||||
-- the ADS-B Must be enabled.
|
||||
---@return integer -- number of obstacles
|
||||
function avoid:num_obstacles() end-- Returns a Location userdata for the last position of the obstacle observed.
|
||||
|
||||
---@param instance integer -- instance number
|
||||
---@return Location_ud --ADSB location
|
||||
function avoid:get_obstacle_loc(instance) end-- Returns a Vector3f that contains the velocity as obtained from ADS-B.
|
||||
|
||||
---@param instance integer -- instance number
|
||||
---@return Vector3f_ud -- 3D velocity in m/s, in NED format
|
||||
function avoid:get_obstacle_vel(instance) end-- Obstacle id as obtained from ADS-B.
|
||||
|
||||
---@param instance integer -- instance number
|
||||
---@return int32_t_ud
|
||||
function avoid:get_obstacle_id(instance) end-- ADS-B message time.
|
||||
|
||||
---@param instance integer -- instance number
|
||||
---@return int32_t_ud
|
||||
function avoid:get_obstacle_time(instance) end
|
||||
|
@ -1039,3 +1039,14 @@ include AP_TemperatureSensor/AP_TemperatureSensor.h
|
||||
singleton AP_TemperatureSensor depends AP_TEMPERATURE_SENSOR_ENABLED
|
||||
singleton AP_TemperatureSensor rename temperature_sensor
|
||||
singleton AP_TemperatureSensor method get_temperature boolean float'Null uint8_t'skip_check
|
||||
|
||||
|
||||
include AP_Avoidance/AP_Avoidance.h
|
||||
singleton AP_Avoidance rename avoid
|
||||
singleton AP_Avoidance method num_obstacles uint8_t
|
||||
singleton AP_Avoidance method get_obstacle_loc Location uint8_t'skip_check
|
||||
singleton AP_Avoidance method get_obstacle_vel Vector3f uint8_t'skip_check
|
||||
singleton AP_Avoidance method get_obstacle_id int32_t uint8_t'skip_check
|
||||
singleton AP_Avoidance method get_obstacle_time int32_t uint8_t'skip_check
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user