2011-12-02 00:19:50 -04:00
|
|
|
#!/usr/bin/env python
|
2016-07-31 07:22:06 -03:00
|
|
|
"""
|
|
|
|
Run a jsbsim model as a child process.
|
|
|
|
"""
|
2016-11-08 07:06:05 -04:00
|
|
|
from __future__ import print_function
|
2016-07-31 07:22:06 -03:00
|
|
|
import atexit
|
|
|
|
import errno
|
|
|
|
import fdpexpect
|
|
|
|
import math
|
|
|
|
import os
|
|
|
|
import select
|
|
|
|
import signal
|
|
|
|
import socket
|
|
|
|
import struct
|
|
|
|
import sys
|
|
|
|
import time
|
|
|
|
|
|
|
|
import pexpect
|
|
|
|
from pymavlink import fgFDM
|
2011-12-02 00:19:50 -04:00
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
from .. pysim import util
|
2011-12-02 00:19:50 -04:00
|
|
|
|
|
|
|
|
|
|
|
class control_state(object):
|
|
|
|
def __init__(self):
|
|
|
|
self.aileron = 0
|
|
|
|
self.elevator = 0
|
|
|
|
self.throttle = 0
|
|
|
|
self.rudder = 0
|
|
|
|
self.ground_height = 0
|
|
|
|
|
|
|
|
sitl_state = control_state()
|
|
|
|
|
|
|
|
|
|
|
|
def interpret_address(addrstr):
|
2016-07-31 07:22:06 -03:00
|
|
|
"""Interpret a IP:port string."""
|
2011-12-02 00:19:50 -04:00
|
|
|
a = addrstr.split(':')
|
|
|
|
a[1] = int(a[1])
|
|
|
|
return tuple(a)
|
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2011-12-02 00:19:50 -04:00
|
|
|
def jsb_set(variable, value):
|
2016-07-31 07:22:06 -03:00
|
|
|
"""Set a JSBSim variable."""
|
2011-12-02 00:19:50 -04:00
|
|
|
global jsb_console
|
|
|
|
jsb_console.send('set %s %s\r\n' % (variable, value))
|
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2012-08-14 03:51:35 -03:00
|
|
|
def setup_template(home):
|
2016-07-31 07:22:06 -03:00
|
|
|
"""Setup aircraft/Rascal/reset.xml ."""
|
2013-08-14 20:47:24 -03:00
|
|
|
global opts
|
2011-12-02 00:19:50 -04:00
|
|
|
v = home.split(',')
|
|
|
|
if len(v) != 4:
|
2012-08-14 03:51:35 -03:00
|
|
|
print("home should be lat,lng,alt,hdg - '%s'" % home)
|
2011-12-02 00:19:50 -04:00
|
|
|
sys.exit(1)
|
|
|
|
latitude = float(v[0])
|
|
|
|
longitude = float(v[1])
|
|
|
|
altitude = float(v[2])
|
|
|
|
heading = float(v[3])
|
|
|
|
sitl_state.ground_height = altitude
|
2012-08-14 03:51:35 -03:00
|
|
|
template = os.path.join('aircraft', 'Rascal', 'reset_template.xml')
|
|
|
|
reset = os.path.join('aircraft', 'Rascal', 'reset.xml')
|
2016-07-31 07:22:06 -03:00
|
|
|
xml = open(template).read() % {'LATITUDE': str(latitude),
|
|
|
|
'LONGITUDE': str(longitude),
|
|
|
|
'HEADING': str(heading)}
|
2012-08-14 03:51:35 -03:00
|
|
|
open(reset, mode='w').write(xml)
|
|
|
|
print("Wrote %s" % reset)
|
2013-08-14 20:47:24 -03:00
|
|
|
|
|
|
|
baseport = int(opts.simout.split(':')[1])
|
|
|
|
|
2015-04-13 20:04:11 -03:00
|
|
|
template = os.path.join('jsb_sim', 'fgout_template.xml')
|
2016-07-31 07:22:06 -03:00
|
|
|
out = os.path.join('jsb_sim', 'fgout.xml')
|
|
|
|
xml = open(template).read() % {'FGOUTPORT': str(baseport+3)}
|
2013-08-14 20:47:24 -03:00
|
|
|
open(out, mode='w').write(xml)
|
|
|
|
print("Wrote %s" % out)
|
|
|
|
|
2015-04-13 20:04:11 -03:00
|
|
|
template = os.path.join('jsb_sim', 'rascal_test_template.xml')
|
2016-07-31 07:22:06 -03:00
|
|
|
out = os.path.join('jsb_sim', 'rascal_test.xml')
|
|
|
|
xml = open(template).read() % {'JSBCONSOLEPORT': str(baseport+4)}
|
2013-08-14 20:47:24 -03:00
|
|
|
open(out, mode='w').write(xml)
|
|
|
|
print("Wrote %s" % out)
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2011-12-02 00:19:50 -04:00
|
|
|
|
|
|
|
def process_sitl_input(buf):
|
2016-07-31 07:22:06 -03:00
|
|
|
"""Process control changes from SITL sim."""
|
2012-08-24 08:22:20 -03:00
|
|
|
control = list(struct.unpack('<14H', buf))
|
|
|
|
pwm = control[:11]
|
|
|
|
(speed, direction, turbulance) = control[11:]
|
|
|
|
|
|
|
|
global wind
|
2016-07-31 07:22:06 -03:00
|
|
|
wind.speed = speed*0.01
|
|
|
|
wind.direction = direction*0.01
|
2012-08-24 08:22:20 -03:00
|
|
|
wind.turbulance = turbulance*0.01
|
2016-07-31 07:22:06 -03:00
|
|
|
|
|
|
|
aileron = (pwm[0]-1500)/500.0
|
2011-12-02 07:45:48 -04:00
|
|
|
elevator = (pwm[1]-1500)/500.0
|
|
|
|
throttle = (pwm[2]-1000)/1000.0
|
2014-06-03 20:40:07 -03:00
|
|
|
if opts.revthr:
|
|
|
|
throttle = 1.0 - throttle
|
2016-07-31 07:22:06 -03:00
|
|
|
rudder = (pwm[3]-1500)/500.0
|
2013-04-04 21:29:15 -03:00
|
|
|
|
|
|
|
if opts.elevon:
|
|
|
|
# fake an elevon plane
|
|
|
|
ch1 = aileron
|
|
|
|
ch2 = elevator
|
2016-07-31 07:22:06 -03:00
|
|
|
aileron = (ch2-ch1)/2.0
|
2019-07-23 22:27:54 -03:00
|
|
|
# the minus does away with the need for RC2_REVERSED=-1
|
2013-04-04 21:29:15 -03:00
|
|
|
elevator = -(ch2+ch1)/2.0
|
2013-04-05 01:20:48 -03:00
|
|
|
|
|
|
|
if opts.vtail:
|
|
|
|
# fake an elevon plane
|
|
|
|
ch1 = elevator
|
|
|
|
ch2 = rudder
|
|
|
|
# this matches VTAIL_OUTPUT==2
|
|
|
|
elevator = (ch2-ch1)/2.0
|
2016-07-31 07:22:06 -03:00
|
|
|
rudder = (ch2+ch1)/2.0
|
2015-04-12 20:07:22 -03:00
|
|
|
|
|
|
|
buf = ''
|
2011-12-02 00:19:50 -04:00
|
|
|
if aileron != sitl_state.aileron:
|
2015-04-12 20:07:22 -03:00
|
|
|
buf += 'set fcs/aileron-cmd-norm %s\n' % aileron
|
2011-12-02 00:19:50 -04:00
|
|
|
sitl_state.aileron = aileron
|
|
|
|
if elevator != sitl_state.elevator:
|
2015-04-12 20:07:22 -03:00
|
|
|
buf += 'set fcs/elevator-cmd-norm %s\n' % elevator
|
2011-12-02 00:19:50 -04:00
|
|
|
sitl_state.elevator = elevator
|
|
|
|
if rudder != sitl_state.rudder:
|
2015-04-12 20:07:22 -03:00
|
|
|
buf += 'set fcs/rudder-cmd-norm %s\n' % rudder
|
2011-12-02 00:19:50 -04:00
|
|
|
sitl_state.rudder = rudder
|
|
|
|
if throttle != sitl_state.throttle:
|
2015-04-12 20:07:22 -03:00
|
|
|
buf += 'set fcs/throttle-cmd-norm %s\n' % throttle
|
2011-12-02 00:19:50 -04:00
|
|
|
sitl_state.throttle = throttle
|
2015-04-12 20:07:22 -03:00
|
|
|
buf += 'step\n'
|
|
|
|
global jsb_console
|
|
|
|
jsb_console.send(buf)
|
2011-12-02 00:19:50 -04:00
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2011-12-13 00:28:03 -04:00
|
|
|
def update_wind(wind):
|
2016-07-31 07:22:06 -03:00
|
|
|
"""Update wind simulation."""
|
2011-12-13 00:28:03 -04:00
|
|
|
(speed, direction) = wind.current()
|
|
|
|
jsb_set('atmosphere/psiw-rad', math.radians(direction))
|
|
|
|
jsb_set('atmosphere/wind-mag-fps', speed/0.3048)
|
2015-03-24 12:03:18 -03:00
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2015-04-12 20:07:22 -03:00
|
|
|
def process_jsb_input(buf, simtime):
|
2016-07-31 07:22:06 -03:00
|
|
|
"""Process FG FDM input from JSBSim."""
|
2015-04-12 20:07:22 -03:00
|
|
|
global fdm, fg_out, sim_out
|
2011-12-02 00:19:50 -04:00
|
|
|
fdm.parse(buf)
|
|
|
|
if fg_out:
|
|
|
|
try:
|
|
|
|
agl = fdm.get('agl', units='meters')
|
|
|
|
fdm.set('altitude', agl+sitl_state.ground_height, units='meters')
|
|
|
|
fdm.set('rpm', sitl_state.throttle*1000)
|
|
|
|
fg_out.send(fdm.pack())
|
|
|
|
except socket.error as e:
|
2016-07-31 07:22:06 -03:00
|
|
|
if e.errno not in [errno.ECONNREFUSED]:
|
2011-12-02 00:19:50 -04:00
|
|
|
raise
|
|
|
|
|
2015-04-12 20:07:22 -03:00
|
|
|
timestamp = int(simtime*1.0e6)
|
|
|
|
|
2015-03-24 12:03:18 -03:00
|
|
|
simbuf = struct.pack('<Q17dI',
|
|
|
|
timestamp,
|
2011-12-02 00:19:50 -04:00
|
|
|
fdm.get('latitude', units='degrees'),
|
|
|
|
fdm.get('longitude', units='degrees'),
|
2011-12-02 07:12:58 -04:00
|
|
|
fdm.get('altitude', units='meters'),
|
2011-12-02 00:19:50 -04:00
|
|
|
fdm.get('psi', units='degrees'),
|
2011-12-02 07:12:58 -04:00
|
|
|
fdm.get('v_north', units='mps'),
|
|
|
|
fdm.get('v_east', units='mps'),
|
2013-03-27 20:28:08 -03:00
|
|
|
fdm.get('v_down', units='mps'),
|
2011-12-02 07:12:58 -04:00
|
|
|
fdm.get('A_X_pilot', units='mpss'),
|
|
|
|
fdm.get('A_Y_pilot', units='mpss'),
|
|
|
|
fdm.get('A_Z_pilot', units='mpss'),
|
2011-12-02 00:19:50 -04:00
|
|
|
fdm.get('phidot', units='dps'),
|
|
|
|
fdm.get('thetadot', units='dps'),
|
|
|
|
fdm.get('psidot', units='dps'),
|
|
|
|
fdm.get('phi', units='degrees'),
|
|
|
|
fdm.get('theta', units='degrees'),
|
|
|
|
fdm.get('psi', units='degrees'),
|
2011-12-02 07:12:58 -04:00
|
|
|
fdm.get('vcas', units='mps'),
|
2013-03-27 20:28:08 -03:00
|
|
|
0x4c56414f)
|
2011-12-02 00:19:50 -04:00
|
|
|
try:
|
|
|
|
sim_out.send(simbuf)
|
|
|
|
except socket.error as e:
|
2016-07-31 07:22:06 -03:00
|
|
|
if e.errno not in [errno.ECONNREFUSED]:
|
2011-12-02 00:19:50 -04:00
|
|
|
raise
|
|
|
|
|
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
################## main program ##################
|
2011-12-02 00:19:50 -04:00
|
|
|
from optparse import OptionParser
|
2011-12-15 08:34:05 -04:00
|
|
|
parser = OptionParser("runsim.py [options]")
|
2011-12-02 00:19:50 -04:00
|
|
|
parser.add_option("--simin", help="SITL input (IP:port)", default="127.0.0.1:5502")
|
|
|
|
parser.add_option("--simout", help="SITL output (IP:port)", default="127.0.0.1:5501")
|
2011-12-12 22:45:18 -04:00
|
|
|
parser.add_option("--fgout", help="FG display output (IP:port)", default="127.0.0.1:5503")
|
2011-12-02 00:19:50 -04:00
|
|
|
parser.add_option("--home", type='string', help="home lat,lng,alt,hdg (required)")
|
2015-04-13 20:04:11 -03:00
|
|
|
parser.add_option("--script", type='string', help='jsbsim model script', default='jsb_sim/rascal_test.xml')
|
2011-12-02 00:19:50 -04:00
|
|
|
parser.add_option("--options", type='string', help='jsbsim startup options')
|
2013-04-04 21:29:15 -03:00
|
|
|
parser.add_option("--elevon", action='store_true', default=False, help='assume elevon input')
|
2014-06-03 20:40:07 -03:00
|
|
|
parser.add_option("--revthr", action='store_true', default=False, help='reverse throttle')
|
2013-04-05 01:20:48 -03:00
|
|
|
parser.add_option("--vtail", action='store_true', default=False, help='assume vtail input')
|
2011-12-13 00:28:03 -04:00
|
|
|
parser.add_option("--wind", dest="wind", help="Simulate wind (speed,direction,turbulance)", default='0,0,0')
|
2015-04-12 20:07:22 -03:00
|
|
|
parser.add_option("--rate", type='int', help="Simulation rate (Hz)", default=1000)
|
|
|
|
parser.add_option("--speedup", type='float', default=1.0, help="speedup from realtime")
|
2011-12-02 00:19:50 -04:00
|
|
|
|
|
|
|
(opts, args) = parser.parse_args()
|
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
for m in ['home', 'script']:
|
2011-12-02 00:19:50 -04:00
|
|
|
if not opts.__dict__[m]:
|
|
|
|
print("Missing required option '%s'" % m)
|
|
|
|
parser.print_help()
|
|
|
|
sys.exit(1)
|
|
|
|
|
2011-12-02 00:21:15 -04:00
|
|
|
os.chdir(util.reltopdir('Tools/autotest'))
|
|
|
|
|
2011-12-02 00:19:50 -04:00
|
|
|
# kill off child when we exit
|
|
|
|
atexit.register(util.pexpect_close_all)
|
|
|
|
|
2012-08-14 03:51:35 -03:00
|
|
|
setup_template(opts.home)
|
|
|
|
|
2011-12-02 00:19:50 -04:00
|
|
|
# start child
|
2015-04-13 20:04:11 -03:00
|
|
|
cmd = "JSBSim --realtime --suspend --nice --simulation-rate=%u --logdirectivefile=jsb_sim/fgout.xml --script=%s" % (opts.rate, opts.script)
|
2011-12-02 00:19:50 -04:00
|
|
|
if opts.options:
|
|
|
|
cmd += ' %s' % opts.options
|
|
|
|
|
|
|
|
jsb = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
|
|
|
|
jsb.delaybeforesend = 0
|
|
|
|
util.pexpect_autoclose(jsb)
|
|
|
|
i = jsb.expect(["Successfully bound to socket for input on port (\d+)",
|
|
|
|
"Could not bind to socket for input"])
|
|
|
|
if i == 1:
|
|
|
|
print("Failed to start JSBSim - is another copy running?")
|
|
|
|
sys.exit(1)
|
|
|
|
jsb_out_address = interpret_address("127.0.0.1:%u" % int(jsb.match.group(1)))
|
|
|
|
jsb.expect("Creating UDP socket on port (\d+)")
|
|
|
|
jsb_in_address = interpret_address("127.0.0.1:%u" % int(jsb.match.group(1)))
|
|
|
|
jsb.expect("Successfully connected to socket for output")
|
|
|
|
jsb.expect("JSBSim Execution beginning")
|
|
|
|
|
|
|
|
# setup output to jsbsim
|
|
|
|
print("JSBSim console on %s" % str(jsb_out_address))
|
|
|
|
jsb_out = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
|
|
|
|
jsb_out.connect(jsb_out_address)
|
|
|
|
jsb_console = fdpexpect.fdspawn(jsb_out.fileno(), logfile=sys.stdout)
|
|
|
|
jsb_console.delaybeforesend = 0
|
|
|
|
|
|
|
|
# setup input from jsbsim
|
|
|
|
print("JSBSim FG FDM input on %s" % str(jsb_in_address))
|
|
|
|
jsb_in = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
|
|
|
|
jsb_in.bind(jsb_in_address)
|
|
|
|
jsb_in.setblocking(0)
|
|
|
|
|
|
|
|
# socket addresses
|
|
|
|
sim_out_address = interpret_address(opts.simout)
|
2016-07-31 07:22:06 -03:00
|
|
|
sim_in_address = interpret_address(opts.simin)
|
2011-12-02 00:19:50 -04:00
|
|
|
|
|
|
|
# setup input from SITL sim
|
|
|
|
sim_in = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
|
|
|
|
sim_in.bind(sim_in_address)
|
|
|
|
sim_in.setblocking(0)
|
|
|
|
|
|
|
|
# setup output to SITL sim
|
|
|
|
sim_out = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
|
|
|
|
sim_out.connect(interpret_address(opts.simout))
|
|
|
|
sim_out.setblocking(0)
|
|
|
|
|
|
|
|
# setup possible output to FlightGear for display
|
|
|
|
fg_out = None
|
|
|
|
if opts.fgout:
|
|
|
|
fg_out = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
|
|
|
|
fg_out.connect(interpret_address(opts.fgout))
|
|
|
|
|
|
|
|
|
2011-12-13 00:28:03 -04:00
|
|
|
# setup wind generator
|
|
|
|
wind = util.Wind(opts.wind)
|
|
|
|
|
2011-12-02 00:19:50 -04:00
|
|
|
fdm = fgFDM.fgFDM()
|
|
|
|
|
|
|
|
jsb_console.send('info\n')
|
|
|
|
jsb_console.send('resume\n')
|
2016-07-31 07:22:06 -03:00
|
|
|
jsb.expect(["trim computation time", "Trim Results"])
|
2011-12-02 00:19:50 -04:00
|
|
|
time.sleep(1.5)
|
2015-04-12 20:07:22 -03:00
|
|
|
jsb_console.send('step\n')
|
2011-12-02 00:19:50 -04:00
|
|
|
jsb_console.logfile = None
|
|
|
|
|
|
|
|
print("Simulator ready to fly")
|
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2011-12-02 00:19:50 -04:00
|
|
|
def main_loop():
|
2016-07-31 07:22:06 -03:00
|
|
|
"""Run main loop."""
|
2011-12-13 00:28:03 -04:00
|
|
|
tnow = time.time()
|
|
|
|
last_report = tnow
|
|
|
|
last_wind_update = tnow
|
2011-12-02 00:19:50 -04:00
|
|
|
frame_count = 0
|
2015-04-12 20:07:22 -03:00
|
|
|
simstep = 1.0/opts.rate
|
|
|
|
simtime = simstep
|
|
|
|
frame_time = 1.0/opts.rate
|
|
|
|
scaled_frame_time = frame_time/opts.speedup
|
|
|
|
last_wall_time = time.time()
|
|
|
|
achieved_rate = opts.speedup
|
2011-12-02 00:19:50 -04:00
|
|
|
|
|
|
|
while True:
|
2015-04-12 20:07:22 -03:00
|
|
|
new_frame = False
|
2011-12-02 00:19:50 -04:00
|
|
|
rin = [jsb_in.fileno(), sim_in.fileno(), jsb_console.fileno(), jsb.fileno()]
|
|
|
|
try:
|
|
|
|
(rin, win, xin) = select.select(rin, [], [], 1.0)
|
|
|
|
except select.error:
|
|
|
|
util.check_parent()
|
|
|
|
continue
|
|
|
|
|
2011-12-06 07:55:13 -04:00
|
|
|
tnow = time.time()
|
|
|
|
|
2011-12-02 00:19:50 -04:00
|
|
|
if jsb_in.fileno() in rin:
|
|
|
|
buf = jsb_in.recv(fdm.packet_size())
|
2015-04-12 20:07:22 -03:00
|
|
|
process_jsb_input(buf, simtime)
|
2011-12-02 00:19:50 -04:00
|
|
|
frame_count += 1
|
2015-04-12 20:07:22 -03:00
|
|
|
new_frame = True
|
2011-12-02 00:19:50 -04:00
|
|
|
|
|
|
|
if sim_in.fileno() in rin:
|
2012-08-24 08:22:20 -03:00
|
|
|
simbuf = sim_in.recv(28)
|
2011-12-02 00:19:50 -04:00
|
|
|
process_sitl_input(simbuf)
|
2015-04-12 20:07:22 -03:00
|
|
|
simtime += simstep
|
2011-12-06 07:55:13 -04:00
|
|
|
last_sim_input = tnow
|
2011-12-02 00:19:50 -04:00
|
|
|
|
|
|
|
# show any jsbsim console output
|
|
|
|
if jsb_console.fileno() in rin:
|
|
|
|
util.pexpect_drain(jsb_console)
|
|
|
|
if jsb.fileno() in rin:
|
|
|
|
util.pexpect_drain(jsb)
|
|
|
|
|
2012-07-02 21:19:20 -03:00
|
|
|
# only simulate wind above 5 meters, to prevent crashes while
|
|
|
|
# waiting for takeoff
|
2012-08-27 03:27:29 -03:00
|
|
|
if tnow - last_wind_update > 0.1:
|
2011-12-13 00:28:03 -04:00
|
|
|
update_wind(wind)
|
|
|
|
last_wind_update = tnow
|
|
|
|
|
2012-04-27 00:32:22 -03:00
|
|
|
if tnow - last_report > 3:
|
2015-04-12 20:07:22 -03:00
|
|
|
print("FPS %u asl=%.1f agl=%.1f roll=%.1f pitch=%.1f a=(%.2f %.2f %.2f) AR=%.1f" % (
|
2011-12-02 00:19:50 -04:00
|
|
|
frame_count / (time.time() - last_report),
|
|
|
|
fdm.get('altitude', units='meters'),
|
|
|
|
fdm.get('agl', units='meters'),
|
|
|
|
fdm.get('phi', units='degrees'),
|
|
|
|
fdm.get('theta', units='degrees'),
|
|
|
|
fdm.get('A_X_pilot', units='mpss'),
|
|
|
|
fdm.get('A_Y_pilot', units='mpss'),
|
2015-04-12 20:07:22 -03:00
|
|
|
fdm.get('A_Z_pilot', units='mpss'),
|
|
|
|
achieved_rate))
|
2011-12-02 00:19:50 -04:00
|
|
|
|
|
|
|
frame_count = 0
|
|
|
|
last_report = time.time()
|
|
|
|
|
2015-04-12 20:07:22 -03:00
|
|
|
if new_frame:
|
|
|
|
now = time.time()
|
|
|
|
if now < last_wall_time + scaled_frame_time:
|
|
|
|
time.sleep(last_wall_time+scaled_frame_time - now)
|
|
|
|
now = time.time()
|
|
|
|
|
|
|
|
if now > last_wall_time and now - last_wall_time < 0.1:
|
|
|
|
rate = 1.0/(now - last_wall_time)
|
|
|
|
achieved_rate = (0.98*achieved_rate) + (0.02*rate)
|
|
|
|
if achieved_rate < opts.rate*opts.speedup:
|
|
|
|
scaled_frame_time *= 0.999
|
|
|
|
else:
|
|
|
|
scaled_frame_time *= 1.001
|
|
|
|
|
|
|
|
last_wall_time = now
|
|
|
|
|
2016-07-31 07:22:06 -03:00
|
|
|
|
2011-12-02 00:19:50 -04:00
|
|
|
def exit_handler():
|
2016-07-31 07:22:06 -03:00
|
|
|
"""Exit the sim."""
|
2015-04-12 20:07:22 -03:00
|
|
|
print("running exit handler")
|
2011-12-02 00:19:50 -04:00
|
|
|
signal.signal(signal.SIGINT, signal.SIG_IGN)
|
|
|
|
signal.signal(signal.SIGTERM, signal.SIG_IGN)
|
|
|
|
# JSBSim really doesn't like to die ...
|
|
|
|
if getattr(jsb, 'pid', None) is not None:
|
|
|
|
os.kill(jsb.pid, signal.SIGKILL)
|
|
|
|
jsb_console.send('quit\n')
|
|
|
|
jsb.close(force=True)
|
|
|
|
util.pexpect_close_all()
|
|
|
|
sys.exit(1)
|
|
|
|
|
|
|
|
signal.signal(signal.SIGINT, exit_handler)
|
|
|
|
signal.signal(signal.SIGTERM, exit_handler)
|
|
|
|
|
|
|
|
try:
|
|
|
|
main_loop()
|
2015-04-12 20:07:22 -03:00
|
|
|
except Exception as ex:
|
|
|
|
print(ex)
|
2011-12-02 00:19:50 -04:00
|
|
|
exit_handler()
|
|
|
|
raise
|