|
|
@ -26,6 +26,7 @@ TRACKER_ARGS="" |
|
|
|
EXTERNAL_SIM=0 |
|
|
|
EXTERNAL_SIM=0 |
|
|
|
MODEL="" |
|
|
|
MODEL="" |
|
|
|
BREAKPOINT="" |
|
|
|
BREAKPOINT="" |
|
|
|
|
|
|
|
OVERRIDE_BUILD_TARGET="" |
|
|
|
|
|
|
|
|
|
|
|
usage() |
|
|
|
usage() |
|
|
|
{ |
|
|
|
{ |
|
|
@ -53,6 +54,7 @@ Options: |
|
|
|
-f FRAME set aircraft frame type |
|
|
|
-f FRAME set aircraft frame type |
|
|
|
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 |
|
|
|
|
|
|
|
-b BUILD_TARGET override SITL build target |
|
|
|
-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 |
|
|
|
-H start HIL |
|
|
|
-e use external simulator |
|
|
|
-e use external simulator |
|
|
@ -73,7 +75,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:l:v:hwf:RNHeMS:DB:" opt; do |
|
|
|
while getopts ":I:VgGcj:TA:t:L:l:v:hwf:RNHeMS:DB:b:" opt; do |
|
|
|
case $opt in |
|
|
|
case $opt in |
|
|
|
v) |
|
|
|
v) |
|
|
|
VEHICLE=$OPTARG |
|
|
|
VEHICLE=$OPTARG |
|
|
@ -143,6 +145,9 @@ while getopts ":I:VgGcj:TA:t:L:l:v:hwf:RNHeMS:DB:" opt; do |
|
|
|
e) |
|
|
|
e) |
|
|
|
EXTERNAL_SIM=1 |
|
|
|
EXTERNAL_SIM=1 |
|
|
|
;; |
|
|
|
;; |
|
|
|
|
|
|
|
b) |
|
|
|
|
|
|
|
OVERRIDE_BUILD_TARGET="$OPTARG" |
|
|
|
|
|
|
|
;; |
|
|
|
h) |
|
|
|
h) |
|
|
|
usage |
|
|
|
usage |
|
|
|
exit 0 |
|
|
|
exit 0 |
|
|
@ -201,11 +206,6 @@ FG_PORT="127.0.0.1:"$((5503+10*$INSTANCE)) |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
EXTRA_PARM="" |
|
|
|
EXTRA_PARM="" |
|
|
|
EXTRA_SIM="" |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
[ "$SPEEDUP" != "1" ] && { |
|
|
|
|
|
|
|
EXTRA_SIM="$EXTRA_SIM --speedup=$SPEEDUP" |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
check_jsbsim_version() |
|
|
|
check_jsbsim_version() |
|
|
|
{ |
|
|
|
{ |
|
|
@ -232,47 +232,38 @@ EOF |
|
|
|
case $FRAME in |
|
|
|
case $FRAME in |
|
|
|
+|quad) |
|
|
|
+|quad) |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=quad" |
|
|
|
|
|
|
|
MODEL="+" |
|
|
|
MODEL="+" |
|
|
|
;; |
|
|
|
;; |
|
|
|
X) |
|
|
|
X) |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
EXTRA_PARM="param set FRAME 1;" |
|
|
|
EXTRA_PARM="param set FRAME 1;" |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=X" |
|
|
|
|
|
|
|
MODEL="X" |
|
|
|
MODEL="X" |
|
|
|
;; |
|
|
|
;; |
|
|
|
octa*) |
|
|
|
octa*) |
|
|
|
BUILD_TARGET="sitl-octa" |
|
|
|
BUILD_TARGET="sitl-octa" |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=octa" |
|
|
|
|
|
|
|
MODEL="$FRAME" |
|
|
|
MODEL="$FRAME" |
|
|
|
;; |
|
|
|
;; |
|
|
|
heli) |
|
|
|
heli) |
|
|
|
BUILD_TARGET="sitl-heli" |
|
|
|
BUILD_TARGET="sitl-heli" |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=heli" |
|
|
|
|
|
|
|
MODEL="heli" |
|
|
|
MODEL="heli" |
|
|
|
;; |
|
|
|
;; |
|
|
|
IrisRos) |
|
|
|
IrisRos) |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=IrisRos" |
|
|
|
|
|
|
|
;; |
|
|
|
;; |
|
|
|
CRRCSim-heli) |
|
|
|
CRRCSim-heli) |
|
|
|
BUILD_TARGET="sitl-heli" |
|
|
|
BUILD_TARGET="sitl-heli" |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=CRRCSim-heli" |
|
|
|
|
|
|
|
MODEL="$FRAME" |
|
|
|
MODEL="$FRAME" |
|
|
|
;; |
|
|
|
;; |
|
|
|
CRRCSim|last_letter*) |
|
|
|
CRRCSim|last_letter*) |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=$FRAME" |
|
|
|
|
|
|
|
MODEL="$FRAME" |
|
|
|
MODEL="$FRAME" |
|
|
|
;; |
|
|
|
;; |
|
|
|
jsbsim*) |
|
|
|
jsbsim*) |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
BUILD_TARGET="sitl" |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=$FRAME" |
|
|
|
|
|
|
|
MODEL="$FRAME" |
|
|
|
MODEL="$FRAME" |
|
|
|
check_jsbsim_version |
|
|
|
check_jsbsim_version |
|
|
|
;; |
|
|
|
;; |
|
|
|
*) |
|
|
|
*) |
|
|
|
EXTRA_SIM="$EXTRA_SIM --frame=$FRAME" |
|
|
|
|
|
|
|
MODEL="$FRAME" |
|
|
|
MODEL="$FRAME" |
|
|
|
;; |
|
|
|
;; |
|
|
|
esac |
|
|
|
esac |
|
|
@ -281,6 +272,10 @@ if [ $DEBUG_BUILD == 1 ]; then |
|
|
|
BUILD_TARGET="$BUILD_TARGET-debug" |
|
|
|
BUILD_TARGET="$BUILD_TARGET-debug" |
|
|
|
fi |
|
|
|
fi |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if [ -n "$OVERRIDE_BUILD_TARGET" ]; then |
|
|
|
|
|
|
|
BUILD_TARGET="$OVERRIDE_BUILD_TARGET" |
|
|
|
|
|
|
|
fi |
|
|
|
|
|
|
|
|
|
|
|
autotest=$(dirname $(readlink -e $0)) |
|
|
|
autotest=$(dirname $(readlink -e $0)) |
|
|
|
pushd $autotest/../../$VEHICLE || { |
|
|
|
pushd $autotest/../../$VEHICLE || { |
|
|
|
echo "Failed to change to vehicle directory for $VEHICLE" |
|
|
|
echo "Failed to change to vehicle directory for $VEHICLE" |
|
|
|