AP_Scripting: camera state gets tracking

This commit is contained in:
Randy Mackay 2023-04-29 09:39:44 +09:00
parent a6cc9f042a
commit 98636287fc
2 changed files with 25 additions and 0 deletions

View File

@ -1113,6 +1113,26 @@ local AP_Camera__camera_state_t_ud = {}
---@return AP_Camera__camera_state_t_ud
function AP_Camera__camera_state_t() end
-- get field
---@return number
function AP_Camera__camera_state_t_ud:tracking_p1x() end
-- get field
---@return number
function AP_Camera__camera_state_t_ud:tracking_p1y() end
-- get field
---@return number
function AP_Camera__camera_state_t_ud:tracking_p2x() end
-- get field
---@return number
function AP_Camera__camera_state_t_ud:tracking_p2y() end
-- get field
---@return integer
function AP_Camera__camera_state_t_ud:tracking_type() end
-- get field
---@return number
function AP_Camera__camera_state_t_ud:focus_value() end

View File

@ -617,6 +617,11 @@ 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_type uint8_t'skip_check read
userdata AP_Camera::camera_state_t field focus_value float'skip_check read
userdata AP_Camera::camera_state_t field tracking_type uint8_t'skip_check read
userdata AP_Camera::camera_state_t field tracking_p1x float'skip_check read
userdata AP_Camera::camera_state_t field tracking_p1y float'skip_check read
userdata AP_Camera::camera_state_t field tracking_p2x float'skip_check read
userdata AP_Camera::camera_state_t field tracking_p2y 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