#!/bin/bash # home location lat, lon, alt, heading LOCATION="CMAC" TRACKER_LOCATION="CMAC_PILOTSBOX" 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 USE_VALGRIND=0 USE_GDB=0 USE_GDB_STOPPED=0 DEBUG_BUILD=0 USE_MAVLINK_GIMBAL=0 CLEAN_BUILD=0 START_ANTENNA_TRACKER=0 WIPE_EEPROM=0 REVERSE_THROTTLE=0 NO_REBUILD=0 START_HIL=0 EXTRA_ARGS="" MODEL="" BREAKPOINT="" OVERRIDE_BUILD_TARGET="" DELAY_START=0 DEFAULTS_PATH="" usage() { cat <&2 usage exit 1 esac done shift $((OPTIND-1)) # kill existing copy if this is the '0' instance only kill_tasks() { [ "$INSTANCE" -eq "0" ] && { for pname in JSBSim lt-JSBSim ArduPlane.elf ArduCopter.elf APMrover2.elf AntennaTracker.elf JSBSIm.exe MAVProxy.exe; do pkill "$pname" done pkill -f runsim.py } } if [ $START_HIL == 0 ]; then kill_tasks fi trap kill_tasks SIGINT # setup ports for this instance MAVLINK_PORT="tcp:127.0.0.1:"$((5760+10*$INSTANCE)) SIMOUT_PORT="127.0.0.1:"$((5501+10*$INSTANCE)) [ -z "$VEHICLE" ] && { CDIR="$PWD" rpath=$(which realpath) [ -n "$rpath" ] && { CDIR=$(realpath $CDIR) } VEHICLE=$(basename $CDIR) } [ -z "$FRAME" -a "$VEHICLE" = "APMrover2" ] && { FRAME="rover" } [ -z "$FRAME" -a "$VEHICLE" = "ArduPlane" ] && { FRAME="jsbsim" } [ -z "$FRAME" -a "$VEHICLE" = "ArduCopter" ] && { FRAME="quad" } [ -z "$FRAME" -a "$VEHICLE" = "AntennaTracker" ] && { FRAME="tracker" } EXTRA_PARM="" check_jsbsim_version() { jsbsim_version=$(JSBSim --version) if [[ $jsbsim_version != *"ArduPilot"* ]] then cat <&2 "$0: Build failed" exit 1 } } fi popd # get the location information if [ -z $CUSTOM_LOCATION ]; then SIMHOME=$(cat $autotest/locations.txt | grep -i "^$LOCATION=" | head -1 | cut -d= -f2) else SIMHOME=$CUSTOM_LOCATION LOCATION="Custom_Location" fi [ -z "$SIMHOME" ] && { echo "Unknown location $LOCATION" usage exit 1 } echo "Starting up at $LOCATION : $SIMHOME" TRACKER_HOME=$(cat $autotest/locations.txt | grep -i "^$TRACKER_LOCATION=" | cut -d= -f2) [ -z "$TRACKER_HOME" ] && { echo "Unknown tracker location $TRACKER_LOCATION" usage exit 1 } if [ $START_ANTENNA_TRACKER == 1 ]; then pushd $autotest/../../AntennaTracker if [ $CLEAN_BUILD == 1 ]; then make clean fi make sitl-debug -j$NUM_PROCS || { make clean make sitl-debug -j$NUM_PROCS } TRACKER_INSTANCE=1 TRACKER_UARTA="tcp:127.0.0.1:"$((5760+10*$TRACKER_INSTANCE)) cmd="nice /tmp/AntennaTracker.build/AntennaTracker.elf -I1 --model=tracker --home=$TRACKER_HOME" $autotest/run_in_terminal_window.sh "AntennaTracker" $cmd || exit 1 popd fi cmd="$VEHICLEDIR/$VEHICLE.elf -S -I$INSTANCE --home $SIMHOME" if [ $WIPE_EEPROM == 1 ]; then cmd="$cmd -w" fi cmd="$cmd --model $MODEL --speedup=$SPEEDUP $EXTRA_ARGS" if [ $USE_MAVLINK_GIMBAL == 1 ]; then echo "Using MAVLink gimbal" 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" $autotest/run_in_terminal_window.sh "ardupilot (valgrind)" valgrind $cmd || exit 1 elif [ $USE_GDB == 1 ]; then echo "Using gdb" tfile=$(mktemp) [ $USE_GDB_STOPPED == 0 ] && { if [ -n "$BREAKPOINT" ]; then echo "b $BREAKPOINT" >> $tfile fi echo r >> $tfile } $autotest/run_in_terminal_window.sh "ardupilot (gdb)" gdb -x $tfile --args $cmd || exit 1 else $autotest/run_in_terminal_window.sh "ardupilot" $cmd || exit 1 fi fi if [ $START_HIL == 1 ]; then $autotest/run_in_terminal_window.sh "JSBSim" $autotest/jsb_sim/runsim.py --home $SIMHOME --speedup=$SPEEDUP || exit 1 fi trap kill_tasks SIGINT # 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 options="" if [ $START_HIL == 0 ]; then options="--master $MAVLINK_PORT --sitl $SIMOUT_PORT" fi # If running inside of a vagrant guest, then we probably want to forward our mavlink out to the containing host OS if [ $USER == "vagrant" ]; then options="$options --out 10.0.2.2:14550" fi options="$options --out 127.0.0.1:14550 --out 127.0.0.1:14551" extra_cmd="" if [ $START_ANTENNA_TRACKER == 1 ]; then options="$options --load-module=tracker" extra_cmd="$extra_cmd module load map; tracker set port $TRACKER_UARTA; tracker start; tracker arm" fi if [ $START_HIL == 1 ]; then options="$options --load-module=HIL" fi if [ $USE_MAVLINK_GIMBAL == 1 ]; then options="$options --load-module=gimbal" fi if [ $DELAY_START != 0 ]; then sleep $DELAY_START fi if [ -f /usr/bin/cygstart ]; then cygstart -w "/cygdrive/c/Program Files (x86)/MAVProxy/mavproxy.exe" $options --cmd="$extra_cmd" $* else mavproxy.py $options --cmd="$extra_cmd" $* fi if [ $START_HIL == 0 ]; then kill_tasks fi