autotest: support starting with HIL for plane

This commit is contained in:
Andrew Tridgell 2014-08-13 20:46:53 +10:00
parent 52cdd6394f
commit 1f7305f516
1 changed files with 17 additions and 2 deletions

View File

@ -18,6 +18,7 @@ START_ANTENNA_TRACKER=0
WIPE_EEPROM=0 WIPE_EEPROM=0
REVERSE_THROTTLE=0 REVERSE_THROTTLE=0
NO_REBUILD=0 NO_REBUILD=0
START_HIL=0
TRACKER_ARGS="" TRACKER_ARGS=""
usage() usage()
@ -43,6 +44,7 @@ Options:
for copters can choose +, X, quad or octa for copters can choose +, X, quad or octa
for planes can choose elevon or vtail for planes can choose elevon or vtail
-j NUM_PROC number of processors to use during build (default 1) -j NUM_PROC number of processors to use during build (default 1)
-H start HIL
mavproxy_options: mavproxy_options:
--map start with a map --map start with a map
@ -59,7 +61,7 @@ EOF
# parse options. Thanks to http://wiki.bash-hackers.org/howto/getopts_tutorial # parse options. Thanks to http://wiki.bash-hackers.org/howto/getopts_tutorial
while getopts ":I:VgGcj:TA:t:L:v:hwf:RN" opt; do while getopts ":I:VgGcj:TA:t:L:v:hwf:RNH" opt; do
case $opt in case $opt in
v) v)
VEHICLE=$OPTARG VEHICLE=$OPTARG
@ -73,6 +75,10 @@ while getopts ":I:VgGcj:TA:t:L:v:hwf:RN" opt; do
N) N)
NO_REBUILD=1 NO_REBUILD=1
;; ;;
H)
START_HIL=1
NO_REBUILD=1
;;
T) T)
START_ANTENNA_TRACKER=1 START_ANTENNA_TRACKER=1
;; ;;
@ -273,6 +279,7 @@ case $VEHICLE in
;; ;;
esac esac
if [ $START_HIL == 0 ]; then
if [ $USE_VALGRIND == 1 ]; then if [ $USE_VALGRIND == 1 ]; then
echo "Using valgrind" echo "Using valgrind"
$autotest/run_in_terminal_window.sh "ardupilot (valgrind)" valgrind $cmd || exit 1 $autotest/run_in_terminal_window.sh "ardupilot (valgrind)" valgrind $cmd || exit 1
@ -286,6 +293,7 @@ elif [ $USE_GDB == 1 ]; then
else else
$autotest/run_in_terminal_window.sh "ardupilot" $cmd || exit 1 $autotest/run_in_terminal_window.sh "ardupilot" $cmd || exit 1
fi fi
fi
trap kill_tasks SIGINT trap kill_tasks SIGINT
@ -298,7 +306,11 @@ $autotest/run_in_terminal_window.sh "Simulator" $RUNSIM || {
sleep 2 sleep 2
# mavproxy.py --master tcp:127.0.0.1:5760 --sitl 127.0.0.1:5501 --out 127.0.0.1:14550 --out 127.0.0.1:14551 # mavproxy.py --master tcp:127.0.0.1:5760 --sitl 127.0.0.1:5501 --out 127.0.0.1:14550 --out 127.0.0.1:14551
options="--master $MAVLINK_PORT --sitl $SIMOUT_PORT --out 127.0.0.1:14550 --out 127.0.0.1:14551" options=""
if [ $START_HIL == 0 ]; then
options="--master $MAVLINK_PORT --sitl $SIMOUT_PORT"
fi
options="$options --out 127.0.0.1:14550 --out 127.0.0.1:14551"
extra_cmd1="" extra_cmd1=""
if [ $WIPE_EEPROM == 1 ]; then if [ $WIPE_EEPROM == 1 ]; then
extra_cmd="param forceload $autotest/$PARMS; $EXTRA_PARM; param fetch" extra_cmd="param forceload $autotest/$PARMS; $EXTRA_PARM; param fetch"
@ -307,5 +319,8 @@ if [ $START_ANTENNA_TRACKER == 1 ]; then
options="$options --load-module=tracker" options="$options --load-module=tracker"
extra_cmd="$extra_cmd module load map; tracker set port $TRACKER_UARTA; tracker start;" extra_cmd="$extra_cmd module load map; tracker set port $TRACKER_UARTA; tracker start;"
fi fi
if [ $START_HIL == 1 ]; then
options="$options --load-module=HIL"
fi
mavproxy.py $options --cmd="$extra_cmd" $* mavproxy.py $options --cmd="$extra_cmd" $*
kill_tasks kill_tasks