-
Notifications
You must be signed in to change notification settings - Fork 20
/
evtol_dynamics_comp.py
640 lines (524 loc) · 23.4 KB
/
evtol_dynamics_comp.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
# --------------------------------------------------------------------------------------------------
# This contains the functions and OpenMDAO component class for the simplified eVTOL flight physics.
# This works at least with OpenMDAO version 2.6.0.
# SI units used for everthing unless otherwise specified.
# Author: Shamsheer Chauhan
# --------------------------------------------------------------------------------------------------
from __future__ import division
import numpy as np
from openmdao.api import ExplicitComponent
def c_atan2(x, y):
""" This is an arctan2 function that works with the complex-step method."""
a = x.real
b = x.imag
c = y.real
d = y.imag
if np.iscomplex(x) or np.iscomplex(y):
return complex(np.arctan2(a, c), (c * b - a * d) / (a ** 2 + c ** 2))
else:
return np.arctan2(a, c)
def give_curve_fit_coeffs(a0, AR, e):
"""
This gives the coefficients for the quartic least-squares curve fit that is used for each wing's
coefficient of drag below 27.5 deg.
Parameters
----------
a0 : float
Airfoil lift-curve slope in 1/rad
AR : float
Aspect ratio
e : float
Span efficiency factor
Returns
-------
quartic_poly_coeffs : array
Coefficients of the curve fit
data_pts : array
Data points that are fitted
"""
cla = a0 / (1 + a0 / (np.pi * e * AR))
data_pts = np.array([[16. / 180. * np.pi, 0.1], # Tangler--Ostowari points
[20. / 180. * np.pi, 0.175], # Tangler--Ostowari points
[25. / 180. * np.pi, 0.275], # Tangler--Ostowari points
[27.5 / 180. * np.pi, 0.363], # Tangler--Ostowari points
[12. / 180. * np.pi,
0.015 + (cla * 12. / 180. * np.pi) ** 2 / np.pi / AR / e],
[10. / 180. * np.pi,
0.012 + (cla * 10. / 180. * np.pi) ** 2 / np.pi / AR / e],
[8. / 180. * np.pi,
0.0095 + (cla * 8. / 180. * np.pi) ** 2 / np.pi / AR / e],
[6. / 180. * np.pi,
0.008 + (cla * 6. / 180. * np.pi) ** 2 / np.pi / AR / e],
[4. / 180. * np.pi,
0.007 + (cla * 4. / 180. * np.pi) ** 2 / np.pi / AR / e],
[2. / 180. * np.pi,
0.0062 + (cla * 2. / 180. * np.pi) ** 2 / np.pi / AR / e],
[0. / 180. * np.pi, 0.006]])
new_fit_matrix = np.array([[1, data_pts[0, 0] ** 2, data_pts[0, 0] ** 4],
[1, data_pts[1, 0] ** 2, data_pts[1, 0] ** 4],
[1, data_pts[2, 0] ** 2, data_pts[2, 0] ** 4],
[1, data_pts[3, 0] ** 2, data_pts[3, 0] ** 4],
[1, data_pts[4, 0] ** 2, data_pts[4, 0] ** 4],
[1, data_pts[5, 0] ** 2, data_pts[5, 0] ** 4],
[1, data_pts[6, 0] ** 2, data_pts[6, 0] ** 4],
[1, data_pts[7, 0] ** 2, data_pts[7, 0] ** 4],
[1, data_pts[8, 0] ** 2, data_pts[8, 0] ** 4],
[1, data_pts[9, 0] ** 2, data_pts[9, 0] ** 4],
[1, data_pts[10, 0] ** 2, data_pts[10, 0] ** 4]])
quartic_poly_coeffs = np.linalg.solve(np.dot(new_fit_matrix.T, new_fit_matrix),
np.dot(new_fit_matrix.T, data_pts[:, 1]))
return quartic_poly_coeffs, data_pts
def Thrust(u0, power, A, T, rho, kappa):
"""
This computes the thrust and induced velocity at the propeller disk.
This uses formulas from propeller momentum theory.
Parameters
----------
u0 : float
Freestream speed normal to the propeller disk
power : float
Power supplied to the propeller disk
A : float
Propeller disk area
T : float
Thrust guess
rho : float
Air density
kappa: float
Corection factor for non-uniform inflow and tip effects
Returns
-------
thrust : float
Thrust
v_i : float
Induced velocity at the propeller disk
"""
T_old = T + 10.
thrust = T
# iteration loop to solve for the thrust as a function of power
while np.abs(T_old.real - thrust.real) > 1e-10:
T_old = thrust
### FPI (Fixed point iteration)
# T_new = power / (u0 + kappa * (-u0/2 + 0.5 * (u0**2 + 2 * thrust / rho / A)**0.5))
# thrust = thrust + (T_new - thrust) * 0.5
# Newton-Raphson
root_term = (u0 ** 2 + 2 * thrust / rho / A) ** 0.5
R = power - thrust * (u0 + kappa * (-u0 / 2 + 0.5 * root_term))
R_prime = -u0 - kappa * (-u0 / 2 + 0.5 * root_term + 0.5 * thrust / rho / A / root_term)
thrust = T_old - R / R_prime
# the induced velocity (i.e., velocity added at the disk) is
v_i = (-u0 / 2 + (u0 ** 2 / 4. + thrust / 2 / rho / A) ** 0.5)
if u0.real < 0:
# This model is not valid if the freestream speed is negative
print("FREESTREAM SPEED IS NEGATIVE!", thrust, v_i)
return thrust, v_i
def Normal_force(u0, radius, thrust, alpha, rho, nB, bc):
"""
This computes the normal force developed by each propeller due to the incidence angle of the flow.
These equations are from "Propeller at high incidence" by de Young, 1965.
Parameters
----------
u0 : float
Freestream speed
radius : float
Propeller radius
thrust : float
Propeller thrust
alpha: float
Incidence angle
rho : float
Air density
nB : float
Number of blades
bc : float
Effective blade chord
Returns
-------
normal_force : float
Normal force generated by one propeller
"""
# conversion factor to convert from m to ft becasue these emperical formulas use imperial units
m2f = 3.28
# propeller 0.75R pitch angle as a function of freestream
beta = 10 + u0 / 67. * 25
u0 = u0 * m2f * np.cos(alpha)
Diam = 2 * radius * m2f
rho = rho * 0.00194
c = bc * m2f
q = 0.5 * rho * u0 ** 2
A_d = np.pi * Diam ** 2 / 4.
Tc = thrust / q / A_d
f = 1 + 0.5 * ((1 + Tc) ** .5 - 1) + Tc / 4. / (2 + Tc)
sigma = 4 * nB / 3 / np.pi * c / Diam
slope = 4.25 * sigma / (1 + 2 * sigma) * np.sin(
beta / 180. * np.pi + 8. / 180. * np.pi) * f * q * A_d
normal_force = slope * np.tan(alpha) / 2.2046 * 9.81
return normal_force
def CLfunc(angle, alpha_stall, AR, e, a0, t_over_c):
"""
This gives the lift coefficient of a wing as a function of angle of attack.
Parameters
----------
angle : float
Angle of attack
alpha_stall : float
Stall angle of attack
AR : float
Aspect ratio
e : float
Span efficiency factor
a0 : float
Airfoil lift-curve slope
t_over_c : float
Thickness-to-chord ratio
Returns
-------
CL : float
Lift coefficient of the wing
"""
if angle.real >= 0:
CLa = a0 / (1 + a0 / (np.pi * e * AR))
CL_stall = CLa * alpha_stall
# CD_max = (1. + 0.065 * AR) / (0.9 + t_over_c)
CD_max = 1.1 + 0.018 * AR
CL1 = CLa * angle
A1 = CD_max / 2
A2 = (CL_stall - CD_max * np.sin(alpha_stall) * np.cos(alpha_stall)) * np.sin(
alpha_stall) / np.cos(alpha_stall) ** 2
CL2 = A1 * np.sin(2 * angle) + A2 * np.cos(angle) ** 2 / np.sin(angle)
CL_array = np.array([-CL1, -CL2])
ks_rho = 50. # Hard coded, see Martins and Poon 2005 for more
fmax = np.max(CL_array)
CL = -(fmax + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (CL_array - fmax)))))
# this is because something strange happens very near 0 for complex step
if angle.real < 1e-8:
CL = CLa * angle
else:
CLa = a0 / (1 + a0 / (np.pi * e * AR))
CL_stall = CLa * alpha_stall
# CD_max = (1. + 0.065 * AR) / (0.9 + t_over_c)
CD_max = 1.1 + 0.018 * AR
CL1 = CLa * angle
A1 = CD_max / 2
A2 = (CL_stall - CD_max * np.sin(alpha_stall) * np.cos(alpha_stall)) * np.sin(
alpha_stall) / np.cos(alpha_stall) ** 2
CL2 = A1 * np.sin(2 * angle) + A2 * np.cos(angle) ** 2 / np.sin(angle)
CL_array = np.array([CL1, CL2])
ks_rho = 50. # Hard coded, see Martins and Poon 2005 for more
fmax = np.max(CL_array)
CL = (fmax + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (CL_array - fmax)))))
# this is because something strange happens very near 0 for complex step
if angle.real > -1e-8:
CL = CLa * angle
return CL
def CDfunc(angle, AR, e, alpha_stall, coeffs, a0, t_over_c):
"""
This gives the drag coefficient of a wing as a function of angle of attack.
Parameters
----------
angle : float
Angle of attack
AR : float
Aspect ratio
e : float
Span efficiency factor
alpha_stall : float
Stall angle of attack
coeffs : array
Curve-fit polynomial coefficients for the drag coefficient below 27.5 deg
a0 : float
Airfoil lift-curve slope
t_over_c : float
Thickness-to-chord ratio
Returns
-------
CD : float
Drag coefficient of the wing
"""
quartic_poly_coeffs = coeffs
cla = a0 / (1 + a0 / (np.pi * e * AR))
cl_stall = cla * alpha_stall
CD_stall = np.dot(quartic_poly_coeffs, np.array([1, alpha_stall ** 2, alpha_stall ** 4]))
CD_max = (1. + 0.065 * AR) / (0.9 + t_over_c)
B1 = CD_max
B2 = (CD_stall - CD_max * np.sin(alpha_stall)) / np.cos(alpha_stall)
if angle.real < 0:
angle = -angle
# this is for the first part (quartic fit)
CD_pt1 = np.dot(quartic_poly_coeffs,
np.array([1, (27.5 / 180. * np.pi) ** 2, (27.5 / 180. * np.pi) ** 4]))
CD_pt2 = B1 * np.sin(28. / 180. * np.pi) + B2 * np.cos(28. / 180. * np.pi)
adjustment_line = (CD_pt2 - CD_pt1) / (0.5 / 180. * np.pi) * (
angle - 28. / 180. * np.pi) + CD_pt2
CD1 = np.dot(quartic_poly_coeffs, np.array([1, angle ** 2, angle ** 4]))
CD_array = np.array([CD1, adjustment_line])
ks_rho = 50. # Hard coded, see Martins and Poon 2005 for more
fmax = np.max(CD_array)
CD2 = (fmax + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (CD_array - fmax)))))
# this is for the second part (Tangler--Ostowari)
CD3 = B1 * np.sin(angle) + B2 * np.cos(angle)
CD_array = np.array([CD3, CD_pt1])
ks_rho = 50. # Hard coded, see Martins and Poon 2005 for more
fmax = np.max(CD_array)
CD4 = (fmax + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (CD_array - fmax)))))
# this puts them together
CD_array = np.array([-CD2, -CD4])
ks_rho = 50. # Hard coded, see Martins and Poon 2005 for more
fmax = np.max(CD_array)
CD4 = -(fmax + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (CD_array - fmax)))))
return CD4
def change(atov, v_inf, theta, T, alpha_stall, CD0, AR, e, rho, S, m, a0, t_over_c, coeffs, v_i,
v_factor, Normal_F):
"""
This computes the change in velocity for each time step.
Parameters
----------
atov : float
Freestream angle to the vertical
v_inf : float
Freestream speed
dt : float
Time step size
theta : float
Wing angle to the vertical
T : float
Thrust
alpha_stall : float
Stall angle of attack
CD0 : float
Parasite drag coefficient for fuse, gear, etc.
AR : float
Aspect ratio
e : float
Span efficiency factor
rho : float
Air density
S : float
Wing planform area
m : float
Mass of the aircraft
a0 : float
Airfoil lift-curve slope
t_over_c : float
Thickness-to-chord ratio
coeffs : array
Curve-fit polynomial coefficients for the drag coefficient below 27.5 deg
v_i : float
Induced-velocity value from the propellers
v_factor : float
Induced-velocity factor
Normal_F : float
Total propeller forces normal to the propeller axes
Returns
-------
delta_xdot : float
Change in horizontal velocity
delta_ydot : float
Change in vertical velocity
CL : float
Wing lift coefficient
CD : float
Wing drag coefficient
aoa_blown : float
Effective angle of attack with prop wash
L : float
Total lift force of the wings
D_wings : float
Total drag force of the wings
D_fuse : float
Drag force of the fuselage
"""
# use angle of attack of wing to estimate CL and CD
aoa = atov - theta
v_chorwise = v_inf * np.cos(aoa)
v_normal = v_inf * np.sin(aoa)
v_chorwise += v_i * v_factor
v_blown = (v_chorwise ** 2 + v_normal ** 2) ** 0.5
aoa_blown = c_atan2(v_normal, v_chorwise)
CL = CLfunc(aoa_blown, alpha_stall, AR, e, a0, t_over_c)
CD = CDfunc(aoa_blown, AR, e, alpha_stall, coeffs, a0, t_over_c)
# compute lift and drag forces
L = 0.5 * rho * v_blown ** 2 * CL * S
D_wings = 0.5 * rho * v_blown ** 2 * CD * S
D_fuse = 0.5 * rho * v_inf ** 2 * CD0 * S
# compute horizontal and vertical changes in velocity
delta_xdot = (T * np.sin(theta) - D_fuse * np.sin(atov) - D_wings * np.sin(
theta + aoa_blown) - L * np.cos(theta + aoa_blown) - Normal_F * np.cos(theta)) / m
delta_ydot = (T * np.cos(theta) - D_fuse * np.cos(atov) - D_wings * np.cos(
theta + aoa_blown) + L * np.sin(theta + aoa_blown) + Normal_F * np.sin(
theta) - m * 9.81) / m
return np.array([delta_xdot, delta_ydot, CL, CD, aoa_blown, L, D_wings, D_fuse])
class Dynamics(ExplicitComponent):
"""
This is the OpenMDAO component that takes the design variables and computes
the objective function and other quantities of interest.
Parameters
----------
powers : array
Electrical power distribution as a function of time
thetas : array
Wing-angle-to-vertical distribution as a function of time
flight_time : float
Duration of flight
Returns
-------
x_dot : float
Final horizontal speed
y_dot : float
Final vertical speed
x : float
Final horizontal position
y : float
Final vertical position
y_min : float
Minimum vertical displacement
u_prop_min : float
Minimum propeller freestream inflow velocity
energy : float
Electrical energy consumed
aoa_max : float
Maximum effective angle of attack
aoa_min : float
Minimum effective angle of attack
acc_max : float
Maximum acceleration magnitude
"""
def initialize(self):
# declare the input dict provided in the run script
self.options.declare('input_dict', types=dict)
self.options.declare('num_nodes', types=int)
def setup(self):
input_dict = self.options['input_dict']
num_nodes = self.options['num_nodes']
# give variable names to user-specified values from input dict
self.x_dot_initial = input_dict['x_dot_initial'] # initial horizontal speed
self.y_dot_initial = input_dict['y_dot_initial'] # initial vertical speed
self.y_initial = input_dict['y_initial'] # initial vertical displacement
self.A_disk = input_dict['A_disk'] # total propeller disk area
self.T_guess = input_dict['T_guess'] # initial thrust guess
self.alpha_stall = input_dict['alpha_stall'] # wing stall angle
self.CD0 = input_dict['CD0'] # coefficient of drag of the fuselage, gear, etc.
self.AR = input_dict['AR'] # aspect ratio
self.e = input_dict['e'] # span efficiency factor of each wing
self.rho = input_dict['rho'] # air density
self.S = input_dict['S'] # total wing reference area
self.m = input_dict['m'] # mass of aircraft
self.a0 = input_dict['a0'] # airfoil lift-curve slope
self.t_over_c = input_dict['t_over_c'] # airfoil thickness-to-chord ratio
self.v_factor = input_dict['induced_velocity_factor'] # induced-velocity factor
self.stall_option = input_dict['stall_option'] # stall option: 's' allows stall, 'ns' does not
# self.num_steps = input_dict['num_steps'] # number of time steps
self.R = input_dict['R'] # propeller radius
self.solidity = input_dict['solidity'] # propeller solidity
self.omega = input_dict['omega'] # propeller angular speed
self.prop_CD0 = input_dict['prop_CD0'] # CD0 for propeller profile power
self.k_elec = input_dict['k_elec'] # factor for mechanical and electrical losses
self.k_ind = input_dict['k_ind'] # factor for induced losses
self.nB = input_dict['nB'] # number of blades per propeller
self.bc = input_dict['bc'] # representative blade chord
self.n_props = input_dict['n_props'] # number of propellers
self.quartic_poly_coeffs, pts = give_curve_fit_coeffs(self.a0, self.AR, self.e)
# openmdao inputs to the component
self.add_input('power', val=np.ones(num_nodes)) # control
self.add_input('theta', val=np.ones(num_nodes)) # control
# openmdao outputs from the component
# state history inputs that some calcs need
self.add_input('vx', val=np.ones(num_nodes))
self.add_input('vy', val=np.ones(num_nodes))
self.add_output('x_dot', val=np.ones(num_nodes)) # state rates for x
self.add_output('y_dot', val=np.ones(num_nodes)) # state rates for y
self.add_output('a_x', val=np.ones(num_nodes)) # state rates for v_x
self.add_output('a_y', val=np.ones(num_nodes)) # state rates for v_y
self.add_output('energy_dot', val=np.ones(num_nodes)) # state rates for energy
# additional intermediate variables we want to track
self.add_output('acc', val=np.ones(num_nodes))
self.add_output('atov', val=np.ones(num_nodes))
self.add_output('CL', val=np.ones(num_nodes))
self.add_output('CD', val=np.ones(num_nodes))
self.add_output('L_wings', val=np.ones(num_nodes))
self.add_output('D_wings', val=np.ones(num_nodes))
self.add_output('D_fuse', val=np.ones(num_nodes))
self.add_output('aoa', val=np.ones(num_nodes))
self.add_output('aoa_prop', val=np.ones(num_nodes))
self.add_output('v_i', val=np.ones(num_nodes))
self.add_output('N', val=np.ones(num_nodes))
self.add_output('thrust', val=np.ones(num_nodes))
self.add_output('u_inf_prop', val=np.ones(num_nodes))
# some internal variables variables
# self.thrusts = np.ones(num_nodes, dtype=complex) # thrusts
# self.atov = np.ones(num_nodes, dtype=complex) # freestream angles to vertical
# self.CL = np.zeros(num_nodes, dtype=complex) # wing lift coefficients
# self.CD = np.zeros(num_nodes, dtype=complex) # wing drag coefficients
# self.aoa = np.zeros(num_nodes, dtype=complex) # effective wing angles of attack
# use complex step for partial derivatives
self.declare_partials('*', '*', method='cs')
self.declare_coloring(method='cs', per_instance=True, show_sparsity=True, show_summary=True)
# Partial derivative coloring
self.declare_coloring(wrt=['*'], method='cs', tol=1.0E-15, num_full_jacs=5,
show_summary=True, show_sparsity=True, min_improve_pct=10.)
def compute(self, inputs, outputs):
thrust = self.T_guess
# time integration
for i in range(self.options['num_nodes']):
power = inputs['power'][i]
theta = inputs['theta'][i]
x_dot = inputs['vx'][i]
y_dot = inputs['vy'][i]
# the freestream angle relative to the vertical is
atov = c_atan2(x_dot, y_dot)
# the freestream speed is
v_inf = (x_dot ** 2 + y_dot ** 2) ** 0.5
outputs['u_inf_prop'][i] = u_inf_prop = v_inf * np.cos(atov - theta)
u_parallel = v_inf * np.sin(atov - theta)
mu = u_parallel / (self.omega * self.R)
CP_profile = self.solidity * self.prop_CD0 / 8. * (1 + 4.6 * mu ** 2)
P_disk = self.k_elec * power - CP_profile * (
self.rho * self.A_disk * (self.omega * self.R) ** 3)
thrust, vi = Thrust(u_inf_prop, P_disk, self.A_disk, thrust, self.rho, self.k_ind)
outputs['thrust'][i] = thrust
Normal_F = Normal_force(v_inf, self.R, thrust / self.n_props, atov - theta, self.rho,
self.nB, self.bc)
# step = change(atov, v_inf, dt, theta, thrust, self.alpha_stall, self.CD0, self.AR, self.e, self.rho, self.S, self.m, self.a0, self.t_over_c, self.quartic_poly_coeffs, vi, self.v_factor, self.n_props * Normal_F)
step = change(atov, v_inf, theta, thrust, self.alpha_stall, self.CD0, self.AR, self.e,
self.rho, self.S, self.m, self.a0, self.t_over_c,
self.quartic_poly_coeffs, vi, self.v_factor, self.n_props * Normal_F)
outputs['acc'][i] = ((step[0]) ** 2 + (step[1]) ** 2) ** 0.5 / 9.81
outputs['atov'][i] = atov
outputs['CL'][i] = step[2]
outputs['CD'][i] = step[3]
outputs['v_i'][i] = vi * self.v_factor
outputs['aoa'][i] = step[4]
outputs['L_wings'][i] = step[5]
outputs['D_wings'][i] = step[6]
outputs['D_fuse'][i] = step[7]
outputs['N'][i] = self.n_props * Normal_F
outputs['aoa_prop'][i] = atov - theta
outputs['x_dot'][i] = inputs['vx'][i]
outputs['y_dot'][i] = inputs['vy'][i]
outputs['a_x'][i] = step[0]
outputs['a_y'][i] = step[1]
outputs['energy_dot'][i] = power
# # use KS function for minimum vertical displacement
# ks_rho = 100. # Hard coded, see Martins and Poon 2005 for more (if using a larger number of time steps than ~500, this ks_rho value should be higher)
# f_max = np.max(-self.y)
# min_y = -(f_max + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (-self.y - f_max)))))
# outputs['y_min'] = min_y
# # use KS function for minimum propeller inflow speed
# ks_rho = 100. # Hard coded, see Martins and Poon 2005 for more (if using a larger number of time steps than ~500, this ks_rho value should be higher)
# f_max = np.max(-self.u_inf_prop)
# self.min_u_prop = -(f_max + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (-self.u_inf_prop - f_max)))))
# outputs['u_prop_min'] = self.min_u_prop
# # use KS function for minimum and maximum effective angles of attack
# if self.stall_option == 'ns':
# ks_rho = 500. # Hard coded, see Martins and Poon 2005 for more
# f_max = np.max(self.aoa)
# max_aoa = (f_max + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (self.aoa - f_max)))))
# outputs['aoa_max'] = max_aoa
# ks_rho = 500. # Hard coded, see Martins and Poon 2005 for more
# f_max = np.max(-self.aoa)
# min_aoa = -(f_max + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (-self.aoa - f_max)))))
# outputs['aoa_min'] = min_aoa
# ks_rho = 500. # Hard coded, see Martins and Poon 2005 for more
# f_max = np.max(self.acc)
# max_acc = (f_max + 1 / ks_rho * np.log(np.sum(np.exp(ks_rho * (self.acc - f_max)))))
# outputs['acc_max'] = max_acc