mirror of https://github.com/ArduPilot/ardupilot
SITL: make it easier to start ArduPlane SITL at any location
this generates a jsbsim startup XML file from a template
This commit is contained in:
parent
93f45f232f
commit
b018d7ba77
|
@ -0,0 +1,11 @@
|
|||
<?xml version="1.0"?>
|
||||
<initialize name="Start up at Canberra Model Aircraft Club">
|
||||
<latitude unit="DEG"> %(LATITUDE)s </latitude>
|
||||
<longitude unit="DEG"> %(LONGITUDE)s </longitude>
|
||||
<altitude unit="M"> 0 </altitude>
|
||||
<vt unit="FT/SEC"> 0.0 </vt>
|
||||
<gamma unit="DEG"> 0.0 </gamma>
|
||||
<phi unit="DEG"> 0.0 </phi>
|
||||
<theta unit="DEG"> 0.0 </theta>
|
||||
<psi unit="DEG"> %(HEADING)s </psi>
|
||||
</initialize>
|
|
@ -8,7 +8,7 @@
|
|||
test ArduPlane using Rascal110 and JSBSim
|
||||
</description>
|
||||
|
||||
<use aircraft="Rascal" initialize="reset_CMAC"/>
|
||||
<use aircraft="Rascal" initialize="reset"/>
|
||||
|
||||
<!-- we control the servos via the jsbsim console
|
||||
interface on TCP 5124 -->
|
||||
|
|
|
@ -31,23 +31,25 @@ def jsb_set(variable, value):
|
|||
global jsb_console
|
||||
jsb_console.send('set %s %s\r\n' % (variable, value))
|
||||
|
||||
def setup_home(home):
|
||||
'''setup home location'''
|
||||
def setup_template(home):
|
||||
'''setup aircraft/Rascal/reset.xml'''
|
||||
v = home.split(',')
|
||||
if len(v) != 4:
|
||||
print("home should be lat,lng,alt,hdg")
|
||||
print("home should be lat,lng,alt,hdg - '%s'" % home)
|
||||
sys.exit(1)
|
||||
latitude = float(v[0])
|
||||
longitude = float(v[1])
|
||||
altitude = float(v[2])
|
||||
heading = float(v[3])
|
||||
sitl_state.ground_height = altitude
|
||||
template = os.path.join('aircraft', 'Rascal', 'reset_template.xml')
|
||||
reset = os.path.join('aircraft', 'Rascal', 'reset.xml')
|
||||
xml = open(template).read() % { 'LATITUDE' : str(latitude),
|
||||
'LONGITUDE' : str(longitude),
|
||||
'HEADING' : str(heading) }
|
||||
open(reset, mode='w').write(xml)
|
||||
print("Wrote %s" % reset)
|
||||
|
||||
jsb_set('position/lat-gc-deg', latitude)
|
||||
jsb_set('position/long-gc-deg', longitude)
|
||||
jsb_set('attitude/psi-rad', math.radians(heading))
|
||||
jsb_set('attitude/phi-rad', 0)
|
||||
jsb_set('attitude/theta-rad', 0)
|
||||
|
||||
def process_sitl_input(buf):
|
||||
'''process control changes from SITL sim'''
|
||||
|
@ -142,6 +144,8 @@ os.chdir(util.reltopdir('Tools/autotest'))
|
|||
# kill off child when we exit
|
||||
atexit.register(util.pexpect_close_all)
|
||||
|
||||
setup_template(opts.home)
|
||||
|
||||
# start child
|
||||
cmd = "JSBSim --realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=jsbsim/fgout.xml --script=%s" % opts.script
|
||||
if opts.options:
|
||||
|
@ -198,9 +202,6 @@ if opts.fgout:
|
|||
# setup wind generator
|
||||
wind = util.Wind(opts.wind)
|
||||
|
||||
|
||||
setup_home(opts.home)
|
||||
|
||||
fdm = fgFDM.fgFDM()
|
||||
|
||||
jsb_console.send('info\n')
|
||||
|
|
Loading…
Reference in New Issue