mirror of https://github.com/ArduPilot/ardupilot
autotest: automatically use sensible defaults for each vehicle type
this make first time use of SITL simpler
This commit is contained in:
parent
415d800957
commit
0d26e3a445
|
@ -27,6 +27,7 @@ MODEL=""
|
|||
BREAKPOINT=""
|
||||
OVERRIDE_BUILD_TARGET=""
|
||||
DELAY_START=0
|
||||
DEFAULTS_PATH=""
|
||||
|
||||
usage()
|
||||
{
|
||||
|
@ -232,24 +233,35 @@ EOF
|
|||
}
|
||||
|
||||
|
||||
autotest="../Tools/autotest"
|
||||
[ -d "$autotest" ] || {
|
||||
# we are not running from one of the standard vehicle directories. Use
|
||||
# the location of the sim_vehicle.sh script to find the path
|
||||
autotest=$(dirname $(readlink -e $0))
|
||||
}
|
||||
|
||||
# modify build target based on copter frame type
|
||||
case $FRAME in
|
||||
+|quad)
|
||||
BUILD_TARGET="sitl"
|
||||
MODEL="+"
|
||||
DEFAULTS_PATH="$autotest/copter_params.parm"
|
||||
;;
|
||||
X)
|
||||
BUILD_TARGET="sitl"
|
||||
EXTRA_PARM="param set FRAME 1;"
|
||||
MODEL="X"
|
||||
DEFAULTS_PATH="$autotest/copter_params.parm"
|
||||
;;
|
||||
octa*)
|
||||
BUILD_TARGET="sitl-octa"
|
||||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/copter_params.parm"
|
||||
;;
|
||||
heli*)
|
||||
BUILD_TARGET="sitl-heli"
|
||||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/Helicopter.parm"
|
||||
;;
|
||||
heli-dual)
|
||||
BUILD_TARGET="sitl-heli-dual"
|
||||
|
@ -263,11 +275,13 @@ case $FRAME in
|
|||
;;
|
||||
IrisRos)
|
||||
BUILD_TARGET="sitl"
|
||||
DEFAULTS_PATH="$autotest/copter_params.parm"
|
||||
;;
|
||||
Gazebo)
|
||||
BUILD_TARGET="sitl"
|
||||
EXTRA_SIM="$EXTRA_SIM --frame=Gazebo"
|
||||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/copter_params.parm"
|
||||
;;
|
||||
CRRCSim|last_letter*)
|
||||
BUILD_TARGET="sitl"
|
||||
|
@ -277,14 +291,17 @@ case $FRAME in
|
|||
BUILD_TARGET="sitl"
|
||||
MODEL="$FRAME"
|
||||
check_jsbsim_version
|
||||
DEFAULTS_PATH="$autotest/ArduPlane.parm"
|
||||
;;
|
||||
quadplane*)
|
||||
BUILD_TARGET="sitl"
|
||||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/quadplane.parm"
|
||||
;;
|
||||
*-heli)
|
||||
BUILD_TARGET="sitl-heli"
|
||||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/Helicopter.parm"
|
||||
;;
|
||||
*)
|
||||
MODEL="$FRAME"
|
||||
|
@ -299,12 +316,6 @@ if [ -n "$OVERRIDE_BUILD_TARGET" ]; then
|
|||
BUILD_TARGET="$OVERRIDE_BUILD_TARGET"
|
||||
fi
|
||||
|
||||
autotest="../Tools/autotest"
|
||||
[ -d "$autotest" ] || {
|
||||
# we are not running from one of the standard vehicle directories. Use
|
||||
# the location of the sim_vehicle.sh script to find the path
|
||||
autotest=$(dirname $(readlink -e $0))
|
||||
}
|
||||
VEHICLEDIR="$autotest/../../$VEHICLE"
|
||||
[ -d "$VEHICLEDIR" ] || {
|
||||
VEHICLEDIR=$(dirname $(readlink -e $VEHICLEDIR))
|
||||
|
@ -400,6 +411,11 @@ if [ $USE_MAVLINK_GIMBAL == 1 ]; then
|
|||
cmd="$cmd --gimbal"
|
||||
fi
|
||||
|
||||
if [ -n "$DEFAULTS_PATH" ]; then
|
||||
echo "Using defaults from $DEFAULTS_PATH"
|
||||
cmd="$cmd --defaults $DEFAULTS_PATH"
|
||||
fi
|
||||
|
||||
if [ $START_HIL == 0 ]; then
|
||||
if [ $USE_VALGRIND == 1 ]; then
|
||||
echo "Using valgrind"
|
||||
|
|
Loading…
Reference in New Issue