diff --git a/Tools/autotest/ArduPlane.parm b/Tools/autotest/ArduPlane.parm index d064f31cb2..886a163618 100644 --- a/Tools/autotest/ArduPlane.parm +++ b/Tools/autotest/ArduPlane.parm @@ -3,10 +3,10 @@ SWITCH_ENABLE 0 MAG_ENABLE 1 TRIM_ARSPD_CM 2200 TRIM_PITCH_CD 0 -TRIM_THROTTLE 70 -LIM_PITCH_MIN -3000 -LIM_PITCH_MAX 3500 -LIM_ROLL_CD 7000 +TRIM_THROTTLE 50 +LIM_PITCH_MIN -2000 +LIM_PITCH_MAX 2500 +LIM_ROLL_CD 6500 LAND_PITCH_CD 300 WHEELSTEER_D 0.1 WHEELSTEER_I 0.5 @@ -20,10 +20,13 @@ ARSPD_FBW_MIN 10 KFF_RDDRMIX 0.5 KFF_PTCHCOMP 0.3 THR_MAX 100 -HDNG2RLL_D 0.4 +HDNG2RLL_D 0.6 HDNG2RLL_I 0.01 HDNG2RLL_IMAX 100.0 HDNG2RLL_P 0.8 +ENRGY2THR_P 0.25 +ENRGY2THR_D 0.2 +ENRGY2THR_I 0.1 RC2_REV -1 RC4_REV -1 RC1_MAX 2000 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 2b4f33e0c7..b91dec6de5 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -75,7 +75,7 @@ def fly_RTL(mavproxy, mav): print("Flying home in RTL") mavproxy.send('switch 2\n') wait_mode(mav, 'RTL') - if not wait_location(mav, homeloc, accuracy=90, + if not wait_location(mav, homeloc, accuracy=120, target_altitude=homeloc.alt+100, height_accuracy=20, timeout=90): return False