mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Scripting: added get_rpy_srate binding
and norm_input_dz binding
This commit is contained in:
parent
9f49570f7f
commit
58cdcf6968
@ -683,10 +683,14 @@ function RC_Channel_ud:norm_input_ignore_trim() end
|
||||
---@return integer
|
||||
function RC_Channel_ud:get_aux_switch_pos() end
|
||||
|
||||
-- desc
|
||||
-- desc return input on a channel from -1 to 1, centered on the trim. Ignores the deadzone
|
||||
---@return number
|
||||
function RC_Channel_ud:norm_input() end
|
||||
|
||||
-- desc return input on a channel from -1 to 1, centered on the trim. Returns zero when within deadzone of the trim
|
||||
---@return number
|
||||
function RC_Channel_ud:norm_input_dz() end
|
||||
|
||||
|
||||
-- desc
|
||||
---@class motors
|
||||
@ -1948,6 +1952,16 @@ function ahrs:get_pitch() end
|
||||
---@return number
|
||||
function ahrs:get_roll() end
|
||||
|
||||
-- desc
|
||||
---@class AC_AttitudeControl
|
||||
AC_AttitudeControl = {}
|
||||
|
||||
-- return slew rates for VTOL controller
|
||||
---@return number -- roll slew rate
|
||||
---@return number -- pitch slew rate
|
||||
---@return number -- yaw slew rate
|
||||
function AC_AttitudeControl:get_rpy_srate() end
|
||||
|
||||
-- desc
|
||||
---@class follow
|
||||
follow = {}
|
||||
|
@ -256,6 +256,7 @@ singleton SRV_Channels method set_angle void SRV_Channel::Aux_servo_function_t'e
|
||||
singleton SRV_Channels method set_range void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t 0 UINT16_MAX
|
||||
|
||||
ap_object RC_Channel method norm_input float
|
||||
ap_object RC_Channel method norm_input_dz float
|
||||
ap_object RC_Channel method get_aux_switch_pos uint8_t
|
||||
ap_object RC_Channel method norm_input_ignore_trim float
|
||||
|
||||
@ -502,3 +503,6 @@ singleton AP_Follow method get_target_location_and_velocity boolean Location'Nul
|
||||
singleton AP_Follow method get_target_location_and_velocity_ofs boolean Location'Null Vector3f'Null
|
||||
singleton AP_Follow method get_target_heading_deg boolean float'Null
|
||||
|
||||
include AC_AttitudeControl/AC_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||
singleton AC_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||
singleton AC_AttitudeControl method get_rpy_srate void float'Ref float'Ref float'Ref
|
||||
|
Loading…
Reference in New Issue
Block a user