Skip to content

Commit

Permalink
AC_Autorotation: Cleanup sensitivity study
Browse files Browse the repository at this point in the history
  • Loading branch information
MattKear committed Apr 10, 2024
1 parent b29a5a6 commit 37ba8c2
Showing 1 changed file with 7 additions and 222 deletions.
229 changes: 7 additions & 222 deletions libraries/AC_Autorotation/Derivation/sensitivity_study.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,81 +38,6 @@ def my_arctanh(x):
print('ArcTanException')
return 0.0

# =====================================================================================
# Math from Ferruccio's original PR
class Flare_Calc_Pre_Changes():
def __init__(self):
self.reset_to_defaults()

def reset_to_defaults(self):
self.var = {}
self.var['_param_solidity'] = 0.05
self.var['_c_l_alpha'] = np.pi*2
self.var['_param_diameter'] = 1.25
self.var['blade_pitch_hover_deg'] = 5.0
self.var['_param_head_speed_set_point'] = 1500
self.var['_param_target_speed'] = 1100
self.var['_t_tch'] = 0.55

def initial_flare_estimate(self):

# estimate hover thrust
# _col_hover_rad = radians(_col_min + (_col_max - _col_min)*_col_hover)
_col_hover_rad = deg2rad(self.var['blade_pitch_hover_deg'])
b = self.var['_param_solidity']*6.28
_disc_area=3.14*(self.var['_param_diameter']*0.5)**2
lambda_eq = (-(b/8.0) + math.sqrt((b**2)/64.0 +((b/3.0)*_col_hover_rad)))*0.5
freq=self.var['_param_head_speed_set_point']/60.0
tip_speed= freq*6.28*self.var['_param_diameter']*0.5
self._lift_hover = ((1.225*(tip_speed**2)*(self.var['_param_solidity']*_disc_area))*((_col_hover_rad/3.0) - (lambda_eq/2.0))*5.8)*0.5

# estimate rate of descent
omega_auto=(self.var['_param_head_speed_set_point']/60.0)*6.28
tip_speed_auto = omega_auto*self.var['_param_diameter']*0.5
c_t = self._lift_hover/(0.6125*_disc_area*(tip_speed**2))
_est_rod=((0.25*(self.var['_param_solidity']*0.011/c_t)*tip_speed_auto)+(((c_t**2)/(self.var['_param_solidity']*0.011))*tip_speed_auto))

# estimate rotor C_d
self._c=(self._lift_hover/((_est_rod**2)*0.5*1.225*_disc_area))*1.15
self._c=min(max(self._c, 0.7), 1.4)

# calc flare altitude
des_spd_fwd=self.var['_param_target_speed']*0.01

flare_alt, delta_t_flare = self.calc_flare_alt(-_est_rod, des_spd_fwd)
return (flare_alt, self._lift_hover/GRAVITY_MSS, delta_t_flare)

def calc_flare_alt(self, sink_rate, fwd_speed):

#compute speed module and glide path angle during descent
speed_module=norm(sink_rate,fwd_speed)
glide_angle=safe_asin(3.14/2-(fwd_speed/speed_module))

# estimate inflow velocity at beginning of flare
inflow= -speed_module*math.sin(glide_angle+deg2rad(AP_ALPHA_TPP))

# estimate flare duration
k_1=abs((-sink_rate+0.001-math.sqrt(self._lift_hover/self._c))/(-sink_rate+0.001+math.sqrt(self._lift_hover/self._c)))
k_2=abs((inflow-math.sqrt(self._lift_hover/self._c))/(inflow+math.sqrt(self._lift_hover/self._c)))
delta_t_flare=(0.5*(self._lift_hover/(9.8065*self._c))*math.sqrt(self._c/self._lift_hover)*math.log(k_1))-(0.5*(self._lift_hover/(9.8065*self._c))*math.sqrt(self._c/self._lift_hover)*math.log(k_2))

