2016-04-27 22:34:15 -03:00
#!/usr/bin/env python
2016-07-04 15:28:06 -03:00
"""
Framework to start a simulated vehicle and connect it to MAVProxy .
Peter Barker , April 2016
based on sim_vehicle . sh by Andrew Tridgell , October 2011
"""
2016-11-08 06:37:02 -04:00
from __future__ import print_function
2016-04-27 22:34:15 -03:00
import atexit
2016-07-04 15:28:06 -03:00
import getpass
import optparse
2016-04-27 22:34:15 -03:00
import os
2016-05-13 17:55:06 -03:00
import os . path
2016-11-14 22:52:34 -04:00
import re
2016-07-04 15:28:06 -03:00
import signal
2016-04-27 22:34:15 -03:00
import subprocess
2016-07-04 15:28:06 -03:00
import sys
2016-04-27 22:34:15 -03:00
import tempfile
import time
2016-08-29 21:49:16 -03:00
import shlex
2016-04-27 22:34:15 -03:00
2016-06-23 12:27:28 -03:00
# List of open terminal windows for macosx
windowID = [ ]
2016-04-27 22:34:15 -03:00
class CompatError ( Exception ) :
2016-07-04 15:28:06 -03:00
""" A custom exception class to hold state if we encounter the parse error we are looking for """
def __init__ ( self , error , opts , rargs ) :
Exception . __init__ ( self , error )
2016-04-27 22:34:15 -03:00
self . opts = opts
self . rargs = rargs
2016-07-04 15:28:06 -03:00
2016-04-27 22:34:15 -03:00
class CompatOptionParser ( optparse . OptionParser ) :
2016-07-04 15:28:06 -03:00
""" An option parser which emulates the behaviour of the old sim_vehicle.sh; if passed -C, the first argument not understood starts a list of arguments that are passed straight to mavproxy """
2016-04-27 22:34:15 -03:00
def __init__ ( self , * args , * * kwargs ) :
optparse . OptionParser . __init__ ( self , * args , * * kwargs )
def error ( self , error ) :
2016-07-04 15:28:06 -03:00
""" Override default error handler called by optparse.OptionParser.parse_args when a parse error occurs; raise a detailed exception which can be caught """
2016-04-27 22:34:15 -03:00
if error . find ( " no such option " ) != - 1 :
raise CompatError ( error , self . values , self . rargs )
optparse . OptionParser . error ( self , error )
2016-07-04 15:28:06 -03:00
def parse_args ( self , args = None , values = None ) :
""" Wrap parse_args so we can catch the exception raised upon discovering the known parameter parsing error """
2016-04-27 22:34:15 -03:00
try :
opts , args = optparse . OptionParser . parse_args ( self )
except CompatError as e :
if not e . opts . sim_vehicle_sh_compatible :
print ( e )
2016-04-28 23:16:53 -03:00
print ( " Perhaps you want --sim_vehicle_sh_compatible (-C)? " )
2016-04-27 22:34:15 -03:00
sys . exit ( 1 )
if e . opts . mavproxy_args :
print ( " --mavproxy-args not permitted in compat mode " )
sys . exit ( 1 )
args = [ ]
opts = e . opts
2016-07-04 15:28:06 -03:00
mavproxy_args = [ str ( e ) [ 16 : ] ] # this trims "no such option" off
2016-04-27 22:34:15 -03:00
mavproxy_args . extend ( e . rargs )
opts . ensure_value ( " mavproxy_args " , " " . join ( mavproxy_args ) )
return opts , args
2016-07-04 15:28:06 -03:00
def cygwin_pidof ( proc_name ) :
""" Thanks to kata198 for this:
2016-04-28 23:16:53 -03:00
https : / / github . com / kata198 / cygwin - ps - misc / blob / master / pidof
2016-07-04 15:28:06 -03:00
"""
pipe = subprocess . Popen ( " ps -ea | grep " + proc_name , shell = True , stdout = subprocess . PIPE )
output_lines = pipe . stdout . read ( ) . replace ( " \r " , " " ) . split ( " \n " )
2016-04-28 23:16:53 -03:00
ret = pipe . wait ( )
pids = [ ]
if ret != 0 :
# No results
2016-07-04 15:28:06 -03:00
return [ ]
for line in output_lines :
if not line :
continue
line_split = [ item for item in line . split ( ' ' ) if item ]
cmd = line_split [ - 1 ] . split ( ' / ' ) [ - 1 ]
if cmd == proc_name :
try :
pid = int ( line_split [ 0 ] . strip ( ) )
except :
pid = int ( line_split [ 1 ] . strip ( ) )
2016-08-22 00:59:22 -03:00
if pid not in pids :
pids . append ( pid )
2016-04-28 23:16:53 -03:00
return pids
2016-07-04 15:28:06 -03:00
2016-04-28 23:16:53 -03:00
def under_cygwin ( ) :
2016-07-04 15:28:06 -03:00
""" Return if Cygwin binary exist """
2016-04-28 23:16:53 -03:00
return os . path . exists ( " /usr/bin/cygstart " )
2016-07-04 15:28:06 -03:00
2016-07-06 11:26:34 -03:00
def under_macos ( ) :
return sys . platform == ' darwin '
2016-07-04 15:28:06 -03:00
2016-04-28 23:16:53 -03:00
def kill_tasks_cygwin ( victims ) :
2016-07-04 15:28:06 -03:00
""" Shell out to ps -ea to find processes to kill """
2016-04-28 23:16:53 -03:00
for victim in list ( victims ) :
pids = cygwin_pidof ( victim )
# progress("pids for (%s): %s" % (victim,",".join([ str(p) for p in pids])))
for apid in pids :
os . kill ( apid , signal . SIGKILL )
2016-07-04 15:28:06 -03:00
2016-07-06 11:26:34 -03:00
def kill_tasks_macos ( ) :
for window in windowID :
cmd = " osascript -e \' tell application \" Terminal \" to close (window(get index of window id %s )) \' " % window
os . system ( cmd )
2016-07-04 15:28:06 -03:00
2016-06-23 00:31:38 -03:00
def kill_tasks_psutil ( victims ) :
2016-07-04 15:28:06 -03:00
""" Use the psutil module to kill tasks by name. Sadly, this module is not available on Windows, but when it is we should be able to *just* use this routine """
2016-06-23 00:31:38 -03:00
import psutil
for proc in psutil . process_iter ( ) :
if proc . status == psutil . STATUS_ZOMBIE :
continue
if proc . name in victims :
proc . kill ( )
2016-07-04 15:28:06 -03:00
2016-06-23 00:31:38 -03:00
def kill_tasks_pkill ( victims ) :
2016-07-04 15:28:06 -03:00
""" Shell out to pkill(1) to kill processed by name """
for victim in victims : # pkill takes a single pattern, so iterate
cmd = [ " pkill " , victim ]
2016-06-23 00:31:38 -03:00
run_cmd_blocking ( " pkill " , cmd , quiet = True )
2016-07-04 15:28:06 -03:00
2016-06-23 00:31:38 -03:00
class BobException ( Exception ) :
2016-07-04 15:28:06 -03:00
""" Handle Bob ' s Exceptions """
2016-06-23 00:31:38 -03:00
pass
2016-07-04 15:28:06 -03:00
2016-04-27 22:34:15 -03:00
def kill_tasks ( ) :
2016-07-04 15:28:06 -03:00
""" Clean up stray processes by name. This is a somewhat shotgun approach """
2016-06-23 00:33:52 -03:00
progress ( " Killing tasks " )
2016-06-23 00:31:38 -03:00
try :
2016-07-31 07:22:06 -03:00
victim_names = {
2016-06-23 00:33:52 -03:00
' JSBSim ' ,
' lt-JSBSim ' ,
' ArduPlane.elf ' ,
' ArduCopter.elf ' ,
' APMrover2.elf ' ,
' AntennaTracker.elf ' ,
' JSBSIm.exe ' ,
' MAVProxy.exe ' ,
' runsim.py ' ,
' AntennaTracker.elf ' ,
2016-07-31 07:22:06 -03:00
}
2016-08-22 00:59:22 -03:00
for frame in _options_for_frame . keys ( ) :
2016-07-31 07:22:06 -03:00
if " waf_target " not in _options_for_frame [ frame ] :
2016-08-22 00:59:22 -03:00
continue
exe_name = os . path . basename ( _options_for_frame [ frame ] [ " waf_target " ] )
victim_names . add ( exe_name )
2016-06-23 00:33:52 -03:00
if under_cygwin ( ) :
return kill_tasks_cygwin ( victim_names )
2016-07-06 11:26:34 -03:00
if under_macos ( ) :
return kill_tasks_macos ( )
2016-06-23 00:33:52 -03:00
try :
kill_tasks_psutil ( victim_names )
2016-07-04 15:28:06 -03:00
except ImportError :
2016-06-23 00:33:52 -03:00
kill_tasks_pkill ( victim_names )
except Exception as e :
progress ( " kill_tasks failed: {} " . format ( str ( e ) ) )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
2016-04-27 22:34:15 -03:00
def check_jsbsim_version ( ) :
2016-07-04 15:28:06 -03:00
""" Assert that the JSBSim we will run is the one we expect to run """
2016-04-28 23:16:53 -03:00
jsbsim_cmd = [ " JSBSim " , " --version " ]
progress_cmd ( " Get JSBSim version " , jsbsim_cmd )
2016-05-15 22:58:53 -03:00
try :
jsbsim_version = subprocess . Popen ( jsbsim_cmd , stdout = subprocess . PIPE ) . communicate ( ) [ 0 ]
2016-07-04 15:28:06 -03:00
except OSError :
jsbsim_version = ' ' # this value will trigger the ".index"
# check below and produce a reasonable
# error message
2016-04-27 22:34:15 -03:00
try :
2016-11-08 06:37:02 -04:00
jsbsim_version . index ( b " ArduPilot " )
2016-04-27 22:34:15 -03:00
except ValueError :
2016-07-04 15:28:06 -03:00
print ( r """
2016-04-27 22:34:15 -03:00
== == == == == == == == == == == == == == == == == == == == == == == == == == == == =
You need the latest ArduPilot version of JSBSim installed
and in your \$ PATH
Please get it from git : / / github . com / tridge / jsbsim . git
See
2016-07-25 08:57:26 -03:00
http : / / ardupilot . org / dev / docs / setting - up - sitl - on - linux . html
2016-04-27 22:34:15 -03:00
for more details
== == == == == == == == == == == == == == == == == == == == == == == == == == == == =
2016-07-04 15:28:06 -03:00
""" )
2016-04-27 22:34:15 -03:00
sys . exit ( 1 )
2016-07-04 15:28:06 -03:00
2016-04-27 22:34:15 -03:00
def progress ( text ) :
2016-07-04 15:28:06 -03:00
""" Display sim_vehicle progress text """
2016-04-27 22:34:15 -03:00
print ( " SIM_VEHICLE: " + text )
2016-07-04 15:28:06 -03:00
2016-04-27 22:34:15 -03:00
def find_autotest_dir ( ) :
2016-07-04 15:28:06 -03:00
""" Return path to autotest directory """
2016-04-27 22:34:15 -03:00
return os . path . dirname ( os . path . realpath ( __file__ ) )
2016-07-04 15:28:06 -03:00
2016-05-12 00:32:36 -03:00
def find_root_dir ( ) :
2016-07-04 15:28:06 -03:00
""" Return path to root directory """
2016-05-12 00:32:36 -03:00
return os . path . realpath ( os . path . join ( find_autotest_dir ( ) , ' ../.. ' ) )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
"""
2016-04-28 23:16:53 -03:00
make_target : option passed to make to create binaries . Usually sitl , and " -debug " may be appended if - D is passed to sim_vehicle . py
2016-04-27 22:34:15 -03:00
default_params_filename : filename of default parameters file . Taken to be relative to autotest dir .
extra_mavlink_cmds : extra parameters that will be passed to mavproxy
2016-07-04 15:28:06 -03:00
"""
2016-04-27 22:34:15 -03:00
_options_for_frame = {
2016-05-13 16:47:12 -03:00
" calibration " : {
" extra_mavlink_cmds " : " module load sitl_calibration; " ,
} ,
2016-05-23 10:38:06 -03:00
# COPTER
2016-04-27 22:34:15 -03:00
" + " : {
2017-01-09 05:55:20 -04:00
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter.parm " ,
2016-04-27 22:34:15 -03:00
} ,
" quad " : {
" model " : " + " ,
2017-01-09 05:55:20 -04:00
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter.parm " ,
2016-04-27 22:34:15 -03:00
} ,
" X " : {
2017-01-09 05:55:20 -04:00
" waf_target " : " bin/arducopter " ,
2016-04-27 22:34:15 -03:00
# this param set FRAME doesn't actually work because mavproxy
# won't set a parameter unless it knows of it, and the param fetch happens asynchronously
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter.parm " ,
2016-07-04 15:28:06 -03:00
" extra_mavlink_cmds " : " param fetch frame; param set FRAME 1; " ,
2016-04-27 22:34:15 -03:00
} ,
2016-05-23 10:30:59 -03:00
" hexa " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter.parm " ,
2016-05-23 10:30:59 -03:00
} ,
2016-11-29 17:02:03 -04:00
" octa-quad " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arducopter " ,
2016-11-29 17:02:03 -04:00
" default_params_filename " : " default_params/copter.parm " ,
} ,
2016-04-27 22:34:15 -03:00
" octa " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter.parm " ,
2016-04-27 22:34:15 -03:00
} ,
" tri " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter-tri.parm " ,
2016-04-27 22:34:15 -03:00
} ,
" y6 " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter-y6.parm " ,
2016-04-27 22:34:15 -03:00
} ,
2016-05-23 10:38:06 -03:00
# COPTER TYPES
" IrisRos " : {
2017-01-09 05:55:20 -04:00
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter.parm " ,
2016-05-23 10:38:06 -03:00
} ,
2016-04-27 22:34:15 -03:00
" firefly " : {
2016-04-28 23:16:53 -03:00
" waf_target " : " bin/arducopter-firefly " ,
2016-07-25 12:17:21 -03:00
" default_params_filename " : " default_params/firefly.parm " ,
2016-04-27 22:34:15 -03:00
} ,
2016-05-23 10:38:06 -03:00
# HELICOPTER
2016-04-27 22:34:15 -03:00
" heli " : {
2016-07-04 15:28:06 -03:00
" make_target " : " sitl-heli " ,
2017-01-10 01:23:45 -04:00
" waf_target " : " bin/arducopter-heli " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter-heli.parm " ,
2016-04-27 22:34:15 -03:00
} ,
2016-05-23 10:38:06 -03:00
" heli-dual " : {
" make_target " : " sitl-heli-dual " ,
2016-07-04 15:28:06 -03:00
" waf_target " : " bin/arducopter-coax " , # is this correct? -pb201604301447
2016-04-27 22:34:15 -03:00
} ,
2016-05-23 10:38:06 -03:00
" heli-compound " : {
" make_target " : " sitl-heli-compound " ,
2016-07-04 15:28:06 -03:00
" waf_target " : " bin/arducopter-coax " , # is this correct? -pb201604301447
2016-04-27 22:34:15 -03:00
} ,
2016-05-26 03:29:37 -03:00
" singlecopter " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter-single.parm " ,
2016-05-26 03:29:37 -03:00
} ,
2016-05-26 04:09:31 -03:00
" coaxcopter " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arducopter " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/copter-coax.parm " ,
2016-05-26 04:09:31 -03:00
} ,
2016-05-23 10:38:06 -03:00
# PLANE
2016-07-04 15:28:06 -03:00
" quadplane-tilttri " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arduplane " ,
2016-07-25 12:17:21 -03:00
" default_params_filename " : " default_params/quadplane-tilttri.parm " ,
2016-05-01 19:52:43 -03:00
} ,
2016-07-04 15:28:06 -03:00
" quadplane-tri " : {
2017-01-09 05:55:20 -04:00
" make_target " : " sitl " ,
" waf_target " : " bin/arduplane " ,
2016-07-25 12:17:21 -03:00
" default_params_filename " : " default_params/quadplane-tri.parm " ,
2016-06-30 01:15:59 -03:00
} ,
2016-07-03 09:03:10 -03:00
" quadplane-cl84 " : {
" make_target " : " sitl " ,
" waf_target " : " bin/arduplane " ,
" default_params_filename " : " default_params/quadplane-cl84.parm " ,
} ,
2016-04-27 22:34:15 -03:00
" quadplane " : {
2016-04-28 23:16:53 -03:00
" waf_target " : " bin/arduplane " ,
2016-07-25 12:17:21 -03:00
" default_params_filename " : " default_params/quadplane.parm " ,
2016-04-27 22:34:15 -03:00
} ,
" plane-elevon " : {
2016-04-28 23:16:53 -03:00
" waf_target " : " bin/arduplane " ,
2016-07-25 12:17:21 -03:00
" default_params_filename " : " default_params/plane-elevons.parm " ,
2016-04-27 22:34:15 -03:00
} ,
" plane-vtail " : {
2016-04-28 23:16:53 -03:00
" waf_target " : " bin/arduplane " ,
2016-07-25 12:17:21 -03:00
" default_params_filename " : " default_params/plane-vtail.parm " ,
2016-04-27 22:34:15 -03:00
} ,
" plane " : {
2016-04-28 23:16:53 -03:00
" waf_target " : " bin/arduplane " ,
2016-07-25 12:17:21 -03:00
" default_params_filename " : " default_params/plane.parm " ,
2016-04-27 22:34:15 -03:00
} ,
2016-05-23 10:38:06 -03:00
# ROVER
2016-05-12 10:30:01 -03:00
" rover " : {
" waf_target " : " bin/ardurover " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/rover.parm " ,
2016-05-12 10:30:01 -03:00
} ,
2016-05-23 21:21:04 -03:00
" rover-skid " : {
" waf_target " : " bin/ardurover " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/rover-skid.parm " ,
2016-05-24 08:02:36 -03:00
} ,
2016-09-16 05:14:23 -03:00
# SIM
" gazebo-iris " : {
2017-01-09 05:55:20 -04:00
" waf_target " : " bin/arducopter " ,
2016-09-14 20:36:56 -03:00
" default_params_filename " : " default_params/gazebo-iris.parm " ,
} ,
2016-09-16 05:14:23 -03:00
" gazebo-zephyr " : {
2016-09-14 20:36:56 -03:00
" waf_target " : " bin/arduplane " ,
" default_params_filename " : " default_params/gazebo-zephyr.parm " ,
2016-05-23 10:38:06 -03:00
} ,
" last_letter " : {
" waf_target " : " bin/arduplane " ,
} ,
" CRRCSim " : {
" waf_target " : " bin/arduplane " ,
} ,
" jsbsim " : {
" waf_target " : " bin/arduplane " ,
2016-08-03 17:48:36 -03:00
" default_params_filename " : " default_params/plane-jsbsim.parm " ,
2016-05-23 21:21:04 -03:00
} ,
2016-04-27 22:34:15 -03:00
}
2016-05-07 20:34:42 -03:00
_default_waf_target = {
" ArduPlane " : " bin/arduplane " ,
2017-01-09 05:55:20 -04:00
" ArduCopter " : " bin/arducopter " ,
2016-05-11 04:43:06 -03:00
" APMrover2 " : " bin/ardurover " ,
2016-05-07 20:34:42 -03:00
" AntennaTracker " : " bin/antennatracker " ,
}
2016-07-04 15:28:06 -03:00
2016-05-07 20:34:42 -03:00
def default_waf_target ( vehicle ) :
2016-07-04 15:28:06 -03:00
""" Returns a waf target based on vehicle type, which is often determined by which directory the user is in """
2016-05-07 20:34:42 -03:00
return _default_waf_target [ vehicle ]
2016-07-04 15:28:06 -03:00
2016-05-07 20:34:42 -03:00
def options_for_frame ( frame , vehicle , opts ) :
2016-07-04 15:28:06 -03:00
""" Return informatiom about how to sitl for frame e.g. build-type==sitl """
2016-05-07 11:31:23 -03:00
ret = None
2016-04-27 22:34:15 -03:00
if frame in _options_for_frame :
ret = _options_for_frame [ frame ]
else :
2016-09-14 20:36:56 -03:00
for p in [ " octa " , " tri " , " y6 " , " firefly " , " heli " , " gazebo " , " last_letter " , " jsbsim " , " quadplane " , " plane-elevon " , " plane-vtail " , " plane " ] :
2016-04-27 22:34:15 -03:00
if frame . startswith ( p ) :
ret = _options_for_frame [ p ]
break
if ret is None :
if frame . endswith ( " -heli " ) :
ret = _options_for_frame [ " heli " ]
if ret is None :
ret = { }
2016-07-04 15:28:06 -03:00
if " model " not in ret :
2016-04-27 22:34:15 -03:00
ret [ " model " ] = frame
2016-04-28 23:16:53 -03:00
2016-07-04 15:28:06 -03:00
if " sitl-port " not in ret :
2016-06-22 01:10:27 -03:00
ret [ " sitl-port " ] = True
2016-06-22 00:42:45 -03:00
if opts . model is not None :
ret [ " model " ] = opts . model
2016-06-30 07:26:14 -03:00
2016-07-04 15:28:06 -03:00
if ( ret [ " model " ] . find ( " xplane " ) != - 1 or ret [ " model " ] . find ( " flightaxis " ) != - 1 ) :
2016-06-30 07:26:14 -03:00
ret [ " sitl-port " ] = False
2016-06-22 00:42:45 -03:00
2016-07-04 15:28:06 -03:00
if " make_target " not in ret :
2016-04-28 23:16:53 -03:00
ret [ " make_target " ] = " sitl "
2016-07-04 15:28:06 -03:00
if " waf_target " not in ret :
2016-05-07 20:34:42 -03:00
ret [ " waf_target " ] = default_waf_target ( vehicle )
2016-04-27 22:34:15 -03:00
if opts . build_target is not None :
2016-04-28 23:16:53 -03:00
ret [ " make_target " ] = opts . build_target
ret [ " waf_target " ] = opts . build_target
2016-04-27 22:34:15 -03:00
return ret
2016-07-04 15:28:06 -03:00
2016-05-25 06:40:14 -03:00
def do_build_waf ( opts , frame_options ) :
2016-07-04 15:28:06 -03:00
""" Build sitl using waf """
2016-04-28 23:16:53 -03:00
progress ( " WAF build " )
old_dir = os . getcwd ( )
2016-05-12 00:32:36 -03:00
root_dir = find_root_dir ( )
2016-04-28 23:16:53 -03:00
os . chdir ( root_dir )
2016-05-12 00:32:36 -03:00
waf_light = os . path . join ( root_dir , " modules/waf/waf-light " )
2016-04-28 23:16:53 -03:00
2016-07-04 15:28:06 -03:00
cmd_configure = [ waf_light , " configure " , " --board " , " sitl " ]
2016-05-06 00:11:53 -03:00
if opts . debug :
cmd_configure . append ( " --debug " )
2016-08-29 21:49:16 -03:00
pieces = [ shlex . split ( x ) for x in opts . waf_configure_args ]
for piece in pieces :
cmd_configure . extend ( piece )
2016-05-06 00:11:53 -03:00
2016-08-29 21:49:16 -03:00
run_cmd_blocking ( " Configure waf " , cmd_configure , check = True )
2016-04-28 23:16:53 -03:00
if opts . clean :
run_cmd_blocking ( " Building clean " , [ waf_light , " clean " ] )
2016-05-11 13:15:30 -03:00
cmd_build = [ waf_light , " build " , " --target " , frame_options [ " waf_target " ] ]
if opts . jobs is not None :
cmd_build + = [ ' -j ' , str ( opts . jobs ) ]
2016-08-29 21:49:16 -03:00
pieces = [ shlex . split ( x ) for x in opts . waf_build_args ]
for piece in pieces :
cmd_build . extend ( piece )
2016-05-11 13:15:30 -03:00
2016-05-11 23:44:56 -03:00
_ , sts = run_cmd_blocking ( " Building " , cmd_build )
2016-04-28 23:16:53 -03:00
2016-07-04 15:28:06 -03:00
if sts != 0 : # build failed
2016-05-07 20:34:42 -03:00
if opts . rebuild_on_failure :
progress ( " Build failed; cleaning and rebuilding " )
run_cmd_blocking ( " Building clean " , [ waf_light , " clean " ] )
2016-04-28 23:16:53 -03:00
2016-05-11 23:44:56 -03:00
_ , sts = run_cmd_blocking ( " Building " , cmd_build )
2016-05-07 20:34:42 -03:00
if sts != 0 :
progress ( " Build failed " )
sys . exit ( 1 )
else :
2016-04-28 23:16:53 -03:00
progress ( " Build failed " )
sys . exit ( 1 )
os . chdir ( old_dir )
def do_build ( vehicledir , opts , frame_options ) :
2016-07-04 15:28:06 -03:00
""" Build build target (e.g. sitl) in directory vehicledir """
2016-04-28 23:16:53 -03:00
if opts . build_system == ' waf ' :
2016-05-25 06:40:14 -03:00
return do_build_waf ( opts , frame_options )
2016-04-28 23:16:53 -03:00
2016-04-27 22:34:15 -03:00
old_dir = os . getcwd ( )
os . chdir ( vehicledir )
if opts . clean :
2016-04-28 23:16:53 -03:00
run_cmd_blocking ( " Building clean " , [ " make " , " clean " ] )
build_target = frame_options [ " make_target " ]
if opts . debug :
build_target + = " -debug "
2016-05-11 13:15:30 -03:00
build_cmd = [ " make " , build_target ]
if opts . jobs is not None :
build_cmd + = [ ' -j ' , str ( opts . jobs ) ]
2016-07-04 15:28:06 -03:00
_ , sts = run_cmd_blocking ( " Building %s " % build_target , build_cmd )
2016-04-27 22:34:15 -03:00
if sts != 0 :
progress ( " Build failed; cleaning and rebuilding " )
2016-05-11 23:44:56 -03:00
run_cmd_blocking ( " Cleaning " , [ " make " , " clean " ] )
2016-07-04 15:28:06 -03:00
_ , sts = run_cmd_blocking ( " Building %s " % build_target , build_cmd )
2016-04-27 22:34:15 -03:00
if sts != 0 :
progress ( " Build failed " )
sys . exit ( 1 )
os . chdir ( old_dir )
2016-07-04 15:28:06 -03:00
2016-11-14 14:48:59 -04:00
def get_user_locations_path ( ) :
''' The user locations.txt file is located by default in
$ XDG_CONFIG_DIR / ardupilot / locations . txt . If $ XDG_CONFIG_DIR is
not defined , we look in $ HOME / . config / ardupilot / locations . txt . If
$ HOME is not defined , we look in . / . config / ardpupilot / locations . txt . '''
config_dir = os . environ . get (
' XDG_CONFIG_DIR ' ,
os . path . join ( os . environ . get ( ' HOME ' , ' . ' ) , ' .config ' ) )
user_locations_path = os . path . join (
config_dir , ' ardupilot ' , ' locations.txt ' )
return user_locations_path
2016-04-27 22:34:15 -03:00
def find_location_by_name ( autotest , locname ) :
2016-07-04 15:28:06 -03:00
""" Search locations.txt for locname, return GPS coords """
2016-11-14 14:48:59 -04:00
locations_userpath = os . environ . get ( ' ARDUPILOT_LOCATIONS ' ,
get_user_locations_path ( ) )
2016-04-27 22:34:15 -03:00
locations_filepath = os . path . join ( autotest , " locations.txt " )
2016-11-14 22:52:34 -04:00
comment_regex = re . compile ( " \ s*#.* " )
2016-11-14 14:48:59 -04:00
for path in [ locations_userpath , locations_filepath ] :
if not os . path . isfile ( path ) :
2016-11-14 22:52:34 -04:00
continue
2016-11-14 14:48:59 -04:00
with open ( path , ' r ' ) as fd :
for line in fd :
line = re . sub ( comment_regex , " " , line )
line = line . rstrip ( " \n " )
if len ( line ) == 0 :
continue
( name , loc ) = line . split ( " = " )
if name == locname :
return loc
2016-07-04 15:28:06 -03:00
print ( " Failed to find location ( %s ) " % cmd_opts . location )
2016-04-27 22:34:15 -03:00
sys . exit ( 1 )
2016-07-04 15:28:06 -03:00
2016-04-28 23:16:53 -03:00
def progress_cmd ( what , cmd ) :
2016-07-04 15:28:06 -03:00
""" Print cmd in a way a user could cut-and-paste to get the same effect """
2016-04-28 23:16:53 -03:00
progress ( what )
2016-07-04 15:28:06 -03:00
shell_text = " %s " % ( " " . join ( [ ' " %s " ' % x for x in cmd ] ) )
2016-04-28 23:16:53 -03:00
progress ( shell_text )
2016-07-04 15:28:06 -03:00
2016-08-29 21:49:16 -03:00
def run_cmd_blocking ( what , cmd , quiet = False , check = False , * * kw ) :
2016-06-23 00:31:38 -03:00
if not quiet :
progress_cmd ( what , cmd )
2016-05-13 17:42:39 -03:00
p = subprocess . Popen ( cmd , * * kw )
2016-08-29 21:49:16 -03:00
ret = os . waitpid ( p . pid , 0 )
_ , sts = ret
if check and sts != 0 :
progress ( " ( %s ) exited with code %d " % ( what , sts , ) )
sys . exit ( 1 )
return ret
2016-07-04 15:28:06 -03:00
2016-04-28 23:16:53 -03:00
2016-04-27 22:34:15 -03:00
def run_in_terminal_window ( autotest , name , cmd ) :
2016-07-04 15:28:06 -03:00
""" Execute the run_in_terminal_window.sh command for cmd """
2016-06-23 12:27:28 -03:00
global windowID
2016-04-27 22:34:15 -03:00
runme = [ os . path . join ( autotest , " run_in_terminal_window.sh " ) , name ]
runme . extend ( cmd )
2016-04-28 23:16:53 -03:00
progress_cmd ( " Run " + name , runme )
2016-06-23 12:27:28 -03:00
2016-07-06 11:26:34 -03:00
if under_macos ( ) :
2016-07-07 19:20:20 -03:00
# on MacOS record the window IDs so we can close them later
2016-07-04 15:28:06 -03:00
out = subprocess . Popen ( runme , stdout = subprocess . PIPE ) . communicate ( ) [ 0 ]
2016-06-23 12:27:28 -03:00
import re
p = re . compile ( ' tab 1 of window id (.*) ' )
windowID . append ( p . findall ( out ) [ 0 ] )
2016-07-07 19:20:20 -03:00
else :
p = subprocess . Popen ( runme )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
tracker_uarta = None # blemish
2016-04-27 22:34:15 -03:00
def start_antenna_tracker ( autotest , opts ) :
2016-07-04 15:28:06 -03:00
""" Compile and run the AntennaTracker, add tracker to mavproxy """
2016-04-27 22:34:15 -03:00
global tracker_uarta
progress ( " Preparing antenna tracker " )
tracker_home = find_location_by_name ( find_autotest_dir ( ) , opts . tracker_location )
vehicledir = os . path . join ( autotest , " ../../ " + " AntennaTracker " )
2016-08-16 19:33:53 -03:00
tracker_frame_options = {
" waf_target " : _default_waf_target [ " AntennaTracker " ] ,
}
do_build ( vehicledir , opts , tracker_frame_options )
2016-04-27 22:34:15 -03:00
tracker_instance = 1
os . chdir ( vehicledir )
2016-07-04 15:28:06 -03:00
tracker_uarta = " tcp:127.0.0.1: " + str ( 5760 + 10 * tracker_instance )
2016-04-27 22:34:15 -03:00
exe = os . path . join ( vehicledir , " AntennaTracker.elf " )
2016-07-04 15:28:06 -03:00
run_in_terminal_window ( autotest , " AntennaTracker " , [ " nice " , exe , " -I " + str ( tracker_instance ) , " --model=tracker " , " --home= " + tracker_home ] )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
def start_vehicle ( binary , autotest , opts , stuff , loc ) :
""" Run the ArduPilot binary """
2016-04-28 23:16:53 -03:00
2016-04-27 22:34:15 -03:00
cmd_name = opts . vehicle
cmd = [ ]
if opts . valgrind :
cmd_name + = " (valgrind) "
cmd . append ( " valgrind " )
if opts . gdb :
cmd_name + = " (gdb) "
cmd . append ( " gdb " )
gdb_commands_file = tempfile . NamedTemporaryFile ( delete = False )
atexit . register ( os . unlink , gdb_commands_file . name )
2016-04-28 23:16:53 -03:00
for breakpoint in opts . breakpoint :
gdb_commands_file . write ( " b %s \n " % ( breakpoint , ) )
2016-04-27 22:34:15 -03:00
gdb_commands_file . write ( " r \n " )
gdb_commands_file . close ( )
cmd . extend ( [ " -x " , gdb_commands_file . name ] )
cmd . append ( " --args " )
2016-05-12 08:09:45 -03:00
if opts . strace :
cmd_name + = " (strace) "
cmd . append ( " strace " )
2016-07-04 15:28:06 -03:00
strace_options = [ ' -o ' , binary + ' .strace ' , ' -s ' , ' 8000 ' , ' -ttt ' ]
2016-05-12 08:09:45 -03:00
cmd . extend ( strace_options )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
cmd . append ( binary )
2016-04-27 22:34:15 -03:00
cmd . append ( " -S " )
2016-07-04 15:28:06 -03:00
cmd . append ( " -I " + str ( opts . instance ) )
2016-04-27 22:34:15 -03:00
cmd . extend ( [ " --home " , loc ] )
if opts . wipe_eeprom :
cmd . append ( " -w " )
cmd . extend ( [ " --model " , stuff [ " model " ] ] )
cmd . extend ( [ " --speedup " , str ( opts . speedup ) ] )
if opts . sitl_instance_args :
2016-07-04 15:28:06 -03:00
cmd . extend ( opts . sitl_instance_args . split ( " " ) ) # this could be a lot better..
2016-04-27 22:34:15 -03:00
if opts . mavlink_gimbal :
cmd . append ( " --gimbal " )
2016-07-04 15:28:06 -03:00
if " default_params_filename " in stuff :
2016-04-27 22:34:15 -03:00
path = os . path . join ( autotest , stuff [ " default_params_filename " ] )
progress ( " Using defaults from ( %s ) " % ( path , ) )
cmd . extend ( [ " --defaults " , path ] )
run_in_terminal_window ( autotest , cmd_name , cmd )
2016-07-04 15:28:06 -03:00
2016-04-27 22:34:15 -03:00
def start_mavproxy ( opts , stuff ) :
2016-07-04 15:28:06 -03:00
""" Run mavproxy """
2016-04-27 22:34:15 -03:00
# FIXME: would be nice to e.g. "mavproxy.mavproxy(....).run" rather than shelling out
extra_cmd = " "
cmd = [ ]
2016-04-28 23:16:53 -03:00
if under_cygwin ( ) :
cmd . append ( " /usr/bin/cygstart " )
2016-04-27 22:34:15 -03:00
cmd . append ( " -w " )
cmd . append ( " /cygdrive/c/Program Files (x86)/MAVProxy/mavproxy.exe " )
else :
cmd . append ( " mavproxy.py " )
if opts . hil :
cmd . extend ( [ " --load-module " , " HIL " ] )
else :
2016-06-22 01:10:27 -03:00
cmd . extend ( [ " --master " , mavlink_port ] )
if stuff [ " sitl-port " ] :
cmd . extend ( [ " --sitl " , simout_port ] )
2016-04-27 22:34:15 -03:00
# If running inside of a vagrant guest, then we probably want to forward our mavlink out to the containing host OS
2016-10-09 07:43:13 -03:00
ports = [ p + 10 * cmd_opts . instance for p in [ 14550 , 14551 ] ]
for port in ports :
2016-12-24 14:28:13 -04:00
if os . path . isfile ( " /ardupilot.vagrant " ) :
2016-10-09 07:43:13 -03:00
cmd . extend ( [ " --out " , " 10.0.2.2: " + str ( port ) ] )
else :
cmd . extend ( [ " --out " , " 127.0.0.1: " + str ( port ) ] )
2016-04-27 22:34:15 -03:00
if opts . tracker :
cmd . extend ( [ " --load-module " , " tracker " ] )
global tracker_uarta
# tracker_uarta is set when we start the tracker...
extra_cmd + = " module load map; tracker set port %s ; tracker start; tracker arm; " % ( tracker_uarta , )
if opts . mavlink_gimbal :
cmd . extend ( [ " --load-module " , " gimbal " ] )
2016-07-04 15:28:06 -03:00
if " extra_mavlink_cmds " in stuff :
2016-04-27 22:34:15 -03:00
extra_cmd + = " " + stuff [ " extra_mavlink_cmds " ]
if opts . mavproxy_args :
2016-07-04 15:28:06 -03:00
cmd . extend ( opts . mavproxy_args . split ( " " ) ) # this could be a lot better..
2016-04-27 22:34:15 -03:00
2016-05-12 14:15:46 -03:00
# compatibility pass-through parameters (for those that don't want
2016-04-28 23:16:53 -03:00
# to use -C :-)
for out in opts . out :
cmd . extend ( [ ' --out ' , out ] )
if opts . map :
cmd . append ( ' --map ' )
if opts . console :
cmd . append ( ' --console ' )
2016-09-09 04:36:37 -03:00
if opts . aircraft is not None :
cmd . extend ( [ ' --aircraft ' , opts . aircraft ] )
2016-04-28 23:16:53 -03:00
2016-04-27 22:34:15 -03:00
if len ( extra_cmd ) :
cmd . extend ( [ ' --cmd ' , extra_cmd ] )
2016-05-13 17:55:06 -03:00
local_mp_modules_dir = os . path . abspath (
2016-07-04 15:28:06 -03:00
os . path . join ( __file__ , ' .. ' , ' .. ' , ' mavproxy_modules ' ) )
2016-05-13 17:55:06 -03:00
env = dict ( os . environ )
env [ ' PYTHONPATH ' ] = local_mp_modules_dir + os . pathsep + env . get ( ' PYTHONPATH ' , ' ' )
run_cmd_blocking ( " Run MavProxy " , cmd , env = env )
2017-01-09 07:40:45 -04:00
progress ( " MAVProxy exited " )
2016-04-27 22:34:15 -03:00
2016-09-09 20:51:56 -03:00
# define and run parser
parser = CompatOptionParser ( " sim_vehicle.py " ,
epilog = " eeprom.bin in the starting directory contains the parameters for your " \
" simulated vehicle. Always start from the same directory. It is " \
" recommended that you start in the main vehicle directory for the vehicle " \
" you are simulating, for example, start in the ArduPlane directory to " \
" simulate ArduPlane " )
parser . add_option ( " -v " , " --vehicle " , type = ' string ' , default = None , help = " vehicle type (ArduPlane, ArduCopter or APMrover2) " )
parser . add_option ( " -f " , " --frame " , type = ' string ' , default = None , help = """ set aircraft frame type
for copters can choose + , X , quad or octa
for planes can choose elevon or vtail """ )
parser . add_option ( " -C " , " --sim_vehicle_sh_compatible " , action = ' store_true ' , default = False , help = " be compatible with the way sim_vehicle.sh works; make this the first option " )
parser . add_option ( " -H " , " --hil " , action = ' store_true ' , default = False , help = " start HIL " )
group_build = optparse . OptionGroup ( parser , " Build options " )
group_build . add_option ( " -N " , " --no-rebuild " , action = ' store_true ' , default = False , help = " don ' t rebuild before starting ardupilot " )
group_build . add_option ( " -D " , " --debug " , action = ' store_true ' , default = False , help = " build with debugging " )
group_build . add_option ( " -c " , " --clean " , action = ' store_true ' , default = False , help = " do a make clean before building " )
group_build . add_option ( " -j " , " --jobs " , default = None , type = ' int ' , help = " number of processors to use during build (default for waf : number of processor, for make : 1) " )
group_build . add_option ( " -b " , " --build-target " , default = None , type = ' string ' , help = " override SITL build target " )
group_build . add_option ( " -s " , " --build-system " , default = " waf " , type = ' choice ' , choices = [ " make " , " waf " ] , help = " build system to use " )
2016-10-18 19:57:09 -03:00
group_build . add_option ( " " , " --rebuild-on-failure " , dest = " rebuild_on_failure " , action = ' store_true ' , default = False , help = " if build fails, do not clean and rebuild " )
2016-09-09 20:51:56 -03:00
group_build . add_option ( " " , " --waf-configure-arg " , action = " append " , dest = " waf_configure_args " , type = " string " , default = [ ] , help = " extra arguments to pass to waf in its configure step " )
group_build . add_option ( " " , " --waf-build-arg " , action = " append " , dest = " waf_build_args " , type = " string " , default = [ ] , help = " extra arguments to pass to waf in its build step " )
parser . add_option_group ( group_build )
group_sim = optparse . OptionGroup ( parser , " Simulation options " )
group_sim . add_option ( " -I " , " --instance " , default = 0 , type = ' int ' , help = " instance of simulator " )
group_sim . add_option ( " -V " , " --valgrind " , action = ' store_true ' , default = False , help = " enable valgrind for memory access checking (very slow!) " )
group_sim . add_option ( " -T " , " --tracker " , action = ' store_true ' , default = False , help = " start an antenna tracker instance " )
group_sim . add_option ( " -A " , " --sitl-instance-args " , type = ' string ' , default = None , help = " pass arguments to SITL instance " )
# group_sim.add_option("-R", "--reverse-throttle", action='store_true', default=False, help="reverse throttle in plane")
group_sim . add_option ( " -G " , " --gdb " , action = ' store_true ' , default = False , help = " use gdb for debugging ardupilot " )
group_sim . add_option ( " -g " , " --gdb-stopped " , action = ' store_true ' , default = False , help = " use gdb for debugging ardupilot (no auto-start) " )
group_sim . add_option ( " -d " , " --delay-start " , default = 0 , type = ' float ' , help = " delays the start of mavproxy by the number of seconds " )
group_sim . add_option ( " -B " , " --breakpoint " , type = ' string ' , action = " append " , default = [ ] , help = " add a breakpoint at given location in debugger " )
group_sim . add_option ( " -M " , " --mavlink-gimbal " , action = ' store_true ' , default = False , help = " enable MAVLink gimbal " )
group_sim . add_option ( " -L " , " --location " , type = ' string ' , default = ' CMAC ' , help = " select start location from Tools/autotest/locations.txt " )
group_sim . add_option ( " -l " , " --custom-location " , type = ' string ' , default = None , help = " set custom start location " )
group_sim . add_option ( " -S " , " --speedup " , default = 1 , type = ' int ' , help = " set simulation speedup (1 for wall clock time) " )
group_sim . add_option ( " -t " , " --tracker-location " , default = ' CMAC_PILOTSBOX ' , type = ' string ' , help = " set antenna tracker start location " )
group_sim . add_option ( " -w " , " --wipe-eeprom " , action = ' store_true ' , default = False , help = " wipe EEPROM and reload parameters " )
group_sim . add_option ( " -m " , " --mavproxy-args " , default = None , type = ' string ' , help = " additional arguments to pass to mavproxy.py " )
group_sim . add_option ( " " , " --strace " , action = ' store_true ' , default = False , help = " strace the ArduPilot binary " )
group_sim . add_option ( " " , " --model " , type = ' string ' , default = None , help = " Override simulation model to use " )
parser . add_option_group ( group_sim )
# special-cased parameters for mavproxy, because some people's fingers
# have long memories, and they don't want to use -C :-)
group = optparse . OptionGroup ( parser , " Compatibility MAVProxy options (consider using --mavproxy-args instead) " )
group . add_option ( " " , " --out " , default = [ ] , type = ' string ' , action = " append " , help = " create an additional mavlink output " )
group . add_option ( " " , " --map " , default = False , action = ' store_true ' , help = " load map module on startup " )
group . add_option ( " " , " --console " , default = False , action = ' store_true ' , help = " load console module on startup " )
group . add_option ( " " , " --aircraft " , default = None , help = " store state and logs in named directory " )
parser . add_option_group ( group )
cmd_opts , cmd_args = parser . parse_args ( )
# clean up processes at exit:
atexit . register ( kill_tasks )
progress ( " Start " )
if cmd_opts . sim_vehicle_sh_compatible and cmd_opts . jobs is None :
cmd_opts . jobs = 1
# validate parameters
if cmd_opts . hil :
if cmd_opts . valgrind :
print ( " May not use valgrind with hil " )
sys . exit ( 1 )
if cmd_opts . gdb or cmd_opts . gdb_stopped :
print ( " May not use gdb with hil " )
sys . exit ( 1 )
if cmd_opts . strace :
print ( " May not use strace with hil " )
sys . exit ( 1 )
if cmd_opts . valgrind and ( cmd_opts . gdb or cmd_opts . gdb_stopped ) :
print ( " May not use valgrind with gdb " )
sys . exit ( 1 )
if cmd_opts . strace and ( cmd_opts . gdb or cmd_opts . gdb_stopped ) :
print ( " May not use strace with gdb " )
sys . exit ( 1 )
if cmd_opts . strace and cmd_opts . valgrind :
print ( " valgrind and strace almost certainly not a good idea " )
# magically determine vehicle type (if required):
if cmd_opts . vehicle is None :
cwd = os . getcwd ( )
cmd_opts . vehicle = os . path . basename ( cwd )
# determine a frame type if not specified:
default_frame_for_vehicle = {
" APMrover2 " : " rover " ,
" ArduPlane " : " jsbsim " ,
" ArduCopter " : " quad " ,
" AntennaTracker " : " tracker " ,
}
if cmd_opts . vehicle not in default_frame_for_vehicle :
# try in parent directories, useful for having config in subdirectories
cwd = os . getcwd ( )
while cwd :
bname = os . path . basename ( cwd )
if not bname :
break
if bname in default_frame_for_vehicle :
cmd_opts . vehicle = bname
break
cwd = os . path . dirname ( cwd )
# try to validate vehicle
if cmd_opts . vehicle not in default_frame_for_vehicle :
progress ( " ** Is ( %s ) really your vehicle type? Try -v VEHICLETYPE if not, or be in the e.g. ArduCopter subdirectory " % ( cmd_opts . vehicle , ) )
# determine frame options (e.g. build type might be "sitl")
if cmd_opts . frame is None :
cmd_opts . frame = default_frame_for_vehicle [ cmd_opts . vehicle ]
# setup ports for this instance
mavlink_port = " tcp:127.0.0.1: " + str ( 5760 + 10 * cmd_opts . instance )
simout_port = " 127.0.0.1: " + str ( 5501 + 10 * cmd_opts . instance )
2016-07-04 15:28:06 -03:00
frame_infos = options_for_frame ( cmd_opts . frame , cmd_opts . vehicle , cmd_opts )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
if frame_infos [ " model " ] == " jsbsim " :
2016-04-27 22:34:15 -03:00
check_jsbsim_version ( )
2016-07-04 15:28:06 -03:00
vehicle_dir = os . path . realpath ( os . path . join ( find_root_dir ( ) , cmd_opts . vehicle ) )
if not os . path . exists ( vehicle_dir ) :
print ( " vehicle directory ( %s ) does not exist " % ( vehicle_dir , ) )
2016-04-27 22:34:15 -03:00
sys . exit ( 1 )
2016-07-04 15:28:06 -03:00
if not cmd_opts . hil :
if cmd_opts . instance == 0 :
2016-04-27 22:34:15 -03:00
kill_tasks ( )
2016-07-04 15:28:06 -03:00
if cmd_opts . tracker :
start_antenna_tracker ( find_autotest_dir ( ) , cmd_opts )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
if cmd_opts . custom_location :
location = cmd_opts . custom_location
progress ( " Starting up at %s " % ( location , ) )
2016-04-27 22:34:15 -03:00
else :
2016-07-04 15:28:06 -03:00
location = find_location_by_name ( find_autotest_dir ( ) , cmd_opts . location )
progress ( " Starting up at %s ( %s ) " % ( location , cmd_opts . location ) )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
if cmd_opts . hil :
2016-04-27 22:34:15 -03:00
# (unlikely)
2016-07-04 15:28:06 -03:00
run_in_terminal_window ( find_autotest_dir ( ) , " JSBSim " , [ os . path . join ( find_autotest_dir ( ) , " jsb_sim/runsim.py " ) , " --home " , location , " --speedup= " + str ( cmd_opts . speedup ) ] )
2016-04-27 22:34:15 -03:00
else :
2016-07-04 15:28:06 -03:00
if not cmd_opts . no_rebuild : # i.e. we should rebuild
do_build ( vehicle_dir , cmd_opts , frame_infos )
2016-04-28 23:16:53 -03:00
2016-07-04 15:28:06 -03:00
if cmd_opts . build_system == " waf " :
if cmd_opts . debug :
2016-05-12 00:32:36 -03:00
binary_basedir = " build/sitl-debug "
2016-05-08 23:11:32 -03:00
else :
2016-05-12 00:32:36 -03:00
binary_basedir = " build/sitl "
2016-07-04 15:28:06 -03:00
vehicle_binary = os . path . join ( find_root_dir ( ) , binary_basedir , frame_infos [ " waf_target " ] )
2016-04-28 23:16:53 -03:00
else :
2016-07-04 15:28:06 -03:00
vehicle_binary = os . path . join ( vehicle_dir , cmd_opts . vehicle + " .elf " )
2016-04-28 23:16:53 -03:00
if not os . path . exists ( vehicle_binary ) :
print ( " Vehicle binary ( %s ) does not exist " % ( vehicle_binary , ) )
sys . exit ( 1 )
2016-07-04 15:28:06 -03:00
start_vehicle ( vehicle_binary , find_autotest_dir ( ) , cmd_opts , frame_infos , location )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
if cmd_opts . delay_start :
progress ( " Sleeping for %f seconds " % ( cmd_opts . delay_start , ) )
time . sleep ( float ( cmd_opts . delay_start ) )
2016-04-27 22:34:15 -03:00
2016-07-04 15:28:06 -03:00
start_mavproxy ( cmd_opts , frame_infos )
2016-04-27 22:34:15 -03:00
sys . exit ( 0 )