AP_Scripting: added set_rudder_offset binding

This commit is contained in:
Andrew Tridgell 2022-12-23 08:21:43 +11:00
parent 63e5261406
commit 84944bbf53
2 changed files with 6 additions and 0 deletions

View File

@ -1621,6 +1621,11 @@ function serialLED:set_num_neopixel(chan, num_leds) end
---@class vehicle
vehicle = {}
-- desc
---@param rudder_pct number
---@param run_yaw_rate_control boolean
function vehicle:set_rudder_offset(rudder_pct, run_yaw_rate_control) end
-- desc
---@return boolean
function vehicle:has_ekf_failsafed() end

View File

@ -254,6 +254,7 @@ singleton AP_Vehicle method get_pan_tilt_norm boolean float'Null float'Null
singleton AP_Vehicle method nav_script_time boolean uint16_t'Null uint8_t'Null float'Null float'Null int16_t'Null int16_t'Null
singleton AP_Vehicle method nav_script_time_done void uint16_t'skip_check
singleton AP_Vehicle method set_target_throttle_rate_rpy void float -100 100 float'skip_check float'skip_check float'skip_check
singleton AP_Vehicle method set_rudder_offset void float'skip_check boolean
singleton AP_Vehicle method set_desired_turn_rate_and_speed boolean float'skip_check float'skip_check
singleton AP_Vehicle method set_desired_speed boolean float'skip_check
singleton AP_Vehicle method nav_scripting_enable boolean uint8_t'skip_check