# estimate flare delta altitude
a=(2*math.sqrt(self._c*9.8065/(self._lift_hover/9.8065)))*delta_t_flare + (2*math.sqrt(self._c*9.8065/(self._lift_hover/9.8065)))*(0.5*(self._lift_hover/(9.8065*self._c))*math.sqrt(self._c/self._lift_hover)*math.log(k_1))
x=1-math.exp(a)
s=1-math.exp((2*math.sqrt(self._c*9.8065/(self._lift_hover/9.8065)))*(0.5*(self._lift_hover/(9.8065*self._c))*math.sqrt(self._c/self._lift_hover)*math.log(k_1)))
d=math.sqrt(self._lift_hover/self._c)
flare_distance=((2*d/(2*math.sqrt(self._c*9.8065/(self._lift_hover/9.8065))))*(a-math.log(abs(x))-(2*math.sqrt(self._c*9.8065/(self._lift_hover/9.8065)))*(0.5*(self._lift_hover/(9.8065*self._c))*math.sqrt(self._c/self._lift_hover)*math.log(k_1)) +math.log(abs(s))))-d*delta_t_flare
delta_h= -flare_distance*math.cos(deg2rad(AP_ALPHA_TPP))

# estimate altitude to begin collective pull
_cushion_alt = (-(sink_rate*math.cos(deg2rad(AP_ALPHA_TPP)))*self.var['_t_tch'])*100.0

# total delta altitude to ground
_flare_alt_calc = _cushion_alt+delta_h*100.0

return _flare_alt_calc*1e-2, delta_t_flare
# =====================================================================================

# =====================================================================================
# Math from Ferruccio's reworked math
class Flare_Calc_Reworked_Math():
Expand All @@ -138,9 +63,7 @@ def initial_flare_estimate(self):
_disc_area = np.pi * 0.25 * self.var['_param_diameter']**2

# Calculating the equivalent inflow ratio (average across the whole blade)
# lambda_eq = -b / 16.0 + math.sqrt((b**2) / 256.0 + b * blade_pitch_hover_rad / 8.0)
lambda_eq = -b / 16.0 + math.sqrt((b**2) / 256.0 + b * blade_pitch_hover_rad / 12.0) # <--------
# lambda_eq = -b / 8.0 + math.sqrt((b**2) / 64.0 + b * blade_pitch_hover_rad / 6.0) # <--------

# Tip speed = head speed (rpm) / 60 * 2pi * rotor diameter/2. Eq below is simplified.
tip_speed_auto = self.var['_param_head_speed_set_point'] * np.pi * self.var['_param_diameter'] / 60.0
Expand All @@ -153,8 +76,8 @@ def initial_flare_estimate(self):
_est_rod = ((0.25 * self.var['_param_solidity'] * ASSUMED_CD0 / c_t_hover) + (c_t_hover**2 / (self.var['_param_solidity'] * ASSUMED_CD0))) * tip_speed_auto

# Estimate rotor C_d
self._c = self._lift_hover / (_est_rod**2)
# self._c = self._lift_hover / (_est_rod**2 * 0.5 * SSL_AIR_DENSITY * _disc_area)
# self._c = self._lift_hover / (_est_rod**2)
self._c = self._lift_hover / (_est_rod**2 * 0.5 * SSL_AIR_DENSITY * _disc_area)

# Calc flare altitude
des_spd_fwd = self.var['_param_target_speed'] * 0.01
Expand All @@ -166,155 +89,19 @@ def calc_flare_alt(self, sink_rate, fwd_speed):

# Compute speed module and glide path angle during descent
speed_module = max(norm(sink_rate, fwd_speed), 0.1)
# glide_angle = safe_asin(np.pi / 2 - (fwd_speed / speed_module))
# glide_angle = safe_acos(- (fwd_speed / speed_module))
glide_angle = np.pi / 2 - safe_asin(fwd_speed / speed_module)

# Estimate inflow velocity at beginning of flare
entry_inflow = - speed_module * math.sin(glide_angle + deg2rad(AP_ALPHA_TPP))

# Add alternitive math here
k_1 = math.sqrt(self._lift_hover / self._c)

# Protect against div by 0 case
if (abs(sink_rate + k_1) < 1.1920928955e-7):
sink_rate -= 0.05

# Estimate flare duration
m = self._lift_hover / GRAVITY_MSS
k_3 = math.sqrt((self._c * GRAVITY_MSS) / m)
k_2 = 1 / (2 * k_3) * math.log(abs((entry_inflow - k_1)/(entry_inflow + k_1)))
a = math.log(abs((sink_rate - k_1)/(sink_rate + k_1)))
b = math.log(abs((entry_inflow - k_1)/(entry_inflow + k_1)))
delta_t_flare = (1 / (2 * k_3)) * (a - b)

