mirror of https://github.com/ArduPilot/ardupilot
autotest: enable internal MAVLink gimbal
and add -B option to help debugging
This commit is contained in:
parent
e7abc07898
commit
9f09ac64cf
|
@ -25,6 +25,7 @@ START_HIL=0
|
||||||
TRACKER_ARGS=""
|
TRACKER_ARGS=""
|
||||||
EXTERNAL_SIM=0
|
EXTERNAL_SIM=0
|
||||||
MODEL=""
|
MODEL=""
|
||||||
|
BREAKPOINT=""
|
||||||
|
|
||||||
usage()
|
usage()
|
||||||
{
|
{
|
||||||
|
@ -37,6 +38,8 @@ Options:
|
||||||
-V enable valgrind for memory access checking (very slow!)
|
-V enable valgrind for memory access checking (very slow!)
|
||||||
-G use gdb for debugging ardupilot
|
-G use gdb for debugging ardupilot
|
||||||
-g use gdb for debugging ardupilot, but don't auto-start
|
-g use gdb for debugging ardupilot, but don't auto-start
|
||||||
|
-D build with debugging
|
||||||
|
-B add a breakpoint at given location in debugger
|
||||||
-T start an antenna tracker instance
|
-T start an antenna tracker instance
|
||||||
-A pass arguments to antenna tracker
|
-A pass arguments to antenna tracker
|
||||||
-t set antenna tracker start location
|
-t set antenna tracker start location
|
||||||
|
@ -47,7 +50,6 @@ Options:
|
||||||
-w wipe EEPROM and reload parameters
|
-w wipe EEPROM and reload parameters
|
||||||
-R reverse throttle in plane
|
-R reverse throttle in plane
|
||||||
-M enable MAVLink gimbal
|
-M enable MAVLink gimbal
|
||||||
-D build with debugging
|
|
||||||
-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
|
||||||
|
@ -71,7 +73,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:D" opt; do
|
while getopts ":I:VgGcj:TA:t:L:l:v:hwf:RNHeMS:DB:" opt; do
|
||||||
case $opt in
|
case $opt in
|
||||||
v)
|
v)
|
||||||
VEHICLE=$OPTARG
|
VEHICLE=$OPTARG
|
||||||
|
@ -104,6 +106,9 @@ while getopts ":I:VgGcj:TA:t:L:l:v:hwf:RNHeMS:D" opt; do
|
||||||
D)
|
D)
|
||||||
DEBUG_BUILD=1
|
DEBUG_BUILD=1
|
||||||
;;
|
;;
|
||||||
|
B)
|
||||||
|
BREAKPOINT="$OPTARG"
|
||||||
|
;;
|
||||||
M)
|
M)
|
||||||
USE_MAVLINK_GIMBAL=1
|
USE_MAVLINK_GIMBAL=1
|
||||||
;;
|
;;
|
||||||
|
@ -190,6 +195,9 @@ set -x
|
||||||
[ -z "$FRAME" -a "$VEHICLE" = "ArduPlane" ] && {
|
[ -z "$FRAME" -a "$VEHICLE" = "ArduPlane" ] && {
|
||||||
FRAME="jsbsim"
|
FRAME="jsbsim"
|
||||||
}
|
}
|
||||||
|
[ -z "$FRAME" -a "$VEHICLE" = "ArduCopter" ] && {
|
||||||
|
FRAME="quad"
|
||||||
|
}
|
||||||
|
|
||||||
EXTRA_PARM=""
|
EXTRA_PARM=""
|
||||||
EXTRA_SIM=""
|
EXTRA_SIM=""
|
||||||
|
@ -224,19 +232,18 @@ case $FRAME in
|
||||||
+|quad)
|
+|quad)
|
||||||
BUILD_TARGET="sitl"
|
BUILD_TARGET="sitl"
|
||||||
EXTRA_SIM="$EXTRA_SIM --frame=quad"
|
EXTRA_SIM="$EXTRA_SIM --frame=quad"
|
||||||
|
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"
|
EXTRA_SIM="$EXTRA_SIM --frame=X"
|
||||||
|
MODEL="X"
|
||||||
;;
|
;;
|
||||||
octa)
|
octa*)
|
||||||
BUILD_TARGET="sitl-octa"
|
BUILD_TARGET="sitl-octa"
|
||||||
EXTRA_SIM="$EXTRA_SIM --frame=octa"
|
EXTRA_SIM="$EXTRA_SIM --frame=octa"
|
||||||
;;
|
MODEL="$FRAME"
|
||||||
octa-quad)
|
|
||||||
BUILD_TARGET="sitl-octa-quad"
|
|
||||||
EXTRA_SIM="$EXTRA_SIM --frame=octa-quad"
|
|
||||||
;;
|
;;
|
||||||
heli)
|
heli)
|
||||||
BUILD_TARGET="sitl-heli"
|
BUILD_TARGET="sitl-heli"
|
||||||
|
@ -280,11 +287,6 @@ if [ $DEBUG_BUILD == 1 ]; then
|
||||||
BUILD_TARGET="$BUILD_TARGET-debug"
|
BUILD_TARGET="$BUILD_TARGET-debug"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $USE_MAVLINK_GIMBAL == 1 ]; then
|
|
||||||
echo "Using MAVLink gimbal"
|
|
||||||
EXTRA_SIM="$EXTRA_SIM --gimbal"
|
|
||||||
fi
|
|
||||||
|
|
||||||
autotest=$(dirname $(readlink -e $0))
|
autotest=$(dirname $(readlink -e $0))
|
||||||
if [ $NO_REBUILD == 0 ]; then
|
if [ $NO_REBUILD == 0 ]; then
|
||||||
pushd $autotest/../../$VEHICLE || {
|
pushd $autotest/../../$VEHICLE || {
|
||||||
|
@ -357,12 +359,8 @@ case $VEHICLE in
|
||||||
cmd="$cmd --model $MODEL --speedup=$SPEEDUP"
|
cmd="$cmd --model $MODEL --speedup=$SPEEDUP"
|
||||||
;;
|
;;
|
||||||
ArduCopter)
|
ArduCopter)
|
||||||
if [ -n "$MODEL" ]; then
|
|
||||||
RUNSIM=""
|
RUNSIM=""
|
||||||
cmd="$cmd --model $MODEL --speedup=$SPEEDUP"
|
cmd="$cmd --model $MODEL --speedup=$SPEEDUP"
|
||||||
else
|
|
||||||
RUNSIM="nice $autotest/pysim/sim_wrapper.py --home=$SIMHOME --simin=$SIMIN_PORT --simout=$SIMOUT_PORT --fgout=$FG_PORT $EXTRA_SIM"
|
|
||||||
fi
|
|
||||||
PARMS="copter_params.parm"
|
PARMS="copter_params.parm"
|
||||||
;;
|
;;
|
||||||
APMrover2)
|
APMrover2)
|
||||||
|
@ -377,6 +375,11 @@ case $VEHICLE in
|
||||||
;;
|
;;
|
||||||
esac
|
esac
|
||||||
|
|
||||||
|
if [ $USE_MAVLINK_GIMBAL == 1 ]; then
|
||||||
|
echo "Using MAVLink gimbal"
|
||||||
|
cmd="$cmd --gimbal"
|
||||||
|
fi
|
||||||
|
|
||||||
if [ $START_HIL == 0 ]; then
|
if [ $START_HIL == 0 ]; then
|
||||||
if [ $USE_VALGRIND == 1 ]; then
|
if [ $USE_VALGRIND == 1 ]; then
|
||||||
echo "Using valgrind"
|
echo "Using valgrind"
|
||||||
|
@ -385,6 +388,9 @@ elif [ $USE_GDB == 1 ]; then
|
||||||
echo "Using gdb"
|
echo "Using gdb"
|
||||||
tfile=$(mktemp)
|
tfile=$(mktemp)
|
||||||
[ $USE_GDB_STOPPED == 0 ] && {
|
[ $USE_GDB_STOPPED == 0 ] && {
|
||||||
|
if [ -n "$BREAKPOINT" ]; then
|
||||||
|
echo "b $BREAKPOINT" >> $tfile
|
||||||
|
fi
|
||||||
echo r >> $tfile
|
echo r >> $tfile
|
||||||
}
|
}
|
||||||
$autotest/run_in_terminal_window.sh "ardupilot (gdb)" gdb -x $tfile --args $cmd || exit 1
|
$autotest/run_in_terminal_window.sh "ardupilot (gdb)" gdb -x $tfile --args $cmd || exit 1
|
||||||
|
|
Loading…
Reference in New Issue