From dc6d15bdaaa8dac649bf07118a64964a7d2ebb70 Mon Sep 17 00:00:00 2001 From: Michelle Rossouw Date: Mon, 22 Jul 2024 16:47:32 +1000 Subject: [PATCH] Tools: Add Quicktune --- Tools/ardupilotwaf/ap_library.py | 1 + Tools/autotest/models/freestyle.param | 36 +++++++++------------------ 2 files changed, 13 insertions(+), 24 deletions(-) diff --git a/Tools/ardupilotwaf/ap_library.py b/Tools/ardupilotwaf/ap_library.py index 9d0971c1e816f..557510a9b2f6d 100644 --- a/Tools/ardupilotwaf/ap_library.py +++ b/Tools/ardupilotwaf/ap_library.py @@ -174,6 +174,7 @@ class ap_library_check_headers(Task.Task): 'libraries/AP_Scripting/lua_generated_bindings.h', 'libraries/AP_NavEKF3/AP_NavEKF3_feature.h', 'libraries/AP_LandingGear/AP_LandingGear_config.h', + 'libraries/AP_Quicktune/AP_Quicktune.h', ) whitelist = tuple(os.path.join(*p.split('/')) for p in whitelist) diff --git a/Tools/autotest/models/freestyle.param b/Tools/autotest/models/freestyle.param index 6ab0ddad76446..2793a4b266b2c 100644 --- a/Tools/autotest/models/freestyle.param +++ b/Tools/autotest/models/freestyle.param @@ -10,34 +10,11 @@ ARMING_RUDDER 0.000000 ATC_ACCEL_P_MAX 160000.000000 ATC_ACCEL_R_MAX 160000.000000 ATC_ACCEL_Y_MAX 120000.000000 -ATC_ANG_PIT_P 15.000000 -ATC_ANG_RLL_P 15.000000 -ATC_ANG_YAW_P 10.000000 ATC_INPUT_TC 0.040000 -ATC_RAT_PIT_P 0.040000 -ATC_RAT_PIT_I 0.040000 -ATC_RAT_PIT_D 0.001200 -ATC_RAT_PIT_FLTD 60.000000 -ATC_RAT_PIT_FLTE 40.000000 -ATC_RAT_PIT_FLTT 60.000000 -ATC_RAT_PIT_SMAX 50.000000 -ATC_RAT_RLL_P 0.048000 -ATC_RAT_RLL_I 0.048000 -ATC_RAT_RLL_D 0.000800 -ATC_RAT_RLL_FLTD 60.000000 -ATC_RAT_RLL_FLTT 60.000000 -ATC_RAT_RLL_SMAX 50.000000 -ATC_RAT_YAW_P 0.500000 -ATC_RAT_YAW_I 0.050000 -ATC_RAT_YAW_D 0.010000 -ATC_RAT_YAW_FLTD 60.000000 -ATC_RAT_YAW_FLTE 2.000000 -ATC_RAT_YAW_FLTT 60.000000 -ATC_RAT_YAW_SMAX 50.000000 ATC_SLEW_YAW 24000.000000 ATC_THR_MIX_MAN 4.000000 AUTO_OPTIONS 3.000000 -BATT_CAPACITY 1300.000000 +BATT_CAPACITY 0.000000 BATT_OPTIONS 64.000000 CIRCLE_RATE 200.000000 DISARM_DELAY 0.000000 @@ -89,3 +66,14 @@ WPNAV_JERK 6.000000 WPNAV_SPEED 3000.000000 WPNAV_SPEED_DN 500.000000 WPNAV_SPEED_UP 500.000000 + +RC6_OPTION 0 +QUIK_ENABLE 1 +QUIK_MAX_REDUCE 90 +QUIK_YAW_D_MAX 0.002 +QUIK_YAW_P_MAX 0.5 + +ATC_RAT_PIT_SMAX 50 +ATC_RAT_RLL_SMAX 50 +ATC_RAT_YAW_SMAX 50 +