diff --git a/Tools/autotest/ArduPlane.parm b/Tools/autotest/ArduPlane.parm index fc01cfb687..21640f54ec 100644 --- a/Tools/autotest/ArduPlane.parm +++ b/Tools/autotest/ArduPlane.parm @@ -2,6 +2,7 @@ LOG_BITMASK 4095 SWITCH_ENABLE 0 MAG_ENABLE 0 TRIM_ARSPD_CM 2200 +TRIM_PITCH_CD -1000 ARSPD_ENABLE 1 ARSP2PTCH_I 0.1 ARSPD_FBW_MAX 30 diff --git a/Tools/autotest/aircraft/Rascal/Rascal.xml b/Tools/autotest/aircraft/Rascal/Rascal.xml index 7ec9446d08..ff96428e75 100644 --- a/Tools/autotest/aircraft/Rascal/Rascal.xml +++ b/Tools/autotest/aircraft/Rascal/Rascal.xml @@ -55,14 +55,14 @@ 33.1 - -9.9 + -12.9 -13.1 - 1.0 - 0.8 - 0.02 + 4.0 + 1.8 + 0.001 12 - 1 + 3 0.0 NONE 0 @@ -70,14 +70,14 @@ 33.1 - 9.9 + 12.9 -13.1 - 1.0 - 0.8 - 0.02 + 4.0 + 1.8 + 0.001 12 - 1 + 3 0.0 NONE 0 @@ -91,13 +91,13 @@ zero pitch, which makes for a better simulation of ground start on the accelerometers/gyros in ArduPlane --> - -7.8 + -3 - 1.0 - 0.8 - 0.02 + 4.0 + 1.8 + 0.05 12 - 1 + 3 360.0 NONE 0 diff --git a/Tools/autotest/aircraft/Rascal/Rascal110-JSBSim.xml b/Tools/autotest/aircraft/Rascal/Rascal110-JSBSim.xml index 732420cf12..a8deb22bb2 100644 --- a/Tools/autotest/aircraft/Rascal/Rascal110-JSBSim.xml +++ b/Tools/autotest/aircraft/Rascal/Rascal110-JSBSim.xml @@ -86,7 +86,7 @@ 68.9 0 - -6.6 + -3 0.8 0.5 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index cbf0157f8e..1bf536f38a 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -9,7 +9,7 @@ testdir=os.path.dirname(os.path.realpath(__file__)) HOME_LOCATION='-35.362938,149.165085,584,270' -WIND="5,180,0.2" # speed,direction,variance +WIND="0,180,0.2" # speed,direction,variance homeloc = None @@ -19,19 +19,26 @@ def takeoff(mavproxy, mav): wait_mode(mav, 'FBWA') # some rudder to counteract the prop torque - mavproxy.send('rc 4 1650\n') + mavproxy.send('rc 4 1700\n') + + # some up elevator to keep the tail down + mavproxy.send('rc 2 1200\n') # get it moving a bit first - mavproxy.send('rc 3 1100\n') + mavproxy.send('rc 3 1050\n') mav.recv_match(condition='VFR_HUD.groundspeed>2', blocking=True) # a bit faster + mavproxy.send('rc 3 1300\n') + mav.recv_match(condition='VFR_HUD.groundspeed>6', blocking=True) + + # a bit faster again, straighten rudder mavproxy.send('rc 3 1600\n') + mavproxy.send('rc 4 1500\n') mav.recv_match(condition='VFR_HUD.groundspeed>12', blocking=True) - # hit the gas harder now, and give it some elevator - mavproxy.send('rc 4 1500\n') - mavproxy.send('rc 2 1200\n') + # hit the gas harder now, and give it some more elevator + mavproxy.send('rc 2 1100\n') mavproxy.send('rc 3 1800\n') # gain a bit of altitude