|
|
|
@ -207,6 +207,14 @@ case $FRAME in
@@ -207,6 +207,14 @@ case $FRAME in
|
|
|
|
|
BUILD_TARGET="sitl" |
|
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=IrisRos" |
|
|
|
|
;; |
|
|
|
|
CRRCSim-heli) |
|
|
|
|
BUILD_TARGET="sitl-heli" |
|
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=CRRCSim-heli" |
|
|
|
|
;; |
|
|
|
|
CRRCSim) |
|
|
|
|
BUILD_TARGET="sitl" |
|
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=CRRCSim" |
|
|
|
|
;; |
|
|
|
|
elevon*) |
|
|
|
|
EXTRA_PARM="param set ELEVON_OUTPUT 4;" |
|
|
|
|
EXTRA_SIM="$EXTRA_SIM --elevon" |
|
|
|
@ -318,11 +326,15 @@ for more details
@@ -318,11 +326,15 @@ for more details
|
|
|
|
|
EOF |
|
|
|
|
exit 1 |
|
|
|
|
fi |
|
|
|
|
RUNSIM="nice $autotest/jsb_sim/runsim.py --home=$SIMHOME --simin=$SIMIN_PORT --simout=$SIMOUT_PORT --fgout=$FG_PORT $EXTRA_SIM" |
|
|
|
|
PARMS="ArduPlane.parm" |
|
|
|
|
if [ $WIPE_EEPROM == 1 ]; then |
|
|
|
|
cmd="$cmd -PFORMAT_VERSION=13 -PSKIP_GYRO_CAL=1 -PRC3_MIN=1000 -PRC3_TRIM=1000" |
|
|
|
|
fi |
|
|
|
|
if [ "$FRAME" = "CRRCSim" ]; then |
|
|
|
|
RUNSIM="nice $autotest/pysim/sim_wrapper.py --frame=CRRCSim --home=$SIMHOME --simin=$SIMIN_PORT --simout=$SIMOUT_PORT --fgout=$FG_PORT $EXTRA_SIM" |
|
|
|
|
else |
|
|
|
|
RUNSIM="nice $autotest/jsb_sim/runsim.py --home=$SIMHOME --simin=$SIMIN_PORT --simout=$SIMOUT_PORT --fgout=$FG_PORT $EXTRA_SIM" |
|
|
|
|
fi |
|
|
|
|
;; |
|
|
|
|
ArduCopter) |
|
|
|
|
RUNSIM="nice $autotest/pysim/sim_wrapper.py --home=$SIMHOME --simin=$SIMIN_PORT --simout=$SIMOUT_PORT --fgout=$FG_PORT $EXTRA_SIM" |
|
|
|
|