AP_Scripting: add mount driver bindings

This commit is contained in:
Randy Mackay 2022-12-28 12:05:18 +09:00
parent 0f24b079e4
commit 0cbdd28f82
2 changed files with 32 additions and 0 deletions

View File

@ -967,6 +967,34 @@ function winch:healthy() end
---@class mount
mount = {}
-- desc
---@param instance integer
---@param roll_deg number
---@param pitch_deg number
---@param yaw_deg number
function mount:set_attitude_euler(instance, roll_deg, pitch_deg, yaw_deg) end
-- desc
---@param instance integer
---@return Location_ud|nil
function mount:get_location_target(instance) end
-- desc
---@param instance integer
---@return number|nil -- roll_deg
---@return number|nil -- pitch_deg
---@return number|nil -- yaw_deg
---@return boolean|nil -- yaw_is_earth_frame
function mount:get_angle_target(instance) end
-- desc
---@param instance integer
---@return number|nil -- roll_degs
---@return number|nil -- pitch_degs
---@return number|nil -- yaw_degs
---@return boolean|nil -- yaw_is_earth_frame
function mount:get_rate_target(instance) end
-- desc
---@param instance integer
---@param target_loc Location_ud

View File

@ -558,6 +558,10 @@ singleton AP_Mount method set_angle_target void uint8_t'skip_check float'skip_ch
singleton AP_Mount method set_rate_target void uint8_t'skip_check float'skip_check float'skip_check float'skip_check boolean
singleton AP_Mount method set_roi_target void uint8_t'skip_check Location
singleton AP_Mount method get_attitude_euler boolean uint8_t'skip_check float'Null float'Null float'Null
singleton AP_Mount method get_rate_target boolean uint8_t'skip_check float'Null float'Null float'Null boolean'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
include AP_Winch/AP_Winch.h depends APM_BUILD_COPTER_OR_HELI
singleton AP_Winch depends APM_BUILD_COPTER_OR_HELI