Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/autotest/sim_vehicle.py
Views: 1798
#!/usr/bin/env python312"""3Framework to start a simulated vehicle and connect it to MAVProxy.45Peter Barker, April 20166based on sim_vehicle.sh by Andrew Tridgell, October 201178AP_FLAKE8_CLEAN910"""11from __future__ import print_function1213import atexit14import datetime15import errno16import optparse17import os18import os.path19import re20import signal21import subprocess22import sys23import tempfile24import textwrap25import time26import shlex27import binascii28import math2930from pysim import util31from pysim import vehicleinfo323334# List of open terminal windows for macosx35windowID = []3637autotest_dir = os.path.dirname(os.path.realpath(__file__))38root_dir = os.path.realpath(os.path.join(autotest_dir, '../..'))3940try:41from pymavlink import mavextra42except ImportError:43sys.path.append(os.path.join(root_dir, "modules/mavlink"))44from pymavlink import mavextra4546os.environ["SIM_VEHICLE_SESSION"] = binascii.hexlify(os.urandom(8)).decode()474849class CompatError(Exception):50"""A custom exception class to hold state if we encounter the parse51error we are looking for"""52def __init__(self, error, opts, rargs):53Exception.__init__(self, error)54self.opts = opts55self.rargs = rargs565758class CompatOptionParser(optparse.OptionParser):59"""An option parser which emulates the behaviour of the old60sim_vehicle.sh; if passed -C, the first argument not understood starts61a list of arguments that are passed straight to mavproxy62"""6364class CustomFormatter(optparse.IndentedHelpFormatter):65def __init__(self, *args, **kwargs):66optparse.IndentedHelpFormatter.__init__(self, *args, **kwargs)6768# taken and modified from from optparse.py's format_option69def format_option_preserve_nl(self, option):70# The help for each option consists of two parts:71# * the opt strings and metavars72# eg. ("-x", or "-fFILENAME, --file=FILENAME")73# * the user-supplied help string74# eg. ("turn on expert mode", "read data from FILENAME")75#76# If possible, we write both of these on the same line:77# -x turn on expert mode78#79# But if the opt string list is too long, we put the help80# string on a second line, indented to the same column it would81# start in if it fit on the first line.82# -fFILENAME, --file=FILENAME83# read data from FILENAME84result = []85opts = self.option_strings[option]86opt_width = self.help_position - self.current_indent - 287if len(opts) > opt_width:88opts = "%*s%s\n" % (self.current_indent, "", opts)89else: # start help on same line as opts90opts = "%*s%-*s " % (self.current_indent, "", opt_width, opts)91result.append(opts)92if option.help:93help_text = self.expand_default(option)94tw = textwrap.TextWrapper(replace_whitespace=False,95initial_indent="",96subsequent_indent=" ",97width=self.help_width)9899for line in help_text.split("\n"):100help_lines = tw.wrap(line)101for wline in help_lines:102result.extend(["%*s%s\n" % (self.help_position,103"",104wline)])105elif opts[-1] != "\n":106result.append("\n")107return "".join(result)108109def format_option(self, option):110if str(option).find('frame') != -1:111return self.format_option_preserve_nl(option)112return optparse.IndentedHelpFormatter.format_option(self, option)113114def __init__(self, *args, **kwargs):115formatter = CompatOptionParser.CustomFormatter()116optparse.OptionParser.__init__(self,117*args,118formatter=formatter,119**kwargs)120121def error(self, error):122"""Override default error handler called by123optparse.OptionParser.parse_args when a parse error occurs;124raise a detailed exception which can be caught125"""126if error.find("no such option") != -1:127raise CompatError(error, self.values, self.rargs)128129optparse.OptionParser.error(self, error)130131def parse_args(self, args=None, values=None):132'''Wrap parse_args so we can catch the exception raised upon133discovering the known parameter parsing error134'''135136try:137opts, args = optparse.OptionParser.parse_args(self)138except CompatError as e:139if not e.opts.sim_vehicle_sh_compatible:140print(e)141print("Perhaps you want --sim_vehicle_sh_compatible (-C)?")142sys.exit(1)143if e.opts.mavproxy_args:144print("--mavproxy-args not permitted in compat mode")145sys.exit(1)146147args = []148opts = e.opts149mavproxy_args = [str(e)[16:]] # this trims "no such option" off150mavproxy_args.extend(e.rargs)151opts.ensure_value("mavproxy_args", " ".join(mavproxy_args))152153return opts, args154155156def cygwin_pidof(proc_name):157""" Thanks to kata198 for this:158https://github.com/kata198/cygwin-ps-misc/blob/master/pidof159"""160pipe = subprocess.Popen("ps -ea | grep " + proc_name,161shell=True,162stdout=subprocess.PIPE)163output_lines = pipe.stdout.read().decode('utf-8').replace("\r", "").split("\n")164ret = pipe.wait()165pids = []166if ret != 0:167# No results168return []169for line in output_lines:170if not line:171continue172line_split = [item for item in line.split(' ') if item]173cmd = line_split[-1].split('/')[-1]174if cmd == proc_name:175try:176pid = int(line_split[0].strip())177except Exception:178pid = int(line_split[1].strip())179if pid not in pids:180pids.append(pid)181return pids182183184def under_cygwin():185"""Return if Cygwin binary exist"""186return os.path.exists("/usr/bin/cygstart")187188189def under_macos():190return sys.platform == 'darwin'191192193def under_vagrant():194return os.path.isfile("/ardupilot.vagrant")195196197def under_wsl2():198import platform199return 'microsoft-standard-WSL2' in platform.release()200201202def wsl2_host_ip():203if not under_wsl2():204return None205206pipe = subprocess.Popen("ip route show default | awk '{print $3}'",207shell=True,208stdout=subprocess.PIPE)209output_lines = pipe.stdout.read().decode('utf-8').strip(' \r\n')210ret = pipe.wait()211212if ret != 0:213# Command exited with an error. The output it generated probably isn't what we're expecting214return None215216if not output_lines:217# No output detected, maybe there's no nameserver or WSL2 has some abnormal firewalls/network settings?218return None219220return str(output_lines)221222223def kill_tasks_cygwin(victims):224"""Shell out to ps -ea to find processes to kill"""225for victim in list(victims):226pids = cygwin_pidof(victim)227# progress("pids for (%s): %s" %228# (victim,",".join([ str(p) for p in pids])))229for apid in pids:230os.kill(apid, signal.SIGKILL)231232233def kill_tasks_macos():234for window in windowID:235cmd = ("osascript -e \'tell application \"Terminal\" to close "236"(window(get index of window id %s))\'" % window)237os.system(cmd)238239240def kill_tasks_psutil(victims):241"""Use the psutil module to kill tasks by name. Sadly, this module is242not available on Windows, but when it is we should be able to *just*243use this routine"""244import psutil245for proc in psutil.process_iter():246pdict = proc.as_dict(attrs=['environ', 'status'])247if pdict['status'] == psutil.STATUS_ZOMBIE:248continue249if pdict['environ'] is not None:250if pdict['environ'].get('SIM_VEHICLE_SESSION') == os.environ['SIM_VEHICLE_SESSION']:251proc.kill()252253254def kill_tasks_pkill(victims):255"""Shell out to pkill(1) to kill processed by name"""256for victim in victims: # pkill takes a single pattern, so iterate257cmd = ["pkill", victim[:15]] # pkill matches only first 15 characters258run_cmd_blocking("pkill", cmd, quiet=True)259260261class BobException(Exception):262"""Handle Bob's Exceptions"""263pass264265266def kill_tasks():267"""Clean up stray processes by name. This is a shotgun approach"""268progress("Killing tasks")269270if cmd_opts.coverage:271import psutil272for proc in psutil.process_iter(['pid', 'name', 'environ']):273if proc.name() not in ["arducopter", "ardurover", "arduplane", "ardusub", "antennatracker"]:274# only kill vehicle that way275continue276if os.environ['SIM_VEHICLE_SESSION'] not in proc.environ().get('SIM_VEHICLE_SESSION'):277# only kill vehicle launched with sim_vehicle.py that way278continue279proc.terminate()280progress("Waiting SITL to exit cleanly and write coverage .gcda")281try:282proc.wait(timeout=30)283progress("Done")284except psutil.TimeoutExpired:285progress("SITL doesn't want to exit cleaning, killing ...")286proc.kill()287288try:289victim_names = {290'JSBSim',291'lt-JSBSim',292'ArduPlane.elf',293'ArduCopter.elf',294'ArduSub.elf',295'Rover.elf',296'AntennaTracker.elf',297'JSBSIm.exe',298'MAVProxy.exe',299'runsim.py',300'AntennaTracker.elf',301'scrimmage',302'ardurover',303'arduplane',304'arducopter'305}306for vehicle in vinfo.options:307for frame in vinfo.options[vehicle]["frames"]:308frame_info = vinfo.options[vehicle]["frames"][frame]309if "waf_target" not in frame_info:310continue311exe_name = os.path.basename(frame_info["waf_target"])312victim_names.add(exe_name)313314if under_cygwin():315return kill_tasks_cygwin(victim_names)316if under_macos() and os.environ.get('DISPLAY'):317# use special macos kill routine if Display is on318return kill_tasks_macos()319320try:321kill_tasks_psutil(victim_names)322except ImportError:323kill_tasks_pkill(victim_names)324except Exception as e:325progress("kill_tasks failed: {}".format(str(e)))326327328def progress(text):329"""Display sim_vehicle progress text"""330print("SIM_VEHICLE: " + text)331332333def wait_unlimited():334"""Wait until signal received"""335while True:336time.sleep(600)337338339vinfo = vehicleinfo.VehicleInfo()340341342def do_build(opts, frame_options):343"""Build sitl using waf"""344progress("WAF build")345346old_dir = os.getcwd()347os.chdir(root_dir)348349waf_light = os.path.join(root_dir, "modules/waf/waf-light")350351configure_target = frame_options.get('configure_target', 'sitl')352353cmd_configure = [waf_light, "configure", "--board", configure_target]354if opts.debug:355cmd_configure.append("--debug")356357if opts.coverage:358cmd_configure.append("--coverage")359360if opts.enable_onvif and 'antennatracker' in frame_options["waf_target"]:361cmd_configure.append("--enable-onvif")362363if opts.OSD:364cmd_configure.append("--enable-sfml")365cmd_configure.append("--sitl-osd")366367if opts.OSDMSP:368cmd_configure.append("--osd")369370if opts.rgbled:371cmd_configure.append("--enable-sfml")372cmd_configure.append("--sitl-rgbled")373374if opts.tonealarm:375cmd_configure.append("--enable-sfml-audio")376377if opts.math_check_indexes:378cmd_configure.append("--enable-math-check-indexes")379380if opts.enable_ekf2:381cmd_configure.append("--enable-EKF2")382383if opts.disable_ekf3:384cmd_configure.append("--disable-EKF3")385386if opts.postype_single:387cmd_configure.append("--postype-single")388389if opts.ekf_double:390cmd_configure.append("--ekf-double")391392if opts.ekf_single:393cmd_configure.append("--ekf-single")394395if opts.force_32bit:396cmd_configure.append("--force-32bit")397398if opts.ubsan:399cmd_configure.append("--ubsan")400401if opts.ubsan_abort:402cmd_configure.append("--ubsan-abort")403404if opts.num_aux_imus:405cmd_configure.append("--num-aux-imus=%s" % opts.num_aux_imus)406407for nv in opts.define:408cmd_configure.append("--define=%s" % nv)409410if opts.enable_dds:411cmd_configure.append("--enable-dds")412413if opts.disable_networking:414cmd_configure.append("--disable-networking")415416if opts.enable_ppp:417cmd_configure.append("--enable-PPP")418419if opts.enable_networking_tests:420cmd_configure.append("--enable-networking-tests")421422pieces = [shlex.split(x) for x in opts.waf_configure_args]423for piece in pieces:424cmd_configure.extend(piece)425426if not cmd_opts.no_configure:427run_cmd_blocking("Configure waf", cmd_configure, check=True)428429if opts.clean:430run_cmd_blocking("Building clean", [waf_light, "clean"])431432print(frame_options)433cmd_build = [waf_light, "build", "--target", frame_options["waf_target"]]434if opts.jobs is not None:435cmd_build += ['-j', str(opts.jobs)]436pieces = [shlex.split(x) for x in opts.waf_build_args]437for piece in pieces:438cmd_build.extend(piece)439440_, sts = run_cmd_blocking("Building", cmd_build)441442if sts != 0: # build failed443if opts.rebuild_on_failure:444progress("Build failed; cleaning and rebuilding")445run_cmd_blocking("Building clean", [waf_light, "clean"])446447_, sts = run_cmd_blocking("Building", cmd_build)448if sts != 0:449progress("Build failed")450sys.exit(1)451else:452progress("Build failed")453sys.exit(1)454455os.chdir(old_dir)456457458def do_build_parameters(vehicle):459# build succeeded460# now build parameters461progress("Building fresh parameter descriptions")462param_parse_path = os.path.join(463autotest_dir, "param_metadata/param_parse.py")464cmd_param_build = ["python", param_parse_path, '--vehicle', vehicle]465466_, sts = run_cmd_blocking("Building fresh params", cmd_param_build)467if sts != 0:468progress("Parameter build failed")469sys.exit(1)470471472def get_user_locations_path():473'''The user locations.txt file is located by default in474$XDG_CONFIG_DIR/ardupilot/locations.txt. If $XDG_CONFIG_DIR is475not defined, we look in $HOME/.config/ardupilot/locations.txt. If476$HOME is not defined, we look in ./.config/ardupilot/locations.txt.'''477478config_dir = os.environ.get(479'XDG_CONFIG_DIR',480os.path.join(os.environ.get('HOME', '.'), '.config'))481482user_locations_path = os.path.join(483config_dir, 'ardupilot', 'locations.txt')484485return user_locations_path486487488def find_offsets(instances, file_path):489offsets = {}490swarminit_filepath = os.path.join(autotest_dir, "swarminit.txt")491comment_regex = re.compile(r"\s*#.*")492for path in [file_path, swarminit_filepath]:493if os.path.isfile(path):494with open(path, 'r') as fd:495for line in fd:496line = re.sub(comment_regex, "", line)497line = line.rstrip("\n")498if len(line) == 0:499continue500(instance, offset) = line.split("=")501instance = (int)(instance)502if (instance not in offsets) and (instance in instances):503offsets[instance] = [(float)(x) for x in offset.split(",")]504continue505if len(offsets) == len(instances):506return offsets507if len(offsets) == len(instances):508return offsets509for instance in instances:510if instance not in offsets:511offsets[instance] = [90.0, 20.0 * instance, 0.0, None]512return offsets513514515def find_geocoder_location(locname):516'''find a location using geocoder and SRTM'''517try:518import geocoder519except ImportError:520print("geocoder not installed")521return None522j = geocoder.osm(locname)523if j is None or not hasattr(j, 'lat') or j.lat is None:524print("geocoder failed to find '%s'" % locname)525return None526lat = j.lat527lon = j.lng528from MAVProxy.modules.mavproxy_map import srtm529downloader = srtm.SRTMDownloader()530downloader.loadFileList()531start = time.time()532alt = None533while time.time() - start < 5:534tile = downloader.getTile(int(math.floor(lat)), int(math.floor(lon)))535if tile:536alt = tile.getAltitudeFromLatLon(lat, lon)537break538if alt is None:539print("timed out getting altitude for '%s'" % locname)540return None541return [lat, lon, alt, 0.0]542543544def find_location_by_name(locname):545"""Search locations.txt for locname, return GPS coords"""546locations_userpath = os.environ.get('ARDUPILOT_LOCATIONS',547get_user_locations_path())548locations_filepath = os.path.join(autotest_dir, "locations.txt")549comment_regex = re.compile(r"\s*#.*")550for path in [locations_userpath, locations_filepath]:551if not os.path.isfile(path):552continue553with open(path, 'r') as fd:554for line in fd:555line = re.sub(comment_regex, "", line)556line = line.rstrip("\n")557if len(line) == 0:558continue559(name, loc) = line.split("=")560if name == locname:561return [(float)(x) for x in loc.split(",")]562563# fallback to geocoder if available564loc = find_geocoder_location(locname)565if loc is None:566sys.exit(1)567return loc568569570def find_spawns(loc, offsets):571lat, lon, alt, heading = loc572spawns = {}573for k in offsets:574(x, y, z, head) = offsets[k]575if head is None:576head = heading577g = mavextra.gps_offset(lat, lon, x, y)578spawns[k] = ",".join([str(g[0]), str(g[1]), str(alt+z), str(head)])579return spawns580581582def progress_cmd(what, cmd):583"""Print cmd in a way a user could cut-and-paste to get the same effect"""584progress(what)585shell_text = "%s" % (" ".join(['"%s"' % x for x in cmd]))586progress(shell_text)587588589def run_cmd_blocking(what, cmd, quiet=False, check=False, **kw):590if not quiet:591progress_cmd(what, cmd)592593try:594p = subprocess.Popen(cmd, **kw)595ret = os.waitpid(p.pid, 0)596except Exception as e:597print("[%s] An exception has occurred with command: '%s'" % (what, (' ').join(cmd)))598print(e)599sys.exit(1)600601_, sts = ret602if check and sts != 0:603progress("(%s) exited with code %d" % (what, sts,))604sys.exit(1)605return ret606607608def run_in_terminal_window(name, cmd, **kw):609610"""Execute the run_in_terminal_window.sh command for cmd"""611global windowID612runme = [os.path.join(autotest_dir, "run_in_terminal_window.sh"), name]613runme.extend(cmd)614progress_cmd("Run " + name, runme)615616if under_macos() and os.environ.get('DISPLAY'):617# on MacOS record the window IDs so we can close them later618out = subprocess.Popen(runme, stdout=subprocess.PIPE, **kw).communicate()[0]619out = out.decode('utf-8')620p = re.compile('tab 1 of window id (.*)')621622tstart = time.time()623while time.time() - tstart < 5:624tabs = p.findall(out)625626if len(tabs) > 0:627break628629time.sleep(0.1)630# sleep for extra 2 seconds for application to start631time.sleep(2)632if len(tabs) > 0:633windowID.append(tabs[0])634else:635progress("Cannot find %s process terminal" % name)636else:637subprocess.Popen(runme, **kw)638639640tracker_serial0 = None # blemish641642643def start_antenna_tracker(opts):644"""Compile and run the AntennaTracker, add tracker to mavproxy"""645646global tracker_serial0647progress("Preparing antenna tracker")648tracker_home = find_location_by_name(opts.tracker_location)649vehicledir = os.path.join(autotest_dir, "../../" + "AntennaTracker")650options = vinfo.options["AntennaTracker"]651tracker_default_frame = options["default_frame"]652tracker_frame_options = options["frames"][tracker_default_frame]653do_build(opts, tracker_frame_options)654tracker_instance = 1655oldpwd = os.getcwd()656os.chdir(vehicledir)657tracker_serial0 = "tcp:127.0.0.1:" + str(5760 + 10 * tracker_instance)658binary_basedir = "build/sitl"659exe = os.path.join(root_dir,660binary_basedir,661"bin/antennatracker")662run_in_terminal_window("AntennaTracker",663["nice",664exe,665"-I" + str(tracker_instance),666"--model=tracker",667"--home=" + ",".join([str(x) for x in tracker_home])])668os.chdir(oldpwd)669670671def start_CAN_Periph(opts, frame_info):672"""Compile and run the sitl_periph"""673674progress("Preparing sitl_periph_universal")675options = vinfo.options["sitl_periph_universal"]['frames']['universal']676defaults_path = frame_info.get('periph_params_filename', None)677if defaults_path is None:678defaults_path = options.get('default_params_filename', None)679680if not isinstance(defaults_path, list):681defaults_path = [defaults_path]682683# add in path and make a comma separated list684defaults_path = ','.join([util.relcurdir(os.path.join(autotest_dir, p)) for p in defaults_path])685686if not cmd_opts.no_rebuild:687do_build(opts, options)688exe = os.path.join(root_dir, 'build/sitl_periph_universal', 'bin/AP_Periph')689cmd = ["nice"]690cmd_name = "sitl_periph_universal"691if opts.valgrind:692cmd_name += " (valgrind)"693cmd.append("valgrind")694# adding this option allows valgrind to cope with the overload695# of operator new696cmd.append("--soname-synonyms=somalloc=nouserintercepts")697cmd.append("--track-origins=yes")698if opts.gdb or opts.gdb_stopped:699cmd_name += " (gdb)"700cmd.append("gdb")701gdb_commands_file = tempfile.NamedTemporaryFile(mode='w', delete=False)702atexit.register(os.unlink, gdb_commands_file.name)703gdb_commands_file.write("set pagination off\n")704if not opts.gdb_stopped:705gdb_commands_file.write("r\n")706gdb_commands_file.close()707cmd.extend(["-x", gdb_commands_file.name])708cmd.append("--args")709cmd.append(exe)710if defaults_path is not None:711cmd.append("--defaults")712cmd.append(defaults_path)713run_in_terminal_window(cmd_name, cmd)714715716def start_vehicle(binary, opts, stuff, spawns=None):717"""Run the ArduPilot binary"""718719cmd_name = opts.vehicle720cmd = []721if opts.valgrind:722cmd_name += " (valgrind)"723cmd.append("valgrind")724# adding this option allows valgrind to cope with the overload725# of operator new726cmd.append("--soname-synonyms=somalloc=nouserintercepts")727cmd.append("--track-origins=yes")728if opts.callgrind:729cmd_name += " (callgrind)"730cmd.append("valgrind")731cmd.append("--tool=callgrind")732if opts.gdb or opts.gdb_stopped:733cmd_name += " (gdb)"734cmd.append("gdb")735gdb_commands_file = tempfile.NamedTemporaryFile(mode='w', delete=False)736atexit.register(os.unlink, gdb_commands_file.name)737738for breakpoint in opts.breakpoint:739gdb_commands_file.write("b %s\n" % (breakpoint,))740if opts.disable_breakpoints:741gdb_commands_file.write("disable\n")742gdb_commands_file.write("set pagination off\n")743if not opts.gdb_stopped:744gdb_commands_file.write("r\n")745gdb_commands_file.close()746cmd.extend(["-x", gdb_commands_file.name])747cmd.append("--args")748elif opts.lldb or opts.lldb_stopped:749cmd_name += " (lldb)"750cmd.append("lldb")751lldb_commands_file = tempfile.NamedTemporaryFile(mode='w', delete=False)752atexit.register(os.unlink, lldb_commands_file.name)753754for breakpoint in opts.breakpoint:755lldb_commands_file.write("b %s\n" % (breakpoint,))756if not opts.lldb_stopped:757lldb_commands_file.write("process launch\n")758lldb_commands_file.close()759cmd.extend(["-s", lldb_commands_file.name])760cmd.append("--")761if opts.strace:762cmd_name += " (strace)"763cmd.append("strace")764strace_options = ['-o', binary + '.strace', '-s', '8000', '-ttt']765cmd.extend(strace_options)766767cmd.append(binary)768if opts.wipe_eeprom:769cmd.append("-w")770cmd.extend(["--model", stuff["model"]])771cmd.extend(["--speedup", str(opts.speedup)])772if opts.sysid is not None:773cmd.extend(["--sysid", str(opts.sysid)])774if opts.slave is not None:775cmd.extend(["--slave", str(opts.slave)])776if opts.enable_fgview:777cmd.extend(["--enable-fgview"])778if opts.sitl_instance_args:779# this could be a lot better:780cmd.extend(opts.sitl_instance_args.split(" "))781if opts.mavlink_gimbal:782cmd.append("--gimbal")783path = None784if "default_params_filename" in stuff:785paths = stuff["default_params_filename"]786if not isinstance(paths, list):787paths = [paths]788paths = [util.relcurdir(os.path.join(autotest_dir, x)) for x in paths]789for x in paths:790if not os.path.isfile(x):791print("The parameter file (%s) does not exist" % (x,))792sys.exit(1)793path = ",".join(paths)794if cmd_opts.count > 1 or opts.auto_sysid:795# we are in a subdirectory when using -n796path = os.path.join("..", path)797progress("Using defaults from (%s)" % (path,))798if opts.flash_storage:799cmd.append("--set-storage-flash-enabled 1")800cmd.append("--set-storage-posix-enabled 0")801elif opts.fram_storage:802cmd.append("--set-storage-fram-enabled 1")803cmd.append("--set-storage-posix-enabled 0")804if opts.add_param_file:805for file in opts.add_param_file:806if not os.path.isfile(file):807print("The parameter file (%s) does not exist" %808(file,))809sys.exit(1)810811if path is not None:812path += "," + str(file)813else:814path = str(file)815816progress("Adding parameters from (%s)" % (str(file),))817if opts.OSDMSP:818path += "," + os.path.join(root_dir, "libraries/AP_MSP/Tools/osdtest.parm")819path += "," + os.path.join(autotest_dir, "default_params/msposd.parm")820subprocess.Popen([os.path.join(root_dir, "libraries/AP_MSP/Tools/msposd.py")])821822if path is not None and len(path) > 0:823cmd.extend(["--defaults", path])824825if cmd_opts.start_time is not None:826# Parse start_time into a double precision number specifying seconds since 1900.827try:828start_time_UTC = time.mktime(datetime.datetime.strptime(cmd_opts.start_time, '%Y-%m-%d-%H:%M').timetuple())829except Exception:830print("Incorrect start time format - require YYYY-MM-DD-HH:MM (given %s)" % cmd_opts.start_time)831sys.exit(1)832833cmd.append("--start-time=%d" % start_time_UTC)834835cmd.append("--sim-address=%s" % cmd_opts.sim_address)836837old_dir = os.getcwd()838for i, i_dir in zip(instances, instance_dir):839c = ["-I" + str(i)]840if spawns is not None:841c.extend(["--home", spawns[i]])842if opts.mcast:843c.extend(["--serial0", "mcast:"])844elif opts.udp:845c.extend(["--serial0", "udpclient:127.0.0.1:" + str(5760+i*10)])846if opts.auto_sysid:847if opts.sysid is not None:848raise ValueError("Can't use auto-sysid and sysid together")849sysid = i + 1850# Take 0-based logging into account851if sysid < 1 or sysid > 255:852raise ValueError("Invalid system id %d" % sysid)853c.extend(["--sysid", str(sysid)])854855os.chdir(i_dir)856run_in_terminal_window(cmd_name, cmd + c)857os.chdir(old_dir)858859860def start_mavproxy(opts, stuff):861"""Run mavproxy"""862# FIXME: would be nice to e.g. "mavproxy.mavproxy(....).run"863# rather than shelling out864865extra_cmd = ""866cmd = []867if under_cygwin():868cmd.append("/usr/bin/cygstart")869cmd.append("-w")870cmd.append("mavproxy.exe")871else:872cmd.append("mavproxy.py")873874if opts.mcast:875cmd.extend(["--master", "mcast:"])876877# returns a valid IP of the host windows computer if we're WSL2.878# This is run before the loop so it only runs once879wsl2_host_ip_str = wsl2_host_ip()880881for i in instances:882if not opts.no_extra_ports:883ports = [14550 + 10 * i]884for port in ports:885if under_vagrant():886# We're running inside of a vagrant guest; forward our887# mavlink out to the containing host OS888cmd.extend(["--out", "10.0.2.2:" + str(port)])889elif wsl2_host_ip_str:890# We're running WSL2; forward our891# mavlink out to the containing host Windows OS892cmd.extend(["--out", str(wsl2_host_ip_str) + ":" + str(port)])893else:894cmd.extend(["--out", "127.0.0.1:" + str(port)])895896if not opts.mcast:897if opts.udp:898cmd.extend(["--master", ":" + str(5760 + 10 * i)])899else:900cmd.extend(["--master", "tcp:127.0.0.1:" + str(5760 + 10 * i)])901if stuff["sitl-port"] and not opts.no_rcin:902cmd.extend(["--sitl", "127.0.0.1:" + str(5501 + 10 * i)])903904if opts.tracker:905cmd.extend(["--load-module", "tracker"])906global tracker_serial0907# tracker_serial0 is set when we start the tracker...908extra_cmd += ("module load map;"909"tracker set port %s; "910"tracker start; "911"tracker arm;" % (tracker_serial0,))912913if opts.mavlink_gimbal:914cmd.extend(["--load-module", "gimbal"])915916if "extra_mavlink_cmds" in stuff:917extra_cmd += " " + stuff["extra_mavlink_cmds"]918919# Parsing the arguments to pass to mavproxy, split args on space920# and "=" signs and ignore those signs within quotation marks921if opts.mavproxy_args:922# It would be great if this could be done with regex923mavargs = opts.mavproxy_args.split(" ")924# Find the arguments with '=' in them and split them up925for i, x in enumerate(mavargs):926if '=' in x:927mavargs[i] = x.split('=')[0]928mavargs.insert(i+1, x.split('=')[1])929# Use this flag to tell if parsing character inbetween a pair930# of quotation marks931inString = False932beginStringIndex = []933endStringIndex = []934# Iterate through the arguments, looking for the arguments935# that begin with a quotation mark and the ones that end with936# a quotation mark937for i, x in enumerate(mavargs):938if not inString and x[0] == "\"":939beginStringIndex.append(i)940mavargs[i] = x[1:]941inString = True942elif inString and x[-1] == "\"":943endStringIndex.append(i)944inString = False945mavargs[i] = x[:-1]946# Replace the list items with one string to be passed into mavproxy947for begin, end in zip(beginStringIndex, endStringIndex):948replacement = " ".join(mavargs[begin:end+1])949mavargs[begin] = replacement950mavargs = mavargs[0:begin+1] + mavargs[end+1:]951cmd.extend(mavargs)952953# compatibility pass-through parameters (for those that don't want954# to use -C :-)955for out in opts.out:956cmd.extend(['--out', out])957if opts.map:958cmd.append('--map')959if opts.console:960cmd.append('--console')961if opts.aircraft is not None:962cmd.extend(['--aircraft', opts.aircraft])963if opts.moddebug:964cmd.append('--moddebug=%u' % opts.moddebug)965if opts.mavcesium:966cmd.extend(["--load-module", "cesium"])967968if opts.fresh_params:969# these were built earlier:970path = os.path.join(os.getcwd(), "apm.pdef.xml")971cmd.extend(['--load-module', 'param:{"xml-filepath":"%s"}' % path])972973if len(extra_cmd):974cmd.extend(['--cmd', extra_cmd])975976# add Tools/mavproxy_modules to PYTHONPATH in autotest so we can977# find random MAVProxy helper modules like sitl_calibration978local_mp_modules_dir = os.path.abspath(979os.path.join(__file__, '..', '..', 'mavproxy_modules'))980env = dict(os.environ)981old = env.get('PYTHONPATH', None)982env['PYTHONPATH'] = local_mp_modules_dir983if old is not None:984env['PYTHONPATH'] += os.path.pathsep + old985986run_cmd_blocking("Run MavProxy", cmd, env=env)987progress("MAVProxy exited")988989if opts.gdb:990# in the case that MAVProxy exits (as opposed to being991# killed), restart it if we are running under GDB. This992# allows ArduPilot to stop (eg. via a very early panic call)993# and have you debugging session not be killed.994while True:995progress("Running under GDB; restarting MAVProxy")996run_cmd_blocking("Run MavProxy", cmd, env=env)997progress("MAVProxy exited; sleeping 10")998time.sleep(10)99910001001vehicle_options_string = '|'.join(vinfo.options.keys())100210031004def generate_frame_help():1005ret = ""1006for vehicle in vinfo.options:1007frame_options = sorted(vinfo.options[vehicle]["frames"].keys())1008frame_options_string = '|'.join(frame_options)1009ret += "%s: %s\n" % (vehicle, frame_options_string)1010return ret101110121013# map from some vehicle aliases back to directory names. APMrover21014# was the old name / directory name for Rover.1015vehicle_map = {1016"APMrover2": "Rover",1017"Copter": "ArduCopter",1018"Plane": "ArduPlane",1019"Sub": "ArduSub",1020"Blimp" : "Blimp",1021"Rover": "Rover",1022}1023# add lower-case equivalents too1024for k in list(vehicle_map.keys()):1025vehicle_map[k.lower()] = vehicle_map[k]10261027# define and run parser1028parser = CompatOptionParser(1029"sim_vehicle.py",1030epilog=""1031"eeprom.bin in the starting directory contains the parameters for your "1032"simulated vehicle. Always start from the same directory. It is "1033"recommended that you start in the main vehicle directory for the vehicle "1034"you are simulating, for example, start in the ArduPlane directory to "1035"simulate ArduPlane")10361037vehicle_choices = list(vinfo.options.keys())10381039# add vehicle aliases to argument parser options:1040for c in vehicle_map.keys():1041vehicle_choices.append(c)10421043parser.add_option("-v", "--vehicle",1044type='choice',1045default=None,1046help="vehicle type (%s)" % vehicle_options_string,1047choices=vehicle_choices)1048parser.add_option("-f", "--frame", type='string', default=None, help="""set vehicle frame type10491050%s""" % (generate_frame_help()))10511052parser.add_option("--vehicle-binary",1053default=None,1054help="vehicle binary path")10551056parser.add_option("-C", "--sim_vehicle_sh_compatible",1057action='store_true',1058default=False,1059help="be compatible with the way sim_vehicle.sh works; "1060"make this the first option")10611062group_build = optparse.OptionGroup(parser, "Build options")1063group_build.add_option("-N", "--no-rebuild",1064action='store_true',1065default=False,1066help="don't rebuild before starting ardupilot")1067group_build.add_option("--no-configure",1068action='store_true',1069default=False,1070help="don't run waf configure before building")1071group_build.add_option("-D", "--debug",1072action='store_true',1073default=False,1074help="build with debugging")1075group_build.add_option("-c", "--clean",1076action='store_true',1077default=False,1078help="do a make clean before building")1079group_build.add_option("-j", "--jobs",1080default=None,1081type='int',1082help="number of processors to use during build "1083"(default for waf : number of processor, for make : 1)")1084group_build.add_option("-b", "--build-target",1085default=None,1086type='string',1087help="override SITL build target")1088group_build.add_option("--enable-math-check-indexes",1089default=False,1090action="store_true",1091dest="math_check_indexes",1092help="enable checking of math indexes")1093group_build.add_option("", "--force-32bit",1094default=False,1095action='store_true',1096dest="force_32bit",1097help="compile sitl using 32-bit")1098group_build.add_option("", "--configure-define",1099default=[],1100action='append',1101dest="define",1102help="create a preprocessor define")1103group_build.add_option("", "--rebuild-on-failure",1104dest="rebuild_on_failure",1105action='store_true',1106default=False,1107help="if build fails, do not clean and rebuild")1108group_build.add_option("", "--waf-configure-arg",1109action="append",1110dest="waf_configure_args",1111type="string",1112default=[],1113help="extra arguments to pass to waf in configure step")1114group_build.add_option("", "--waf-build-arg",1115action="append",1116dest="waf_build_args",1117type="string",1118default=[],1119help="extra arguments to pass to waf in its build step")1120group_build.add_option("", "--coverage",1121action='store_true',1122default=False,1123help="use coverage build")1124group_build.add_option("", "--ubsan",1125default=False,1126action='store_true',1127dest="ubsan",1128help="compile sitl with undefined behaviour sanitiser")1129group_build.add_option("", "--ubsan-abort",1130default=False,1131action='store_true',1132dest="ubsan_abort",1133help="compile sitl with undefined behaviour sanitiser and abort on error")1134group_build.add_option("--num-aux-imus",1135dest="num_aux_imus",1136default=0,1137type='int',1138help='number of auxiliary IMUs to simulate')1139parser.add_option_group(group_build)11401141group_sim = optparse.OptionGroup(parser, "Simulation options")1142group_sim.add_option("-I", "--instance",1143default=0,1144type='int',1145help="instance of simulator")1146group_sim.add_option("-n", "--count",1147type='int',1148default=1,1149help="vehicle count; if this is specified, -I is used as a base-value")1150group_sim.add_option("-i", "--instances",1151default=None,1152type='string',1153help="a space delimited list of instances to spawn; if specified, overrides -I and -n.")1154group_sim.add_option("-V", "--valgrind",1155action='store_true',1156default=False,1157help="enable valgrind for memory access checking (slow!)")1158group_sim.add_option("", "--callgrind",1159action='store_true',1160default=False,1161help="enable valgrind for performance analysis (slow!!)")1162group_sim.add_option("-T", "--tracker",1163action='store_true',1164default=False,1165help="start an antenna tracker instance")1166group_sim.add_option("", "--enable-onvif",1167action="store_true",1168help="enable onvif camera control sim using AntennaTracker")1169group_sim.add_option("", "--can-peripherals",1170action='store_true',1171default=False,1172help="start a DroneCAN peripheral instance")1173group_sim.add_option("-A", "--sitl-instance-args",1174type='string',1175default=None,1176help="pass arguments to SITL instance")1177group_sim.add_option("-G", "--gdb",1178action='store_true',1179default=False,1180help="use gdb for debugging ardupilot")1181group_sim.add_option("-g", "--gdb-stopped",1182action='store_true',1183default=False,1184help="use gdb for debugging ardupilot (no auto-start)")1185group_sim.add_option("--lldb",1186action='store_true',1187default=False,1188help="use lldb for debugging ardupilot")1189group_sim.add_option("--lldb-stopped",1190action='store_true',1191default=False,1192help="use ldb for debugging ardupilot (no auto-start)")1193group_sim.add_option("-d", "--delay-start",1194default=0,1195type='float',1196help="delay start of mavproxy by this number of seconds")1197group_sim.add_option("-B", "--breakpoint",1198type='string',1199action="append",1200default=[],1201help="add a breakpoint at given location in debugger")1202group_sim.add_option("--disable-breakpoints",1203default=False,1204action='store_true',1205help="disable all breakpoints before starting")1206group_sim.add_option("-M", "--mavlink-gimbal",1207action='store_true',1208default=False,1209help="enable MAVLink gimbal")1210group_sim.add_option("-L", "--location", type='string',1211default=None,1212help="use start location from "1213"Tools/autotest/locations.txt")1214group_sim.add_option("-l", "--custom-location",1215type='string',1216default=None,1217help="set custom start location (lat,lon,alt,heading)")1218group_sim.add_option("-S", "--speedup",1219default=1,1220type='int',1221help="set simulation speedup (1 for wall clock time)")1222group_sim.add_option("-t", "--tracker-location",1223default='CMAC_PILOTSBOX',1224type='string',1225help="set antenna tracker start location")1226group_sim.add_option("-w", "--wipe-eeprom",1227action='store_true',1228default=False, help="wipe EEPROM and reload parameters")1229group_sim.add_option("-m", "--mavproxy-args",1230default=None,1231type='string',1232help="additional arguments to pass to mavproxy.py")1233group_sim.add_option("", "--scrimmage-args",1234default=None,1235type='string',1236help="arguments used to populate SCRIMMAGE mission (comma-separated). "1237"Currently visual_model, motion_model, and terrain are supported. "1238"Usage: [instance=]argument=value...")1239group_sim.add_option("", "--strace",1240action='store_true',1241default=False,1242help="strace the ArduPilot binary")1243group_sim.add_option("", "--model",1244type='string',1245default=None,1246help="Override simulation model to use")1247group_sim.add_option("", "--use-dir",1248type='string',1249default=None,1250help="Store SITL state and output in named directory")1251group_sim.add_option("", "--no-mavproxy",1252action='store_true',1253default=False,1254help="Don't launch MAVProxy")1255group_sim.add_option("", "--fresh-params",1256action='store_true',1257dest='fresh_params',1258default=False,1259help="Generate and use local parameter help XML")1260group_sim.add_option("", "--mcast",1261action="store_true",1262default=False,1263help="Use multicasting at default 239.255.145.50:14550")1264group_sim.add_option("", "--udp",1265action="store_true",1266default=False,1267help="Use UDP on 127.0.0.1:5760")1268group_sim.add_option("", "--osd",1269action='store_true',1270dest='OSD',1271default=False,1272help="Enable SITL OSD")1273group_sim.add_option("", "--osdmsp",1274action='store_true',1275dest='OSDMSP',1276default=False,1277help="Enable SITL OSD using MSP")1278group_sim.add_option("", "--tonealarm",1279action='store_true',1280dest='tonealarm',1281default=False,1282help="Enable SITL ToneAlarm")1283group_sim.add_option("", "--rgbled",1284action='store_true',1285dest='rgbled',1286default=False,1287help="Enable SITL RGBLed")1288group_sim.add_option("", "--add-param-file",1289type='string',1290action="append",1291default=None,1292help="Add a parameters file to use")1293group_sim.add_option("", "--no-extra-ports",1294action='store_true',1295dest='no_extra_ports',1296default=False,1297help="Disable setup of UDP 14550 and 14551 output")1298group_sim.add_option("-Z", "--swarm",1299type='string',1300default=None,1301help="Specify path of swarminit.txt for shifting spawn location")1302group_sim.add_option("", "--auto-offset-line",1303type="string",1304default=None,1305help="Argument of form BEARING,DISTANCE. When running multiple instances, form a line along bearing with an interval of DISTANCE", # NOQA1306)1307group_sim.add_option("--flash-storage",1308action='store_true',1309help="use flash storage emulation")1310group_sim.add_option("--fram-storage",1311action='store_true',1312help="use fram storage emulation")1313group_sim.add_option("--enable-ekf2",1314action='store_true',1315help="disable EKF2 in build")1316group_sim.add_option("--disable-ekf3",1317action='store_true',1318help="disable EKF3 in build")1319group_sim.add_option("", "--start-time",1320default=None,1321type='string',1322help="specify simulation start time in format YYYY-MM-DD-HH:MM in your local time zone")1323group_sim.add_option("", "--sysid",1324type='int',1325default=None,1326help="Set SYSID_THISMAV")1327group_sim.add_option("--postype-single",1328action='store_true',1329help="force single precision postype_t")1330group_sim.add_option("--ekf-double",1331action='store_true',1332help="use double precision in EKF")1333group_sim.add_option("--ekf-single",1334action='store_true',1335help="use single precision in EKF")1336group_sim.add_option("", "--slave",1337type='int',1338default=0,1339help="Set the number of JSON slave")1340group_sim.add_option("", "--auto-sysid",1341default=False,1342action='store_true',1343help="Set SYSID_THISMAV based upon instance number")1344group_sim.add_option("", "--sim-address",1345type=str,1346default="127.0.0.1",1347help="IP address of the simulator. Defaults to localhost")1348group_sim.add_option("--enable-dds", action='store_true',1349help="Enable the dds client to connect with ROS2/DDS")1350group_sim.add_option("--disable-networking", action='store_true',1351help="Disable networking APIs")1352group_sim.add_option("--enable-ppp", action='store_true',1353help="Enable PPP networking")1354group_sim.add_option("--enable-networking-tests", action='store_true',1355help="Enable networking tests")1356group_sim.add_option("--enable-fgview", action='store_true',1357help="Enable FlightGear output")13581359parser.add_option_group(group_sim)136013611362# special-cased parameters for mavproxy, because some people's fingers1363# have long memories, and they don't want to use -C :-)1364group = optparse.OptionGroup(parser,1365"Compatibility MAVProxy options "1366"(consider using --mavproxy-args instead)")1367group.add_option("", "--out",1368default=[],1369type='string',1370action="append",1371help="create an additional mavlink output")1372group.add_option("", "--map",1373default=False,1374action='store_true',1375help="load map module on startup")1376group.add_option("", "--mavcesium",1377default=False,1378action='store_true',1379help="load MAVCesium module on startup")13801381group.add_option("", "--console",1382default=False,1383action='store_true',1384help="load console module on startup")1385group.add_option("", "--aircraft",1386default=None,1387help="store state and logs in named directory")1388group.add_option("", "--moddebug",1389default=0,1390type=int,1391help="mavproxy module debug")1392group.add_option("", "--no-rcin",1393action='store_true',1394help="disable mavproxy rcin")1395parser.add_option_group(group)13961397group_completion = optparse.OptionGroup(parser, "Completion helpers")1398group_completion.add_option("", "--list-vehicle",1399action='store_true',1400help="List the vehicles")1401group_completion.add_option("", "--list-frame",1402type='string',1403default=None,1404help="List the vehicle frames")1405parser.add_option_group(group_completion)14061407cmd_opts, cmd_args = parser.parse_args()14081409if cmd_opts.list_vehicle:1410print(' '.join(vinfo.options.keys()))1411sys.exit(1)1412if cmd_opts.list_frame:1413frame_options = sorted(vinfo.options[cmd_opts.list_frame]["frames"].keys())1414frame_options_string = ' '.join(frame_options)1415print(frame_options_string)1416sys.exit(1)14171418# clean up processes at exit:1419atexit.register(kill_tasks)14201421progress("Start")14221423if cmd_opts.sim_vehicle_sh_compatible and cmd_opts.jobs is None:1424cmd_opts.jobs = 114251426# validate parameters1427if cmd_opts.valgrind and (cmd_opts.gdb or cmd_opts.gdb_stopped or cmd_opts.lldb or cmd_opts.lldb_stopped):1428print("May not use valgrind with gdb or lldb")1429sys.exit(1)14301431if cmd_opts.valgrind and cmd_opts.callgrind:1432print("May not use valgrind with callgrind")1433sys.exit(1)14341435if cmd_opts.strace and (cmd_opts.gdb or cmd_opts.gdb_stopped or cmd_opts.lldb or cmd_opts.lldb_stopped):1436print("May not use strace with gdb or lldb")1437sys.exit(1)14381439if (cmd_opts.gdb or cmd_opts.gdb_stopped) and (cmd_opts.lldb or cmd_opts.lldb_stopped):1440print("May not use lldb with gdb")1441sys.exit(1)14421443if cmd_opts.instance < 0:1444print("May not specify a negative instance ID")1445sys.exit(1)14461447if cmd_opts.count < 1:1448print("May not specify a count less than 1")1449sys.exit(1)14501451if cmd_opts.strace and cmd_opts.valgrind:1452print("valgrind and strace almost certainly not a good idea")14531454if cmd_opts.strace and cmd_opts.callgrind:1455print("callgrind and strace almost certainly not a good idea")14561457if cmd_opts.sysid and cmd_opts.auto_sysid:1458print("Cannot use auto-sysid together with sysid")1459sys.exit(1)14601461# magically determine vehicle type (if required):1462if cmd_opts.vehicle is None:1463cwd = os.getcwd()1464cmd_opts.vehicle = os.path.basename(cwd)14651466if cmd_opts.vehicle not in vinfo.options:1467# try in parent directories, useful for having config in subdirectories1468cwd = os.getcwd()1469while cwd:1470bname = os.path.basename(cwd)1471if not bname:1472break1473if bname in vinfo.options:1474cmd_opts.vehicle = bname1475break1476cwd = os.path.dirname(cwd)14771478if cmd_opts.vehicle in vehicle_map:1479cmd_opts.vehicle = vehicle_map[cmd_opts.vehicle]1480elif cmd_opts.vehicle.lower() in vehicle_map:1481cmd_opts.vehicle = vehicle_map[cmd_opts.vehicle.lower()]14821483# try to validate vehicle1484if cmd_opts.vehicle not in vinfo.options:1485progress('''1486** Is (%s) really your vehicle type?1487Perhaps you could try -v %s1488You could also try changing directory to e.g. the ArduCopter subdirectory1489''' % (cmd_opts.vehicle, vehicle_options_string))1490sys.exit(1)14911492# determine frame options (e.g. build type might be "sitl")1493if cmd_opts.frame is None:1494cmd_opts.frame = vinfo.options[cmd_opts.vehicle]["default_frame"]14951496frame_infos = vinfo.options_for_frame(cmd_opts.frame,1497cmd_opts.vehicle,1498cmd_opts)14991500vehicle_dir = os.path.realpath(os.path.join(root_dir, cmd_opts.vehicle))1501if not os.path.exists(vehicle_dir):1502print("vehicle directory (%s) does not exist" % (vehicle_dir,))1503sys.exit(1)15041505if cmd_opts.instances is not None:1506instances = set()1507for i in cmd_opts.instances.split(' '):1508i = (int)(i)1509if i < 0:1510print("May not specify a negative instance ID")1511sys.exit(1)1512instances.add(i)1513instances = sorted(instances) # to list1514else:1515instances = range(cmd_opts.instance, cmd_opts.instance + cmd_opts.count)15161517if cmd_opts.instance == 0:1518kill_tasks()15191520if cmd_opts.tracker:1521start_antenna_tracker(cmd_opts)15221523if cmd_opts.can_peripherals or frame_infos.get('periph_params_filename', None) is not None:1524start_CAN_Periph(cmd_opts, frame_infos)15251526if cmd_opts.custom_location:1527location = [(float)(x) for x in cmd_opts.custom_location.split(",")]1528progress("Starting up at %s" % (location,))1529elif cmd_opts.location is not None:1530location = find_location_by_name(cmd_opts.location)1531progress("Starting up at %s (%s)" % (location, cmd_opts.location))1532else:1533progress("Starting up at SITL location")1534location = None1535if cmd_opts.swarm is not None:1536offsets = find_offsets(instances, cmd_opts.swarm)1537elif cmd_opts.auto_offset_line is not None:1538if location is None:1539raise ValueError("location needed for auto-offset-line")1540(bearing, metres) = cmd_opts.auto_offset_line.split(",")1541bearing = float(bearing)1542metres = float(metres)1543dist = 01544offsets = {}1545for x in instances:1546offsets[x] = [dist*math.sin(math.radians(bearing)), dist*math.cos(math.radians(bearing)), 0, 0]1547dist += metres1548else:1549offsets = {x: [0.0, 0.0, 0.0, None] for x in instances}1550if location is not None:1551spawns = find_spawns(location, offsets)1552else:1553spawns = None15541555if cmd_opts.use_dir is not None:1556base_dir = os.path.realpath(cmd_opts.use_dir)1557try:1558os.makedirs(base_dir)1559except OSError as exception:1560if exception.errno != errno.EEXIST:1561raise1562os.chdir(base_dir)1563else:1564base_dir = os.getcwd()1565instance_dir = []1566if len(instances) == 1:1567instance_dir.append(base_dir)1568else:1569for i in instances:1570i_dir = os.path.join(base_dir, str(i))1571try:1572os.makedirs(i_dir)1573except OSError as exception:1574if exception.errno != errno.EEXIST:1575raise1576finally:1577instance_dir.append(i_dir)15781579if True:1580if not cmd_opts.no_rebuild: # i.e. we should rebuild1581do_build(cmd_opts, frame_infos)15821583if cmd_opts.fresh_params:1584do_build_parameters(cmd_opts.vehicle)15851586if cmd_opts.vehicle_binary is not None:1587vehicle_binary = cmd_opts.vehicle_binary1588else:1589binary_basedir = "build/sitl"1590vehicle_binary = os.path.join(root_dir,1591binary_basedir,1592frame_infos["waf_target"])15931594if not os.path.exists(vehicle_binary):1595print("Vehicle binary (%s) does not exist" % (vehicle_binary,))1596sys.exit(1)15971598start_vehicle(vehicle_binary,1599cmd_opts,1600frame_infos,1601spawns=spawns)160216031604if cmd_opts.delay_start:1605progress("Sleeping for %f seconds" % (cmd_opts.delay_start,))1606time.sleep(float(cmd_opts.delay_start))16071608tmp = None1609if cmd_opts.frame in ['scrimmage-plane', 'scrimmage-copter']:1610# import only here so as to avoid jinja dependency in whole script1611from jinja2 import Environment, FileSystemLoader1612from tempfile import mkstemp1613entities = []1614config = {}1615config['plane'] = cmd_opts.vehicle == 'ArduPlane'1616if location is not None:1617config['lat'] = location[0]1618config['lon'] = location[1]1619config['alt'] = location[2]1620entities = {}1621for i in instances:1622(x, y, z, heading) = offsets[i]1623entities[i] = {1624'x': x, 'y': y, 'z': z, 'heading': heading,1625'to_ardupilot_port': 9003 + i * 10,1626'from_ardupilot_port': 9002 + i * 10,1627'to_ardupilot_ip': '127.0.0.1'1628}1629if cmd_opts.scrimmage_args is not None:1630scrimmage_args = cmd_opts.scrimmage_args.split(',')1631global_opts = ['terrain']1632instance_opts = ['motion_model', 'visual_model']1633for arg in scrimmage_args:1634arg = arg.split('=', 2)1635if len(arg) == 2:1636k, v = arg1637if k in global_opts:1638config[k] = v1639elif k in instance_opts:1640for i in entities:1641# explicit instance args take precedence; don't overwrite1642if k not in entities[i]:1643entities[i][k] = v1644elif len(arg) == 3:1645i, k, v = arg1646try:1647i = int(i)1648except ValueError:1649continue1650if i in entities and k in instance_opts:1651entities[i][k] = v1652config['entities'] = list(entities.values())1653env = Environment(loader=FileSystemLoader(os.path.join(autotest_dir, 'template')))1654mission = env.get_template('scrimmage.xml.j2').render(**config)1655tmp = mkstemp()1656atexit.register(os.remove, tmp[1])16571658with os.fdopen(tmp[0], 'w') as fd:1659fd.write(mission)1660run_in_terminal_window('SCRIMMAGE', ['scrimmage', tmp[1]])166116621663if cmd_opts.delay_start:1664progress("Sleeping for %f seconds" % (cmd_opts.delay_start,))1665time.sleep(float(cmd_opts.delay_start))16661667try:1668if cmd_opts.no_mavproxy:1669time.sleep(3) # output our message after run_in_terminal_window.sh's1670progress("Waiting for SITL to exit")1671wait_unlimited()1672else:1673start_mavproxy(cmd_opts, frame_infos)1674except KeyboardInterrupt:1675progress("Keyboard Interrupt received ...")16761677sys.exit(0)167816791680