mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
autotest: added -S parameter for simulation speedup
This commit is contained in:
parent
cfe12f38a5
commit
16f09a6eae
@ -101,7 +101,7 @@ parser.add_option("--rate", dest="rate", type='int', help="SIM update rate", def
|
||||
parser.add_option("--wind", dest="wind", help="Simulate wind (speed,direction,turbulance)", default='0,0,0')
|
||||
parser.add_option("--frame", dest="frame", help="frame type (+,X,octo)", default='+')
|
||||
parser.add_option("--gimbal", dest="gimbal", action='store_true', default=False, help="enable gimbal")
|
||||
parser.add_option("--nowait", action='store_true', help="don't pause between updates")
|
||||
parser.add_option("--speedup", type='float', default=1.0, help="speedup from realtime")
|
||||
|
||||
(opts, args) = parser.parse_args()
|
||||
|
||||
@ -169,6 +169,7 @@ print("Starting at lat=%f lon=%f alt=%.1f heading=%.1f" % (
|
||||
a.yaw))
|
||||
|
||||
frame_time = 1.0/opts.rate
|
||||
scaled_frame_time = frame_time/opts.speedup
|
||||
|
||||
if opts.gimbal:
|
||||
from gimbal import Gimbal3Axis
|
||||
@ -192,8 +193,8 @@ while True:
|
||||
sim_send(m, a)
|
||||
|
||||
now = time.time()
|
||||
if not opts.nowait and now < last_wall_time + frame_time:
|
||||
time.sleep(last_wall_time+frame_time - now)
|
||||
if now < last_wall_time + scaled_frame_time:
|
||||
time.sleep(last_wall_time+scaled_frame_time - now)
|
||||
last_wall_time = time.time()
|
||||
|
||||
a.time_advance(frame_time)
|
||||
|
@ -79,7 +79,8 @@ parser.add_option("--simout", dest="simout", help="SIM output (IP:port)",
|
||||
parser.add_option("--home", dest="home", type='string', default=None, help="home lat,lng,alt,hdg (required)")
|
||||
parser.add_option("--rate", dest="rate", type='int', help="SIM update rate", default=1000)
|
||||
parser.add_option("--skid-steering", action='store_true', default=False, help="Use skid steering")
|
||||
parser.add_option("--nowait", action='store_true', help="don't pause between updates")
|
||||
parser.add_option("--speedup", type='float', default=1.0, help="speedup from realtime")
|
||||
|
||||
|
||||
(opts, args) = parser.parse_args()
|
||||
|
||||
@ -132,6 +133,8 @@ print("Starting at lat=%f lon=%f alt=%f heading=%.1f" % (
|
||||
a.yaw))
|
||||
|
||||
frame_time = 1.0/opts.rate
|
||||
scaled_frame_time = frame_time/opts.speedup
|
||||
|
||||
last_wall_time = time.time()
|
||||
|
||||
counter = 0
|
||||
@ -149,8 +152,8 @@ while True:
|
||||
sim_send(a)
|
||||
|
||||
now = time.time()
|
||||
if not opts.nowait and now < last_wall_time + frame_time:
|
||||
time.sleep(last_wall_time+frame_time - now)
|
||||
if not opts.nowait and now < last_wall_time + scaled_frame_time:
|
||||
time.sleep(last_wall_time+scaled_frame_time - now)
|
||||
last_wall_time = time.time()
|
||||
|
||||
a.time_advance(frame_time)
|
||||
|
@ -7,6 +7,7 @@ VEHICLE=""
|
||||
BUILD_TARGET="sitl"
|
||||
FRAME=""
|
||||
NUM_PROCS=1
|
||||
SPEEDUP="1"
|
||||
|
||||
# check the instance number to allow for multiple copies of the sim running at once
|
||||
INSTANCE=0
|
||||
@ -48,6 +49,7 @@ Options:
|
||||
-j NUM_PROC number of processors to use during build (default 1)
|
||||
-H start HIL
|
||||
-e use external simulator
|
||||
-S SPEEDUP set simulation speedup (1 for wall clock time)
|
||||
|
||||
mavproxy_options:
|
||||
--map start with a map
|
||||
@ -64,7 +66,7 @@ EOF
|
||||
|
||||
|
||||
# parse options. Thanks to http://wiki.bash-hackers.org/howto/getopts_tutorial
|
||||
while getopts ":I:VgGcj:TA:t:L:v:hwf:RNHeM" opt; do
|
||||
while getopts ":I:VgGcj:TA:t:L:v:hwf:RNHeMS:" opt; do
|
||||
case $opt in
|
||||
v)
|
||||
VEHICLE=$OPTARG
|
||||
@ -107,6 +109,9 @@ while getopts ":I:VgGcj:TA:t:L:v:hwf:RNHeM" opt; do
|
||||
f)
|
||||
FRAME="$OPTARG"
|
||||
;;
|
||||
S)
|
||||
SPEEDUP="$OPTARG"
|
||||
;;
|
||||
t)
|
||||
TRACKER_LOCATION="$OPTARG"
|
||||
;;
|
||||
@ -171,39 +176,43 @@ set -x
|
||||
EXTRA_PARM=""
|
||||
EXTRA_SIM=""
|
||||
|
||||
[ "$SPEEDUP" != "1" ] && {
|
||||
EXTRA_SIM="$EXTRA_SIM --speedup=$SPEEDUP"
|
||||
}
|
||||
|
||||
# modify build target based on copter frame type
|
||||
case $FRAME in
|
||||
+|quad)
|
||||
BUILD_TARGET="sitl"
|
||||
EXTRA_SIM="--frame=quad"
|
||||
EXTRA_SIM="$EXTRA_SIM --frame=quad"
|
||||
;;
|
||||
X)
|
||||
BUILD_TARGET="sitl"
|
||||
EXTRA_PARM="param set FRAME 1;"
|
||||
EXTRA_SIM="--frame=X"
|
||||
EXTRA_SIM="$EXTRA_SIM --frame=X"
|
||||
;;
|
||||
octa)
|
||||
BUILD_TARGET="sitl-octa"
|
||||
EXTRA_SIM="--frame=octa"
|
||||
EXTRA_SIM="$EXTRA_SIM --frame=octa"
|
||||
;;
|
||||
octa-quad)
|
||||
BUILD_TARGET="sitl-octa-quad"
|
||||
EXTRA_SIM="--frame=octa-quad"
|
||||
EXTRA_SIM="$EXTRA_SIM --frame=octa-quad"
|
||||
;;
|
||||
heli)
|
||||
BUILD_TARGET="sitl-heli"
|
||||
EXTRA_SIM="--frame=heli"
|
||||
EXTRA_SIM="$EXTRA_SIM --frame=heli"
|
||||
;;
|
||||
elevon*)
|
||||
EXTRA_PARM="param set ELEVON_OUTPUT 4;"
|
||||
EXTRA_SIM="--elevon"
|
||||
EXTRA_SIM="$EXTRA_SIM --elevon"
|
||||
;;
|
||||
vtail)
|
||||
EXTRA_PARM="param set VTAIL_OUTPUT 4;"
|
||||
EXTRA_SIM="--vtail"
|
||||
EXTRA_SIM="$EXTRA_SIM --vtail"
|
||||
;;
|
||||
skid)
|
||||
EXTRA_SIM="--skid-steering"
|
||||
EXTRA_SIM="$EXTRA_SIM --skid-steering"
|
||||
;;
|
||||
obc)
|
||||
BUILD_TARGET="sitl-obc"
|
||||
@ -219,7 +228,7 @@ esac
|
||||
|
||||
if [ $USE_MAVLINK_GIMBAL == 1 ]; then
|
||||
echo "Using MAVLink gimbal"
|
||||
EXTRA_SIM="--gimbal"
|
||||
EXTRA_SIM="$EXTRA_SIM --gimbal"
|
||||
fi
|
||||
|
||||
autotest=$(dirname $(readlink -e $0))
|
||||
|
Loading…
Reference in New Issue
Block a user