# # Estimate flare delta altitude
k_4 = (2 * k_2 * k_3) + (2 * k_3 * delta_t_flare)
try:
flare_distance = ((k_1 / k_3) * (k_4 - math.log(abs(1-math.exp(k_4))) - (2 * k_2 * k_3 - math.log(abs(1 - math.exp(2 * k_2 * k_3)))))) - k_1 * delta_t_flare
except:
flare_distance = 0
delta_h = -flare_distance * math.cos(deg2rad(AP_ALPHA_TPP))

# Estimate altitude to begin collective pull
_cushion_alt = (-(sink_rate * math.cos(deg2rad(AP_ALPHA_TPP))) * self.var['_t_tch']) * 100.0

# Total delta altitude to ground
_flare_alt_calc = _cushion_alt + delta_h * 100.0

return _flare_alt_calc*1e-2, delta_t_flare
# =====================================================================================

# =====================================================================================
# Math from my branch, after my reworks
class Flare_Calc():
def __init__(self):
self.reset_to_defaults()

def reset_to_defaults(self):
self.var = {}
self.var['_param_solidity'] = 0.05
self.var['_c_l_alpha'] = np.pi*2
self.var['_param_diameter'] = 1.25
self.var['blade_pitch_hover_deg'] = 5.0
self.var['_param_head_speed_set_point'] = 1500
self.var['_param_target_speed'] = 1100
self.var['_t_tch'] = 0.55

def initial_flare_estimate(self):

blade_pitch_hover_rad = deg2rad(self.var['blade_pitch_hover_deg'])

b = self.var['_param_solidity'] * self.var['_c_l_alpha']
_disc_area = np.pi * 0.25 * self.var['_param_diameter']**2

# Calculating the equivalent inflow ratio (average across the whole blade)
# lambda_eq = -b / 16.0 + math.sqrt((b**2) / 256.0 + b * blade_pitch_hover_rad / 8.0)
# lambda_eq = -b / 16.0 + math.sqrt((b**2) / 256.0 + b * blade_pitch_hover_rad / 12.0) # <--------
lambda_eq = -b / 8.0 + math.sqrt((b**2) / 64.0 + b * blade_pitch_hover_rad / 6.0) # <--------

# Tip speed = head speed (rpm) / 60 * 2pi * rotor diameter/2. Eq below is simplified.
tip_speed_auto = self.var['_param_head_speed_set_point'] * np.pi * self.var['_param_diameter'] / 60.0

# Calc the coefficient of thrust in the hover
c_t_hover = 0.5 * b * (blade_pitch_hover_rad / 3.0 - lambda_eq / 2.0)
self._lift_hover = c_t_hover * SSL_AIR_DENSITY * _disc_area * tip_speed_auto**2
entry_inflow = - sink_rate

# Estimate rate of descent
_est_rod = ((0.25 * self.var['_param_solidity'] * ASSUMED_CD0 / c_t_hover) + (c_t_hover**2 / (self.var['_param_solidity'] * ASSUMED_CD0))) * tip_speed_auto

# Estimate rotor C_d
self._c = (self._lift_hover / (_est_rod**2 * 0.5 * SSL_AIR_DENSITY * _disc_area)) * 1.15
self._c = min(max(self._c, 0.7), 1.4)

# Calc flare altitude
des_spd_fwd = self.var['_param_target_speed'] * 0.01

flare_alt, delta_t_flare = self.calc_flare_alt(-_est_rod, des_spd_fwd)
return (flare_alt, self._lift_hover/GRAVITY_MSS, delta_t_flare)

# def calc_flare_alt(self, sink_rate, fwd_speed):

# # Compute speed module and glide path angle during descent
# speed_module = max(norm(sink_rate, fwd_speed), 0.1)
# glide_angle = safe_asin(np.pi / 2 - (fwd_speed / speed_module))
z_m = self._lift_hover / GRAVITY_MSS
print(z_m)

# # Estimate inflow velocity at beginning of flare
# inflow = - speed_module * math.sin(glide_angle + deg2rad(AP_ALPHA_TPP))
delta_h = 10

# # Estimate flare duration
# k_1 = np.abs((-sink_rate + 0.001 - math.sqrt(self._lift_hover / self._c))/(-sink_rate + 0.001 + math.sqrt(self._lift_hover / self._c)))
# k_2 = np.abs((inflow - math.sqrt(self._lift_hover / self._c)) / (inflow + math.sqrt(self._lift_hover / self._c)))
# delta_t_flare = (0.5 * (self._lift_hover / (GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_1)) - (0.5 * (self._lift_hover / (GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_2))

