autotest: added -R to sim_vehicle.sh for reverse throttle

This commit is contained in:
Andrew Tridgell 2014-06-04 09:40:07 +10:00
parent a7868dd6b3
commit 0ca5a60f25
2 changed files with 12 additions and 1 deletions

View File

@ -80,6 +80,8 @@ def process_sitl_input(buf):
aileron = (pwm[0]-1500)/500.0
elevator = (pwm[1]-1500)/500.0
throttle = (pwm[2]-1000)/1000.0
if opts.revthr:
throttle = 1.0 - throttle
rudder = (pwm[3]-1500)/500.0
if opts.elevon:
@ -170,6 +172,7 @@ parser.add_option("--home", type='string', help="home lat,lng,alt,hdg (requir
parser.add_option("--script", type='string', help='jsbsim model script', default='jsbsim/rascal_test.xml')
parser.add_option("--options", type='string', help='jsbsim startup options')
parser.add_option("--elevon", action='store_true', default=False, help='assume elevon input')
parser.add_option("--revthr", action='store_true', default=False, help='reverse throttle')
parser.add_option("--vtail", action='store_true', default=False, help='assume vtail input')
parser.add_option("--wind", dest="wind", help="Simulate wind (speed,direction,turbulance)", default='0,0,0')

View File

@ -16,6 +16,7 @@ USE_GDB_STOPPED=0
CLEAN_BUILD=0
START_ANTENNA_TRACKER=0
WIPE_EEPROM=0
REVERSE_THROTTLE=0
usage()
{
@ -33,6 +34,7 @@ Options:
-L select start location from Tools/autotest/locations.txt
-c do a make clean before building
-w wipe EEPROM and reload parameters
-R reverse throttle in plane
-f FRAME set aircraft frame type
for copters can choose +, X, quad or octa
for planes can choose elevon or vtail
@ -53,7 +55,7 @@ EOF
# parse options. Thanks to http://wiki.bash-hackers.org/howto/getopts_tutorial
while getopts ":I:VgGcj:TL:v:hwf:" opt; do
while getopts ":I:VgGcj:TL:v:hwf:R" opt; do
case $opt in
v)
VEHICLE=$OPTARG
@ -67,6 +69,9 @@ while getopts ":I:VgGcj:TL:v:hwf:" opt; do
T)
START_ANTENNA_TRACKER=1
;;
R)
REVERSE_THROTTLE=1
;;
G)
USE_GDB=1
;;
@ -232,6 +237,9 @@ fi
case $VEHICLE in
ArduPlane)
[ "$REVERSE_THROTTLE" == 1 ] && {
EXTRA_SIM="$EXTRA_SIM --revthr"
}
RUNSIM="nice $autotest/jsbsim/runsim.py --home=$SIMHOME --simin=$SIMIN_PORT --simout=$SIMOUT_PORT --fgout=$FG_PORT $EXTRA_SIM"
PARMS="ArduPlane.parm"
if [ $WIPE_EEPROM == 1 ]; then