diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 44aed3c9c0..765f438dfb 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1095,39 +1095,39 @@ function camera:record_video(instance, start_recording) end function camera:take_picture(instance) end -- desc ----@class camera_state_t_ud -local camera_state_t_ud = {} +---@class AP_Camera__camera_state_t_ud +local AP_Camera__camera_state_t_ud = {} ----@return camera_state_t_ud -function camera_state_t() end +---@return AP_Camera__camera_state_t_ud +function AP_Camera__camera_state_t() end -- get field ---@return boolean -function camera_state_t_ud:auto_focus() end +function AP_Camera__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_type() end +function AP_Camera__camera_state_t_ud:focus_step() end -- get field ---@return number -function camera_state_t_ud:zoom_value() end - --- get field ----@return boolean -function camera_state_t_ud:recording_video() end +function AP_Camera__camera_state_t_ud:zoom_value() end -- get field ---@return integer -function camera_state_t_ud:take_pic_incr() end +function AP_Camera__camera_state_t_ud:zoom_type() end + +-- get field +---@return boolean +function AP_Camera__camera_state_t_ud:recording_video() end + +-- get field +---@return integer +function AP_Camera__camera_state_t_ud:take_pic_incr() end -- desc ---@param instance integer ----@return camera_state_t_ud|nil +---@return AP_Camera__camera_state_t_ud|nil function camera:get_state(instance) end -- desc diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index b53ccc7fc9..8dc9b05ce7 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -610,14 +610,14 @@ singleton AP_Camera semaphore 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 -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_type uint8_t'skip_check read -userdata camera_state_t field zoom_value float'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 +userdata AP_Camera::camera_state_t depends (AP_CAMERA_SCRIPTING_ENABLED == 1) +userdata AP_Camera::camera_state_t field take_pic_incr uint16_t'skip_check read +userdata AP_Camera::camera_state_t field recording_video boolean read +userdata AP_Camera::camera_state_t field zoom_type uint8_t'skip_check read +userdata AP_Camera::camera_state_t field zoom_value float'skip_check read +userdata AP_Camera::camera_state_t field focus_step int8_t'skip_check read +userdata AP_Camera::camera_state_t field auto_focus boolean read +singleton AP_Camera method get_state boolean uint8_t'skip_check AP_Camera::camera_state_t'Null include AP_Winch/AP_Winch.h singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI