mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Scripting: remove mount get_camera_state
AP_Camera scripting backend provides access
This commit is contained in:
parent
554d52b6fe
commit
1a375f1ff5
@ -1030,15 +1030,6 @@ function camera:get_state(instance) end
|
||||
---@class mount
|
||||
mount = {}
|
||||
|
||||
-- desc
|
||||
---@param param1 integer
|
||||
---@return integer|nil -- pic_count
|
||||
---@return boolean|nil -- record_video
|
||||
---@return integer|nil -- zoom_step
|
||||
---@return integer|nil -- focus_step
|
||||
---@return boolean|nil -- auto_focus
|
||||
function mount:get_camera_state(param1) end
|
||||
|
||||
-- desc
|
||||
---@param instance integer
|
||||
---@param roll_deg number
|
||||
|
@ -602,7 +602,6 @@ singleton AP_Mount method get_rate_target boolean uint8_t'skip_check float'Null
|
||||
singleton AP_Mount method get_angle_target boolean uint8_t'skip_check float'Null float'Null float'Null boolean'Null
|
||||
singleton AP_Mount method get_location_target boolean uint8_t'skip_check Location'Null
|
||||
singleton AP_Mount method set_attitude_euler void uint8_t'skip_check float'skip_check float'skip_check float'skip_check
|
||||
singleton AP_Mount method get_camera_state boolean uint8_t'skip_check uint16_t'Null boolean'Null int8_t'Null int8_t'Null boolean'Null
|
||||
|
||||
include AP_Camera/AP_Camera.h
|
||||
singleton AP_Camera depends AP_CAMERA_ENABLED == 1
|
||||
|
Loading…
Reference in New Issue
Block a user