# # Estimate flare delta altitude
# sq_gravity = GRAVITY_MSS**2
# a = (2 * math.sqrt(self._c * sq_gravity / self._lift_hover )) * delta_t_flare + (2 * math.sqrt(self._c * sq_gravity / self._lift_hover )) * (0.5 * (self._lift_hover / (GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_1))
# x = 1 - math.exp(a)
# s = 1 - math.exp((2 * math.sqrt(self._c * sq_gravity / self._lift_hover )) * (0.5 * (self._lift_hover/(GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_1)))
# d = math.sqrt(self._lift_hover / self._c)
# flare_distance = ((2 * d / (2 * math.sqrt(self._c * sq_gravity / self._lift_hover ))) * (a - math.log(abs(x)) - (2 * math.sqrt(self._c * sq_gravity / self._lift_hover )) * (0.5 * (self._lift_hover / (GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_1)) + math.log(abs(s)))) - d * delta_t_flare
# delta_h = -flare_distance * math.cos(deg2rad(AP_ALPHA_TPP))

# # Estimate altitude to begin collective pull
# _cushion_alt = (-(sink_rate * math.cos(deg2rad(AP_ALPHA_TPP))) * self.var['_t_tch']) * 100.0

# # Total delta altitude to ground
# _flare_alt_calc = _cushion_alt + delta_h * 100.0

# return _flare_alt_calc*1e-2, delta_t_flare

def calc_flare_alt(self, sink_rate, fwd_speed):

# Compute speed module and glide path angle during descent
speed_module = max(norm(sink_rate, fwd_speed), 0.1)
glide_angle = safe_asin(np.pi / 2 - (fwd_speed / speed_module))

# Estimate inflow velocity at beginning of flare
inflow = - speed_module * math.sin(glide_angle + deg2rad(AP_ALPHA_TPP))

# Estimate flare duration
b = math.sqrt(self._lift_hover / self._c)
v_initial = inflow
v_final = -sink_rate + 0.001
delta_t_flare = (self._lift_hover / (self._c*GRAVITY_MSS)) * ((-coth(v_final/b)/b) - (-coth(v_initial/b)/b))

# Old Estimate for flare duration
k_1 = np.abs((-sink_rate + 0.001 - math.sqrt(self._lift_hover / self._c))/(-sink_rate + 0.001 + math.sqrt(self._lift_hover / self._c)))
k_2 = np.abs((inflow - math.sqrt(self._lift_hover / self._c)) / (inflow + math.sqrt(self._lift_hover / self._c)))
delta_t_flare = (0.5 * (self._lift_hover / (GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_1)) - (0.5 * (self._lift_hover / (GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_2))

# Estimate flare delta altitude
sq_gravity = GRAVITY_MSS**2
a = (2 * math.sqrt(self._c * sq_gravity / self._lift_hover )) * delta_t_flare + (2 * math.sqrt(self._c * sq_gravity / self._lift_hover )) * (0.5 * (self._lift_hover / (GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_1))
x = 1 - math.exp(a)
s = 1 - math.exp((2 * math.sqrt(self._c * sq_gravity / self._lift_hover )) * (0.5 * (self._lift_hover/(GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_1)))
d = math.sqrt(self._lift_hover / self._c)
flare_distance = ((2 * d / (2 * math.sqrt(self._c * sq_gravity / self._lift_hover ))) * (a - math.log(abs(x)) - (2 * math.sqrt(self._c * sq_gravity / self._lift_hover )) * (0.5 * (self._lift_hover / (GRAVITY_MSS * self._c)) * math.sqrt(self._c / self._lift_hover) * math.log(k_1)) + math.log(abs(s)))) - d * delta_t_flare
delta_h = -flare_distance * math.cos(deg2rad(AP_ALPHA_TPP))

# Estimate altitude to begin collective pull
_cushion_alt = (-(sink_rate * math.cos(deg2rad(AP_ALPHA_TPP))) * self.var['_t_tch']) * 100.0
_cushion_alt = (-sink_rate * self.var['_t_tch']) * 100.0

# Total delta altitude to ground
_flare_alt_calc = _cushion_alt + delta_h * 100.0
Expand Down Expand Up @@ -370,9 +157,7 @@ def plot_single_var_sensitivity(obj, var_name, var_array):

if __name__=='__main__':
# Setup flare object to do calculations
# flare_obj = Flare_Calc_Pre_Changes()
flare_obj = Flare_Calc_Reworked_Math()
# flare_obj = Flare_Calc()

N_PTS = 100000

Expand Down

0 comments on commit 37ba8c2

Please sign in to comment.