mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
autotest: use internal sim code for JSBSim
This commit is contained in:
parent
7692889248
commit
ebf358138f
@ -343,7 +343,8 @@ EOF
|
||||
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"
|
||||
RUNSIM=""
|
||||
cmd="$cmd --model jsbsim --speedup=$SPEEDUP"
|
||||
fi
|
||||
;;
|
||||
ArduCopter)
|
||||
@ -352,7 +353,7 @@ EOF
|
||||
;;
|
||||
APMrover2)
|
||||
RUNSIM=""
|
||||
cmd="$cmd --model $FRAME"
|
||||
cmd="$cmd --model $FRAME --speedup=$SPEEDUP"
|
||||
PARMS="Rover.parm"
|
||||
;;
|
||||
*)
|
||||
|
Loading…
Reference in New Issue
Block a user