AP_Scripting: add AP_Camera::get_state bindings

This commit is contained in:
Randy Mackay 2023-04-08 11:41:57 +09:00 committed by Peter Barker
parent f357bc53fe
commit 554d52b6fe
2 changed files with 39 additions and 0 deletions

View File

@ -994,6 +994,38 @@ function camera:record_video(instance, start_recording) end
---@param instance integer ---@param instance integer
function camera:take_picture(instance) end function camera:take_picture(instance) end
-- desc
---@class camera_state_t_ud
local camera_state_t_ud = {}
---@return camera_state_t_ud
function camera_state_t() end
-- get field
---@return boolean
function camera_state_t_ud:auto_focus() end
-- get field
---@return integer
function camera_state_t_ud:focus_step() end
-- get field
---@return integer
function camera_state_t_ud:zoom_step() end
-- get field
---@return boolean
function camera_state_t_ud:recording_video() end
-- get field
---@return integer
function camera_state_t_ud:take_pic_incr() end
-- desc
---@param instance integer
---@return camera_state_t_ud|nil
function camera:get_state(instance) end
-- desc -- desc
---@class mount ---@class mount
mount = {} mount = {}

View File

@ -610,6 +610,13 @@ singleton AP_Camera rename camera
singleton AP_Camera method take_picture void uint8_t'skip_check 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 record_video boolean uint8_t'skip_check boolean
singleton AP_Camera method set_trigger_distance void uint8_t'skip_check float'skip_check singleton AP_Camera method set_trigger_distance void uint8_t'skip_check float'skip_check
userdata camera_state_t depends (AP_CAMERA_SCRIPTING_ENABLED == 1)
userdata camera_state_t field take_pic_incr uint16_t'skip_check read
userdata camera_state_t field recording_video boolean read
userdata camera_state_t field zoom_step int8_t'skip_check read
userdata camera_state_t field focus_step int8_t'skip_check read
userdata camera_state_t field auto_focus boolean read
singleton AP_Camera method get_state boolean uint8_t'skip_check camera_state_t'Null
include AP_Winch/AP_Winch.h include AP_Winch/AP_Winch.h
singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI