mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 09:33:59 -03:00
autotest: added -T option to sim_arduplane.sh
starts an antenna tracker
This commit is contained in:
parent
83269bbea7
commit
4f44351d4e
@ -2,15 +2,17 @@
|
|||||||
|
|
||||||
# home location lat, lon, alt, heading
|
# home location lat, lon, alt, heading
|
||||||
SIMHOME="-35.363261,149.165230,584,353"
|
SIMHOME="-35.363261,149.165230,584,353"
|
||||||
|
TRACKER_HOME="-35.362734,149.165300,586,270"
|
||||||
|
|
||||||
# check the instance number to allow for multiple copies of the sim running at once
|
# check the instance number to allow for multiple copies of the sim running at once
|
||||||
INSTANCE=0
|
INSTANCE=0
|
||||||
USE_VALGRIND=0
|
USE_VALGRIND=0
|
||||||
USE_GDB=0
|
USE_GDB=0
|
||||||
CLEAN_BUILD=0
|
CLEAN_BUILD=0
|
||||||
|
START_ANTENNA_TRACKER=0
|
||||||
|
|
||||||
# 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:VGc" opt; do
|
while getopts ":I:VGcT" opt; do
|
||||||
case $opt in
|
case $opt in
|
||||||
I)
|
I)
|
||||||
INSTANCE=$OPTARG
|
INSTANCE=$OPTARG
|
||||||
@ -18,6 +20,9 @@ while getopts ":I:VGc" opt; do
|
|||||||
V)
|
V)
|
||||||
USE_VALGRIND=1
|
USE_VALGRIND=1
|
||||||
;;
|
;;
|
||||||
|
T)
|
||||||
|
START_ANTENNA_TRACKER=1
|
||||||
|
;;
|
||||||
G)
|
G)
|
||||||
USE_GDB=1
|
USE_GDB=1
|
||||||
;;
|
;;
|
||||||
@ -37,8 +42,8 @@ shift $((OPTIND-1))
|
|||||||
|
|
||||||
# kill existing copy if this is the '0' instance only
|
# kill existing copy if this is the '0' instance only
|
||||||
[ "$INSTANCE" -eq "0" ] && {
|
[ "$INSTANCE" -eq "0" ] && {
|
||||||
killall -q JSBSim lt-JSBSim ArduPlane.elf
|
killall -q JSBSim lt-JSBSim ArduPlane.elf AntennaTracker.elf
|
||||||
pkill -f runsim.py
|
pkill -f runsim.py sim_tracker.py
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -62,6 +67,25 @@ make sitl -j4 || {
|
|||||||
}
|
}
|
||||||
popd
|
popd
|
||||||
|
|
||||||
|
if [ $START_ANTENNA_TRACKER == 1 ]; then
|
||||||
|
pushd $autotest/../AntennaTracker
|
||||||
|
if [ $CLEAN_BUILD == 1 ]; then
|
||||||
|
make clean
|
||||||
|
fi
|
||||||
|
make sitl -j4 || {
|
||||||
|
make clean
|
||||||
|
make sitl -j4
|
||||||
|
}
|
||||||
|
TRACKER_INSTANCE=1
|
||||||
|
TRACKIN_PORT="127.0.0.1:"$((5502+10*$TRACKER_INSTANCE))
|
||||||
|
TRACKOUT_PORT="127.0.0.1:"$((5501+10*$TRACKER_INSTANCE))
|
||||||
|
TRACKER_UARTA="tcp:127.0.0.1:"$((5760+10*$TRACKER_INSTANCE))
|
||||||
|
cmd="nice /tmp/AntennaTracker.build/AntennaTracker.elf -I1"
|
||||||
|
$autotest/run_in_terminal_window.sh "AntennaTracker" $cmd || exit 1
|
||||||
|
$autotest/run_in_terminal_window.sh "pysim(Tracker)" nice $autotest/pysim/sim_tracker.py --home=$TRACKER_HOME --simin=$TRACKIN_PORT --simout=$TRACKOUT_PORT || exit 1
|
||||||
|
popd
|
||||||
|
fi
|
||||||
|
|
||||||
cmd="/tmp/ArduPlane.build/ArduPlane.elf -I$INSTANCE"
|
cmd="/tmp/ArduPlane.build/ArduPlane.elf -I$INSTANCE"
|
||||||
|
|
||||||
if [ $USE_VALGRIND == 1 ]; then
|
if [ $USE_VALGRIND == 1 ]; then
|
||||||
@ -89,4 +113,9 @@ sleep 2
|
|||||||
# sim_arduplane.sh --out /dev/serial/by-id/usb-FTDI* --baudrate 57600 --map --console
|
# sim_arduplane.sh --out /dev/serial/by-id/usb-FTDI* --baudrate 57600 --map --console
|
||||||
|
|
||||||
# mavproxy.py --master tcp:127.0.0.1:5760 --sitl 127.0.0.1:5501 --out 127.0.0.1:14550 --out 127.0.0.1:14551
|
# mavproxy.py --master tcp:127.0.0.1:5760 --sitl 127.0.0.1:5501 --out 127.0.0.1:14550 --out 127.0.0.1:14551
|
||||||
mavproxy.py --master $MAVLINK_PORT --sitl $SIMOUT_PORT --out 127.0.0.1:14550 --out 127.0.0.1:14551 $*
|
options="--master $MAVLINK_PORT --sitl $SIMOUT_PORT --out 127.0.0.1:14550 --out 127.0.0.1:14551"
|
||||||
|
if [ $START_ANTENNA_TRACKER == 1 ]; then
|
||||||
|
mavproxy.py $options --load-module=tracker --cmd="set moddebug 1; tracker set port $TRACKER_UARTA" $*
|
||||||
|
else
|
||||||
|
mavproxy.py $options $*
|
||||||
|
fi
|
||||||
|
Loading…
Reference in New Issue
Block a user