-
Notifications
You must be signed in to change notification settings - Fork 2
/
PSim.py
1079 lines (837 loc) · 36.4 KB
/
PSim.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# FGROOT = /usr/share/games/flightgear
# DRI_PRIME=1 fgfs --airport=SBGP --aircraft=Embraer170 --aircraft-dir=./FlightGear/Aircraft/E-jet-family/ --native-fdm=socket,in,60,,5500,udp --fdm=null --enable-hud --in-air --fog-disable --shading-smooth --texture-filtering=4 --timeofday=morning --altitude=2500 --prop:/sim/hud/path[1]=Huds/NTPS.xml
# DRI_PRIME=1 fgfs --airport=LOWI --aircraft=Embraer170 --aircraft-dir=./FlightGear/Aircraft/E-jet-family/ --native-fdm=socket,in,60,,5500,udp --fdm=null --enable-hud --in-air --fog-disable --shading-smooth --texture-filtering=4 --timeofday=morning --altitude=2500 --prop:/sim/hud/path[1]=Huds/fte.xml 2>/dev/null
# FG with JSBSim:
# DRI_PRIME=1 fgfs --airport=SBGP --aircraft=Embraer170 --aircraft-dir=./FlightGear/Aircraft/E-jet-family/ --enable-hud --fog-disable --shading-smooth --texture-filtering=4 --timeofday=morning
# DRI_PRIME=1 fgfs --airport=KSFO --runway=28R --aircraft=757-200-RB211 --aircraft-dir=~/.fgfs/Aircraft/org.flightgear.fgaddon.stable_2020/Aircraft/757-200 --enable-hud --fog-disable --shading-smooth --texture-filtering=4 --timeofday=morning
# "v" muda o visual
# https://wiki.flightgear.org/Command_line_options
'''
Partial Python implementation of the non-linear flight dynamics model proposed by:
Group for Aeronautical Research and Technology Europe (GARTEUR) - Research Civil Aircraft Model (RCAM)
http://garteur.org/wp-content/reports/FM/FM_AG-08_TP-088-3.pdf
The excellent tutorials by Christopher Lum (for Matlab/Simulink) were used as a guide:
1 - Equations/Modeling
https://www.youtube.com/watch?v=bFFAL9lI2IQ
2 - Matlab implementation
https://www.youtube.com/watch?v=m5sEln5bWuM
The program runs the integration loop as fast as possible, adjusting the integration steps to the available computing cycles
It uses Numba to speed up the main functions involved in the integration loop
Output is sent to FlightGear (FG), over UDP, at a reduced frame rate (60)
The FG interface uses the class implemented by Andrew Tridgel (fgFDM):
https://github.com/ArduPilot/pymavlink/blob/master/fgFDM.py
currently, the UDP address is set to the local machine.
Run this program and from a separate terminal, start FG with one of the following commands (depending on the aircraft addons installed):
fgfs --airport=KSFO --runway=28R --aircraft=ufo --native-fdm=socket,in,60,,5500,udp --fdm=null
fgfs --airport=KSFO --runway=28R --aircraft=Embraer170 --aircraft-dir=./FlightGear/Aircraft/E-jet-family/ --native-fdm=socket,in,60,,5500,udp --fdm=null
fgfs --airport=KSFO --runway=28R --aircraft=757-200-RB211 --aircraft-dir=~/.fgfs/Aircraft/org.flightgear.fgaddon.stable_2020/Aircraft/757-200 --native-fdm=socket,in,60,,5500,udp --fdm=null
fgfs --airport=KSFO --runway=28R --aircraft=757-200-RB211 --aircraft-dir=~/.fgfs/Aircraft/org.flightgear.fgaddon.stable_2020/Aircraft/757-200 --native-fdm=socket,in,60,,5500,udp --fdm=null --enable-hud --turbulence=0.5 --in-air --enable-rembrandt
DRI_PRIME=1 fgfs --airport=LOWI --aircraft=Embraer170 --aircraft-dir=./FlightGear/Aircraft/E-jet-family/ --native-fdm=socket,in,60,,5500,udp --fdm=null --enable-hud --in-air --fog-disable --shading-smooth --texture-filtering=4 --timeofday=morning --altitude=2500 --prop:/sim/hud/path[1]=Huds/fte.xml 2>/dev/null
REQUIRES a joystick to work.
TODO:
1) add engine dynamics (spool up/down)
2) add atmospheric disturbances/turbulence
3) add other actuator dynamics
4) save/read trim point
5) fuel detot / inertia update
'''
# imports
import numpy as np
import pandas as pd
from scipy import integrate
# for trimming routine
from scipy.optimize import minimize
import time
from numba import jit
#import numba
import math
import csv
import sys
sys.path.insert(1, '../')
# FlightGear comm class
from fgDFM import *
import socket
# International Standard Atmosphere library
from ISA_library import *
#joystick interface
import pygame
# # helper functions
def make_plots(x_data=np.array([0,1,2]), y_data=np.array([0,1,2]), \
header=['PSim_Time', 'u', 'v', 'w', 'p', 'q', 'r', 'phi', 'theta', 'psi', 'lat', 'lon', 'h', 'V_N', 'V_E', 'V_D', 'dA', 'dE', 'dR', 'dT1', 'dT2'], skip=0):
'''
Function to plot results.
Inputs:
x_data - time vector
y_data - n-dimentional array with parameters to be plotted
header has standard sequence of parameters/labels as generated by simulator
skip: number of header items to skip
'''
plotlist = []
plt.ioff()
plt.clf()
counter = 1
myfig = plt.figure(figsize = (16,(y_data.shape[1]*4)))
myfig.patch.set_edgecolor('w')
plt.subplots_adjust(hspace = 0.0)
for y_data_idx in range(y_data.shape[1]):
strip_chart_y_data = y_data[:,y_data_idx]
ax = myfig.add_subplot(y_data.shape[1], 1, counter)
ax.plot(x_data, strip_chart_y_data)
plt.ylabel(header[y_data_idx+skip])
plt.grid(True)
counter += 1
return myfig
def save2disk(filename, x_data=np.array([0,1,2]), y_data=np.array([0,1,2]), \
header=['u', 'v', 'w', 'p', 'q', 'r', 'phi', 'theta', 'psi', 'lat', 'lon', 'h', 'V_N', 'V_E', 'V_D', 'dA', 'dE', 'dR', 'dT1', 'dT2'], skip=0):
'''
saves data to disk
'''
with open(filename, 'w') as f:
y_dim = y_data.shape[1]
data_header = header[skip:y_dim]
data_header.insert(0, 'PSim_Time')
writer = csv.writer(f)
writer.writerow(data_header)
for idx, row in enumerate(collector):
row_list = row.tolist()
row_list.insert(0, x_data[idx].astype('float'))
writer.writerow(row_list)
@jit
def VA(uvw:np.ndarray) -> float:
'''
Calculate true airspeed
input:
uvw: vector of 3 speeds u, v, w
returns:
true airspeed
'''
return np.sqrt(np.dot(uvw.T, uvw))
def get_rho(altitude:float)->float:
'''
calculate the air density given an altitude in feet
'''
return rho0 * sigma(altitude * m2ft)
@jit
def fpa(V_NED)->float:
'''
returns flight path angle
input is a vector with North, East and Down velocities
'''
return np.arctan2(-V_NED[2], np.sqrt(V_NED[0]**2 + V_NED[1]**2))
def course(V_NED)->float:
'''
returns the course, given NED velocities
'''
return np.pi/2 - np.arctan2(V_NED[0], V_NED[1])
@jit
def add_wind(NED:np.ndarray, std_dev:np.ndarray)->np.ndarray:
'''
returns wind at altitude Hp.
inputs:
NED: vector with wind speed
std_dev: vector with standard deviations for wind (one value for each N, E, D)
output:
wind speed vector
'''
return NED + np.multiply(np.random.rand(3), std_dev)
def get_doublet(t_vector, t=0, duration=1, amplitude=0.1):
'''
calculates a doublet input
inputs:
t_vector: time vector
t: value at which the doublet should start
duration: duration of the high/low input states
amplituyde: multiplication factor to set amplitude
returns:
doublet vector
'''
rise_idx = np.argmax(t_vector>=t)
drop_idx = np.argmax(t_vector >=(t+duration/2))
zero_idx = np.argmax(t_vector >=(t+duration))
res = np.zeros(t_vector.shape)
res[rise_idx:drop_idx] = 1 * amplitude
res[drop_idx:zero_idx] = -1 * amplitude
return res
def get_step(t_vector, t=0, amplitude=0.1):
'''
calculates a step input
inputs:
t_vector: time vector
t: value at which the doublet should start
amplituyde: multiplication factor to set amplitude
returns:
step vector
'''
rise_idx = np.argmax(t_vector>=t)
res = np.zeros(t_vector.shape)
res[rise_idx:] = 1 * amplitude
return res
def create_cmd(t_vector=np.zeros(5), input_channel='ail', cmd_type='doublet', at_time=0.0, duration=1.0, amplitude=0.0):
'''
helper function to create a doublet or step in a channel
inputs:
t_vector: time vector
input_channel: selector for axis (see if/else below)
cmd_type: selector for doublet or step
at_time: value at which the inpute should start
duration: duration of the high/low input states
amplituyde: multiplication factor to set amplitude
returns:
input_ch_number: integer with the index of command to be added to integration loop
cmd: vector with command
'''
if input_channel == 'ail':
input_ch_num = 0
elif input_channel == 'elev':
input_ch_num = 1
elif input_channel == 'rud':
input_ch_num = 2
elif input_channel == 'thru':
input_ch_num = 3
elif input_channel == 'none' or input_channel == 'None':
cmd = np.zeros(t_vector.shape)
input_ch_num = 0
else:
input_ch_num = -1
if cmd_type=='doublet' and input_ch_num>=0:
cmd = get_doublet(t_vector, t=at_time, duration=duration, amplitude=amplitude)
elif cmd_type=='step' and input_ch_num>=0:
cmd = get_step(t_vector, t=at_time, amplitude=amplitude)
else:
print('error - command type not recognized')
cmd = np.zeros(t_vector.shape)
input_ch_num = 0
return input_ch_num, cmd
def set_FDM(this_fgFDM, X, U_norm, latlon, alt, body_accels):
'''
function to set the current time step data to be sent to FlightGear
inputs are:
X - states
U - controls
latlon - in radians
alt - in meters
NED - velocities in m/s
'''
this_fgFDM.set('phi', X[6])
this_fgFDM.set('theta', X[7])
this_fgFDM.set('psi', X[8])
this_fgFDM.set('phidot', X[3])
this_fgFDM.set('thetadot', X[4])
this_fgFDM.set('psidot', X[5])
# this sets units to kts because the HUD does not apply any conversions to the speed
# if we send speed in fps as the API requires, the HUD displays wrong value
this_fgFDM.set('vcas', Vt2Vc(VA(X[:3]), alt*m2ft) * ms2kt)
this_fgFDM.set('cur_time', int(time.perf_counter() ), units='seconds')
this_fgFDM.set('latitude', latlon[0], units='radians')
this_fgFDM.set('longitude', latlon[1], units='radians')
this_fgFDM.set('altitude', alt, units='meters')
this_fgFDM.set('left_aileron', -U_norm[0])
this_fgFDM.set('right_aileron', +U_norm[0])
this_fgFDM.set('elevator', U_norm[1])
this_fgFDM.set('rudder', -U_norm[2])
this_fgFDM.set('A_X_pilot', body_accels[0], units='mpss')
this_fgFDM.set('A_Y_pilot', body_accels[1], units='mpss')
this_fgFDM.set('A_Z_pilot', body_accels[2], units='mpss')
def get_joy_inputs(joystick, U_trim, fr):
'''
function that will read joystick positions and adjust controls:
1. joy will change controls on top of trim point
2. trim settings (buttons) will change trim point
3. engine does not have trim function, but depending on
button pressed, throttle should be commanded left/right/both
'''
U = np.zeros(U_trim.shape)
# # # TRIM
# multipliers to adjust how much trim is added per integration step.
pitch_trim_step = 0.006 / fr
aileron_trim_step = 0.003 / fr
#rudder_trim_step = 0.005 # not implemented yet
throttle_trim_step = 0.001 / fr
# read joystick button states for trimming
zero_ail_rud_thr = joystick.get_button(0)
pitch_dn = joystick.get_button(4)
pitch_up = joystick.get_button(2)
roll_rt = joystick.get_button(7)
roll_lt = joystick.get_button(6)
T1_fd = joystick.get_button(8)
T1_af = joystick.get_button(10)
T2_fd = joystick.get_button(9)
T2_af = joystick.get_button(11)
exit_signal = joystick.get_button(1)
# if trigger is pressed, then zero out aileron, rudder states and make thrust equal on both sides
if zero_ail_rud_thr == 1:
U_trim[0] = 0.0
U_trim[2] = 0.0
U_trim[3] = U_trim[4]
U_trim[0] = U_trim[0] - aileron_trim_step * roll_rt + aileron_trim_step * roll_lt
U_trim[1] = U_trim[1] - pitch_trim_step * pitch_up + pitch_trim_step * pitch_dn
#U_trim[2] = U_trim[2] + rudder_trim_step * - rudder_trim_step * roll_lt
U_trim[3] = U_trim[3] - throttle_trim_step * T1_af + throttle_trim_step * T1_fd
U_trim[4] = U_trim[4] - throttle_trim_step * T2_af + throttle_trim_step * T2_fd
# # # JOYSTICK COMMAND
# joystick constants/multipliers to adjust correct movement and amplitude
ail_factor = -0.7
elev_factor = -0.5
rud_factor = -0.52
thr_factor = -0.2
U[0] = U_trim[0] + joystick.get_axis(0) * ail_factor
U[1] = U_trim[1] + joystick.get_axis(1) * elev_factor
U[2] = U_trim[2] + joystick.get_axis(2) * rud_factor
U[3] = U_trim[3] + joystick.get_axis(3) * thr_factor
U[4] = U_trim[4] + joystick.get_axis(3) * thr_factor
return U, U_trim, exit_signal
# geodsy
# https://www.youtube.com/watch?v=4BJ-GpYbZlU
@jit
def WGS84_MN(lat:float):
'''
Meridian Radius of Curvature
Prime Vertical Radius of Curvature
for WGS-84
Input is latitude in degress (decimal)
'''
a = 6378137.0 #meters
e_sqrd = 6.69437999014E-3
M = (a * (1 - e_sqrd)) / ((1 - e_sqrd * np.sin(lat)**2)**(1.5))
N = a / ((1 - e_sqrd * np.sin(lat)**2)**(0.5))
return M, N
@jit
def latlonh_dot(V_NED, lat, h):
'''
V_north: m/s
M: m
h: m
'''
M, N = WGS84_MN(lat)
return np.array([(V_NED[0]) / (M + h),
(V_NED[1]) / ((N + h) * np.cos(lat)),
-V_NED[2]])
# controls
def control_norm(U:np.array, U_lim:np.array) -> np.array:
'''
normalizes controls to be sent to FG
inputs:
U controls: positions (in radians)
U_lim: control limits (in radians)
returns:
vector with control positions normalized between 1 and -1
'''
U_norm = []
for i in range(U.shape[0]):
if U[i] <= 0:
U_norm.append(-U[i] / U_lim[i][0])
else:
U_norm.append(U[i] / U_lim[i][1])
return np.array(U_norm)
@jit
def control_sat(U:np.ndarray) -> np.ndarray:
'''
saturates the control inputs to maximum allowable in RCAM model
'''
#----------------- control limits / saturation ---------------------
u0min = -25 * deg2rad
u0max = 25 * deg2rad
u1min = -25 * deg2rad
u1max = 10 * deg2rad
u2min = -30 * deg2rad
u2max = 30 * deg2rad
u3min = 0.5 * deg2rad # need to implement engine shutoff - with drag instead of thrust
u3max = 10 * deg2rad
u4min = 0.5 * deg2rad
u4max = 10 * deg2rad
#value_if_true if condition else value_if_false
i = 0
u0 = U[i] if (U[i]>=u0min and U[i]<=u0max) else u0min if U[i]<u0min else u0max; i += 1
u1 = U[i] if (U[i]>=u1min and U[i]<=u1max) else u1min if U[i]<u1min else u1max; i += 1
u2 = U[i] if (U[i]>=u2min and U[i]<=u2max) else u2min if U[i]<u2min else u2max; i += 1
u3 = U[i] if (U[i]>=u3min and U[i]<=u3max) else u3min if U[i]<u3min else u3max; i += 1
u4 = U[i] if (U[i]>=u4min and U[i]<=u4max) else u4min if U[i]<u4min else u4max
return np.array([u0, u1, u2, u3, u4])
# flight dynamics model
@jit
def RCAM_model(X:np.ndarray, U:np.ndarray, rho:float) -> np.ndarray:
'''
RCAM model implementation
sources: RCAM docs and Christopher Lum
Group for Aeronautical Research and Technology Europe (GARTEUR) - Research Civil Aircraft Model (RCAM)
http://garteur.org/wp-content/reports/FM/FM_AG-08_TP-088-3.pdf
Christopher Lum - Equations/Modeling
https://www.youtube.com/watch?v=bFFAL9lI2IQ
Christopher Lum - Matlab implementation
https://www.youtube.com/watch?v=m5sEln5bWuM
inputs:
X: states
0: u (m/s)
1: v (m/s)
2: w (m/s)
3: p (rad/s)
4: q (rad/s)
5: r (rad/s)
6: phi (rad)
7: theta (rad)
8: psi (rad)
U: controls
0: aileron (rad)
1: stabilator (rad)
2: rudder (rad)
3: throttle 1 (rad)
4: throttle 2 (rad)
rho: density for current altitude
outputs:
X_dot: derivatives of states (same order)
'''
#------------------------ constants -------------------------------
# Nominal vehicle constants
m = 120000; # kg - total mass
cbar = 6.6 # m - mean aerodynamic chord
lt = 24.8 # m - tail AC distance to CG
S = 260 # m2 - wing area
St = 64 # m2 - tail area
# centre of gravity position
Xcg = 0.23 * cbar # m - x pos of CG in Fm
Ycg = 0.0 # m - y pos of CG in Fm
Zcg = 0.10 * cbar # m - z pos of CG in Fm ERRATA - table 2.4 has 0.0 and table 2.5 has 0.10 cbar
# aerodynamic center position
Xac = 0.12 * cbar # m - x pos of aerodynamic center in Fm
Yac = 0.0 # m - y pos of aerodynamic center in Fm
Zac = 0.0 # m - z pos of aerodynamic center in Fm
# engine point of thrust aplication
Xapt1 = 0 # m - x position of engine 1 in Fm
Yapt1 = -7.94 # m - y position of engine 1 in Fm
Zapt1 = -1.9 # m - z position of engine 1 in Fm
Xapt2 = 0 # m - x position of engine 2 in Fm
Yapt2 = 7.94 # m - y position of engine 2 in Fm
Zapt2 = -1.9 # m - z position of engine 2 in Fm
# other constants
#rho = 1.225 # kg/m3 - air density
g = 9.81 # m/s2 - gravity
depsda = 0.25 # rad/rad - change in downwash wrt alpha
deg2rad = np.pi / 180 # from degrees to radians
alpha_L0 = -11.5 * deg2rad # rad - zero lift AOA
n = 5.5 # adm - slope of linear ragion of lift slope
a3 = -768.5 # adm - coeff of alpha^3
a2 = 609.2 # adm - - coeff of alpha^2
a1 = -155.2 # adm - - coeff of alpha^1
a0 = 15.212 # adm - - coeff of alpha^0 ERRATA RCAM has 15.2
alpha_switch = 14.5 * deg2rad # rad - kink point of lift slope
#----------------- intermediate variables ---------------------------
# airspeed
Va = np.sqrt(X[0]**2 + X[1]**2 + X[2]**2) # m/s
# alpha and beta
#np.arctan2 --> y, x
alpha = np.arctan2(X[2], X[0])
beta = np.arcsin(X[1]/Va)
# dynamic pressure
Q = 0.5 * rho * Va**2
# define vectors wbe_b and V_b
wbe_b = np.array([X[3], X[4], X[5]])
V_b = np.array([X[0], X[1], X[2]])
#----------------- aerodynamic force coefficients ---------------------
# CL - wing + body
CL_wb = n * (alpha - alpha_L0) if alpha <= alpha_switch else a3 * alpha**3 + a2 * alpha**2 + a1 * alpha + a0
# CL thrust
epsilon = depsda * (alpha - alpha_L0)
alpha_t = alpha - epsilon + U[1] + 1.3 * X[4] * lt / Va
CL_t = 3.1 * (St / S) * alpha_t
# Total CL
CL = CL_wb + CL_t
# Total CD
CD = 0.13 + 0.07 * (n * alpha + 0.654)**2
# Total CY
CY = -1.6 * beta + 0.24 * U[2]
#------------------- dimensional aerodynamic forces --------------------
# forces in F_s
FA_s = np.array([-CD * Q* S, CY * Q * S, -CL * Q * S])
# rotate forces to body axis (F_b)
C_bs = np.array([[np.cos(alpha), 0.0, -np.sin(alpha)],
[0.0, 1.0, 0.0],
[np.sin(alpha), 0.0, np.cos(alpha)]], dtype=np.dtype('f8'))
FA_b = np.dot(C_bs, FA_s)
#------------------ aerodynamic moment coefficients about AC -----------
# moments in F_b
eta11 = -1.4 * beta
eta21 = -0.59 - (3.1 * (St * lt) / (S * cbar)) * (alpha - epsilon)
eta31 = (1 - alpha * (180 / (15 * np.pi))) * beta
eta = np.array([eta11, eta21, eta31])
dCMdx = (cbar / Va) * np.array([[-11.0, 0.0, 5.0],
[ 0.0, (-4.03 * (St * lt**2) / (S * cbar**2)), 0.0],
[1.7, 0.0, -11.5]], dtype=np.dtype('f8'))
dCMdu = np.array([[-0.6, 0.0, 0.22],
[0.0, (-3.1 * (St * lt) / (S * cbar)), 0.0],
[0.0, 0.0, -0.63]], dtype=np.dtype('f8'))
# CM about AC in Fb
CMac_b = eta + np.dot(dCMdx, wbe_b) + np.dot(dCMdu, np.array([U[0], U[1], U[2]]))
#------------------- aerodynamic moment about AC -------------------------
# normalize to aerodynamic moment
MAac_b = CMac_b * Q * S * cbar
#-------------------- aerodynamic moment about CG ------------------------
rcg_b = np.array([Xcg, Ycg, Zcg])
rac_b = np.array([Xac, Yac, Zac])
MAcg_b = MAac_b + np.cross(FA_b, rcg_b - rac_b)
#---------------------- engine force and moment --------------------------
# thrust
F1 = U[3] * m * g
F2 = U[4] * m * g
#thrust vectors (assuming aligned with x axis)
FE1_b = np.array([F1, 0, 0])
FE2_b = np.array([F2, 0, 0])
FE_b = FE1_b + FE2_b
# engine moments
mew1 = np.array([Xcg - Xapt1, Yapt1 - Ycg, Zcg - Zapt1])
mew2 = np.array([Xcg - Xapt2, Yapt2 - Ycg, Zcg - Zapt2])
MEcg1_b = np.cross(mew1, FE1_b)
MEcg2_b = np.cross(mew2, FE2_b)
MEcg_b = MEcg1_b + MEcg2_b
#---------------------- gravity effects ----------------------------------
g_b = np.array([-g * np.sin(X[7]), g * np.cos(X[7]) * np.sin(X[6]), g * np.cos(X[7]) * np.cos(X[6])])
Fg_b = m * g_b
#---------------------- state derivatives --------------------------------
# inertia tensor
Ib = m * np.array([[40.07, 0.0, -2.0923],
[0.0, 64.0, 0.0],
[-2.0923, 0.0, 99.92]], dtype=np.dtype('f8')) # ERRATA on Ixz p. 12 vs p. 91
invIb = np.linalg.inv(Ib)
# form F_b and calculate u, v, w dot
F_b = Fg_b + FE_b + FA_b
x0x1x2_dot = (1 / m) * F_b - np.cross(wbe_b, V_b)
# form Mcg_b and calc p, q r dot
Mcg_b = MAcg_b + MEcg_b
x3x4x5_dot = np.dot(invIb, (Mcg_b - np.cross(wbe_b, np.dot(Ib , wbe_b))))
#phi, theta, psi dot
H_phi = np.array([[1.0, np.sin(X[6]) * np.tan(X[7]), np.cos(X[6]) * np.tan(X[7])],
[0.0, np.cos(X[6]), -np.sin(X[6])],
[0.0, np.sin(X[6]) / np.cos(X[7]), np.cos(X[6]) / np.cos(X[7])]], dtype=np.dtype('f8'))
x6x7x8_dot = np.dot(H_phi, wbe_b)
#--------------------- place in first order form --------------------------
X_dot = np.concatenate((x0x1x2_dot, x3x4x5_dot, x6x7x8_dot))
return X_dot
# Navigation Equations
# source:
# Christopher Lum - "The Naviation Equations: Computing Position North, East and Down"
# https://www.youtube.com/watch?v=XQZV-YZ7asE
@jit
def NED(uvw, phithetapsi):
'''
compute the NED velocities from:
inputs
uvw: array with u, v, w
phithetapsi: array with phi, theta, psi
returns
velocities in NED
remember that h_dot = -Vd
'''
u = uvw[0]
v = uvw[1]
w = uvw[2]
phi = phithetapsi[0]
the = phithetapsi[1]
psi = phithetapsi[2]
c1v = np.array([[np.cos(psi), np.sin(psi), 0.0],
[-np.sin(psi), np.cos(psi), 0.0],
[0.0, 0.0, 1.0]])
c21 = np.array([[np.cos(the), 0.0, -np.sin(the)],
[0.0, 1.0, 0.0],
[np.sin(the), 0.0, np.cos(the)]])
cb2 = np.array([[1.0, 0.0, 0.0],
[0.0, np.cos(phi), np.sin(phi)],
[0.0, -np.sin(phi), np.cos(phi)]])
cbv = np.dot(cb2, np.dot(c21,c1v)) #numba does not support np.matmul
return np.dot(cbv.T, uvw)
# # # # # Model integration # # # # #
# # # wrappers
# Scipy's "integrate.ode" does not accept a numba/@jit compiled function
# therefore, we need to create dummy wrappers
def RCAM_model_wrapper(t, X, U, rho):
return RCAM_model(X, U, rho)
def NED_wrapper(t, X, NED):
return NED
def latlonh_dot_wrapper(t, X, V_NED, lat, h):
return latlonh_dot(V_NED, lat, h)
# # # integrators
def ss_integrator(t_ini:float, X0:np.ndarray, U:np.ndarray, rho:float):
'''
single step integrator
returns scipy object, initialized
'''
RK_integrator = integrate.ode(RCAM_model_wrapper)
RK_integrator.set_integrator('dopri5')
RK_integrator.set_f_params(control_sat(U), rho)
RK_integrator.set_initial_value(X0, t_ini)
return RK_integrator
def time_span_int(t_ini:float, t_fin:float, dt:float, X0:np.ndarray, U:np.ndarray, rho:float) -> np.ndarray:
'''
function to integrate the model in a time span, with FIXED dt
inputs:
t_ini: initial time in seconds
t-fin: final time in seconds
dt: delta time between steps, in seconds
X0: initial states
U: controls positions
outputs:
t_vector: time vector
result_array: states integrated for all time steps in time vector
'''
t_vector = np.arange(np.datetime64('2011-06-15T00:00'), np.datetime64('2011-06-15T00:00') + np.timedelta64(t_fin, 's'),np.timedelta64(int(dt*1000),'ms'), dtype='datetime64')
RK_integrator = integrate.ode(RCAM_model_wrapper)
RK_integrator.set_integrator('dopri5')
RK_integrator.set_f_params(control_sat(U), rho)
RK_integrator.set_initial_value(X0, t_ini)
collector = []
for _ in t_vector:
RK_integrator.integrate(RK_integrator.t + dt)
aux = np.insert(RK_integrator.y, 0, RK_integrator.t)
collector.append(aux)
result_array = np.array(collector)
return(t_vector, result_array)
def latlonh_int(t_ini:float, latlonh0:np.ndarray, V_NED):
'''
single step integrator for lat/long/height
returns scipy object, initialized
'''
RK_integrator = integrate.ode(latlonh_dot_wrapper)
RK_integrator.set_integrator('dopri5')
RK_integrator.set_f_params(V_NED, latlonh0[0], latlonh0[2])
RK_integrator.set_initial_value(latlonh0, t_ini)
return RK_integrator
# # Trimmer
def trim_functional2(Z:np.ndarray, VA_trim, gamma_trim, v_trim, phi_trim, psi_trim, rho_trim) -> np.dtype('f8'):
'''
functional to calculate a cost for minimizer (used to find trim point)
no constraints yet
inputs:
Z: lumped vector of X (states) and U (control)
trim targets:
VA_trim: airspeed [m/s]
gamma_trim: climb gradient [rad]
v-trim: side speed [m/s]
phi_trim: roll angle [rad]
psi_trim: course angle [rad]
****
method
Q.T*H*Q
with H = diagonal matrix of "1"s (equal weights for all states)
returns:
cost [float]
'''
X = Z[:9]
U = Z[9:]
X_dot = RCAM_model(X, control_sat(U), rho_trim)
V_NED_current = NED(X_dot[:3], X_dot[3:6])
VA_current = VA(X[:3])
gamma_current = X[7] - np.arctan2(X[2], X[0]) # only valid for wings level case
Q = np.concatenate((X_dot, [VA_current - VA_trim], [gamma_current - gamma_trim], [X[1] - v_trim], [X[6] - phi_trim], [X[8] - psi_trim]))
diag_ones = np.ones(Q.shape[0])
H = np.diag(diag_ones)
return np.dot(np.dot(Q.T, H), Q)
def trim_model(VA_trim=85.0, gamma_trim=0.0, v_trim=0.0, phi_trim=0.0, psi_trim=0.0, rho_trim=1.225,
X0=np.array([85, 0, 0, 0, 0, 0, 0, 0.1, 0]),
U0=np.array([0, -0.1, 0, 0.08, 0.08])) -> np.ndarray:
'''
uses scipy minimize on functional to find trim point
'''
print(f'trimming with X0 = {X0}')
print(f'trimming with U0 = {U0}')
X0[0] = VA_trim
Z0 = np.concatenate((X0, U0))
result = minimize(trim_functional2, Z0, args=(VA_trim, gamma_trim, v_trim, phi_trim, psi_trim, rho_trim),
method='L-BFGS-B', options={'disp':False, 'maxiter':5000,\
'gtol':1e-25, 'ftol':1e-25, \
'maxls':4000})
return result.x, result.message
# # Init
def initialize(VA_t=85.0, gamma_t=0.0, latlon=np.zeros(2), altitude=10000, psi_t=0.0):
'''
this initializes the integrators at a straight and level flight condition
inputs:
VA_t: true airspeed at trim (m/s)
gamma_t: flight path angle at trim (rad)
latlon: initial lat and long (rad)
altitude: trim altitude (ft)
psi_t: initial heading (rad)
outputs:
AC_integrator: aircraft integrator object
X0: initial states found at trim point
U0: initial commands found at trim point
latlonh_integrator: navigation equation scipy object integrator
'''
ft2m = 0.3048
t0 = 0.0 #intial time for integrators
print(f'initializing model with altitude {altitude} ft, rho={get_rho(altitude)}')
alt_m = altitude * ft2m
latlonh0 = np.array([latlon[0]*deg2rad, latlon[1]*deg2rad, alt_m])
# trim model
res4, res4_status = trim_model(VA_trim=VA_t, gamma_trim=gamma_t, v_trim=t0,
phi_trim=0.0, psi_trim=psi_t*deg2rad, rho_trim=get_rho(altitude))
print(res4_status)
X0 = res4[:9]
U0 = res4[9:]
print(f'initial states: {X0}')
print(f'initial inputs: {U0}')
# initialize integrators
AC_integrator = ss_integrator(t0, X0, U0, get_rho(altitude))
NED0 = NED(X0[:3], X0[6:]) #uvw and phithetapsi
latlonh_integrator = latlonh_int(t0, latlonh0, NED0)
return AC_integrator, X0, U0, latlonh_integrator
if __name__ == "__main__":
deg2rad = np.pi / 180 # from degrees to radians
# Network socket to communicate with FlightGear
UDP_IP = "127.0.0.1"
UDP_PORT = 5500
UDP_IP2 = "192.168.0.163"
UDP_PORT2 = 5501
sock = socket.socket(socket.AF_INET, # Internet
socket.SOCK_DGRAM) # UDP
sock2 = socket.socket(socket.AF_INET, # Internet
socket.SOCK_DGRAM) # UDP
pygame.init() # automatically initializes joystick also
joystick_count = pygame.joystick.get_count()
if joystick_count == 0:
print('connect joystick first')
exit()
print(f'found {joystick_count} joysticks connected.')
this_joy = pygame.joystick.Joystick(0)
print(f'{this_joy.get_name()}, axes={this_joy.get_numaxes()}')
signals_header = ['u', 'v', 'w', 'p', 'q', 'r', 'phi', 'theta', 'psi', 'lat', 'lon', 'h', 'V_N', 'V_E', 'V_D', 'dA', 'dE', 'dR', 'dT1', 'dT2']
############################################################################
# INITIAL CONDITIONS
# Altitude
init_alt = 2100 #ft
# IAS
v_trim = 140 * kt2ms
# Gamma
gamma_trim = 0.0 * deg2rad
# Lat/Lon
#init_latlon = np.array([37.6213, -122.3790]) #in degrees - the func initialize transforms to radians internally
#init_latlon = np.array([-21.7632, -48.4051]) #in degrees - SBGP
init_latlon = np.array([47.2548, 11.2963]) #in degrees - LOWI short final TFB
# Heading
init_psi = 82.0
############################################################################
# instantiate FG comms object and initialize it
my_fgFDM = fgFDM()
my_fgFDM.set('latitude', init_latlon[0], units='degrees')
my_fgFDM.set('longitude', init_latlon[1], units='degrees')
my_fgFDM.set('altitude', init_alt, units='meters')
my_fgFDM.set('agl', init_alt, units='meters')
my_fgFDM.set('num_engines', 2)
my_fgFDM.set('num_tanks', 1)
my_fgFDM.set('num_wheels', 3)
my_fgFDM.set('cur_time', int(time.perf_counter()), units='seconds')
#----------------- control limits / saturation ---------------------
U_limits = [(-25 * deg2rad, 25 * deg2rad),
(-25 * deg2rad, 10 * deg2rad),
(-30 * deg2rad, 30 * deg2rad),
(0.5 * deg2rad, 10 * deg2rad),
(0.5 * deg2rad, 10 * deg2rad)]
#######################################################################################
# SIMULATION OPTIONS
# start time
t0 = 0
# total simulation time
tf = 10 * 60 #minutes
# simulation loop frame rate throttling
simFR = 400 # (Hz)
# frames per second to be sent out to FG
fgFR = 60 # (Hz)
wind_speed = np.array([0, 0, 0]) # (m/s), NED
wind_stddev = np.array([1, 1, 0]) #
#######################################################################################
# initializations
# data collectors
collector = []
t_vector_collector = []
prev_uvw = np.array([0,0,0])
current_uvw = np.array([0,0,0])
# aircraft initialization (includes trimming)
this_AC_int, X1, U1, this_latlonh_int = initialize(VA_t=v_trim, gamma_t=gamma_trim, latlon=init_latlon, altitude=init_alt, psi_t=init_psi)
U_man = U1.copy()
# frame variables
current_alt = init_alt
current_latlon = init_latlon
frame_count = 0
send_frame_trigger = False
fg_time_adder = 0 # counts the time between integration steps to trigger sending out a frame to FlightGear
fgdt = 1 / (fgFR + 1) # (s) fg frame period
run_sim_loop = False
simdt = 1 / simFR # (s) desired simulation time step
sim_time_adder = 0 # counts the time between integration steps to trigger next simulation frame
dt = 0 # actual integration time step
prev_dt = dt
grav_accel = 9.81 # m/s
exit_signal = 0 # if joystick button #1 is pressed, ends simulation
# main loop
while this_AC_int.t <= tf and exit_signal == 0:
# get clock
start = time.perf_counter()
if run_sim_loop:
_ = pygame.event.get()
# get density, inputs
current_rho = get_rho(current_alt * m2ft)
U_man, U1, exit_signal = get_joy_inputs(this_joy, U1, simFR)
U_man = control_sat(U_man)
# set current integration step commands, density and integrate aircraft states
prev_uvw = current_uvw