mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: camera set_zoom binding replaces set_zoom_step
This commit is contained in:
parent
ddaff85166
commit
4090c50e8f
|
@ -1111,7 +1111,11 @@ function camera_state_t_ud:focus_step() end
|
|||
|
||||
-- get field
|
||||
---@return integer
|
||||
function camera_state_t_ud:zoom_step() end
|
||||
function camera_state_t_ud:zoom_type() end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function camera_state_t_ud:zoom_value() end
|
||||
|
||||
-- get field
|
||||
---@return boolean
|
||||
|
|
|
@ -613,7 +613,8 @@ singleton AP_Camera method set_trigger_distance void uint8_t'skip_check float'sk
|
|||
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 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
|
||||
|
|
Loading…
Reference in New Issue