mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: camera state bindings use Vector2f
This commit is contained in:
parent
267cbf9a37
commit
2be750eaf8
|
@ -1114,20 +1114,12 @@ local 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
|
||||
---@return Vector2f_ud
|
||||
function AP_Camera__camera_state_t_ud:tracking_p1() 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
|
||||
---@return Vector2f_ud
|
||||
function AP_Camera__camera_state_t_ud:tracking_p2() end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
|
|
|
@ -618,10 +618,8 @@ 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
|
||||
userdata AP_Camera::camera_state_t field tracking_p1 Vector2f read
|
||||
userdata AP_Camera::camera_state_t field tracking_p2 Vector2f read
|
||||
singleton AP_Camera method get_state boolean uint8_t'skip_check AP_Camera::camera_state_t'Null
|
||||
|
||||
include AP_Winch/AP_Winch.h
|
||||
|
|
Loading…
Reference in New Issue