#!/bin/bash # run multiple instances of the 'px4' binary, with the gazebo SITL simulation # It assumes px4 is already built, with 'make px4_sitl_default gazebo' # The simulator is expected to send to TCP port 4560+i for i in [0, N-1] # For example gazebo can be run like this: #./Tools/gazebo_sitl_multiple_run.sh -n 10 -m iris function cleanup() { pkill -x px4 pkill gzclient pkill gzserver } function spawn_model() { MODEL=$1 N=$2 #Instance Number X=$3 Y=$4 X=${X:=0.0} Y=${Y:=$((3*${N}))} SUPPORTED_MODELS=("iris" "plane" "standard_vtol" "rover" "r1_rover" "typhoon_h480") if [[ " ${SUPPORTED_MODELS[*]} " != *"$MODEL"* ]]; then echo "ERROR: Currently only vehicle model $MODEL is not supported!" echo " Supported Models: [${SUPPORTED_MODELS[@]}]" trap "cleanup" SIGINT SIGTERM EXIT exit 1 fi working_dir="$build_path/instance_$n" [ ! -d "$working_dir" ] && mkdir -p "$working_dir" pushd "$working_dir" &>/dev/null echo "starting instance $N in $(pwd)" ../bin/px4 -i $N -d "$build_path/etc" -w sitl_${MODEL}_${N} -s etc/init.d-posix/rcS >out.log 2>err.log & python3 ${src_path}/Tools/sitl_gazebo/scripts/jinja_gen.py ${src_path}/Tools/sitl_gazebo/models/${MODEL}/${MODEL}.sdf.jinja ${src_path}/Tools/sitl_gazebo --mavlink_tcp_port $((4560+${N})) --mavlink_udp_port $((14560+${N})) --mavlink_id $((1+${N})) --gst_udp_port $((5600+${N})) --video_uri $((5600+${N})) --mavlink_cam_udp_port $((14530+${N})) --output-file /tmp/${MODEL}_${N}.sdf echo "Spawning ${MODEL}_${N} at ${X} ${Y}" gz model --spawn-file=/tmp/${MODEL}_${N}.sdf --model-name=${MODEL}_${N} -x ${X} -y ${Y} -z 0.83 popd &>/dev/null } if [ "$1" == "-h" ] || [ "$1" == "--help" ] then echo "Usage: $0 [-n ] [-m ] [-w ] [-s