AP_Scripting: add camera bindings
This commit is contained in:
parent
322ef64aad
commit
03148a113f
@ -975,6 +975,25 @@ function winch:relax() end
|
||||
---@return boolean
|
||||
function winch:healthy() end
|
||||
|
||||
-- desc
|
||||
---@class camera
|
||||
camera = {}
|
||||
|
||||
-- desc
|
||||
---@param instance integer
|
||||
---@param distance_m number
|
||||
function camera:set_trigger_distance(instance, distance_m) end
|
||||
|
||||
-- desc
|
||||
---@param instance integer
|
||||
---@param start_recording boolean
|
||||
---@return boolean
|
||||
function camera:record_video(instance, start_recording) end
|
||||
|
||||
-- desc
|
||||
---@param instance integer
|
||||
function camera:take_picture(instance) end
|
||||
|
||||
-- desc
|
||||
---@class mount
|
||||
mount = {}
|
||||
|
@ -604,6 +604,13 @@ singleton AP_Mount method get_location_target boolean uint8_t'skip_check Locatio
|
||||
singleton AP_Mount method set_attitude_euler void uint8_t'skip_check float'skip_check float'skip_check float'skip_check
|
||||
singleton AP_Mount method get_camera_state boolean uint8_t'skip_check uint16_t'Null boolean'Null int8_t'Null int8_t'Null boolean'Null
|
||||
|
||||
include AP_Camera/AP_Camera.h
|
||||
singleton AP_Camera depends AP_CAMERA_ENABLED == 1
|
||||
singleton AP_Camera rename camera
|
||||
singleton AP_Camera method take_picture void uint8_t'skip_check
|
||||
singleton AP_Camera method record_video boolean uint8_t'skip_check boolean
|
||||
singleton AP_Camera method set_trigger_distance void uint8_t'skip_check float'skip_check
|
||||
|
||||
include AP_Winch/AP_Winch.h
|
||||
singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI
|
||||
singleton AP_Winch rename winch
|
||||
|
Loading…
Reference in New Issue
Block a user