@ -1,47 +1,51 @@
#!/usr/bin/env python
#!/usr/bin/env python
# framework to start a simulated vehicle and connect it to MAVProxy
"""
# Peter Barker, April 2016
Framework to start a simulated vehicle and connect it to MAVProxy .
# based on sim_vehicle.sh by Andrew Tridgell, October 2011
Peter Barker , April 2016
based on sim_vehicle . sh by Andrew Tridgell , October 2011
"""
import optparse
import sys
import atexit
import atexit
import getpass
import optparse
import os
import os
import os . path
import os . path
import signal
import subprocess
import subprocess
import sys
import tempfile
import tempfile
import getpass
import time
import time
import signal
# List of open terminal windows for macosx
# List of open terminal windows for macosx
windowID = [ ]
windowID = [ ]
class CompatError ( Exception ) :
class CompatError ( Exception ) :
''' a custom exception class to hold state if we encounter the parse error we are looking for'''
""" A custom exception class to hold state if we encounter the parse error we are looking for"""
def __init__ ( self , error , opts , rargs ) :
def __init__ ( self , error , opts , rargs ) :
Exception . __init__ ( self , error )
Exception . __init__ ( self , error )
self . opts = opts
self . opts = opts
self . rargs = rargs
self . rargs = rargs
class CompatOptionParser ( optparse . OptionParser ) :
class CompatOptionParser ( optparse . OptionParser ) :
''' 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'''
""" 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"""
def __init__ ( self , * args , * * kwargs ) :
def __init__ ( self , * args , * * kwargs ) :
optparse . OptionParser . __init__ ( self , * args , * * kwargs )
optparse . OptionParser . __init__ ( self , * args , * * kwargs )
def error ( self , error ) :
def error ( self , error ) :
''' o verride default error handler called by optparse.OptionParser.parse_args when a parse error occurs; raise a detailed exception which can be caught'''
""" O verride default error handler called by optparse.OptionParser.parse_args when a parse error occurs; raise a detailed exception which can be caught"""
if error . find ( " no such option " ) != - 1 :
if error . find ( " no such option " ) != - 1 :
raise CompatError ( error , self . values , self . rargs )
raise CompatError ( error , self . values , self . rargs )
optparse . OptionParser . error ( self , error )
optparse . OptionParser . error ( self , error )
def parse_args ( self ) :
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 '''
""" Wrap parse_args so we can catch the exception raised upon discovering the known parameter parsing error """
mavproxy_args = [ ]
try :
try :
opts , args = optparse . OptionParser . parse_args ( self )
opts , args = optparse . OptionParser . parse_args ( self )
except CompatError as e :
except CompatError as e :
@ -55,60 +59,66 @@ class CompatOptionParser(optparse.OptionParser):
args = [ ]
args = [ ]
opts = e . opts
opts = e . opts
mavproxy_args = [ ]
mavproxy_args = [ str ( e ) [ 16 : ] ] # this trims "no such option" off
mavproxy_args . append ( str ( e ) [ 16 : ] ) # this trims "no such option" off
mavproxy_args . extend ( e . rargs )
mavproxy_args . extend ( e . rargs )
opts . ensure_value ( " mavproxy_args " , " " . join ( mavproxy_args ) )
opts . ensure_value ( " mavproxy_args " , " " . join ( mavproxy_args ) )
return opts , args
return opts , args
def cygwin_pidof ( procName ) :
''' Thanks to kata198 for this:
def cygwin_pidof ( proc_name ) :
""" Thanks to kata198 for this:
https : / / github . com / kata198 / cygwin - ps - misc / blob / master / pidof
https : / / github . com / kata198 / cygwin - ps - misc / blob / master / pidof
'''
"""
pipe = subprocess . Popen ( " ps -ea | grep " + procN ame , shell = True , stdout = subprocess . PIPE )
pipe = subprocess . Popen ( " ps -ea | grep " + proc_n ame , shell = True , stdout = subprocess . PIPE )
outputL ines = pipe . stdout . read ( ) . replace ( " \r " , " " ) . split ( " \n " )
output_l ines = pipe . stdout . read ( ) . replace ( " \r " , " " ) . split ( " \n " )
ret = pipe . wait ( )
ret = pipe . wait ( )
pids = [ ]
pids = [ ]
if ret != 0 :
if ret != 0 :
# No results
# No results
return [ ]
return [ ]
for line in outputL ines :
for line in output_l ines :
if not line :
if not line :
continue
continue
lineS plit = [ item for item in line . split ( ' ' ) if item ]
line_s plit = [ item for item in line . split ( ' ' ) if item ]
cmd = lineS plit [ - 1 ] . split ( ' / ' ) [ - 1 ]
cmd = line_s plit [ - 1 ] . split ( ' / ' ) [ - 1 ]
if cmd == procN ame :
if cmd == proc_n ame :
try :
try :
pid = int ( lineS plit [ 0 ] . strip ( ) )
pid = int ( line_s plit [ 0 ] . strip ( ) )
except :
except :
pid = int ( lineS plit [ 1 ] . strip ( ) )
pid = int ( line_s plit [ 1 ] . strip ( ) )
pid = str ( pid )
str_ pid = str ( pid )
if pid not in pids :
if str_ pid not in pids :
pids . append ( pid )
pids . append ( str_ pid)
return pids
return pids
def under_cygwin ( ) :
def under_cygwin ( ) :
""" Return if Cygwin binary exist """
return os . path . exists ( " /usr/bin/cygstart " )
return os . path . exists ( " /usr/bin/cygstart " )
def under_macos ( ) :
def under_macos ( ) :
return sys . platform == ' darwin '
return sys . platform == ' darwin '
def kill_tasks_cygwin ( victims ) :
def kill_tasks_cygwin ( victims ) :
''' shell out to ps -ea to find processes to kill '''
""" Shell out to ps -ea to find processes to kill """
for victim in list ( victims ) :
for victim in list ( victims ) :
pids = cygwin_pidof ( victim )
pids = cygwin_pidof ( victim )
# progress("pids for (%s): %s" % (victim,",".join([ str(p) for p in pids])))
# progress("pids for (%s): %s" % (victim,",".join([ str(p) for p in pids])))
for apid in pids :
for apid in pids :
os . kill ( apid , signal . SIGKILL )
os . kill ( apid , signal . SIGKILL )
def kill_tasks_macos ( ) :
def kill_tasks_macos ( ) :
for window in windowID :
for window in windowID :
cmd = " osascript -e \' tell application \" Terminal \" to close (window(get index of window id %s )) \' " % window
cmd = " osascript -e \' tell application \" Terminal \" to close (window(get index of window id %s )) \' " % window
os . system ( cmd )
os . system ( cmd )
def kill_tasks_psutil ( victims ) :
def kill_tasks_psutil ( victims ) :
''' u se 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'''
""" U se 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"""
import psutil
import psutil
for proc in psutil . process_iter ( ) :
for proc in psutil . process_iter ( ) :
if proc . status == psutil . STATUS_ZOMBIE :
if proc . status == psutil . STATUS_ZOMBIE :
@ -116,18 +126,21 @@ def kill_tasks_psutil(victims):
if proc . name in victims :
if proc . name in victims :
proc . kill ( )
proc . kill ( )
def kill_tasks_pkill ( victims ) :
def kill_tasks_pkill ( victims ) :
''' shell out to pkill(1) to kill processed by name '''
""" Shell out to pkill(1) to kill processed by name """
for victim in victims : # pkill takes a single pattern, so iterate
for victim in victims : # pkill takes a single pattern, so iterate
cmd = [ " pkill " ]
cmd = [ " pkill " , victim ]
cmd . append ( victim )
run_cmd_blocking ( " pkill " , cmd , quiet = True )
run_cmd_blocking ( " pkill " , cmd , quiet = True )
class BobException ( Exception ) :
class BobException ( Exception ) :
""" Handle Bob ' s Exceptions """
pass
pass
def kill_tasks ( ) :
def kill_tasks ( ) :
''' clean up stray processes by name. This is a somewhat shotgun approach '''
""" Clean up stray processes by name. This is a somewhat shotgun approach """
progress ( " Killing tasks " )
progress ( " Killing tasks " )
try :
try :
victim_names = [
victim_names = [
@ -150,7 +163,7 @@ def kill_tasks():
try :
try :
kill_tasks_psutil ( victim_names )
kill_tasks_psutil ( victim_names )
except ImportError as e :
except ImportError :
kill_tasks_pkill ( victim_names )
kill_tasks_pkill ( victim_names )
except Exception as e :
except Exception as e :
progress ( " kill_tasks failed: {} " . format ( str ( e ) ) )
progress ( " kill_tasks failed: {} " . format ( str ( e ) ) )
@ -158,140 +171,144 @@ def kill_tasks():
# clean up processes at exit:
# clean up processes at exit:
atexit . register ( kill_tasks )
atexit . register ( kill_tasks )
def check_jsbsim_version ( ) :
def check_jsbsim_version ( ) :
''' assert that the JSBSim we will run is the one we expect to run '''
""" Assert that the JSBSim we will run is the one we expect to run """
jsbsim_cmd = [ " JSBSim " , " --version " ]
jsbsim_cmd = [ " JSBSim " , " --version " ]
progress_cmd ( " Get JSBSim version " , jsbsim_cmd )
progress_cmd ( " Get JSBSim version " , jsbsim_cmd )
try :
try :
jsbsim_version = subprocess . Popen ( jsbsim_cmd , stdout = subprocess . PIPE ) . communicate ( ) [ 0 ]
jsbsim_version = subprocess . Popen ( jsbsim_cmd , stdout = subprocess . PIPE ) . communicate ( ) [ 0 ]
except OSError as e :
except OSError :
jsbsim_version = ' ' # this value will trigger the ".index"
jsbsim_version = ' ' # this value will trigger the ".index"
# check below and produce a reasonable
# check below and produce a reasonable
# error message
# error message
try :
try :
jsbsim_version . index ( " ArduPilot " )
jsbsim_version . index ( " ArduPilot " )
except ValueError :
except ValueError :
print ( '''
print ( r """
== == == == == == == == == == == == == == == == == == == == == == == == == == == == =
== == == == == == == == == == == == == == == == == == == == == == == == == == == == =
You need the latest ArduPilot version of JSBSim installed
You need the latest ArduPilot version of JSBSim installed
and in your \$ PATH
and in your \$ PATH
Please get it from git : / / github . com / tridge / jsbsim . git
Please get it from git : / / github . com / tridge / jsbsim . git
See
See
http : / / dev . ardupilot . org / wiki / simulation - 2 / sitl - simulator - software - in - the - loop / setting - up - sitl - on - linux /
http : / / dev . ardupilot . org / wiki / simulation - 2 / sitl - simulator - software - in - the - loop / setting - up - sitl - on - linux /
for more details
for more details
== == == == == == == == == == == == == == == == == == == == == == == == == == == == =
== == == == == == == == == == == == == == == == == == == == == == == == == == == == =
''' )
""" )
sys . exit ( 1 )
sys . exit ( 1 )
def progress ( text ) :
def progress ( text ) :
''' display sim_vehicle progress text '''
""" Display sim_vehicle progress text """
print ( " SIM_VEHICLE: " + text )
print ( " SIM_VEHICLE: " + text )
def find_autotest_dir ( ) :
def find_autotest_dir ( ) :
''' return path to autotest directory '''
""" Return path to autotest directory """
return os . path . dirname ( os . path . realpath ( __file__ ) )
return os . path . dirname ( os . path . realpath ( __file__ ) )
def find_root_dir ( ) :
def find_root_dir ( ) :
''' return path to root directory '''
""" Return path to root directory """
return os . path . realpath ( os . path . join ( find_autotest_dir ( ) , ' ../.. ' ) )
return os . path . realpath ( os . path . join ( find_autotest_dir ( ) , ' ../.. ' ) )
progress ( " Start " )
progress ( " Start " )
# define and run parser
# define and run parser
parser = CompatOptionParser ( " sim_vehicle.py " , epilog = '''
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
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 ( " -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
parser . add_option ( " -f " , " --frame " , type = ' string ' , default = None , help = """ set aircraft frame type
for copters can choose + , X , quad or octa
for copters can choose + , X , quad or octa
for planes can choose elevon or vtail ''' )
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 ( " -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 " )
parser . add_option ( " -H " , " --hil " , action = ' store_true ' , default = False , help = " start HIL " )
group_build = optparse . OptionGroup ( parser , " Build options " )
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 ( " -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 ( " -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 ( " -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 ( " -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 ( " -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 ' )
group_build . add_option ( " -s " , " --build-system " , default = " waf " , type = ' choice ' , choices = [ " make " , " waf " ] , help = " build system to use " )
group_build . add_option ( " " , " --no-rebuild-on-failure " , dest = " rebuild_on_failure " , action = ' store_false ' , default = True , help = ' if build fails, do not clean and rebuild ' )
group_build . add_option ( " " , " --no-rebuild-on-failure " , dest = " rebuild_on_failure " , action = ' store_false ' , default = True , help = " if build fails, do not clean and rebuild " )
parser . add_option_group ( group_build )
parser . add_option_group ( group_build )
group_sim = optparse . OptionGroup ( parser , " Simulation options " )
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 ( " -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 ( " -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 ( " -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 ( " -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("-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 " , 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 ( " -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 ( " -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 ( " -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 ( " -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 " , " --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 ( " -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 ( " -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 ( " -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 ( " -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 ( " -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 ( " " , " --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 ' )
group_sim . add_option ( " " , " --model " , type = ' string ' , default = None , help = " Override simulation model to use " )
parser . add_option_group ( group_sim )
parser . add_option_group ( group_sim )
# special-cased parameters for mavproxy, because some people's fingers
# special-cased parameters for mavproxy, because some people's fingers
# have long memories, and they don't want to use -C :-)
# have long memories, and they don't want to use -C :-)
group = optparse . OptionGroup ( parser , " Compatibility MAVProxy options (consider using --mavproxy-args instead) " )
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 ( " " , " --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 ( " " , " --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 ( " " , " --console " , default = False , action = ' store_true ' , help = " load console module on startup " )
parser . add_option_group ( group )
parser . add_option_group ( group )
opts , args = parser . parse_args ( )
cmd_ opts, cmd_ args = parser . parse_args ( )
if opts . sim_vehicle_sh_compatible and opts . jobs is None :
if cmd_ opts. sim_vehicle_sh_compatible and cmd_ opts. jobs is None :
opts . jobs = 1
cmd_ opts. jobs = 1
# validate parameters
# validate parameters
if opts . hil :
if cmd_ opts. hil :
if opts . valgrind :
if cmd_ opts. valgrind :
print ( " May not use valgrind with hil " )
print ( " May not use valgrind with hil " )
sys . exit ( 1 )
sys . exit ( 1 )
if opts . gdb or opts . gdb_stopped :
if cmd_ opts. gdb or cmd_ opts. gdb_stopped :
print ( " May not use gdb with hil " )
print ( " May not use gdb with hil " )
sys . exit ( 1 )
sys . exit ( 1 )
if opts . strace :
if cmd_ opts. strace :
print ( " May not use strace with hil " )
print ( " May not use strace with hil " )
sys . exit ( 1 )
sys . exit ( 1 )
if opts . valgrind and ( opts . gdb or opts . gdb_stopped ) :
if cmd_ opts. valgrind and ( cmd_ opts. gdb or cmd_ opts. gdb_stopped ) :
print ( " May not use valgrind with gdb " )
print ( " May not use valgrind with gdb " )
sys . exit ( 1 )
sys . exit ( 1 )
if opts . strace and ( opts . gdb or opts . gdb_stopped ) :
if cmd_ opts. strace and ( cmd_ opts. gdb or cmd_ opts. gdb_stopped ) :
print ( " May not use strace with gdb " )
print ( " May not use strace with gdb " )
sys . exit ( 1 )
sys . exit ( 1 )
if opts . strace and opts . valgrind :
if cmd_ opts. strace and cmd_ opts. valgrind :
print ( " valgrind and strace almost certainly not a good idea " )
print ( " valgrind and strace almost certainly not a good idea " )
# magically determine vehicle type (if required):
# magically determine vehicle type (if required):
if opts . vehicle is None :
if cmd_ opts. vehicle is None :
cwd = os . getcwd ( )
cwd = os . getcwd ( )
opts . vehicle = os . path . basename ( cwd )
cmd_ opts. vehicle = os . path . basename ( cwd )
# determine a frame type if not specified:
# determine a frame type if not specified:
default_frame_for_vehicle = {
default_frame_for_vehicle = {
" APMrover2 " : " rover " ,
" APMrover2 " : " rover " ,
" ArduPlane " : " jsbsim " ,
" ArduPlane " : " jsbsim " ,
" ArduCopter " : " quad " ,
" ArduCopter " : " quad " ,
" AntennaTracker " : " tracker "
" AntennaTracker " : " tracker " ,
}
}
if not default_frame_for_vehicle . has_key ( opts . vehicle ) :
if cmd_opts . vehicle not in default_frame_for_vehicle :
# try in parent directories, useful for having config in subdirectories
# try in parent directories, useful for having config in subdirectories
cwd = os . getcwd ( )
cwd = os . getcwd ( )
while cwd :
while cwd :
@ -299,27 +316,27 @@ if not default_frame_for_vehicle.has_key(opts.vehicle):
if not bname :
if not bname :
break
break
if bname in default_frame_for_vehicle :
if bname in default_frame_for_vehicle :
opts . vehicle = bname
cmd_ opts. vehicle = bname
break
break
cwd = os . path . dirname ( cwd )
cwd = os . path . dirname ( cwd )
# try to validate vehicle
# try to validate vehicle
if not default_frame_for_vehicle . has_key ( opts . 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 " % ( opts . 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")
# determine frame options (e.g. build type might be "sitl")
if opts . frame is None :
if cmd_ opts. frame is None :
opts . frame = default_frame_for_vehicle [ opts . vehicle ]
cmd_ opts. frame = default_frame_for_vehicle [ cmd_ opts. vehicle ]
# setup ports for this instance
# setup ports for this instance
mavlink_port = " tcp:127.0.0.1: " + str ( 5760 + 10 * opts . instance )
mavlink_port = " tcp:127.0.0.1: " + str ( 5760 + 10 * cmd_ opts. instance )
simout_port = " 127.0.0.1: " + str ( 5501 + 10 * opts . instance )
simout_port = " 127.0.0.1: " + str ( 5501 + 10 * cmd_ opts. instance )
'''
"""
make_target : option passed to make to create binaries . Usually sitl , and " -debug " may be appended if - D is passed to sim_vehicle . py
make_target : option passed to make to create binaries . Usually sitl , and " -debug " may be appended if - D is passed to sim_vehicle . py
default_params_filename : filename of default parameters file . Taken to be relative to autotest dir .
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
extra_mavlink_cmds : extra parameters that will be passed to mavproxy
'''
"""
_options_for_frame = {
_options_for_frame = {
" calibration " : {
" calibration " : {
" extra_mavlink_cmds " : " module load sitl_calibration; " ,
" extra_mavlink_cmds " : " module load sitl_calibration; " ,
@ -327,37 +344,37 @@ _options_for_frame = {
# COPTER
# COPTER
" + " : {
" + " : {
" waf_target " : " bin/arducopter-quad " ,
" waf_target " : " bin/arducopter-quad " ,
" default_params_filename " : " copter_params.parm "
" default_params_filename " : " copter_params.parm " ,
} ,
} ,
" quad " : {
" quad " : {
" model " : " + " ,
" model " : " + " ,
" waf_target " : " bin/arducopter-quad " ,
" waf_target " : " bin/arducopter-quad " ,
" default_params_filename " : " copter_params.parm "
" default_params_filename " : " copter_params.parm " ,
} ,
} ,
" X " : {
" X " : {
" waf_target " : " bin/arducopter-quad " ,
" waf_target " : " bin/arducopter-quad " ,
# this param set FRAME doesn't actually work because mavproxy
# 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
# won't set a parameter unless it knows of it, and the param fetch happens asynchronously
" default_params_filename " : " copter_params.parm " ,
" default_params_filename " : " copter_params.parm " ,
" extra_mavlink_cmds " : " param fetch frame; param set FRAME 1; "
" extra_mavlink_cmds " : " param fetch frame; param set FRAME 1; " ,
} ,
} ,
" hexa " : {
" hexa " : {
" make_target " : " sitl-hexa " ,
" make_target " : " sitl-hexa " ,
" waf_target " : " bin/arducopter-hexa " ,
" waf_target " : " bin/arducopter-hexa " ,
" default_params_filename " : " copter_params.parm " ,
" default_params_filename " : " copter_params.parm " ,
} ,
} ,
" octa " : {
" octa " : {
" make_target " : " sitl-octa " ,
" make_target " : " sitl-octa " ,
" waf_target " : " bin/arducopter-octa " ,
" waf_target " : " bin/arducopter-octa " ,
" default_params_filename " : " copter_params.parm " ,
" default_params_filename " : " copter_params.parm " ,
} ,
} ,
" tri " : {
" tri " : {
" make_target " : " sitl-tri " ,
" make_target " : " sitl-tri " ,
" waf_target " : " bin/arducopter-tri " ,
" waf_target " : " bin/arducopter-tri " ,
" default_params_filename " : " tri_params.parm " ,
" default_params_filename " : " tri_params.parm " ,
} ,
} ,
" y6 " : {
" y6 " : {
" make_target " : " sitl-y6 " ,
" make_target " : " sitl-y6 " ,
" waf_target " : " bin/arducopter-y6 " ,
" waf_target " : " bin/arducopter-y6 " ,
" default_params_filename " : " y6_params.parm " ,
" default_params_filename " : " y6_params.parm " ,
} ,
} ,
@ -372,37 +389,37 @@ _options_for_frame = {
} ,
} ,
# HELICOPTER
# HELICOPTER
" heli " : {
" heli " : {
" make_target " : " sitl-heli " ,
" make_target " : " sitl-heli " ,
" waf_target " : " bin/arducopter-heli " ,
" waf_target " : " bin/arducopter-heli " ,
" default_params_filename " : " Helicopter.parm " ,
" default_params_filename " : " Helicopter.parm " ,
} ,
} ,
" heli-dual " : {
" heli-dual " : {
" make_target " : " sitl-heli-dual " ,
" make_target " : " sitl-heli-dual " ,
" waf_target " : " bin/arducopter-coax " , # is this correct? -pb201604301447
" waf_target " : " bin/arducopter-coax " , # is this correct? -pb201604301447
} ,
} ,
" heli-compound " : {
" heli-compound " : {
" make_target " : " sitl-heli-compound " ,
" make_target " : " sitl-heli-compound " ,
" waf_target " : " bin/arducopter-coax " , # is this correct? -pb201604301447
" waf_target " : " bin/arducopter-coax " , # is this correct? -pb201604301447
} ,
} ,
" singlecopter " : {
" singlecopter " : {
" make_target " : " sitl-single " ,
" make_target " : " sitl-single " ,
" waf_target " : " bin/arducopter-single " ,
" waf_target " : " bin/arducopter-single " ,
" default_params_filename " : " SingleCopter.parm " ,
" default_params_filename " : " SingleCopter.parm " ,
} ,
} ,
" coaxcopter " : {
" coaxcopter " : {
" make_target " : " sitl-coax " ,
" make_target " : " sitl-coax " ,
" waf_target " : " bin/arducopter-coax " ,
" waf_target " : " bin/arducopter-coax " ,
" default_params_filename " : " CoaxCopter.parm " ,
" default_params_filename " : " CoaxCopter.parm " ,
} ,
} ,
# PLANE
# PLANE
" quadplane-tilttri " : {
" quadplane-tilttri " : {
" make_target " : " sitl-tri " ,
" make_target " : " sitl-tri " ,
" waf_target " : " bin/arduplane-tri " ,
" waf_target " : " bin/arduplane-tri " ,
" default_params_filename " : " quadplane-tilttri.parm " ,
" default_params_filename " : " quadplane-tilttri.parm " ,
} ,
} ,
" quadplane-tri " : {
" quadplane-tri " : {
" make_target " : " sitl-tri " ,
" make_target " : " sitl-tri " ,
" waf_target " : " bin/arduplane-tri " ,
" waf_target " : " bin/arduplane-tri " ,
" default_params_filename " : " quadplane-tri.parm " ,
" default_params_filename " : " quadplane-tri.parm " ,
} ,
} ,
" quadplane " : {
" quadplane " : {
@ -454,17 +471,19 @@ _default_waf_target = {
" AntennaTracker " : " bin/antennatracker " ,
" AntennaTracker " : " bin/antennatracker " ,
}
}
def default_waf_target ( vehicle ) :
def default_waf_target ( vehicle ) :
''' r eturns a waf target based on vehicle type, which is often determined by which directory the user is in'''
""" R eturns a waf target based on vehicle type, which is often determined by which directory the user is in"""
return _default_waf_target [ vehicle ]
return _default_waf_target [ vehicle ]
def options_for_frame ( frame , vehicle , opts ) :
def options_for_frame ( frame , vehicle , opts ) :
''' return informatiom about how to sitl for frame e.g. build-type==sitl '''
""" Return informatiom about how to sitl for frame e.g. build-type==sitl """
ret = None
ret = None
if frame in _options_for_frame :
if frame in _options_for_frame :
ret = _options_for_frame [ frame ]
ret = _options_for_frame [ frame ]
else :
else :
for p in [ " octa " , " tri " , " y6 " , " firefly " , " heli " , " last_letter " , " jsbsim " , " quadplane " , " plane-elevon " , " plane-vtail " , " plane " ] :
for p in [ " octa " , " tri " , " y6 " , " firefly " , " heli " , " last_letter " , " jsbsim " , " quadplane " , " plane-elevon " , " plane-vtail " , " plane " ] :
if frame . startswith ( p ) :
if frame . startswith ( p ) :
ret = _options_for_frame [ p ]
ret = _options_for_frame [ p ]
break
break
@ -474,23 +493,22 @@ def options_for_frame(frame, vehicle, opts):
if ret is None :
if ret is None :
ret = { }
ret = { }
if not ret . has_key ( " model " ) :
if " model " not in ret :
ret [ " model " ] = frame
ret [ " model " ] = frame
if not ret . has_key ( " sitl-port " ) :
if " sitl-port " not in ret :
ret [ " sitl-port " ] = True
ret [ " sitl-port " ] = True
if opts . model is not None :
if opts . model is not None :
ret [ " model " ] = opts . model
ret [ " model " ] = opts . model
if ( ret [ " model " ] . find ( " xplane " ) != - 1 or
if ( ret [ " model " ] . find ( " xplane " ) != - 1 or ret [ " model " ] . find ( " flightaxis " ) != - 1 ) :
ret [ " model " ] . find ( " flightaxis " ) != - 1 ) :
ret [ " sitl-port " ] = False
ret [ " sitl-port " ] = False
if not ret . has_key ( " make_target " ) :
if " make_target " not in ret :
ret [ " make_target " ] = " sitl "
ret [ " make_target " ] = " sitl "
if not ret . has_key ( " waf_target " ) :
if " waf_target " not in ret :
ret [ " waf_target " ] = default_waf_target ( vehicle )
ret [ " waf_target " ] = default_waf_target ( vehicle )
if opts . build_target is not None :
if opts . build_target is not None :
@ -499,8 +517,9 @@ def options_for_frame(frame, vehicle, opts):
return ret
return ret
def do_build_waf ( opts , frame_options ) :
def do_build_waf ( opts , frame_options ) :
''' build sitl using waf '''
""" Build sitl using waf """
progress ( " WAF build " )
progress ( " WAF build " )
old_dir = os . getcwd ( )
old_dir = os . getcwd ( )
@ -509,7 +528,7 @@ def do_build_waf(opts, frame_options):
waf_light = os . path . join ( root_dir , " modules/waf/waf-light " )
waf_light = os . path . join ( root_dir , " modules/waf/waf-light " )
cmd_configure = [ waf_light , " configure " , " --board " , " sitl " ]
cmd_configure = [ waf_light , " configure " , " --board " , " sitl " ]
if opts . debug :
if opts . debug :
cmd_configure . append ( " --debug " )
cmd_configure . append ( " --debug " )
@ -524,7 +543,7 @@ def do_build_waf(opts, frame_options):
_ , sts = run_cmd_blocking ( " Building " , cmd_build )
_ , sts = run_cmd_blocking ( " Building " , cmd_build )
if sts != 0 : # build failed
if sts != 0 : # build failed
if opts . rebuild_on_failure :
if opts . rebuild_on_failure :
progress ( " Build failed; cleaning and rebuilding " )
progress ( " Build failed; cleaning and rebuilding " )
run_cmd_blocking ( " Building clean " , [ waf_light , " clean " ] )
run_cmd_blocking ( " Building clean " , [ waf_light , " clean " ] )
@ -541,7 +560,7 @@ def do_build_waf(opts, frame_options):
def do_build ( vehicledir , opts , frame_options ) :
def do_build ( vehicledir , opts , frame_options ) :
''' build build target (e.g. sitl) in directory vehicledir '''
""" Build build target (e.g. sitl) in directory vehicledir """
if opts . build_system == ' waf ' :
if opts . build_system == ' waf ' :
return do_build_waf ( opts , frame_options )
return do_build_waf ( opts , frame_options )
@ -561,42 +580,47 @@ def do_build(vehicledir, opts, frame_options):
if opts . jobs is not None :
if opts . jobs is not None :
build_cmd + = [ ' -j ' , str ( opts . jobs ) ]
build_cmd + = [ ' -j ' , str ( opts . jobs ) ]
_ , sts = run_cmd_blocking ( " Building %s " % ( build_target ) , build_cmd )
_ , sts = run_cmd_blocking ( " Building %s " % build_target , build_cmd )
if sts != 0 :
if sts != 0 :
progress ( " Build failed; cleaning and rebuilding " )
progress ( " Build failed; cleaning and rebuilding " )
run_cmd_blocking ( " Cleaning " , [ " make " , " clean " ] )
run_cmd_blocking ( " Cleaning " , [ " make " , " clean " ] )
_ , sts = run_cmd_blocking ( " Building %s " % ( build_target ) , build_cmd )
_ , sts = run_cmd_blocking ( " Building %s " % build_target , build_cmd )
if sts != 0 :
if sts != 0 :
progress ( " Build failed " )
progress ( " Build failed " )
sys . exit ( 1 )
sys . exit ( 1 )
os . chdir ( old_dir )
os . chdir ( old_dir )
def find_location_by_name ( autotest , locname ) :
def find_location_by_name ( autotest , locname ) :
''' search locations.txt for locname, return GPS coords '''
""" Search locations.txt for locname, return GPS coords """
locations_filepath = os . path . join ( autotest , " locations.txt " )
locations_filepath = os . path . join ( autotest , " locations.txt " )
for line in open ( locations_filepath , ' r ' ) :
for line in open ( locations_filepath , ' r ' ) :
line = line . rstrip ( " \n " )
line = line . rstrip ( " \n " )
( name , loc ) = line . split ( " = " )
( name , loc ) = line . split ( " = " )
if name == locname :
if name == locname :
return loc
return loc
print ( " Failed to find location ( %s ) " % ( opts . location ) )
print ( " Failed to find location ( %s ) " % cmd_ opts. location )
sys . exit ( 1 )
sys . exit ( 1 )
def progress_cmd ( what , cmd ) :
def progress_cmd ( what , cmd ) :
''' print cmd in a way a user could cut-and-paste to get the same effect '''
""" Print cmd in a way a user could cut-and-paste to get the same effect """
progress ( what )
progress ( what )
shell_text = " %s " % ( " " . join ( [ ' " %s " ' % x for x in cmd ] ) )
shell_text = " %s " % ( " " . join ( [ ' " %s " ' % x for x in cmd ] ) )
progress ( shell_text )
progress ( shell_text )
def run_cmd_blocking ( what , cmd , quiet = False , * * kw ) :
def run_cmd_blocking ( what , cmd , quiet = False , * * kw ) :
if not quiet :
if not quiet :
progress_cmd ( what , cmd )
progress_cmd ( what , cmd )
p = subprocess . Popen ( cmd , * * kw )
p = subprocess . Popen ( cmd , * * kw )
return os . waitpid ( p . pid , 0 )
return os . waitpid ( p . pid , 0 )
def run_in_terminal_window ( autotest , name , cmd ) :
def run_in_terminal_window ( autotest , name , cmd ) :
''' execute the run_in_terminal_window.sh command for cmd '''
""" Execute the run_in_terminal_window.sh command for cmd """
global windowID
global windowID
runme = [ os . path . join ( autotest , " run_in_terminal_window.sh " ) , name ]
runme = [ os . path . join ( autotest , " run_in_terminal_window.sh " ) , name ]
runme . extend ( cmd )
runme . extend ( cmd )
@ -604,17 +628,18 @@ def run_in_terminal_window(autotest, name, cmd):
if under_macos ( ) :
if under_macos ( ) :
# on MacOS record the window IDs so we can close them later
# on MacOS record the window IDs so we can close them later
out = subprocess . Popen ( runme , stdout = subprocess . PIPE ) . communicate ( ) [ 0 ]
out = subprocess . Popen ( runme , stdout = subprocess . PIPE ) . communicate ( ) [ 0 ]
import re
import re
p = re . compile ( ' tab 1 of window id (.*) ' )
p = re . compile ( ' tab 1 of window id (.*) ' )
windowID . append ( p . findall ( out ) [ 0 ] )
windowID . append ( p . findall ( out ) [ 0 ] )
else :
else :
p = subprocess . Popen ( runme )
p = subprocess . Popen ( runme )
tracker_uarta = None # blemish
tracker_uarta = None # blemish
def start_antenna_tracker ( autotest , opts ) :
def start_antenna_tracker ( autotest , opts ) :
''' compile and run the AntennaTracker, add tracker to mavproxy '''
""" Compile and run the AntennaTracker, add tracker to mavproxy """
global tracker_uarta
global tracker_uarta
progress ( " Preparing antenna tracker " )
progress ( " Preparing antenna tracker " )
tracker_home = find_location_by_name ( find_autotest_dir ( ) , opts . tracker_location )
tracker_home = find_location_by_name ( find_autotest_dir ( ) , opts . tracker_location )
@ -622,12 +647,13 @@ def start_antenna_tracker(autotest, opts):
do_build ( vehicledir , opts , " sitl-debug " )
do_build ( vehicledir , opts , " sitl-debug " )
tracker_instance = 1
tracker_instance = 1
os . chdir ( vehicledir )
os . chdir ( vehicledir )
tracker_uarta = " tcp:127.0.0.1: " + str ( 5760 + 10 * tracker_instance )
tracker_uarta = " tcp:127.0.0.1: " + str ( 5760 + 10 * tracker_instance )
exe = os . path . join ( vehicledir , " AntennaTracker.elf " )
exe = os . path . join ( vehicledir , " AntennaTracker.elf " )
run_in_terminal_window ( autotest , " AntennaTracker " , [ " nice " , exe , " -I " + str ( tracker_instance ) , " --model=tracker " , " --home= " + tracker_home ] )
run_in_terminal_window ( autotest , " AntennaTracker " , [ " nice " , exe , " -I " + str ( tracker_instance ) , " --model=tracker " , " --home= " + tracker_home ] )
def start_vehicle ( vehicle_binary , autotest , opts , stuff , loc ) :
''' run the ArduPilot binary '''
def start_vehicle ( binary , autotest , opts , stuff , loc ) :
""" Run the ArduPilot binary """
cmd_name = opts . vehicle
cmd_name = opts . vehicle
cmd = [ ]
cmd = [ ]
@ -649,30 +675,31 @@ def start_vehicle(vehicle_binary, autotest, opts, stuff, loc):
if opts . strace :
if opts . strace :
cmd_name + = " (strace) "
cmd_name + = " (strace) "
cmd . append ( " strace " )
cmd . append ( " strace " )
strace_options = [ ' -o ' , vehicle_ binary + ' .strace ' , ' -s ' , ' 8000 ' , ' -ttt ' ]
strace_options = [ ' -o ' , binary + ' .strace ' , ' -s ' , ' 8000 ' , ' -ttt ' ]
cmd . extend ( strace_options )
cmd . extend ( strace_options )
cmd . append ( vehicle_ binary)
cmd . append ( binary )
cmd . append ( " -S " )
cmd . append ( " -S " )
cmd . append ( " -I " + str ( opts . instance ) )
cmd . append ( " -I " + str ( opts . instance ) )
cmd . extend ( [ " --home " , loc ] )
cmd . extend ( [ " --home " , loc ] )
if opts . wipe_eeprom :
if opts . wipe_eeprom :
cmd . append ( " -w " )
cmd . append ( " -w " )
cmd . extend ( [ " --model " , stuff [ " model " ] ] )
cmd . extend ( [ " --model " , stuff [ " model " ] ] )
cmd . extend ( [ " --speedup " , str ( opts . speedup ) ] )
cmd . extend ( [ " --speedup " , str ( opts . speedup ) ] )
if opts . sitl_instance_args :
if opts . sitl_instance_args :
cmd . extend ( opts . sitl_instance_args . split ( " " ) ) # this could be a lot better..
cmd . extend ( opts . sitl_instance_args . split ( " " ) ) # this could be a lot better..
if opts . mavlink_gimbal :
if opts . mavlink_gimbal :
cmd . append ( " --gimbal " )
cmd . append ( " --gimbal " )
if stuff . has_key ( " default_params_filename " ) :
if " default_params_filename " in stuff :
path = os . path . join ( autotest , stuff [ " default_params_filename " ] )
path = os . path . join ( autotest , stuff [ " default_params_filename " ] )
progress ( " Using defaults from ( %s ) " % ( path , ) )
progress ( " Using defaults from ( %s ) " % ( path , ) )
cmd . extend ( [ " --defaults " , path ] )
cmd . extend ( [ " --defaults " , path ] )
run_in_terminal_window ( autotest , cmd_name , cmd )
run_in_terminal_window ( autotest , cmd_name , cmd )
def start_mavproxy ( opts , stuff ) :
def start_mavproxy ( opts , stuff ) :
''' run mavproxy '''
""" Run mavproxy """
# FIXME: would be nice to e.g. "mavproxy.mavproxy(....).run" rather than shelling out
# FIXME: would be nice to e.g. "mavproxy.mavproxy(....).run" rather than shelling out
extra_cmd = " "
extra_cmd = " "
@ -695,7 +722,7 @@ def start_mavproxy(opts, stuff):
if getpass . getuser ( ) == " vagrant " :
if getpass . getuser ( ) == " vagrant " :
cmd . extend ( [ " --out " , " 10.0.2.2:14550 " ] )
cmd . extend ( [ " --out " , " 10.0.2.2:14550 " ] )
for port in [ 14550 , 14551 ] :
for port in [ 14550 , 14551 ] :
cmd . extend ( [ " --out " , " 127.0.0.1: " + str ( port ) ] )
cmd . extend ( [ " --out " , " 127.0.0.1: " + str ( port ) ] )
if opts . tracker :
if opts . tracker :
cmd . extend ( [ " --load-module " , " tracker " ] )
cmd . extend ( [ " --load-module " , " tracker " ] )
@ -706,11 +733,11 @@ def start_mavproxy(opts, stuff):
if opts . mavlink_gimbal :
if opts . mavlink_gimbal :
cmd . extend ( [ " --load-module " , " gimbal " ] )
cmd . extend ( [ " --load-module " , " gimbal " ] )
if stuff . has_key ( " extra_mavlink_cmds " ) :
if " extra_mavlink_cmds " in stuff :
extra_cmd + = " " + stuff [ " extra_mavlink_cmds " ]
extra_cmd + = " " + stuff [ " extra_mavlink_cmds " ]
if opts . mavproxy_args :
if opts . mavproxy_args :
cmd . extend ( opts . mavproxy_args . split ( " " ) ) # this could be a lot better..
cmd . extend ( opts . mavproxy_args . split ( " " ) ) # this could be a lot better..
# compatibility pass-through parameters (for those that don't want
# compatibility pass-through parameters (for those that don't want
# to use -C :-)
# to use -C :-)
@ -725,63 +752,63 @@ def start_mavproxy(opts, stuff):
cmd . extend ( [ ' --cmd ' , extra_cmd ] )
cmd . extend ( [ ' --cmd ' , extra_cmd ] )
local_mp_modules_dir = os . path . abspath (
local_mp_modules_dir = os . path . abspath (
os . path . join ( __file__ , ' .. ' , ' .. ' , ' mavproxy_modules ' ) )
os . path . join ( __file__ , ' .. ' , ' .. ' , ' mavproxy_modules ' ) )
env = dict ( os . environ )
env = dict ( os . environ )
env [ ' PYTHONPATH ' ] = local_mp_modules_dir + os . pathsep + env . get ( ' PYTHONPATH ' , ' ' )
env [ ' PYTHONPATH ' ] = local_mp_modules_dir + os . pathsep + env . get ( ' PYTHONPATH ' , ' ' )
run_cmd_blocking ( " Run MavProxy " , cmd , env = env )
run_cmd_blocking ( " Run MavProxy " , cmd , env = env )
progress ( " MAVProxy exitted " )
progress ( " MAVProxy exitted " )
frame_opt ion s = options_for_frame ( opts . frame , opts . vehicle , opts )
frame_inf os = options_for_frame ( cmd_ opts. frame , cmd_ opts. vehicle , cmd_ opts)
if frame_opt ion s [ " model " ] == " jsbsim " :
if frame_inf os [ " model " ] == " jsbsim " :
check_jsbsim_version ( )
check_jsbsim_version ( )
vehicledir = os . path . realpath ( os . path . join ( find_root_dir ( ) , opts . vehicle ) )
vehicle_ dir = os . path . realpath ( os . path . join ( find_root_dir ( ) , cmd_ opts. vehicle ) )
if not os . path . exists ( vehicledir ) :
if not os . path . exists ( vehicle_ dir ) :
print ( " vehicle directory ( %s ) does not exist " % ( vehicledir , ) )
print ( " vehicle directory ( %s ) does not exist " % ( vehicle_ dir , ) )
sys . exit ( 1 )
sys . exit ( 1 )
if not opts . hil :
if not cmd_ opts. hil :
if opts . instance == 0 :
if cmd_ opts. instance == 0 :
kill_tasks ( )
kill_tasks ( )
if opts . tracker :
if cmd_ opts. tracker :
start_antenna_tracker ( find_autotest_dir ( ) , opts )
start_antenna_tracker ( find_autotest_dir ( ) , cmd_ opts)
if opts . custom_location :
if cmd_ opts. custom_location :
loc = opts . custom_location
location = cmd_ opts. custom_location
progress ( " Starting up at %s " % ( loc , ) )
progress ( " Starting up at %s " % ( location , ) )
else :
else :
loc = find_location_by_name ( find_autotest_dir ( ) , opts . location )
location = find_location_by_name ( find_autotest_dir ( ) , cmd_ opts. location )
progress ( " Starting up at %s ( %s ) " % ( loc , opts . location ) )
progress ( " Starting up at %s ( %s ) " % ( location , cmd_ opts. location ) )
if opts . hil :
if cmd_ opts. hil :
# (unlikely)
# (unlikely)
run_in_terminal_window ( find_autotest_dir ( ) , " JSBSim " , [ os . path . join ( find_autotest_dir ( ) , " jsb_sim/runsim.py " ) , " --home " , loc , " --speedup= " + str ( opts . speedup ) ] )
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 ) ] )
else :
else :
if not opts . no_rebuild : # i.e. we should rebuild
if not cmd_ opts. no_rebuild : # i.e. we should rebuild
do_build ( vehicledir , opts , frame_opt ion s )
do_build ( vehicle_ dir , cmd_ opts, frame_inf os )
if opts . build_system == " waf " :
if cmd_ opts. build_system == " waf " :
if opts . debug :
if cmd_ opts. debug :
binary_basedir = " build/sitl-debug "
binary_basedir = " build/sitl-debug "
else :
else :
binary_basedir = " build/sitl "
binary_basedir = " build/sitl "
vehicle_binary = os . path . join ( find_root_dir ( ) , binary_basedir , frame_opt ion s [ " waf_target " ] )
vehicle_binary = os . path . join ( find_root_dir ( ) , binary_basedir , frame_inf os [ " waf_target " ] )
else :
else :
vehicle_binary = os . path . join ( vehicledir , opts . vehicle + " .elf " )
vehicle_binary = os . path . join ( vehicle_ dir , cmd_ opts. vehicle + " .elf " )
if not os . path . exists ( vehicle_binary ) :
if not os . path . exists ( vehicle_binary ) :
print ( " Vehicle binary ( %s ) does not exist " % ( vehicle_binary , ) )
print ( " Vehicle binary ( %s ) does not exist " % ( vehicle_binary , ) )
sys . exit ( 1 )
sys . exit ( 1 )
start_vehicle ( vehicle_binary , find_autotest_dir ( ) , opts , frame_opt ion s , loc )
start_vehicle ( vehicle_binary , find_autotest_dir ( ) , cmd_ opts, frame_inf os , location )
if opts . delay_start :
if cmd_ opts. delay_start :
progress ( " Sleeping for %f seconds " % ( opts . delay_start , ) )
progress ( " Sleeping for %f seconds " % ( cmd_ opts. delay_start , ) )
time . sleep ( float ( opts . delay_start ) )
time . sleep ( float ( cmd_ opts. delay_start ) )
start_mavproxy ( opts , frame_opt ion s )
start_mavproxy ( cmd_ opts, frame_inf os )
sys . exit ( 0 )
sys . exit ( 0 )