diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 765f438dfb..dd985775f5 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1102,12 +1102,12 @@ local AP_Camera__camera_state_t_ud = {} function AP_Camera__camera_state_t() end -- get field ----@return boolean -function AP_Camera__camera_state_t_ud:auto_focus() end +---@return number +function AP_Camera__camera_state_t_ud:focus_value() end -- get field ---@return integer -function AP_Camera__camera_state_t_ud:focus_step() end +function AP_Camera__camera_state_t_ud:focus_type() end -- get field ---@return number diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 8dc9b05ce7..1f14130c42 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -615,8 +615,8 @@ 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 +userdata AP_Camera::camera_state_t field focus_type uint8_t'skip_check read +userdata AP_Camera::camera_state_t field focus_value float'skip_check read singleton AP_Camera method get_state boolean uint8_t'skip_check AP_Camera::camera_state_t'Null include AP_Winch/AP_Winch.h