autotest: make the Rascal a tail dragger again
good for testing wheeled takeoff
This commit is contained in:
parent
938bd8b58d
commit
63e77806cf
@ -2,6 +2,7 @@ LOG_BITMASK 4095
|
|||||||
SWITCH_ENABLE 0
|
SWITCH_ENABLE 0
|
||||||
MAG_ENABLE 0
|
MAG_ENABLE 0
|
||||||
TRIM_ARSPD_CM 2200
|
TRIM_ARSPD_CM 2200
|
||||||
|
TRIM_PITCH_CD -1000
|
||||||
ARSPD_ENABLE 1
|
ARSPD_ENABLE 1
|
||||||
ARSP2PTCH_I 0.1
|
ARSP2PTCH_I 0.1
|
||||||
ARSPD_FBW_MAX 30
|
ARSPD_FBW_MAX 30
|
||||||
|
@ -55,14 +55,14 @@
|
|||||||
<contact type="BOGEY" name="LEFT_MLG">
|
<contact type="BOGEY" name="LEFT_MLG">
|
||||||
<location unit="IN">
|
<location unit="IN">
|
||||||
<x> 33.1 </x>
|
<x> 33.1 </x>
|
||||||
<y> -9.9 </y>
|
<y> -12.9 </y>
|
||||||
<z> -13.1 </z>
|
<z> -13.1 </z>
|
||||||
</location>
|
</location>
|
||||||
<static_friction> 1.0 </static_friction>
|
<static_friction> 4.0 </static_friction>
|
||||||
<dynamic_friction> 0.8 </dynamic_friction>
|
<dynamic_friction> 1.8 </dynamic_friction>
|
||||||
<rolling_friction> 0.02 </rolling_friction>
|
<rolling_friction> 0.001 </rolling_friction>
|
||||||
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
|
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
|
||||||
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
|
<damping_coeff unit="LBS/FT/SEC"> 3 </damping_coeff>
|
||||||
<max_steer unit="DEG"> 0.0 </max_steer>
|
<max_steer unit="DEG"> 0.0 </max_steer>
|
||||||
<brake_group> NONE </brake_group>
|
<brake_group> NONE </brake_group>
|
||||||
<retractable>0</retractable>
|
<retractable>0</retractable>
|
||||||
@ -70,14 +70,14 @@
|
|||||||
<contact type="BOGEY" name="RIGHT_MLG">
|
<contact type="BOGEY" name="RIGHT_MLG">
|
||||||
<location unit="IN">
|
<location unit="IN">
|
||||||
<x> 33.1 </x>
|
<x> 33.1 </x>
|
||||||
<y> 9.9 </y>
|
<y> 12.9 </y>
|
||||||
<z> -13.1 </z>
|
<z> -13.1 </z>
|
||||||
</location>
|
</location>
|
||||||
<static_friction> 1.0 </static_friction>
|
<static_friction> 4.0 </static_friction>
|
||||||
<dynamic_friction> 0.8 </dynamic_friction>
|
<dynamic_friction> 1.8 </dynamic_friction>
|
||||||
<rolling_friction> 0.02 </rolling_friction>
|
<rolling_friction> 0.001 </rolling_friction>
|
||||||
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
|
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
|
||||||
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
|
<damping_coeff unit="LBS/FT/SEC"> 3 </damping_coeff>
|
||||||
<max_steer unit="DEG"> 0.0 </max_steer>
|
<max_steer unit="DEG"> 0.0 </max_steer>
|
||||||
<brake_group> NONE </brake_group>
|
<brake_group> NONE </brake_group>
|
||||||
<retractable>0</retractable>
|
<retractable>0</retractable>
|
||||||
@ -91,13 +91,13 @@
|
|||||||
zero pitch, which makes for a better simulation
|
zero pitch, which makes for a better simulation
|
||||||
of ground start on the accelerometers/gyros in
|
of ground start on the accelerometers/gyros in
|
||||||
ArduPlane -->
|
ArduPlane -->
|
||||||
<z> -7.8 </z>
|
<z> -3 </z>
|
||||||
</location>
|
</location>
|
||||||
<static_friction> 1.0 </static_friction>
|
<static_friction> 4.0 </static_friction>
|
||||||
<dynamic_friction> 0.8 </dynamic_friction>
|
<dynamic_friction> 1.8 </dynamic_friction>
|
||||||
<rolling_friction> 0.02 </rolling_friction>
|
<rolling_friction> 0.05 </rolling_friction>
|
||||||
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
|
<spring_coeff unit="LBS/FT"> 12 </spring_coeff>
|
||||||
<damping_coeff unit="LBS/FT/SEC"> 1 </damping_coeff>
|
<damping_coeff unit="LBS/FT/SEC"> 3 </damping_coeff>
|
||||||
<max_steer unit="DEG"> 360.0 </max_steer>
|
<max_steer unit="DEG"> 360.0 </max_steer>
|
||||||
<brake_group> NONE </brake_group>
|
<brake_group> NONE </brake_group>
|
||||||
<retractable>0</retractable>
|
<retractable>0</retractable>
|
||||||
|
@ -86,7 +86,7 @@
|
|||||||
<location unit="IN">
|
<location unit="IN">
|
||||||
<x> 68.9 </x>
|
<x> 68.9 </x>
|
||||||
<y> 0 </y>
|
<y> 0 </y>
|
||||||
<z> -6.6 </z>
|
<z> -3 </z>
|
||||||
</location>
|
</location>
|
||||||
<static_friction> 0.8 </static_friction>
|
<static_friction> 0.8 </static_friction>
|
||||||
<dynamic_friction> 0.5 </dynamic_friction>
|
<dynamic_friction> 0.5 </dynamic_friction>
|
||||||
|
@ -9,7 +9,7 @@ testdir=os.path.dirname(os.path.realpath(__file__))
|
|||||||
|
|
||||||
|
|
||||||
HOME_LOCATION='-35.362938,149.165085,584,270'
|
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
|
homeloc = None
|
||||||
|
|
||||||
@ -19,19 +19,26 @@ def takeoff(mavproxy, mav):
|
|||||||
wait_mode(mav, 'FBWA')
|
wait_mode(mav, 'FBWA')
|
||||||
|
|
||||||
# some rudder to counteract the prop torque
|
# 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
|
# 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)
|
mav.recv_match(condition='VFR_HUD.groundspeed>2', blocking=True)
|
||||||
|
|
||||||
# a bit faster
|
# 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 3 1600\n')
|
||||||
|
mavproxy.send('rc 4 1500\n')
|
||||||
mav.recv_match(condition='VFR_HUD.groundspeed>12', blocking=True)
|
mav.recv_match(condition='VFR_HUD.groundspeed>12', blocking=True)
|
||||||
|
|
||||||
# hit the gas harder now, and give it some elevator
|
# hit the gas harder now, and give it some more elevator
|
||||||
mavproxy.send('rc 4 1500\n')
|
mavproxy.send('rc 2 1100\n')
|
||||||
mavproxy.send('rc 2 1200\n')
|
|
||||||
mavproxy.send('rc 3 1800\n')
|
mavproxy.send('rc 3 1800\n')
|
||||||
|
|
||||||
# gain a bit of altitude
|
# gain a bit of altitude
|
||||||
|
Loading…
Reference in New Issue
Block a user