From af364b4d55ea746317318ef973c09dd28e44c3fb Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 17 Feb 2021 10:11:34 +0000 Subject: [PATCH 001/253] New no-structural solver --- sharpy/solvers/nostructural.py | 72 ++++++++++++++++++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100644 sharpy/solvers/nostructural.py diff --git a/sharpy/solvers/nostructural.py b/sharpy/solvers/nostructural.py new file mode 100644 index 000000000..44628c2b2 --- /dev/null +++ b/sharpy/solvers/nostructural.py @@ -0,0 +1,72 @@ +import numpy as np + +import sharpy.utils.cout_utils as cout +import sharpy.utils.settings as settings +from sharpy.utils.solver_interface import solver, BaseSolver, solver_from_string + +_BaseStructural = solver_from_string('_BaseStructural') + +@solver +class NoStructural(_BaseStructural): + """ + Structural solver used for the static simulation of free-flying structures. + + This solver provides an interface to the structural library (``xbeam``) and updates the structural parameters + for every k-th step of the FSI iteration. + + This solver can be called as part of a standalone structural simulation or as the structural solver of a coupled + static aeroelastic simulation. + + """ + solver_id = 'NoStructural' + solver_classification = 'structural' + + # settings list + settings_types = _BaseStructural.settings_types.copy() + settings_default = _BaseStructural.settings_default.copy() + settings_description = _BaseStructural.settings_description.copy() + + settings_types['initial_position'] = 'list(float)' + settings_default['initial_position'] = np.array([0.0, 0.0, 0.0]) + + settings_table = settings.SettingsTable() + __doc__ += settings_table.generate(settings_types, settings_default, settings_description) + + def __init__(self): + self.data = None + self.settings = None + + def initialise(self, data, custom_settings=None): + self.data = data + if custom_settings is None: + self.settings = data.settings[self.solver_id] + else: + self.settings = custom_settings + settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + + def run(self): + self.data.structure.timestep_info[self.data.ts].for_pos[0:3] = self.settings['initial_position'] + self.extract_resultants() + return self.data + + def next_step(self): + self.data.structure.next_step() + + def extract_resultants(self, tstep=None): + if tstep is None: + tstep = self.data.structure.timestep_info[self.data.ts] + steady, grav = tstep.extract_resultants(self.data.structure, force_type=['steady', 'grav']) + totals = steady + grav + return totals[0:3], totals[3:6] + + def update(self, tstep=None): + self.create_q_vector(tstep) + + def create_q_vector(self, tstep=None): + import sharpy.structure.utils.xbeamlib as xb + if tstep is None: + tstep = self.data.structure.timestep_info[-1] + + xb.xbeam_solv_disp2state(self.data.structure, tstep) + + From 581e84bde8d9f40616ac710e36d59c35cd2707d7 Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 17 Feb 2021 10:40:04 +0000 Subject: [PATCH 002/253] WIP --- sharpy/controllers/bladepitchpid.py | 44 ++++++++++++++++++++--------- sharpy/solvers/dynamiccoupled.py | 7 +++++ 2 files changed, 37 insertions(+), 14 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index e2995ce1e..d97b02856 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -67,6 +67,10 @@ class BladePitchPid(controller_interface.BaseController): settings_default['blade_num_body'] = [0,] settings_description['blade_num_body'] = 'Body number of the blade(s) to pitch' + settings_types['max_pitch_rate'] = 'float' + settings_default['max_pitch_rate'] = 0.1396 + settings_description['max_pitch_rate'] = 'Maximum pitch rate [rad/s]' + # Output parameters settings_types['write_controller_log'] = 'bool' settings_default['write_controller_log'] = True @@ -177,17 +181,27 @@ def control(self, data, controlled_state): # Apply control order # rot_mat = algebra.rotation3d_x(control_command) - quat = algebra.rotate_quaternion(struct_tstep.quat, control_command*np.array([1., 0., 0.])) - - # euler = np.array([prescribed_sp[0], 0., 0.]) - struct_tstep.quat = quat - struct_tstep.for_vel[3] = control_command/self.settings['dt'] - struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] + print("control_command: ", control_command) + # print("init euler: ", algebra.quat2euler(struct_tstep.quat)) + change_quat = False + if change_quat: + quat = algebra.rotate_quaternion(struct_tstep.quat, control_command*np.array([1., 0., 0.])) + # print("final euler: ", algebra.quat2euler(quat)) + # euler = np.array([prescribed_sp[0], 0., 0.]) + struct_tstep.quat = quat + change_vel = True + if change_vel: + # struct_tstep.for_vel[3] = control_command/self.settings['dt'] + # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] + struct_tstep.for_vel[3] = np.sign(control_command)*self.settings['max_pitch_rate'] + + # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] - data.structure.dynamic_input[data.ts - 1]['for_vel'] = struct_tstep.for_vel.copy() - data.structure.dynamic_input[data.ts - 1]['for_acc'] = struct_tstep.for_acc.copy() + data.structure.dynamic_input[data.ts - 1]['for_vel'] = struct_tstep.for_vel.copy() + data.structure.dynamic_input[data.ts - 1]['for_acc'] = struct_tstep.for_acc.copy() - data.aero.generate_zeta_timestep_info(struct_tstep, + if True: + data.aero.generate_zeta_timestep_info(struct_tstep, aero_tstep, data.structure, data.aero.aero_settings, @@ -213,9 +227,9 @@ def compute_prescribed_sp(self, time): Compute the set point relevant for the controller """ if self.settings['sp_source'] == 'file': - pitch = np.interp(time, - self.prescribed_sp_time_history[:, 0], - self.prescribed_sp_time_history[:, 1]) + sp = np.interp(time, + self.prescribed_sp_time_history[:, 0], + self.prescribed_sp_time_history[:, 1]) # vel = np.interp(time, # self.prescribed_sp_time_history[:, 0], # self.prescribed_sp_time_history[:, 2]) @@ -223,7 +237,7 @@ def compute_prescribed_sp(self, time): # self.prescribed_sp_time_history[:, 0], # self.prescribed_sp_time_history[:, 3]) # self.prescribed_sp.append(np.array([pitch, vel, acc])) - self.prescribed_sp.append(pitch) + self.prescribed_sp.append(sp) return self.prescribed_sp[-1] @@ -237,8 +251,10 @@ def compute_system_pv(self, struct_tstep, beam): elif self.settings['sp_type'] == 'rbm': steady, unsteady, grav = struct_tstep.extract_resultants(beam, force_type=['steady', 'unsteady', 'gravity'], ibody=0) - rbm = np.linalg.norm(steady[3:6] + unsteady[3:6] + grav[3:6]) + # rbm = np.linalg.norm(steady[3:6] + unsteady[3:6] + grav[3:6]) + rbm = steady[4] + unsteady[4] + grav[4] self.system_pv.append(rbm) + print("rbm: ", rbm) return self.system_pv[-1] # def extract_time_history(self, controlled_state): diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 6d4368e15..b0e38fa6a 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -493,6 +493,12 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): structural_kstep, aero_kstep = self.process_controller_output( state) + # print(structural_kstep.quat) + # print(structural_kstep.for_vel) + # print(structural_kstep.for_acc) + # print(self.data.structure.dynamic_input[self.data.ts - 1]['for_vel']) + # print(self.data.structure.dynamic_input[self.data.ts - 1]['for_acc']) + # compute unsteady contribution force_coeff = 0.0 unsteady_contribution = False @@ -586,6 +592,7 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): structural_kstep, force_coeff) + # print(structural_kstep.steady_applied_forces[:, -1]) # relaxation relax_factor = self.relaxation_factor(k) relax(self.data.structure, From dff1acc539417d59b0a00bd3c987f6d493d21726 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 18 Feb 2021 11:59:50 +0000 Subject: [PATCH 003/253] PID on rbm and pitch vel --- sharpy/controllers/bladepitchpid.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index d97b02856..99f86510a 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -178,7 +178,12 @@ def control(self, data, controlled_state): 'I': self.settings['I'], 'D': self.settings['D']}, i_current=data.ts) - + + if control_command < -self.settings['max_pitch_rate']: + control_command = -self.settings['max_pitch_rate'] + elif control_command > self.settings['max_pitch_rate']: + control_command = self.settings['max_pitch_rate'] + # Apply control order # rot_mat = algebra.rotation3d_x(control_command) print("control_command: ", control_command) @@ -193,14 +198,15 @@ def control(self, data, controlled_state): if change_vel: # struct_tstep.for_vel[3] = control_command/self.settings['dt'] # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] - struct_tstep.for_vel[3] = np.sign(control_command)*self.settings['max_pitch_rate'] - + # struct_tstep.for_vel[3] = np.sign(control_command)*self.settings['max_pitch_rate'] # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] + struct_tstep.for_vel[3] = control_command + struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] data.structure.dynamic_input[data.ts - 1]['for_vel'] = struct_tstep.for_vel.copy() data.structure.dynamic_input[data.ts - 1]['for_acc'] = struct_tstep.for_acc.copy() - if True: + if False: data.aero.generate_zeta_timestep_info(struct_tstep, aero_tstep, data.structure, From 1aebccaad9b7d9849d6f8f2aef0ca0a7601d65c8 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 19 Feb 2021 09:34:19 +0000 Subject: [PATCH 004/253] filter process value --- sharpy/controllers/bladepitchpid.py | 20 ++++++++++++++++++-- 1 file changed, 18 insertions(+), 2 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 99f86510a..657dc7887 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -1,4 +1,5 @@ import numpy as np +from scipy.signal import StateSpace, lsim import sharpy.utils.controller_interface as controller_interface import sharpy.utils.settings as settings @@ -33,6 +34,11 @@ class BladePitchPid(controller_interface.BaseController): settings_default['D'] = 0.0 settings_description['D'] = 'Differential gain of the controller' + # Filter + settings_types['lp_cut_freq'] = 'float' + settings_default['lp_cut_freq'] = 0. + settings_description['lp_cut_freq'] = 'Cutting frequency of the low pass filter of the process value. Choose 0 for no filter' + # Set point parameters settings_types['sp_type'] = 'str' settings_default['sp_type'] = None @@ -141,6 +147,12 @@ def initialise(self, in_dict, controller_id=None): self.settings['D'], self.settings['dt']) + if self.settings['lp_cut_freq'] == 0.: + self.filter_pv = False + else: + self.filter_pv = True + alpha = np.exp(-self.settings['lp_cut_freq']*self.settings['dt']) + self.filter = StateSpace(alpha, (1-alpha), alpha, (1-alpha), self.settings['dt']) def control(self, data, controlled_state): r""" @@ -164,7 +176,11 @@ def control(self, data, controlled_state): prescribed_sp = self.compute_prescribed_sp(time) sys_pv = self.compute_system_pv(struct_tstep, data.structure) - + # Apply filter + if self.filter_pv: + filtered_pv = lsim(self.filter, sys_pv) + else: + filtered_pv = self.system_pv # get current state input # self.real_state_input_history.append(self.extract_time_history(controlled_state)) @@ -173,7 +189,7 @@ def control(self, data, controlled_state): # # apply it where needed. control_command, detail = self.controller_wrapper( required_input=self.prescribed_sp, - current_input=self.system_pv, + current_input=filtered_pv, control_param={'P': self.settings['P'], 'I': self.settings['I'], 'D': self.settings['D']}, From 9c25f6bcea0e6efc122fa2128b366b16707aaf4f Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 19 Feb 2021 19:39:53 +0000 Subject: [PATCH 005/253] save resultants dynamiccoupled --- sharpy/solvers/dynamiccoupled.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index b0e38fa6a..777599bd9 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -662,7 +662,9 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): structural_kstep.for_vel[2], np.sum(structural_kstep.steady_applied_forces[:, 0]), np.sum(structural_kstep.steady_applied_forces[:, 2])]) - self.structural_solver.extract_resultants() + (self.data.structure.timestep_info[self.data.ts].total_forces[0:3], + self.data.structure.timestep_info[self.data.ts].total_forces[3:6]) = ( + self.structural_solver.extract_resultants(self.data.structure.timestep_info[self.data.ts])) # run postprocessors if self.with_postprocessors: for postproc in self.postprocessors: From 7c0c5816418ec2ee931ea9da6e3cfe9dd607b7f1 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 22 Feb 2021 10:24:36 +0000 Subject: [PATCH 006/253] anti-windup --- sharpy/controllers/bladepitchpid.py | 6 ++++++ sharpy/utils/control_utils.py | 27 ++++++++++++++++++++++----- 2 files changed, 28 insertions(+), 5 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 657dc7887..1b9594ba4 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -39,6 +39,10 @@ class BladePitchPid(controller_interface.BaseController): settings_default['lp_cut_freq'] = 0. settings_description['lp_cut_freq'] = 'Cutting frequency of the low pass filter of the process value. Choose 0 for no filter' + settings_types['anti_windup_lim'] = 'list(float)' + settings_default['anti_windup_lim'] = None + settings_description['anti_windup_lim'] = 'Limits of actuation to apply anti windup' + # Set point parameters settings_types['sp_type'] = 'str' settings_default['sp_type'] = None @@ -147,6 +151,8 @@ def initialise(self, in_dict, controller_id=None): self.settings['D'], self.settings['dt']) + self.controller_implementation.set_anti_windup_lim(self.settings['anti_windup_lim']) + if self.settings['lp_cut_freq'] == 0.: self.filter_pv = False else: diff --git a/sharpy/utils/control_utils.py b/sharpy/utils/control_utils.py index 7ec48b334..c6d29536b 100644 --- a/sharpy/utils/control_utils.py +++ b/sharpy/utils/control_utils.py @@ -61,9 +61,14 @@ def __init__(self, gain_p, gain_i, gain_d, dt): self._n_calls = 0 + self._anti_windup_lim = None + def set_point(self, point): self._point = point + def set_anti_windup_lim(self, lim): + self._anti_windup_lim = lim + def reset_integrator(self): self._accumulated_integral = 0.0 @@ -88,11 +93,23 @@ def __call__(self, state): detailed[2] = derivative*self._kd # Integral gain - self._accumulated_integral += error*self._dt - if self._accumulated_integral < self._integral_limits[0]: - self._accumulated_integral = self._integral_limits[0] - elif self._accumulated_integral > self._integral_limits[1]: - self._accumulated_integral = self._integral_limits[1] + aux_acc_int = self._accumulated_integral + error*self._dt + if aux_acc_int < self._integral_limits[0]: + aux_acc_int = self._integral_limits[0] + elif aux_acc_int > self._integral_limits[1]: + aux_acc_int = self._integral_limits[1] + + if self._anti_windup_lim is not None: + # Apply anti wind up + aux_actuation = actuation + aux_acc_int*self._ki + if ((aux_actuation > self._anti_windup_lim[0]) and + (aux_actuation < self._anti_windup_lim[1])): + # Within limits + self._accumulated_integral = aux_acc_int + # If the system exceeds the limits, this + # will not be added to the self._accumulated_integral + else: + self._accumulated_integral = aux_acc_int actuation += self._accumulated_integral*self._ki detailed[1] = self._accumulated_integral*self._ki From 308515ad7fc25d4ad6f64d4caa78d05c8098c2cc Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 23 Feb 2021 09:39:51 +0000 Subject: [PATCH 007/253] remove not needed StaticCoupledRBM solver --- cases/coupled/WindTurbine/generate_rotor.py | 150 +++++--- sharpy/generators/straightwake.py | 6 +- sharpy/solvers/staticcoupledrbm.py | 362 -------------------- tests/utils/test_generate_cases.py | 20 +- 4 files changed, 118 insertions(+), 420 deletions(-) delete mode 100644 sharpy/solvers/staticcoupledrbm.py diff --git a/cases/coupled/WindTurbine/generate_rotor.py b/cases/coupled/WindTurbine/generate_rotor.py index 80700343b..0c593c5b3 100644 --- a/cases/coupled/WindTurbine/generate_rotor.py +++ b/cases/coupled/WindTurbine/generate_rotor.py @@ -37,20 +37,39 @@ mstar = int(revs_in_wake*2.*np.pi/dphi) -rotor = template_wt.rotor_from_excel_type02( - chord_panels, - rotation_velocity, - pitch_deg, - excel_file_name = route + '../../../docs/source/content/example_notebooks/source/type02_db_NREL5MW_v01.xlsx', - excel_sheet_parameters = 'parameters', - excel_sheet_structural_blade = 'structural_blade', - excel_sheet_discretization_blade = 'discretization_blade', - excel_sheet_aero_blade = 'aero_blade', - excel_sheet_airfoil_info = 'airfoil_info', - excel_sheet_airfoil_coord = 'airfoil_coord', - m_distribution = 'uniform', - n_points_camber = 100, - tol_remove_points = 1e-8) + +op_params = {} +op_params['rotation_velocity'] = rotation_velocity +op_params['pitch_deg'] = pitch_deg +op_params['wsp'] = WSP +op_params['dt'] = dt + +geom_params = {} +geom_params['chord_panels'] = chord_panels +geom_params['tol_remove_points'] = 1e-8 +geom_params['n_points_camber'] = 100 +geom_params['h5_cross_sec_prop'] = None +geom_params['m_distribution'] = 'uniform' + +options = {} +options['camber_effect_on_twist'] = False +options['user_defined_m_distribution_type'] = None +options['include_polars'] = False +options['separate_blades'] = False + +excel_description = {} +excel_description['excel_file_name'] = '../../../docs/source/content/example_notebooks/source/type02_db_NREL5MW_v01.xlsx' +excel_description['excel_sheet_parameters'] = 'parameters' +excel_description['excel_sheet_structural_blade'] = 'structural_blade' +excel_description['excel_sheet_discretization_blade'] = 'discretization_blade' +excel_description['excel_sheet_aero_blade'] = 'aero_blade' +excel_description['excel_sheet_airfoil_info'] = 'airfoil_info' +excel_description['excel_sheet_airfoil_chord'] = 'airfoil_coord' + +rotor, hub_nodes = template_wt.rotor_from_excel_type03(op_params, + geom_params, + excel_description, + options) ###################################################################### ###################### DEFINE SIMULATION ########################### @@ -60,7 +79,7 @@ SimInfo.solvers['SHARPy']['flow'] = ['BeamLoader', 'AerogridLoader', - 'StaticCoupledRBM', + 'StaticCoupled', 'BeamPlot', 'AerogridPlot', 'DynamicCoupled', @@ -77,44 +96,85 @@ SimInfo.solvers['BeamLoader']['unsteady'] = 'on' +# Compute mstar +SimInfo.solvers['AerogridLoader']['wake_shape_generator'] = 'HelicoidalWake' +SimInfo.solvers['AerogridLoader']['wake_shape_generator_input'] = {'u_inf': WSP, + 'u_inf_direction': SimInfo.solvers['SteadyVelocityField']['u_inf_direction'], + 'rotation_velocity': rotation_velocity*np.array([0., 0., 1.]), + 'dt': dt, + 'dphi1': dphi, + 'ndphi1': int(revs_in_wake*np.pi/dphi), + 'r': 1., + 'dphimax': 10*deg2rad} + +import sharpy.utils.generator_interface as gi +gi.dictionary_of_generators(print_info=False) +hw = gi.dict_of_generators['HelicoidalWake'] +wsg_in = SimInfo.solvers['AerogridLoader']['wake_shape_generator_input'] # for simplicity +angle = 0 +mstar = 0 +while angle < (revs_in_wake*2*np.pi): + mstar += 1 + angle += hw.get_dphi(mstar, wsg_in['dphi1'], + wsg_in['ndphi1'], + wsg_in['r'], + wsg_in['dphimax']) + SimInfo.solvers['AerogridLoader']['unsteady'] = 'on' SimInfo.solvers['AerogridLoader']['mstar'] = mstar SimInfo.solvers['AerogridLoader']['freestream_dir'] = np.array([0.,0.,0.]) -SimInfo.solvers['NonLinearStatic']['max_iterations'] = 200 -SimInfo.solvers['NonLinearStatic']['num_load_steps'] = 1 -SimInfo.solvers['NonLinearStatic']['min_delta'] = 1e-5 - -SimInfo.solvers['StaticCoupledRBM']['structural_solver'] = 'RigidDynamicPrescribedStep' -SimInfo.solvers['StaticCoupledRBM']['structural_solver_settings'] = SimInfo.solvers['RigidDynamicPrescribedStep'] -SimInfo.solvers['StaticCoupledRBM']['structural_solver'] = 'NonLinearDynamicPrescribedStep' -SimInfo.solvers['StaticCoupledRBM']['structural_solver_settings'] = SimInfo.solvers['NonLinearDynamicPrescribedStep'] -SimInfo.solvers['StaticCoupledRBM']['structural_solver'] = 'NonLinearStatic' -SimInfo.solvers['StaticCoupledRBM']['structural_solver_settings'] = SimInfo.solvers['NonLinearStatic'] -SimInfo.solvers['StaticCoupledRBM']['aero_solver'] = 'SHWUvlm' -SimInfo.solvers['StaticCoupledRBM']['aero_solver_settings'] = SimInfo.solvers['SHWUvlm'] - -SimInfo.solvers['StaticCoupledRBM']['tolerance'] = 1e-6 -SimInfo.solvers['StaticCoupledRBM']['n_load_steps'] = 0 -SimInfo.solvers['StaticCoupledRBM']['relaxation_factor'] = 0. - -SimInfo.solvers['SHWUvlm']['convection_scheme'] = 2 -SimInfo.solvers['SHWUvlm']['num_cores'] = 15 -SimInfo.solvers['SHWUvlm']['rot_vel'] = rotation_velocity -SimInfo.solvers['SHWUvlm']['rot_axis'] = np.array([0.,0.,1.]) -SimInfo.solvers['SHWUvlm']['rot_center'] = np.zeros((3),) - -# SimInfo.solvers['StaticCoupledRBM']['newmark_damp'] = 0.1 +struct_static_solver = 'NonLinearStatic' + +SimInfo.solvers[struct_static_solver]['gravity_on'] = False +SimInfo.solvers[struct_static_solver]['max_iterations'] = 100 +SimInfo.solvers[struct_static_solver]['num_load_steps'] = 1 +SimInfo.solvers[struct_static_solver]['min_delta'] = 1e-5 +SimInfo.solvers[struct_static_solver]['newmark_damp'] = 1e-4 +SimInfo.solvers[struct_static_solver]['dt'] = dt + +SimInfo.solvers['StaticUvlm']['horseshoe'] = False +SimInfo.solvers['StaticUvlm']['num_cores'] = 16 +SimInfo.solvers['StaticUvlm']['n_rollup'] = 0 +SimInfo.solvers['StaticUvlm']['rollup_dt'] = dt +SimInfo.solvers['StaticUvlm']['rollup_aic_refresh'] = 1 +SimInfo.solvers['StaticUvlm']['rollup_tolerance'] = 1e-8 +SimInfo.solvers['StaticUvlm']['rbm_vel_g'] = np.array([0., 0., 0., + 0., 0., rotation_velocity]) +SimInfo.solvers['StaticUvlm']['cfl1'] = True +SimInfo.solvers['StaticUvlm']['vortex_radius'] = 1e-6 +SimInfo.solvers['StaticUvlm']['vortex_radius_wake_ind'] = 1e-3 +SimInfo.solvers['StaticUvlm']['velocity_field_generator'] = 'SteadyVelocityField' +SimInfo.solvers['StaticUvlm']['velocity_field_input'] = SimInfo.solvers['SteadyVelocityField'] + +SimInfo.solvers['StaticCoupled']['structural_solver'] = struct_static_solver +SimInfo.solvers['StaticCoupled']['structural_solver_settings'] = SimInfo.solvers[struct_static_solver] +SimInfo.solvers['StaticCoupled']['aero_solver'] = 'StaticUvlm' +SimInfo.solvers['StaticCoupled']['aero_solver_settings'] = SimInfo.solvers['StaticUvlm'] + +SimInfo.solvers['StaticCoupled']['tolerance'] = 1e-6 +SimInfo.solvers['StaticCoupled']['n_load_steps'] = 0 +SimInfo.solvers['StaticCoupled']['relaxation_factor'] = 0. + SimInfo.solvers['StepUvlm']['convection_scheme'] = 2 -SimInfo.solvers['StepUvlm']['num_cores'] = 15 +SimInfo.solvers['StepUvlm']['num_cores'] = 8 +SimInfo.solvers['StepUvlm']['velocity_field_generator'] = 'SteadyVelocityField' +SimInfo.solvers['StepUvlm']['velocity_field_input'] = SimInfo.solvers['SteadyVelocityField'] +SimInfo.solvers['StepUvlm']['cfl1'] = True + +struct_dyn_solver = 'NonLinearDynamicPrescribedStep' + +SimInfo.solvers[struct_dyn_solver]['gravity_on'] = False +SimInfo.solvers[struct_dyn_solver]['max_iterations'] = 300 +SimInfo.solvers[struct_dyn_solver]['min_delta'] = 1e-5 +SimInfo.solvers[struct_dyn_solver]['newmark_damp'] = 1e-4 +SimInfo.solvers[struct_dyn_solver]['dt'] = dt SimInfo.solvers['WriteVariablesTime']['FoR_variables'] = ['total_forces',] SimInfo.solvers['WriteVariablesTime']['FoR_number'] = [0,] -# SimInfo.solvers['DynamicCoupled']['structural_solver'] = 'NonLinearDynamicMultibody' -# SimInfo.solvers['DynamicCoupled']['structural_solver_settings'] = SimInfo.solvers['NonLinearDynamicMultibody'] -SimInfo.solvers['DynamicCoupled']['structural_solver'] = 'RigidDynamicPrescribedStep' -SimInfo.solvers['DynamicCoupled']['structural_solver_settings'] = SimInfo.solvers['RigidDynamicPrescribedStep'] +SimInfo.solvers['DynamicCoupled']['structural_solver'] = struct_dyn_solver +SimInfo.solvers['DynamicCoupled']['structural_solver_settings'] = SimInfo.solvers[struct_dyn_solver] SimInfo.solvers['DynamicCoupled']['aero_solver'] = 'StepUvlm' SimInfo.solvers['DynamicCoupled']['aero_solver_settings'] = SimInfo.solvers['StepUvlm'] SimInfo.solvers['DynamicCoupled']['postprocessors'] = ['BeamPlot', 'AerogridPlot', 'WriteVariablesTime', 'Cleanup'] @@ -123,7 +183,6 @@ 'WriteVariablesTime': SimInfo.solvers['WriteVariablesTime'], 'Cleanup': SimInfo.solvers['Cleanup']} SimInfo.solvers['DynamicCoupled']['minimum_steps'] = 0 - SimInfo.define_num_steps(time_steps) # Define dynamic simulation @@ -142,3 +201,4 @@ rotor.generate_h5_files(SimInfo.solvers['SHARPy']['route'], SimInfo.solvers['SHARPy']['case']) SimInfo.generate_solver_file() SimInfo.generate_dyn_file(time_steps) + diff --git a/sharpy/generators/straightwake.py b/sharpy/generators/straightwake.py index 560c0a934..ef0de7e90 100644 --- a/sharpy/generators/straightwake.py +++ b/sharpy/generators/straightwake.py @@ -80,9 +80,9 @@ def initialise(self, data, in_dict=None): elif 'StaticCoupled' in data.settings: aero_solver_name = data.settings['StaticCoupled']['aero_solver'] aero_solver_settings = data.settings['StaticCoupled']['aero_solver_settings'] - elif 'StaticCoupledRBM' in data.settings: - aero_solver_name = data.settings['StaticCoupledRBM']['aero_solver'] - aero_solver_settings = data.settings['StaticCoupledRBM']['aero_solver_settings'] + elif 'StaticCoupled' in data.settings: + aero_solver_name = data.settings['StaticCoupled']['aero_solver'] + aero_solver_settings = data.settings['StaticCoupled']['aero_solver_settings'] elif 'DynamicCoupled' in data.settings: aero_solver_name = data.settings['DynamicCoupled']['aero_solver'] aero_solver_settings = data.settings['DynamicCoupled']['aero_solver_settings'] diff --git a/sharpy/solvers/staticcoupledrbm.py b/sharpy/solvers/staticcoupledrbm.py deleted file mode 100644 index 28521d9b9..000000000 --- a/sharpy/solvers/staticcoupledrbm.py +++ /dev/null @@ -1,362 +0,0 @@ -import ctypes as ct - -import numpy as np - -import sharpy.aero.utils.mapping as mapping -import sharpy.utils.cout_utils as cout -import sharpy.utils.solver_interface as solver_interface -from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings -import sharpy.utils.algebra as algebra -import sharpy.utils.correct_forces as cf -import sharpy.utils.generator_interface as gen_interface - -@solver -class StaticCoupledRBM(BaseSolver): - """ - Steady coupled solver including rigid body motions - """ - - solver_id = 'StaticCoupledRBM' - solver_classification = 'coupled' - - settings_types = dict() - settings_default = dict() - settings_description = dict() - settings_options = dict() - - settings_types['print_info'] = 'bool' - settings_default['print_info'] = True - settings_description['print_info'] = 'Output run-time information' - - settings_types['structural_solver'] = 'str' - settings_default['structural_solver'] = None - settings_description['structural_solver'] = 'Name of the structural solver used in the computation' - - settings_types['structural_solver_settings'] = 'dict' - settings_default['structural_solver_settings'] = None - settings_description['structural_solver_settings'] = 'Dictionary os settings needed by the structural solver' - - settings_types['aero_solver'] = 'str' - settings_default['aero_solver'] = None - settings_description['aero_solver'] = 'Name of the aerodynamic solver used in the computation' - - settings_types['aero_solver_settings'] = 'dict' - settings_default['aero_solver_settings'] = None - settings_description['aero_solver_settings'] = 'Dictionary os settings needed by the aerodynamic solver' - - settings_types['max_iter'] = 'int' - settings_default['max_iter'] = 100 - settings_description['max_iter'] = 'Maximum numeber of FSI iterations' - - settings_types['n_load_steps'] = 'int' - settings_default['n_load_steps'] = 1 - settings_description['n_load_steps'] = 'Number of steps to ramp up the application of loads' - - settings_types['tolerance'] = 'float' - settings_default['tolerance'] = 1e-5 - settings_description['tolerance'] = 'FSI tolerance' - - settings_types['relaxation_factor'] = 'float' - settings_default['relaxation_factor'] = 0. - settings_description['relaxation_factor'] = 'Relaxation factor' - - settings_types['correct_forces_method'] = 'str' - settings_default['correct_forces_method'] = '' - settings_description['correct_forces_method'] = 'Function used to correct aerodynamic forces. Check :py:mod:`sharpy.utils.correct_forces`' - settings_options['correct_forces_method'] = ['efficiency', 'polars'] - - settings_types['runtime_generators'] = 'dict' - settings_default['runtime_generators'] = dict() - settings_description['runtime_generators'] = 'The dictionary keys are the runtime generators to be used. ' \ - 'The dictionary values are dictionaries with the settings ' \ - 'needed by each generator.' - - settings_table = settings.SettingsTable() - __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options) - - def __init__(self): - - self.data = None - self.settings = None - self.structural_solver = None - self.aero_solver = None - - self.previous_force = None - - self.correct_forces = False - self.correct_forces_function = None - - self.runtime_generators = dict() - self.with_runtime_generators = False - - def initialise(self, data, input_dict=None): - self.data = data - if input_dict is None: - self.settings = data.settings[self.solver_id] - else: - self.settings = input_dict - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default, - options=self.settings_options) - - self.structural_solver = solver_interface.initialise_solver(self.settings['structural_solver']) - self.structural_solver.initialise(self.data, self.settings['structural_solver_settings']) - self.aero_solver = solver_interface.initialise_solver(self.settings['aero_solver']) - self.aero_solver.initialise(self.structural_solver.data, self.settings['aero_solver_settings']) - self.data = self.aero_solver.data - - # load info from dyn dictionary - self.data.structure.add_unsteady_information(self.data.structure.dyn_dict, 1) - - # Define the function to correct aerodynamic forces - if self.settings['correct_forces_method'] is not '': - self.correct_forces = True - self.correct_forces_function = cf.dict_of_corrections[self.settings['correct_forces_method']] - - # initialise runtime generators - self.runtime_generators = dict() - if self.settings['runtime_generators']: - self.with_runtime_generators = True - for id, param in self.settings['runtime_generators'].items(): - gen = gen_interface.generator_from_string(id) - self.runtime_generators[id] = gen() - self.runtime_generators[id].initialise(param, data=self.data) - - def increase_ts(self): - self.data.ts += 1 - self.structural_solver.next_step() - self.aero_solver.next_step() - - def cleanup_timestep_info(self): - if max(len(self.data.aero.timestep_info), len(self.data.structure.timestep_info)) > 1: - # copy last info to first - self.data.aero.timestep_info[0] = self.data.aero.timestep_info[-1].copy() - self.data.structure.timestep_info[0] = self.data.structure.timestep_info[-1].copy() - # delete all the rest - while len(self.data.aero.timestep_info) - 1: - del self.data.aero.timestep_info[-1] - while len(self.data.structure.timestep_info) - 1: - del self.data.structure.timestep_info[-1] - - self.data.ts = 0 - - def run(self): - - # Include the rbm - # print("ts", self.data.ts) - self.data.structure.timestep_info[-1].for_vel = self.data.structure.dynamic_input[0]['for_vel'] - - for i_step in range(self.settings['n_load_steps'].value + 1): - if (i_step == self.settings['n_load_steps'].value and - self.settings['n_load_steps'].value > 0): - break - # load step coefficient - if not self.settings['n_load_steps'].value == 0: - load_step_multiplier = (i_step + 1.0)/self.settings['n_load_steps'].value - else: - load_step_multiplier = 1.0 - - # new storage every load step - if i_step > 0: - self.increase_ts() - - for i_iter in range(self.settings['max_iter'].value): - if self.settings['print_info'].value: - cout.cout_wrap('i_step: %u, i_iter: %u' % (i_step, i_iter)) - - # run aero - self.data = self.aero_solver.run() - - # map force - struct_forces = mapping.aero2struct_force_mapping( - self.data.aero.timestep_info[self.data.ts].forces, - self.data.aero.struct2aero_mapping, - self.data.aero.timestep_info[self.data.ts].zeta, - self.data.structure.timestep_info[self.data.ts].pos, - self.data.structure.timestep_info[self.data.ts].psi, - self.data.structure.node_master_elem, - self.data.structure.connectivities, - self.data.structure.timestep_info[self.data.ts].cag(), - self.data.aero.aero_dict) - - if self.correct_forces: - struct_forces = self.correct_forces_function(self.data, - self.data.aero.timestep_info[self.data.ts], - self.data.structure.timestep_info[self.data.ts], - struct_forces, - rho=self.aero_solver.settings['rho'].value) - - # Add external forces - if self.with_runtime_generators: - self.data.structure.timestep_info[self.data.ts].runtime_generated_forces.fill(0.) - params = dict() - params['data'] = self.data - params['struct_tstep'] = self.data.structure.timestep_info[self.data.ts] - params['aero_tstep'] = self.data.aero.timestep_info[self.data.ts] - for id, runtime_generator in self.runtime_generators.items(): - runtime_generator.generate(params) - - struct_forces += self.data.structure.timestep_info[self.data.ts].runtime_generated_forces - - if not self.settings['relaxation_factor'].value == 0.: - if i_iter == 0: - self.previous_force = struct_forces.copy() - - temp = struct_forces.copy() - struct_forces = ((1.0 - self.settings['relaxation_factor'].value)*struct_forces + - self.settings['relaxation_factor'].value*self.previous_force) - self.previous_force = temp - - # copy force in beam - with_gravity_setting = True - try: - old_g = self.structural_solver.settings['gravity'].value - self.structural_solver.settings['gravity'] = old_g*load_step_multiplier - except KeyError: - with_gravity_setting = False - temp1 = load_step_multiplier*(struct_forces + self.data.structure.ini_info.steady_applied_forces) - self.data.structure.timestep_info[self.data.ts].steady_applied_forces[:] = temp1 - # run beam - prev_quat = self.data.structure.timestep_info[self.data.ts].quat.copy() - self.data = self.structural_solver.run() - # The following line removes the rbm - self.data.structure.timestep_info[self.data.ts].quat = prev_quat.copy() - if with_gravity_setting: - self.structural_solver.settings['gravity'] = ct.c_double(old_g) - - # update grid - self.aero_solver.update_step() - - # print("psi[-1]", self.data.structure.timestep_info[-1].psi[-1,1,:]) - # convergence - if self.convergence(i_iter): - # create q and dqdt vectors - self.structural_solver.update(self.data.structure.timestep_info[self.data.ts]) - self.data = self.aero_solver.run() - self.cleanup_timestep_info() - break - - if self.settings['print_info']: - resultants = self.extract_resultants() - cout.cout_wrap('Resultant forces and moments: ' + str(resultants)) - return self.data - - def convergence(self, i_iter): - if i_iter == self.settings['max_iter'].value - 1: - cout.cout_wrap('StaticCoupled did not converge!', 0) - # quit(-1) - - # Avoid rerunning UVLM if the structural solver is rigid - if "rigid" in self.settings['structural_solver'].lower(): - return True - - if i_iter == 0: - self.initial_pos = self.data.structure.timestep_info[self.data.ts].pos.copy() - self.initial_psi = self.data.structure.timestep_info[self.data.ts].psi.copy() - - self.prev_pos = self.initial_pos.copy() - self.prev_psi = self.initial_psi.copy() - - for i,j in np.ndindex(self.initial_pos.shape): - if np.abs(self.initial_pos[i,j]) < 1.: - self.initial_pos[i,j] = 1. - for i,j,k in np.ndindex(self.initial_psi.shape): - if np.abs(self.initial_psi[i,j,k]) < 1.: - self.initial_psi[i,j,k] = 1. - return False - - res_pos = np.amax(np.abs((self.data.structure.timestep_info[self.data.ts].pos - self.prev_pos)/self.initial_pos)) - res_psi = np.amax(np.abs((self.data.structure.timestep_info[self.data.ts].psi - self.prev_psi)/self.initial_psi)) - res_pos_dot = np.amax(np.abs(self.data.structure.timestep_info[self.data.ts].pos_dot)) - res_psi_dot = np.amax(np.abs(self.data.structure.timestep_info[self.data.ts].psi_dot)) - - self.prev_pos = self.data.structure.timestep_info[self.data.ts].pos.copy() - self.prev_psi = self.data.structure.timestep_info[self.data.ts].psi.copy() - - if self.settings['print_info'].value: - cout.cout_wrap('Pos res = %8e. Psi res = %8e.' % (res_pos, res_psi), 2) - cout.cout_wrap('Pos_dot res = %8e. Psi_dot res = %8e.' % (res_pos_dot, res_psi_dot), 2) - - if res_pos < self.settings['tolerance'].value: - if res_psi < self.settings['tolerance'].value: - if res_pos_dot < self.settings['tolerance'].value: - if res_psi_dot < self.settings['tolerance'].value: - return True - - return False - - # return_value = None - # if i_iter == 0: - # self.initial_residual = np.linalg.norm(self.data.structure.timestep_info[self.data.ts].pos) - # self.previous_residual = self.initial_residual - # self.current_residual = self.initial_residual - # return False - # - # self.current_residual = np.linalg.norm(self.data.structure.timestep_info[self.data.ts].pos) - # if self.settings['print_info'].value: - # cout.cout_wrap('Res = %8e' % (np.abs(self.current_residual - self.previous_residual)/self.previous_residual), 2) - # - # if return_value is None: - # if np.abs(self.current_residual - self.previous_residual)/self.initial_residual < self.settings['tolerance'].value: - # return_value = True - # else: - # self.previous_residual = self.current_residual - # return_value = False - # - # if return_value is None: - # return_value = False - # - # return return_value - - def change_trim(self, alpha, thrust, thrust_nodes, tail_deflection, tail_cs_index): - # self.cleanup_timestep_info() - self.data.structure.timestep_info = [] - self.data.structure.timestep_info.append(self.data.structure.ini_info.copy()) - aero_copy = self.data.aero.timestep_info[-1] - self.data.aero.timestep_info = [] - self.data.aero.timestep_info.append(aero_copy) - self.data.ts = 0 - # alpha - orientation_quat = algebra.euler2quat(np.array([0.0, alpha, 0.0])) - self.data.structure.timestep_info[0].quat[:] = orientation_quat[:] - - try: - self.force_orientation - except AttributeError: - self.force_orientation = np.zeros((len(thrust_nodes), 3)) - for i_node, node in enumerate(thrust_nodes): - self.force_orientation[i_node, :] = ( - algebra.unit_vector(self.data.structure.ini_info.steady_applied_forces[node, 0:3])) - # print(self.force_orientation) - - # thrust - # thrust is scaled so that the direction of the forces is conserved - # in all nodes. - # the `thrust` parameter is the force PER node. - # if there are two or more nodes in thrust_nodes, the total forces - # is n_nodes_in_thrust_nodes*thrust - # thrust forces have to be indicated in structure.ini_info - # print(algebra.unit_vector(self.data.structure.ini_info.steady_applied_forces[0, 0:3])*thrust) - for i_node, node in enumerate(thrust_nodes): - # self.data.structure.ini_info.steady_applied_forces[i_node, 0:3] = ( - # algebra.unit_vector(self.data.structure.ini_info.steady_applied_forces[i_node, 0:3])*thrust) - self.data.structure.ini_info.steady_applied_forces[node, 0:3] = ( - self.force_orientation[i_node, :]*thrust) - self.data.structure.timestep_info[0].steady_applied_forces[node, 0:3] = ( - self.force_orientation[i_node, :]*thrust) - - # tail deflection - try: - self.data.aero.aero_dict['control_surface_deflection'][tail_cs_index] = tail_deflection - except KeyError: - raise Exception('This model has no control surfaces') - except IndexError: - raise Exception('The tail control surface index > number of surfaces') - - # update grid - self.aero_solver.update_step() - - def extract_resultants(self, tstep=None): - return self.structural_solver.extract_resultants(tstep) diff --git a/tests/utils/test_generate_cases.py b/tests/utils/test_generate_cases.py index 285d1fe33..2fa6d8b7f 100644 --- a/tests/utils/test_generate_cases.py +++ b/tests/utils/test_generate_cases.py @@ -94,7 +94,7 @@ def setUp(self): SimInfo.solvers['SHARPy']['flow'] = ['BeamLoader', 'AerogridLoader', - 'StaticCoupledRBM', + 'StaticCoupled', 'DynamicCoupled', 'SaveData'] @@ -122,16 +122,16 @@ def setUp(self): 'dt': dt, 'rotation_velocity': rotation_velocity*np.array([0., 0., 1.])} - SimInfo.solvers['StaticCoupledRBM']['structural_solver'] = 'RigidDynamicPrescribedStep' - SimInfo.solvers['StaticCoupledRBM']['structural_solver_settings'] = SimInfo.solvers['RigidDynamicPrescribedStep'] - # SimInfo.solvers['StaticCoupledRBM']['structural_solver'] = 'NonLinearDynamicPrescribedStep' - # SimInfo.solvers['StaticCoupledRBM']['structural_solver_settings'] = SimInfo.solvers['NonLinearDynamicPrescribedStep'] - SimInfo.solvers['StaticCoupledRBM']['aero_solver'] = 'StaticUvlm' - SimInfo.solvers['StaticCoupledRBM']['aero_solver_settings'] = SimInfo.solvers['StaticUvlm'] + SimInfo.solvers['StaticCoupled']['structural_solver'] = 'RigidDynamicPrescribedStep' + SimInfo.solvers['StaticCoupled']['structural_solver_settings'] = SimInfo.solvers['RigidDynamicPrescribedStep'] + # SimInfo.solvers['StaticCoupled']['structural_solver'] = 'NonLinearDynamicPrescribedStep' + # SimInfo.solvers['StaticCoupled']['structural_solver_settings'] = SimInfo.solvers['NonLinearDynamicPrescribedStep'] + SimInfo.solvers['StaticCoupled']['aero_solver'] = 'StaticUvlm' + SimInfo.solvers['StaticCoupled']['aero_solver_settings'] = SimInfo.solvers['StaticUvlm'] - SimInfo.solvers['StaticCoupledRBM']['tolerance'] = 1e-6 - SimInfo.solvers['StaticCoupledRBM']['n_load_steps'] = 0 - SimInfo.solvers['StaticCoupledRBM']['relaxation_factor'] = 0. + SimInfo.solvers['StaticCoupled']['tolerance'] = 1e-6 + SimInfo.solvers['StaticCoupled']['n_load_steps'] = 0 + SimInfo.solvers['StaticCoupled']['relaxation_factor'] = 0. SimInfo.solvers['StaticUvlm']['horseshoe'] = False SimInfo.solvers['StaticUvlm']['num_cores'] = 8 From 4cbdd81bd0a46f59bcc0efb98c509579508bc328 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 23 Feb 2021 21:11:04 +0000 Subject: [PATCH 008/253] update jupyter wt --- .../example_notebooks/wind_turbine.ipynb | 1345 +++++++++-------- 1 file changed, 681 insertions(+), 664 deletions(-) diff --git a/docs/source/content/example_notebooks/wind_turbine.ipynb b/docs/source/content/example_notebooks/wind_turbine.ipynb index aef0d448d..b7c923958 100644 --- a/docs/source/content/example_notebooks/wind_turbine.ipynb +++ b/docs/source/content/example_notebooks/wind_turbine.ipynb @@ -179,7 +179,6 @@ "name": "stdout", "output_type": "stream", "text": [ - "\u001b[33mrotor_from_excel_type02 is obsolete! rotor_from_excel_type03 instead!\u001b[0m\n", "\u001b[33mWARNING: The poisson cofficient is assumed equal to 0.3\u001b[0m\n", "\u001b[33mWARNING: Cross-section area is used as shear area\u001b[0m\n", "\u001b[33mWARNING: Using perpendicular axis theorem to compute the inertia around xB\u001b[0m\n", @@ -189,22 +188,38 @@ } ], "source": [ - "rotor = template_wt.rotor_from_excel_type02(\n", - " chord_panels,\n", - " rotation_velocity,\n", - " pitch_deg,\n", - " excel_file_name= 'source/type02_db_NREL5MW_v01.xlsx',\n", - " excel_sheet_parameters = 'parameters',\n", - " excel_sheet_structural_blade = 'structural_blade',\n", - " excel_sheet_discretization_blade = 'discretization_blade',\n", - " excel_sheet_aero_blade = 'aero_blade',\n", - " excel_sheet_airfoil_info = 'airfoil_info',\n", - " excel_sheet_airfoil_coord = 'airfoil_coord',\n", - " m_distribution = 'uniform',\n", - " n_points_camber = 100,\n", - " tol_remove_points = 1e-8,\n", - " wsp = WSP,\n", - " dt = dt)" + "op_params = {} \n", + "op_params['rotation_velocity'] = rotation_velocity \n", + "op_params['pitch_deg'] = pitch_deg \n", + "op_params['wsp'] = WSP \n", + "op_params['dt'] = dt \n", + " \n", + "geom_params = {} \n", + "geom_params['chord_panels'] = chord_panels \n", + "geom_params['tol_remove_points'] = 1e-8 \n", + "geom_params['n_points_camber'] = 100 \n", + "geom_params['h5_cross_sec_prop'] = None \n", + "geom_params['m_distribution'] = 'uniform' \n", + " \n", + "options = {} \n", + "options['camber_effect_on_twist'] = False \n", + "options['user_defined_m_distribution_type'] = None \n", + "options['include_polars'] = False \n", + "options['separate_blades'] = False \n", + " \n", + "excel_description = {} \n", + "excel_description['excel_file_name'] = 'source/type02_db_NREL5MW_v01.xlsx' \n", + "excel_description['excel_sheet_parameters'] = 'parameters' \n", + "excel_description['excel_sheet_structural_blade'] = 'structural_blade' \n", + "excel_description['excel_sheet_discretization_blade'] = 'discretization_blade' \n", + "excel_description['excel_sheet_aero_blade'] = 'aero_blade' \n", + "excel_description['excel_sheet_airfoil_info'] = 'airfoil_info' \n", + "excel_description['excel_sheet_airfoil_chord'] = 'airfoil_coord' \n", + " \n", + "rotor, hub_nodes = template_wt.rotor_from_excel_type03(op_params, \n", + " geom_params, \n", + " excel_description, \n", + " options) " ] }, { @@ -235,14 +250,14 @@ "if steady_simulation:\n", " SimInfo.solvers['SHARPy']['flow'] = ['BeamLoader',\n", " 'AerogridLoader',\n", - " 'StaticCoupledRBM',\n", + " 'StaticCoupled',\n", " 'BeamPlot',\n", " 'AerogridPlot', \n", " 'SaveData'] \n", "else:\n", " SimInfo.solvers['SHARPy']['flow'] = ['BeamLoader',\n", " 'AerogridLoader',\n", - " 'StaticCoupledRBM',\n", + " 'StaticCoupled',\n", " 'DynamicCoupled']\n", " \n", "SimInfo.solvers['SHARPy']['case'] = case\n", @@ -269,14 +284,14 @@ " 'r': 1.,\n", " 'dphimax': 10*deg2rad}\n", " \n", - "SimInfo.solvers['StaticCoupledRBM']['structural_solver'] = 'RigidDynamicPrescribedStep'\n", - "SimInfo.solvers['StaticCoupledRBM']['structural_solver_settings'] = SimInfo.solvers['RigidDynamicPrescribedStep']\n", - "SimInfo.solvers['StaticCoupledRBM']['aero_solver'] = 'StaticUvlm'\n", - "SimInfo.solvers['StaticCoupledRBM']['aero_solver_settings'] = SimInfo.solvers['StaticUvlm']\n", + "SimInfo.solvers['StaticCoupled']['structural_solver'] = 'RigidDynamicPrescribedStep'\n", + "SimInfo.solvers['StaticCoupled']['structural_solver_settings'] = SimInfo.solvers['RigidDynamicPrescribedStep']\n", + "SimInfo.solvers['StaticCoupled']['aero_solver'] = 'StaticUvlm'\n", + "SimInfo.solvers['StaticCoupled']['aero_solver_settings'] = SimInfo.solvers['StaticUvlm']\n", "\n", - "SimInfo.solvers['StaticCoupledRBM']['tolerance'] = 1e-8\n", - "SimInfo.solvers['StaticCoupledRBM']['n_load_steps'] = 0\n", - "SimInfo.solvers['StaticCoupledRBM']['relaxation_factor'] = 0.\n", + "SimInfo.solvers['StaticCoupled']['tolerance'] = 1e-8\n", + "SimInfo.solvers['StaticCoupled']['n_load_steps'] = 0\n", + "SimInfo.solvers['StaticCoupled']['relaxation_factor'] = 0.\n", "\n", "SimInfo.solvers['StaticUvlm']['num_cores'] = 8\n", "SimInfo.solvers['StaticUvlm']['velocity_field_generator'] = 'SteadyVelocityField'\n", @@ -366,8 +381,8 @@ " License available at /~https://github.com/imperialcollegelondon/sharpy\u001b[0m\n", "\u001b[36mRunning SHARPy from /home/arturo/code/sharpy/docs/source/content/example_notebooks\u001b[0m\n", "\u001b[36mSHARPy being run is in /home/arturo/code/sharpy\u001b[0m\n", - "\u001b[36mThe branch being run is dev_minor_fixes_v1.2\u001b[0m\n", - "\u001b[36mThe version and commit hash are: v1.2-4-g59db8ef7-59db8ef7\u001b[0m\n", + "\u001b[36mThe branch being run is dev_blade_pitch\u001b[0m\n", + "\u001b[36mThe version and commit hash are: v1.2-240-g308515ad-308515ad\u001b[0m\n", "\u001b[36mThe available solvers on this session are:\u001b[0m\n", "\u001b[36m_BaseStructural \u001b[0m\n", "\u001b[36mAerogridLoader \u001b[0m\n", @@ -384,14 +399,18 @@ "\u001b[36mNonLinearDynamicPrescribedStep \u001b[0m\n", "\u001b[36mNonLinearStatic \u001b[0m\n", "\u001b[36mNonLinearStaticMultibody \u001b[0m\n", + "\u001b[36mNoStructural \u001b[0m\n", "\u001b[36mPrescribedUvlm \u001b[0m\n", + "\u001b[36mRigidDynamicCoupledStep \u001b[0m\n", "\u001b[36mRigidDynamicPrescribedStep \u001b[0m\n", "\u001b[36mStaticCoupled \u001b[0m\n", - "\u001b[36mStaticCoupledRBM \u001b[0m\n", "\u001b[36mStaticTrim \u001b[0m\n", "\u001b[36mStaticUvlm \u001b[0m\n", "\u001b[36mStepLinearUVLM \u001b[0m\n", "\u001b[36mStepUvlm \u001b[0m\n", + "\u001b[36m_BaseTimeIntegrator \u001b[0m\n", + "\u001b[36mNewmarkBeta \u001b[0m\n", + "\u001b[36mGeneralisedAlpha \u001b[0m\n", "\u001b[36mTrim \u001b[0m\n", "\u001b[36mFrequencyResponse \u001b[0m\n", "\u001b[36mWriteVariablesTime \u001b[0m\n", @@ -403,13 +422,13 @@ "\u001b[36mAsymptoticStability \u001b[0m\n", "\u001b[36mUDPout \u001b[0m\n", "\u001b[36mPickleData \u001b[0m\n", + "\u001b[36mPreSharpy \u001b[0m\n", "\u001b[36mSaveData \u001b[0m\n", "\u001b[36mSaveParametricCase \u001b[0m\n", "\u001b[36mStallCheck \u001b[0m\n", "\u001b[36mBeamLoads \u001b[0m\n", "\u001b[36mPlotFlowField \u001b[0m\n", "\u001b[36mAerogridPlot \u001b[0m\n", - "\u001b[36mPreSharpy \u001b[0m\n", "\u001b[36mGenerating an instance of BeamLoader\u001b[0m\n", "\u001b[36mGenerating an instance of AerogridLoader\u001b[0m\n", "Variable shear_direction has no assigned value in the settings file.\u001b[0m\n", @@ -430,11 +449,17 @@ " In total: 1152 bound panels\u001b[0m\n", " In total: 64800 wake panels\u001b[0m\n", " Total number of panels = 65952\u001b[0m\n", - "\u001b[36mGenerating an instance of StaticCoupledRBM\u001b[0m\n", + "\u001b[36mGenerating an instance of StaticCoupled\u001b[0m\n", "\u001b[36mGenerating an instance of RigidDynamicPrescribedStep\u001b[0m\n", "\u001b[36mGenerating an instance of StaticUvlm\u001b[0m\n", - "i_step: 0, i_iter: 0\u001b[0m\n", - "Resultant forces and moments: (array([-1.90055971e-10, 3.63968411e-10, 6.87246081e+04]), array([-3.93376922e-08, 2.77476602e-08, 6.11460556e+06]))\u001b[0m\n", + "\u001b[0m\n", + "\u001b[0m\n", + "\u001b[0m\n", + "|=====|=====|============|==========|==========|==========|==========|==========|==========|\u001b[0m\n", + "|iter |step | log10(res) | Fx | Fy | Fz | Mx | My | Mz |\u001b[0m\n", + "|=====|=====|============|==========|==========|==========|==========|==========|==========|\u001b[0m\n", + "| 0 | 0 | 0.00000 | -0.0000 | 0.0000 |58835.1377| -0.0000 | 0.0000 |6121580.8013|\u001b[0m\n", + "| 1 | 0 | -inf | -0.0000 | 0.0000 |58835.1377| -0.0000 | 0.0000 |6121580.8013|\u001b[0m\n", "\u001b[36mGenerating an instance of DynamicCoupled\u001b[0m\n", "\u001b[36mGenerating an instance of RigidDynamicPrescribedStep\u001b[0m\n", "\u001b[36mGenerating an instance of StepUvlm\u001b[0m\n", @@ -442,509 +467,501 @@ "\u001b[36mGenerating an instance of AerogridPlot\u001b[0m\n", "\u001b[36mGenerating an instance of Cleanup\u001b[0m\n", "\u001b[36mGenerating an instance of SaveData\u001b[0m\n", - "Variable save_linear has no assigned value in the settings file.\u001b[0m\n", - "\u001b[34m will default to the value: c_bool(False)\u001b[0m\n", - "Variable save_linear_uvlm has no assigned value in the settings file.\u001b[0m\n", - "\u001b[34m will default to the value: c_bool(False)\u001b[0m\n", - "Variable skip_attr has no assigned value in the settings file.\u001b[0m\n", - "\u001b[34m will default to the value: ['fortran', 'airfoils', 'airfoil_db', 'settings_types', 'ct_dynamic_forces_list', 'ct_gamma_dot_list', 'ct_gamma_list', 'ct_gamma_star_list', 'ct_normals_list', 'ct_u_ext_list', 'ct_u_ext_star_list', 'ct_zeta_dot_list', 'ct_zeta_list', 'ct_zeta_star_list', 'dynamic_input', ['fortran', 'airfoils', 'airfoil_db', 'settings_types', 'ct_dynamic_forces_list', 'ct_forces_list', 'ct_gamma_dot_list', 'ct_gamma_list', 'ct_gamma_star_list', 'ct_normals_list', 'ct_u_ext_list', 'ct_u_ext_star_list', 'ct_zeta_dot_list', 'ct_zeta_list', 'ct_zeta_star_list', 'dynamic_input']]\u001b[0m\n", - "Variable format has no assigned value in the settings file.\u001b[0m\n", - "\u001b[34m will default to the value: h5\u001b[0m\n", "\u001b[0m\n", "\u001b[0m\n", "\u001b[0m\n", "|=======|========|======|==============|==============|==============|==============|==============|\u001b[0m\n", "| ts | t | iter | struc ratio | iter time | residual vel | FoR_vel(x) | FoR_vel(z) |\u001b[0m\n", "|=======|========|======|==============|==============|==============|==============|==============|\u001b[0m\n", - "| 1 | 0.0551 | 1 | 0.000357 | 40.488192 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 2 | 0.1102 | 1 | 0.000354 | 39.338936 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 3 | 0.1653 | 1 | 0.000379 | 37.049113 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 4 | 0.2204 | 1 | 0.000359 | 38.520681 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 5 | 0.2755 | 1 | 0.000339 | 40.461803 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 6 | 0.3306 | 1 | 0.000384 | 36.008442 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 7 | 0.3857 | 1 | 0.000386 | 36.160005 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 8 | 0.4408 | 1 | 0.000384 | 36.330230 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 9 | 0.4959 | 1 | 0.000382 | 36.444612 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 10 | 0.5510 | 1 | 0.000382 | 36.361346 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 11 | 0.6061 | 1 | 0.000331 | 42.494632 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 12 | 0.6612 | 1 | 0.000388 | 35.835702 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 13 | 0.7163 | 1 | 0.000382 | 36.318603 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 14 | 0.7713 | 1 | 0.000379 | 36.528724 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 15 | 0.8264 | 1 | 0.000385 | 35.707857 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 16 | 0.8815 | 1 | 0.000391 | 35.811018 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 17 | 0.9366 | 1 | 0.000381 | 36.171373 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 18 | 0.9917 | 1 | 0.000388 | 36.011277 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 19 | 1.0468 | 1 | 0.000388 | 35.550915 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 20 | 1.1019 | 1 | 0.000378 | 36.141212 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 21 | 1.1570 | 1 | 0.000390 | 35.668463 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 22 | 1.2121 | 1 | 0.000389 | 35.923531 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 23 | 1.2672 | 1 | 0.000379 | 35.988187 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 24 | 1.3223 | 1 | 0.000391 | 35.571374 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 25 | 1.3774 | 1 | 0.000388 | 35.639834 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 26 | 1.4325 | 1 | 0.000386 | 36.500306 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 27 | 1.4876 | 1 | 0.000382 | 35.931512 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 28 | 1.5427 | 1 | 0.000387 | 35.814282 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 29 | 1.5978 | 1 | 0.000385 | 36.070211 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 30 | 1.6529 | 1 | 0.000378 | 36.540373 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" + "| 1 | 0.0551 | 1 | 0.000892 | 32.003247 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 2 | 0.1102 | 1 | 0.000829 | 34.424959 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 3 | 0.1653 | 1 | 0.000897 | 31.674002 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 4 | 0.2204 | 1 | 0.000917 | 30.999806 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 5 | 0.2755 | 1 | 0.000910 | 31.273636 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 6 | 0.3306 | 1 | 0.000907 | 31.360496 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 7 | 0.3857 | 1 | 0.000927 | 30.898685 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 8 | 0.4408 | 1 | 0.000922 | 31.080507 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 9 | 0.4959 | 1 | 0.000917 | 31.008975 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 10 | 0.5510 | 1 | 0.000913 | 31.051142 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 11 | 0.6061 | 1 | 0.000916 | 30.973677 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 12 | 0.6612 | 1 | 0.000922 | 30.960834 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 13 | 0.7163 | 1 | 0.000897 | 31.733305 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 14 | 0.7713 | 1 | 0.000917 | 30.951755 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 15 | 0.8264 | 1 | 0.000918 | 30.906685 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 16 | 0.8815 | 1 | 0.000896 | 32.725117 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 17 | 0.9366 | 1 | 0.000824 | 34.665609 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 18 | 0.9917 | 1 | 0.000887 | 32.271645 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 19 | 1.0468 | 1 | 0.000892 | 32.066907 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 20 | 1.1019 | 1 | 0.000891 | 32.330094 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 21 | 1.1570 | 1 | 0.000900 | 31.906545 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 22 | 1.2121 | 1 | 0.000904 | 31.585152 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 23 | 1.2672 | 1 | 0.000923 | 32.065384 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 24 | 1.3223 | 1 | 0.000900 | 31.655170 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 25 | 1.3774 | 1 | 0.000872 | 32.705481 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 26 | 1.4325 | 1 | 0.000866 | 32.846920 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 27 | 1.4876 | 1 | 0.000905 | 31.668165 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 28 | 1.5427 | 1 | 0.000883 | 32.061146 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 29 | 1.5978 | 1 | 0.000887 | 32.765074 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 30 | 1.6529 | 1 | 0.000861 | 33.212694 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 31 | 1.7080 | 1 | 0.000878 | 32.706162 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 32 | 1.7631 | 1 | 0.000808 | 35.254301 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 33 | 1.8182 | 1 | 0.000914 | 31.894184 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 34 | 1.8733 | 1 | 0.000897 | 31.895611 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 35 | 1.9284 | 1 | 0.000900 | 31.743104 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ - "| 31 | 1.7080 | 1 | 0.000377 | 36.473098 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 32 | 1.7631 | 1 | 0.000386 | 35.843986 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 33 | 1.8182 | 1 | 0.000387 | 35.850814 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 34 | 1.8733 | 1 | 0.000399 | 35.627213 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 35 | 1.9284 | 1 | 0.000386 | 35.592384 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 36 | 1.9835 | 1 | 0.000402 | 35.870112 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 37 | 2.0386 | 1 | 0.000383 | 36.312248 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 38 | 2.0937 | 1 | 0.000387 | 36.062439 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 39 | 2.1488 | 1 | 0.000388 | 35.772526 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 40 | 2.2039 | 1 | 0.000384 | 35.826909 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 41 | 2.2590 | 1 | 0.000389 | 35.516679 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 42 | 2.3140 | 1 | 0.000385 | 35.530276 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 43 | 2.3691 | 1 | 0.000369 | 37.477879 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 44 | 2.4242 | 1 | 0.000381 | 35.945669 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 45 | 2.4793 | 1 | 0.000388 | 35.521011 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 46 | 2.5344 | 1 | 0.000393 | 35.711026 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 47 | 2.5895 | 1 | 0.000387 | 35.473274 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 48 | 2.6446 | 1 | 0.000391 | 35.504850 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 49 | 2.6997 | 1 | 0.000382 | 36.244426 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 50 | 2.7548 | 1 | 0.000385 | 36.081752 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 51 | 2.8099 | 1 | 0.000388 | 35.793996 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 52 | 2.8650 | 1 | 0.000386 | 35.664569 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 53 | 2.9201 | 1 | 0.000389 | 35.633045 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 54 | 2.9752 | 1 | 0.000380 | 36.212780 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 55 | 3.0303 | 1 | 0.000388 | 35.589546 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 56 | 3.0854 | 1 | 0.000381 | 35.784243 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 57 | 3.1405 | 1 | 0.000381 | 35.947786 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 58 | 3.1956 | 1 | 0.000389 | 35.587564 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 59 | 3.2507 | 1 | 0.000385 | 35.719752 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 60 | 3.3058 | 1 | 0.000384 | 36.233398 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 61 | 3.3609 | 1 | 0.000383 | 35.731236 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 62 | 3.4160 | 1 | 0.000386 | 35.747795 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 63 | 3.4711 | 1 | 0.000387 | 35.460856 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 64 | 3.5262 | 1 | 0.000387 | 35.515425 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 65 | 3.5813 | 1 | 0.000390 | 35.522385 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 66 | 3.6364 | 1 | 0.000389 | 35.582639 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 67 | 3.6915 | 1 | 0.000385 | 35.614268 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 68 | 3.7466 | 1 | 0.000388 | 35.597461 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 69 | 3.8017 | 1 | 0.000383 | 35.830363 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 70 | 3.8567 | 1 | 0.000386 | 35.710349 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 71 | 3.9118 | 1 | 0.000379 | 36.670369 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 72 | 3.9669 | 1 | 0.000350 | 39.563633 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 73 | 4.0220 | 1 | 0.000320 | 43.024997 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 74 | 4.0771 | 1 | 0.000343 | 41.449370 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 75 | 4.1322 | 1 | 0.000333 | 42.165985 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 76 | 4.1873 | 1 | 0.000324 | 42.408628 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 77 | 4.2424 | 1 | 0.000347 | 41.199170 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 78 | 4.2975 | 1 | 0.000341 | 40.640078 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 79 | 4.3526 | 1 | 0.000368 | 38.140525 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 80 | 4.4077 | 1 | 0.000387 | 38.046563 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 81 | 4.4628 | 1 | 0.000348 | 40.257442 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 82 | 4.5179 | 1 | 0.000391 | 37.356549 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 83 | 4.5730 | 1 | 0.000384 | 35.736403 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 84 | 4.6281 | 1 | 0.000383 | 35.668711 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 85 | 4.6832 | 1 | 0.000390 | 35.577590 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 86 | 4.7383 | 1 | 0.000388 | 35.617214 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 87 | 4.7934 | 1 | 0.000386 | 35.811345 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 88 | 4.8485 | 1 | 0.000387 | 35.559163 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 89 | 4.9036 | 1 | 0.000385 | 35.592978 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 90 | 4.9587 | 1 | 0.000386 | 36.103376 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 91 | 5.0138 | 1 | 0.000383 | 35.788276 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 92 | 5.0689 | 1 | 0.000380 | 36.142021 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 93 | 5.1240 | 1 | 0.000391 | 35.667435 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 94 | 5.1791 | 1 | 0.000392 | 35.683454 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 95 | 5.2342 | 1 | 0.000360 | 38.830787 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 96 | 5.2893 | 1 | 0.000365 | 39.488803 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 97 | 5.3444 | 1 | 0.000374 | 38.630671 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 98 | 5.3994 | 1 | 0.000388 | 36.099641 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 99 | 5.4545 | 1 | 0.000393 | 35.490358 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 100 | 5.5096 | 1 | 0.000391 | 35.796994 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 101 | 5.5647 | 1 | 0.000389 | 35.562579 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 102 | 5.6198 | 1 | 0.000384 | 35.580445 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 103 | 5.6749 | 1 | 0.000378 | 36.491877 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 104 | 5.7300 | 1 | 0.000384 | 35.621075 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 105 | 5.7851 | 1 | 0.000384 | 36.057451 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 106 | 5.8402 | 1 | 0.000379 | 36.225240 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 107 | 5.8953 | 1 | 0.000378 | 36.244058 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 108 | 5.9504 | 1 | 0.000349 | 39.388410 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 109 | 6.0055 | 1 | 0.000332 | 41.948640 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" + "| 36 | 1.9835 | 1 | 0.000907 | 31.382207 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 37 | 2.0386 | 1 | 0.000889 | 31.995525 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 38 | 2.0937 | 1 | 0.000896 | 31.669265 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 39 | 2.1488 | 1 | 0.000892 | 32.021120 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 40 | 2.2039 | 1 | 0.000895 | 32.341717 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 41 | 2.2590 | 1 | 0.000909 | 31.194986 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 42 | 2.3140 | 1 | 0.000913 | 31.075842 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 43 | 2.3691 | 1 | 0.000905 | 31.220793 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 44 | 2.4242 | 1 | 0.000865 | 32.660052 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 45 | 2.4793 | 1 | 0.000913 | 31.252726 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 46 | 2.5344 | 1 | 0.000717 | 39.589737 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 47 | 2.5895 | 1 | 0.000689 | 43.339545 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 48 | 2.6446 | 1 | 0.000654 | 43.501825 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 49 | 2.6997 | 1 | 0.000888 | 32.114099 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 50 | 2.7548 | 1 | 0.000894 | 31.591624 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 51 | 2.8099 | 1 | 0.000911 | 31.120782 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 52 | 2.8650 | 1 | 0.000918 | 31.005261 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 53 | 2.9201 | 1 | 0.000923 | 30.937075 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 54 | 2.9752 | 1 | 0.000920 | 31.006048 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 55 | 3.0303 | 1 | 0.000926 | 30.934778 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 56 | 3.0854 | 1 | 0.000910 | 31.056369 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 57 | 3.1405 | 1 | 0.000933 | 31.085487 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 58 | 3.1956 | 1 | 0.000925 | 30.989723 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 59 | 3.2507 | 1 | 0.000932 | 30.994836 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 60 | 3.3058 | 1 | 0.000916 | 31.033034 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 61 | 3.3609 | 1 | 0.000918 | 30.934751 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 62 | 3.4160 | 1 | 0.000928 | 30.999680 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 63 | 3.4711 | 1 | 0.000911 | 30.978938 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 64 | 3.5262 | 1 | 0.000926 | 30.976717 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 65 | 3.5813 | 1 | 0.000907 | 31.276748 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 66 | 3.6364 | 1 | 0.000911 | 31.264278 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 67 | 3.6915 | 1 | 0.000915 | 31.093838 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 68 | 3.7466 | 1 | 0.000924 | 31.082399 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 69 | 3.8017 | 1 | 0.000919 | 30.964752 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 70 | 3.8567 | 1 | 0.000863 | 33.050274 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 71 | 3.9118 | 1 | 0.000915 | 31.032668 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 72 | 3.9669 | 1 | 0.000912 | 30.922833 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 73 | 4.0220 | 1 | 0.000918 | 30.893852 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 74 | 4.0771 | 1 | 0.000971 | 31.148592 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 75 | 4.1322 | 1 | 0.000920 | 30.974765 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 76 | 4.1873 | 1 | 0.000904 | 31.115302 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 77 | 4.2424 | 1 | 0.000919 | 31.070263 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 78 | 4.2975 | 1 | 0.000932 | 30.954521 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 79 | 4.3526 | 1 | 0.000902 | 31.636753 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 80 | 4.4077 | 1 | 0.000887 | 32.539172 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 81 | 4.4628 | 1 | 0.000820 | 34.997592 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 82 | 4.5179 | 1 | 0.000650 | 45.337859 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 83 | 4.5730 | 1 | 0.000657 | 43.207602 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 84 | 4.6281 | 1 | 0.000898 | 31.524481 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 85 | 4.6832 | 1 | 0.000921 | 31.117602 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 86 | 4.7383 | 1 | 0.000832 | 34.343085 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 87 | 4.7934 | 1 | 0.000624 | 46.383277 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 88 | 4.8485 | 1 | 0.000673 | 43.034549 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 89 | 4.9036 | 1 | 0.000809 | 35.412812 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 90 | 4.9587 | 1 | 0.000972 | 31.025067 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 91 | 5.0138 | 1 | 0.000917 | 31.065905 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 92 | 5.0689 | 1 | 0.000910 | 31.646625 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 93 | 5.1240 | 1 | 0.000684 | 41.495273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 94 | 5.1791 | 1 | 0.000672 | 42.896018 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 95 | 5.2342 | 1 | 0.000721 | 39.449060 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 96 | 5.2893 | 1 | 0.000914 | 31.205017 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 97 | 5.3444 | 1 | 0.000920 | 30.984492 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 98 | 5.3994 | 1 | 0.000924 | 30.922404 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 99 | 5.4545 | 1 | 0.000912 | 30.943627 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 100 | 5.5096 | 1 | 0.000909 | 31.230726 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 101 | 5.5647 | 1 | 0.000908 | 31.102787 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 102 | 5.6198 | 1 | 0.000917 | 31.079339 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 103 | 5.6749 | 1 | 0.000917 | 31.224959 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 104 | 5.7300 | 1 | 0.000918 | 30.897047 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 105 | 5.7851 | 1 | 0.000919 | 30.946830 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 106 | 5.8402 | 1 | 0.000929 | 31.049852 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 107 | 5.8953 | 1 | 0.000957 | 30.911006 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 108 | 5.9504 | 1 | 0.000936 | 31.019474 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 109 | 6.0055 | 1 | 0.000917 | 31.004980 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 110 | 6.0606 | 1 | 0.000924 | 31.007143 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 111 | 6.1157 | 1 | 0.000912 | 31.071975 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 112 | 6.1708 | 1 | 0.000912 | 30.917326 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 113 | 6.2259 | 1 | 0.000915 | 30.961683 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 114 | 6.2810 | 1 | 0.000909 | 31.010302 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ - "| 110 | 6.0606 | 1 | 0.000355 | 38.839836 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 111 | 6.1157 | 1 | 0.000355 | 38.759202 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 112 | 6.1708 | 1 | 0.000386 | 35.600075 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 113 | 6.2259 | 1 | 0.000385 | 35.839082 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 114 | 6.2810 | 1 | 0.000380 | 36.186849 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 115 | 6.3361 | 1 | 0.000377 | 36.621883 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 116 | 6.3912 | 1 | 0.000379 | 36.275201 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 117 | 6.4463 | 1 | 0.000378 | 35.842331 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 118 | 6.5014 | 1 | 0.000387 | 35.500655 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 119 | 6.5565 | 1 | 0.000385 | 36.050353 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 120 | 6.6116 | 1 | 0.000389 | 35.547445 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 121 | 6.6667 | 1 | 0.000383 | 36.142716 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 122 | 6.7218 | 1 | 0.000373 | 36.931774 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 123 | 6.7769 | 1 | 0.000387 | 35.598713 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 124 | 6.8320 | 1 | 0.000387 | 35.657159 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 125 | 6.8871 | 1 | 0.000382 | 36.247044 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 126 | 6.9421 | 1 | 0.000384 | 36.012199 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 127 | 6.9972 | 1 | 0.000349 | 39.318324 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 128 | 7.0523 | 1 | 0.000323 | 42.077667 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 129 | 7.1074 | 1 | 0.000356 | 38.948464 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 130 | 7.1625 | 1 | 0.000373 | 36.818358 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 131 | 7.2176 | 1 | 0.000389 | 35.572695 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 132 | 7.2727 | 1 | 0.000381 | 35.734033 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 133 | 7.3278 | 1 | 0.000328 | 41.861129 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 134 | 7.3829 | 1 | 0.000384 | 35.741543 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 135 | 7.4380 | 1 | 0.000382 | 36.004194 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 136 | 7.4931 | 1 | 0.000374 | 36.753781 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 137 | 7.5482 | 1 | 0.000382 | 36.184311 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 138 | 7.6033 | 1 | 0.000380 | 36.016616 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 139 | 7.6584 | 1 | 0.000385 | 35.684941 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 140 | 7.7135 | 1 | 0.000381 | 36.057082 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 141 | 7.7686 | 1 | 0.000375 | 36.661641 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 142 | 7.8237 | 1 | 0.000392 | 35.471661 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 143 | 7.8788 | 1 | 0.000383 | 35.831519 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 144 | 7.9339 | 1 | 0.000381 | 36.024105 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 145 | 7.9890 | 1 | 0.000382 | 36.058372 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 146 | 8.0441 | 1 | 0.000380 | 36.179709 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 147 | 8.0992 | 1 | 0.000383 | 35.549545 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 148 | 8.1543 | 1 | 0.000386 | 35.754811 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 149 | 8.2094 | 1 | 0.000383 | 35.818427 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 150 | 8.2645 | 1 | 0.000382 | 36.092540 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 151 | 8.3196 | 1 | 0.000385 | 35.985869 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 152 | 8.3747 | 1 | 0.000388 | 35.769897 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 153 | 8.4298 | 1 | 0.000380 | 36.107692 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 154 | 8.4848 | 1 | 0.000375 | 36.822373 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 155 | 8.5399 | 1 | 0.000383 | 35.925939 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 156 | 8.5950 | 1 | 0.000383 | 35.689360 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 157 | 8.6501 | 1 | 0.000387 | 35.565501 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 158 | 8.7052 | 1 | 0.000386 | 36.075303 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 159 | 8.7603 | 1 | 0.000387 | 35.582501 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 160 | 8.8154 | 1 | 0.000375 | 36.749945 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 161 | 8.8705 | 1 | 0.000386 | 35.895865 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 162 | 8.9256 | 1 | 0.000383 | 35.577409 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 163 | 8.9807 | 1 | 0.000382 | 36.287305 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 164 | 9.0358 | 1 | 0.000385 | 35.961110 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 165 | 9.0909 | 1 | 0.000388 | 35.679620 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 166 | 9.1460 | 1 | 0.000380 | 35.868955 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 167 | 9.2011 | 1 | 0.000387 | 35.544262 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 168 | 9.2562 | 1 | 0.000384 | 35.553532 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 169 | 9.3113 | 1 | 0.000380 | 36.430609 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 170 | 9.3664 | 1 | 0.000385 | 35.572744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 171 | 9.4215 | 1 | 0.000383 | 36.004555 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 172 | 9.4766 | 1 | 0.000386 | 35.823607 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 173 | 9.5317 | 1 | 0.000386 | 35.621179 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 174 | 9.5868 | 1 | 0.000385 | 35.808610 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 175 | 9.6419 | 1 | 0.000391 | 35.504888 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 176 | 9.6970 | 1 | 0.000387 | 35.928391 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 177 | 9.7521 | 1 | 0.000381 | 35.996520 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 178 | 9.8072 | 1 | 0.000384 | 36.044228 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 179 | 9.8623 | 1 | 0.000389 | 35.651942 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 180 | 9.9174 | 1 | 0.000388 | 35.531221 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 181 | 9.9725 | 1 | 0.000381 | 36.053196 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 182 |10.0275 | 1 | 0.000384 | 35.918099 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 183 |10.0826 | 1 | 0.000388 | 35.594792 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 184 |10.1377 | 1 | 0.000386 | 35.700397 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 185 |10.1928 | 1 | 0.000382 | 35.859218 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 186 |10.2479 | 1 | 0.000385 | 35.736251 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 187 |10.3030 | 1 | 0.000351 | 39.551531 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 188 |10.3581 | 1 | 0.000383 | 35.795977 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" + "| 115 | 6.3361 | 1 | 0.000937 | 31.016248 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 116 | 6.3912 | 1 | 0.000916 | 30.918273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 117 | 6.4463 | 1 | 0.000919 | 31.072337 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 118 | 6.5014 | 1 | 0.000916 | 31.076478 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 119 | 6.5565 | 1 | 0.000915 | 30.992306 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 120 | 6.6116 | 1 | 0.000906 | 31.038977 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 121 | 6.6667 | 1 | 0.000920 | 30.893811 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 122 | 6.7218 | 1 | 0.000918 | 31.017417 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 123 | 6.7769 | 1 | 0.000919 | 30.938301 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 124 | 6.8320 | 1 | 0.000918 | 30.992443 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 125 | 6.8871 | 1 | 0.000927 | 30.876471 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 126 | 6.9421 | 1 | 0.000926 | 31.022833 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 127 | 6.9972 | 1 | 0.000957 | 31.079162 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 128 | 7.0523 | 1 | 0.000930 | 30.912956 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 129 | 7.1074 | 1 | 0.000917 | 30.920774 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 130 | 7.1625 | 1 | 0.000926 | 30.889295 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 131 | 7.2176 | 1 | 0.000928 | 30.952314 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 132 | 7.2727 | 1 | 0.000928 | 30.948958 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 133 | 7.3278 | 1 | 0.000933 | 30.914106 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 134 | 7.3829 | 1 | 0.000946 | 30.961606 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 135 | 7.4380 | 1 | 0.000909 | 31.023403 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 136 | 7.4931 | 1 | 0.000915 | 31.114690 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 137 | 7.5482 | 1 | 0.000934 | 30.938297 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 138 | 7.6033 | 1 | 0.000924 | 30.948950 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 139 | 7.6584 | 1 | 0.000918 | 31.025968 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 140 | 7.7135 | 1 | 0.000915 | 31.038340 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 141 | 7.7686 | 1 | 0.000922 | 30.895676 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 142 | 7.8237 | 1 | 0.000911 | 30.999057 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 143 | 7.8788 | 1 | 0.000908 | 30.910233 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 144 | 7.9339 | 1 | 0.000919 | 31.004791 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 145 | 7.9890 | 1 | 0.000922 | 30.905117 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 146 | 8.0441 | 1 | 0.000930 | 30.995744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 147 | 8.0992 | 1 | 0.000921 | 30.923201 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 148 | 8.1543 | 1 | 0.000917 | 30.989188 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 149 | 8.2094 | 1 | 0.000907 | 31.033752 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 150 | 8.2645 | 1 | 0.000912 | 31.093257 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 151 | 8.3196 | 1 | 0.000919 | 30.918701 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 152 | 8.3747 | 1 | 0.000923 | 30.913795 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 153 | 8.4298 | 1 | 0.000937 | 30.977022 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 154 | 8.4848 | 1 | 0.000916 | 31.022006 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 155 | 8.5399 | 1 | 0.000922 | 30.903273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 156 | 8.5950 | 1 | 0.001047 | 31.571999 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 157 | 8.6501 | 1 | 0.000945 | 30.975473 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 158 | 8.7052 | 1 | 0.000917 | 30.915441 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 159 | 8.7603 | 1 | 0.000913 | 30.937728 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 160 | 8.8154 | 1 | 0.000915 | 30.942585 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 161 | 8.8705 | 1 | 0.000916 | 30.966433 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 162 | 8.9256 | 1 | 0.000913 | 30.941522 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 163 | 8.9807 | 1 | 0.000918 | 30.932131 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 164 | 9.0358 | 1 | 0.000914 | 30.935404 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 165 | 9.0909 | 1 | 0.000907 | 30.975778 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 166 | 9.1460 | 1 | 0.000918 | 30.856382 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 167 | 9.2011 | 1 | 0.000919 | 30.987064 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 168 | 9.2562 | 1 | 0.000924 | 30.910973 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 169 | 9.3113 | 1 | 0.000922 | 30.918958 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 170 | 9.3664 | 1 | 0.000919 | 30.954364 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 171 | 9.4215 | 1 | 0.000886 | 32.110778 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 172 | 9.4766 | 1 | 0.000908 | 31.343746 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 173 | 9.5317 | 1 | 0.000938 | 30.921140 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 174 | 9.5868 | 1 | 0.000947 | 31.042633 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 175 | 9.6419 | 1 | 0.000918 | 30.901971 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 176 | 9.6970 | 1 | 0.000917 | 31.145731 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 177 | 9.7521 | 1 | 0.000875 | 32.249622 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 178 | 9.8072 | 1 | 0.000912 | 30.969236 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 179 | 9.8623 | 1 | 0.000914 | 31.004783 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 180 | 9.9174 | 1 | 0.000937 | 30.933874 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 181 | 9.9725 | 1 | 0.000911 | 31.110613 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 182 |10.0275 | 1 | 0.000939 | 31.085973 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 183 |10.0826 | 1 | 0.000925 | 30.870848 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 184 |10.1377 | 1 | 0.000923 | 30.926473 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 185 |10.1928 | 1 | 0.000916 | 31.146158 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 186 |10.2479 | 1 | 0.000917 | 30.947480 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 187 |10.3030 | 1 | 0.000923 | 30.908379 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 188 |10.3581 | 1 | 0.000954 | 31.005452 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 189 |10.4132 | 1 | 0.000926 | 31.012259 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 190 |10.4683 | 1 | 0.000928 | 30.888091 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 191 |10.5234 | 1 | 0.000922 | 31.017826 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 192 |10.5785 | 1 | 0.000937 | 30.900784 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 193 |10.6336 | 1 | 0.000912 | 31.008140 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ - "| 189 |10.4132 | 1 | 0.000385 | 35.829776 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 190 |10.4683 | 1 | 0.000352 | 38.827525 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 191 |10.5234 | 1 | 0.000387 | 35.562966 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 192 |10.5785 | 1 | 0.000383 | 36.313870 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 193 |10.6336 | 1 | 0.000379 | 36.330277 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 194 |10.6887 | 1 | 0.000384 | 35.712089 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 195 |10.7438 | 1 | 0.000388 | 35.658495 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 196 |10.7989 | 1 | 0.000382 | 35.887891 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 197 |10.8540 | 1 | 0.000387 | 35.722417 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 198 |10.9091 | 1 | 0.000390 | 35.526182 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 199 |10.9642 | 1 | 0.000381 | 36.085630 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 200 |11.0193 | 1 | 0.000385 | 35.969131 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 201 |11.0744 | 1 | 0.000386 | 35.557638 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 202 |11.1295 | 1 | 0.000347 | 39.351766 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 203 |11.1846 | 1 | 0.000388 | 35.709878 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 204 |11.2397 | 1 | 0.000382 | 36.024435 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 205 |11.2948 | 1 | 0.000376 | 36.271692 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 206 |11.3499 | 1 | 0.000369 | 36.718708 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 207 |11.4050 | 1 | 0.000385 | 36.154718 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 208 |11.4601 | 1 | 0.000379 | 36.283367 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 209 |11.5152 | 1 | 0.000381 | 36.108245 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 210 |11.5702 | 1 | 0.000382 | 36.155390 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 211 |11.6253 | 1 | 0.000380 | 36.020020 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 212 |11.6804 | 1 | 0.000380 | 35.944611 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 213 |11.7355 | 1 | 0.000375 | 36.336681 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 214 |11.7906 | 1 | 0.000383 | 36.189386 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 215 |11.8457 | 1 | 0.000375 | 36.877583 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 216 |11.9008 | 1 | 0.000375 | 37.018581 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 217 |11.9559 | 1 | 0.000389 | 35.473751 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 218 |12.0110 | 1 | 0.000389 | 35.532822 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 219 |12.0661 | 1 | 0.000391 | 35.520981 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 220 |12.1212 | 1 | 0.000384 | 35.638531 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 221 |12.1763 | 1 | 0.000383 | 35.598408 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 222 |12.2314 | 1 | 0.000384 | 35.930382 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 223 |12.2865 | 1 | 0.000383 | 36.085939 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 224 |12.3416 | 1 | 0.000381 | 35.987070 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 225 |12.3967 | 1 | 0.000382 | 35.807852 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 226 |12.4518 | 1 | 0.000380 | 35.809904 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 227 |12.5069 | 1 | 0.000385 | 35.647728 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 228 |12.5620 | 1 | 0.000350 | 39.013245 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 229 |12.6171 | 1 | 0.000372 | 36.197728 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 230 |12.6722 | 1 | 0.000385 | 35.554344 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 231 |12.7273 | 1 | 0.000387 | 35.785000 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 232 |12.7824 | 1 | 0.000387 | 35.660144 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 233 |12.8375 | 1 | 0.000389 | 35.589894 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 234 |12.8926 | 1 | 0.000389 | 35.582738 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 235 |12.9477 | 1 | 0.000390 | 35.532291 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 236 |13.0028 | 1 | 0.000383 | 35.841360 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 237 |13.0579 | 1 | 0.000389 | 35.544870 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 238 |13.1129 | 1 | 0.000383 | 35.657454 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 239 |13.1680 | 1 | 0.000382 | 36.289361 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 240 |13.2231 | 1 | 0.000387 | 35.443005 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 241 |13.2782 | 1 | 0.000387 | 35.512198 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 242 |13.3333 | 1 | 0.000400 | 35.603413 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 243 |13.3884 | 1 | 0.000381 | 35.578255 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 244 |13.4435 | 1 | 0.000386 | 35.649547 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 245 |13.4986 | 1 | 0.000389 | 35.596087 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 246 |13.5537 | 1 | 0.000381 | 36.121754 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 247 |13.6088 | 1 | 0.000388 | 35.778132 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 248 |13.6639 | 1 | 0.000390 | 35.574921 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 249 |13.7190 | 1 | 0.000388 | 35.661108 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 250 |13.7741 | 1 | 0.000383 | 36.003308 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 251 |13.8292 | 1 | 0.000369 | 37.023199 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 252 |13.8843 | 1 | 0.000383 | 35.928010 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 253 |13.9394 | 1 | 0.000389 | 35.566548 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 254 |13.9945 | 1 | 0.000387 | 35.764471 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 255 |14.0496 | 1 | 0.000388 | 35.750198 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 256 |14.1047 | 1 | 0.000382 | 36.001819 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 257 |14.1598 | 1 | 0.000392 | 35.804229 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 258 |14.2149 | 1 | 0.000384 | 35.970414 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 259 |14.2700 | 1 | 0.000388 | 35.738937 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 260 |14.3251 | 1 | 0.000385 | 35.981197 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 261 |14.3802 | 1 | 0.000390 | 35.716256 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 262 |14.4353 | 1 | 0.000387 | 35.796356 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 263 |14.4904 | 1 | 0.000386 | 35.634159 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 264 |14.5455 | 1 | 0.000386 | 35.583267 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 265 |14.6006 | 1 | 0.000384 | 35.920408 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 266 |14.6556 | 1 | 0.000384 | 35.868483 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 267 |14.7107 | 1 | 0.000388 | 35.637693 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" + "| 194 |10.6887 | 1 | 0.000924 | 30.905508 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 195 |10.7438 | 1 | 0.000957 | 31.092918 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 196 |10.7989 | 1 | 0.000922 | 30.984259 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 197 |10.8540 | 1 | 0.000912 | 30.918213 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 198 |10.9091 | 1 | 0.000918 | 30.906566 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 199 |10.9642 | 1 | 0.000920 | 30.978359 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 200 |11.0193 | 1 | 0.000921 | 30.990309 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 201 |11.0744 | 1 | 0.000922 | 30.998848 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 202 |11.1295 | 1 | 0.000919 | 30.988585 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 203 |11.1846 | 1 | 0.000967 | 30.932929 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 204 |11.2397 | 1 | 0.000961 | 31.166006 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 205 |11.2948 | 1 | 0.000923 | 30.916330 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 206 |11.3499 | 1 | 0.000918 | 31.015378 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 207 |11.4050 | 1 | 0.000920 | 30.935401 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 208 |11.4601 | 1 | 0.000919 | 30.982654 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 209 |11.5152 | 1 | 0.000897 | 31.874632 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 210 |11.5702 | 1 | 0.000908 | 31.118416 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 211 |11.6253 | 1 | 0.000931 | 31.217766 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 212 |11.6804 | 1 | 0.000903 | 31.346483 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 213 |11.7355 | 1 | 0.000920 | 30.971118 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 214 |11.7906 | 1 | 0.000929 | 31.000595 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 215 |11.8457 | 1 | 0.000915 | 30.969266 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 216 |11.9008 | 1 | 0.000913 | 31.803210 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 217 |11.9559 | 1 | 0.000913 | 31.008861 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 218 |12.0110 | 1 | 0.000912 | 30.917057 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 219 |12.0661 | 1 | 0.000905 | 31.483228 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 220 |12.1212 | 1 | 0.000925 | 30.923689 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 221 |12.1763 | 1 | 0.000916 | 30.942301 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 222 |12.2314 | 1 | 0.000918 | 30.963086 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 223 |12.2865 | 1 | 0.000900 | 31.521071 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 224 |12.3416 | 1 | 0.000925 | 30.931045 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 225 |12.3967 | 1 | 0.000906 | 31.197149 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 226 |12.4518 | 1 | 0.000913 | 31.144852 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 227 |12.5069 | 1 | 0.000895 | 31.983333 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 228 |12.5620 | 1 | 0.000900 | 31.542461 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 229 |12.6171 | 1 | 0.000920 | 31.045717 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 230 |12.6722 | 1 | 0.000897 | 31.491388 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 231 |12.7273 | 1 | 0.000918 | 30.903177 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 232 |12.7824 | 1 | 0.000915 | 31.084838 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 233 |12.8375 | 1 | 0.000920 | 30.906922 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 234 |12.8926 | 1 | 0.000912 | 31.119419 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 235 |12.9477 | 1 | 0.000881 | 31.875403 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 236 |13.0028 | 1 | 0.000889 | 31.890126 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 237 |13.0579 | 1 | 0.000916 | 30.947009 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 238 |13.1129 | 1 | 0.000903 | 31.104523 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 239 |13.1680 | 1 | 0.000908 | 31.200449 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 240 |13.2231 | 1 | 0.000918 | 31.005172 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 241 |13.2782 | 1 | 0.000923 | 31.013511 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 242 |13.3333 | 1 | 0.000917 | 31.053680 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 243 |13.3884 | 1 | 0.000918 | 30.949748 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 244 |13.4435 | 1 | 0.000897 | 31.708627 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 245 |13.4986 | 1 | 0.000896 | 31.703804 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 246 |13.5537 | 1 | 0.000936 | 30.964896 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 247 |13.6088 | 1 | 0.000916 | 31.018459 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 248 |13.6639 | 1 | 0.000906 | 31.030132 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 249 |13.7190 | 1 | 0.000697 | 40.540772 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 250 |13.7741 | 1 | 0.000939 | 30.990541 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 251 |13.8292 | 1 | 0.000930 | 31.189301 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 252 |13.8843 | 1 | 0.000908 | 31.074319 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 253 |13.9394 | 1 | 0.000926 | 30.931407 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 254 |13.9945 | 1 | 0.000908 | 30.975691 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 255 |14.0496 | 1 | 0.000921 | 30.952020 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 256 |14.1047 | 1 | 0.000922 | 30.929284 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 257 |14.1598 | 1 | 0.000924 | 30.884744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 258 |14.2149 | 1 | 0.000910 | 30.982695 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 259 |14.2700 | 1 | 0.000924 | 30.994780 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 260 |14.3251 | 1 | 0.000914 | 31.057176 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 261 |14.3802 | 1 | 0.000924 | 30.977462 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 262 |14.4353 | 1 | 0.000910 | 30.970187 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 263 |14.4904 | 1 | 0.000925 | 30.897495 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 264 |14.5455 | 1 | 0.000919 | 30.917634 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 265 |14.6006 | 1 | 0.000910 | 31.083578 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 266 |14.6556 | 1 | 0.000912 | 31.073436 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 267 |14.7107 | 1 | 0.000904 | 31.496094 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 268 |14.7658 | 1 | 0.000912 | 30.973318 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 269 |14.8209 | 1 | 0.000921 | 31.001805 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 270 |14.8760 | 1 | 0.000921 | 31.058672 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 271 |14.9311 | 1 | 0.000919 | 30.941234 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 272 |14.9862 | 1 | 0.000915 | 31.067117 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ - "| 268 |14.7658 | 1 | 0.000384 | 35.878748 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 269 |14.8209 | 1 | 0.000384 | 35.956619 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 270 |14.8760 | 1 | 0.000388 | 35.757834 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 271 |14.9311 | 1 | 0.000386 | 35.516229 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 272 |14.9862 | 1 | 0.000382 | 35.664562 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 273 |15.0413 | 1 | 0.000388 | 35.536456 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 274 |15.0964 | 1 | 0.000380 | 35.959082 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 275 |15.1515 | 1 | 0.000384 | 35.817666 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 276 |15.2066 | 1 | 0.000388 | 35.632972 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 277 |15.2617 | 1 | 0.000381 | 36.023971 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 278 |15.3168 | 1 | 0.000382 | 36.228877 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 279 |15.3719 | 1 | 0.000391 | 35.522156 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 280 |15.4270 | 1 | 0.000329 | 41.616403 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 281 |15.4821 | 1 | 0.000374 | 36.553234 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 282 |15.5372 | 1 | 0.000380 | 36.292320 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 283 |15.5923 | 1 | 0.000387 | 35.972432 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 284 |15.6474 | 1 | 0.000389 | 35.704273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 285 |15.7025 | 1 | 0.000380 | 36.309011 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 286 |15.7576 | 1 | 0.000386 | 35.549626 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 287 |15.8127 | 1 | 0.000384 | 35.685215 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 288 |15.8678 | 1 | 0.000385 | 35.756432 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 289 |15.9229 | 1 | 0.000387 | 35.418947 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 290 |15.9780 | 1 | 0.000389 | 35.632131 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 291 |16.0331 | 1 | 0.000388 | 35.610906 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 292 |16.0882 | 1 | 0.000389 | 35.543379 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 293 |16.1433 | 1 | 0.000387 | 35.506023 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 294 |16.1983 | 1 | 0.000386 | 35.765901 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 295 |16.2534 | 1 | 0.000389 | 35.724982 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 296 |16.3085 | 1 | 0.000389 | 35.508379 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 297 |16.3636 | 1 | 0.000389 | 35.526813 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 298 |16.4187 | 1 | 0.000390 | 35.638860 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 299 |16.4738 | 1 | 0.000386 | 35.424226 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 300 |16.5289 | 1 | 0.000390 | 35.588059 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 301 |16.5840 | 1 | 0.000381 | 36.367140 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 302 |16.6391 | 1 | 0.000382 | 35.846821 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 303 |16.6942 | 1 | 0.000389 | 35.616853 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 304 |16.7493 | 1 | 0.000390 | 35.519614 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 305 |16.8044 | 1 | 0.000386 | 35.861074 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 306 |16.8595 | 1 | 0.000387 | 35.542549 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 307 |16.9146 | 1 | 0.000392 | 35.596805 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 308 |16.9697 | 1 | 0.000380 | 36.500158 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 309 |17.0248 | 1 | 0.000387 | 35.797396 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 310 |17.0799 | 1 | 0.000391 | 35.509726 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 311 |17.1350 | 1 | 0.000389 | 35.751043 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 312 |17.1901 | 1 | 0.000385 | 35.522428 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 313 |17.2452 | 1 | 0.000386 | 35.637847 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 314 |17.3003 | 1 | 0.000379 | 35.938939 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 315 |17.3554 | 1 | 0.000391 | 35.505755 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 316 |17.4105 | 1 | 0.000384 | 35.749119 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 317 |17.4656 | 1 | 0.000386 | 35.633515 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 318 |17.5207 | 1 | 0.000387 | 35.618267 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 319 |17.5758 | 1 | 0.000391 | 35.736981 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 320 |17.6309 | 1 | 0.000385 | 35.705815 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 321 |17.6860 | 1 | 0.000385 | 35.946867 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 322 |17.7410 | 1 | 0.000386 | 35.627028 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 323 |17.7961 | 1 | 0.000386 | 35.611765 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 324 |17.8512 | 1 | 0.000384 | 35.768071 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 325 |17.9063 | 1 | 0.000389 | 35.613754 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 326 |17.9614 | 1 | 0.000385 | 35.612616 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 327 |18.0165 | 1 | 0.000391 | 35.606615 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 328 |18.0716 | 1 | 0.000382 | 36.004974 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 329 |18.1267 | 1 | 0.000386 | 35.771311 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 330 |18.1818 | 1 | 0.000386 | 35.866339 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 331 |18.2369 | 1 | 0.000386 | 35.648709 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 332 |18.2920 | 1 | 0.000386 | 35.545881 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 333 |18.3471 | 1 | 0.000391 | 35.553222 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 334 |18.4022 | 1 | 0.000386 | 36.050690 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 335 |18.4573 | 1 | 0.000388 | 35.671565 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 336 |18.5124 | 1 | 0.000387 | 35.843625 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 337 |18.5675 | 1 | 0.000390 | 35.922205 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 338 |18.6226 | 1 | 0.000388 | 35.854475 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 339 |18.6777 | 1 | 0.000373 | 36.964895 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 340 |18.7328 | 1 | 0.000374 | 38.166658 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 341 |18.7879 | 1 | 0.000372 | 37.057246 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 342 |18.8430 | 1 | 0.000383 | 36.740177 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 343 |18.8981 | 1 | 0.000361 | 38.441733 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 344 |18.9532 | 1 | 0.000372 | 37.669709 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 345 |19.0083 | 1 | 0.000373 | 37.108291 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 346 |19.0634 | 1 | 0.000407 | 35.527445 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" + "| 273 |15.0413 | 1 | 0.000914 | 30.991765 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 274 |15.0964 | 1 | 0.000910 | 31.124020 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 275 |15.1515 | 1 | 0.000937 | 31.242097 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 276 |15.2066 | 1 | 0.000923 | 30.869329 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 277 |15.2617 | 1 | 0.000913 | 31.004095 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 278 |15.3168 | 1 | 0.000920 | 30.970996 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 279 |15.3719 | 1 | 0.000927 | 30.917484 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 280 |15.4270 | 1 | 0.000911 | 30.892718 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 281 |15.4821 | 1 | 0.000914 | 30.960543 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 282 |15.5372 | 1 | 0.000913 | 30.893237 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 283 |15.5923 | 1 | 0.000921 | 31.036962 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 284 |15.6474 | 1 | 0.000916 | 31.041628 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 285 |15.7025 | 1 | 0.000919 | 30.893108 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 286 |15.7576 | 1 | 0.000922 | 30.907060 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 287 |15.8127 | 1 | 0.000907 | 31.154682 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 288 |15.8678 | 1 | 0.000917 | 31.055366 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 289 |15.9229 | 1 | 0.000908 | 31.073641 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 290 |15.9780 | 1 | 0.000909 | 30.925398 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 291 |16.0331 | 1 | 0.000931 | 30.933038 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 292 |16.0882 | 1 | 0.000932 | 30.883366 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 293 |16.1433 | 1 | 0.000925 | 30.974573 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 294 |16.1983 | 1 | 0.000926 | 30.920426 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 295 |16.2534 | 1 | 0.000909 | 30.992082 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 296 |16.3085 | 1 | 0.000910 | 31.053425 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 297 |16.3636 | 1 | 0.000919 | 30.943481 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 298 |16.4187 | 1 | 0.000920 | 31.073522 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 299 |16.4738 | 1 | 0.000912 | 31.017014 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 300 |16.5289 | 1 | 0.000913 | 30.950815 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 301 |16.5840 | 1 | 0.000919 | 30.873358 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 302 |16.6391 | 1 | 0.000917 | 30.949980 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 303 |16.6942 | 1 | 0.000912 | 31.149671 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 304 |16.7493 | 1 | 0.000683 | 41.283571 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 305 |16.8044 | 1 | 0.000657 | 42.893068 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 306 |16.8595 | 1 | 0.000662 | 43.174875 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 307 |16.9146 | 1 | 0.000881 | 32.450967 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 308 |16.9697 | 1 | 0.000915 | 31.021247 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 309 |17.0248 | 1 | 0.000921 | 30.962266 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 310 |17.0799 | 1 | 0.000920 | 30.990332 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 311 |17.1350 | 1 | 0.000917 | 30.915749 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 312 |17.1901 | 1 | 0.000917 | 30.961650 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 313 |17.2452 | 1 | 0.000903 | 30.992689 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 314 |17.3003 | 1 | 0.000925 | 31.008350 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 315 |17.3554 | 1 | 0.000904 | 31.472609 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 316 |17.4105 | 1 | 0.000909 | 31.018433 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 317 |17.4656 | 1 | 0.000913 | 31.128679 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 318 |17.5207 | 1 | 0.000916 | 31.038997 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 319 |17.5758 | 1 | 0.000909 | 30.992505 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 320 |17.6309 | 1 | 0.000915 | 30.903055 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 321 |17.6860 | 1 | 0.000919 | 31.084218 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 322 |17.7410 | 1 | 0.000908 | 31.119063 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 323 |17.7961 | 1 | 0.000910 | 31.273114 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 324 |17.8512 | 1 | 0.000921 | 30.880844 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 325 |17.9063 | 1 | 0.000910 | 31.029546 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 326 |17.9614 | 1 | 0.000916 | 30.941567 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 327 |18.0165 | 1 | 0.000913 | 31.233166 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 328 |18.0716 | 1 | 0.000929 | 30.970063 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 329 |18.1267 | 1 | 0.000912 | 31.140351 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 330 |18.1818 | 1 | 0.000908 | 31.050875 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 331 |18.2369 | 1 | 0.000909 | 31.189776 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 332 |18.2920 | 1 | 0.000914 | 30.987210 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 333 |18.3471 | 1 | 0.000959 | 31.032436 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 334 |18.4022 | 1 | 0.000915 | 31.036937 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 335 |18.4573 | 1 | 0.000916 | 31.051169 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 336 |18.5124 | 1 | 0.000923 | 30.913584 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 337 |18.5675 | 1 | 0.000924 | 30.979053 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 338 |18.6226 | 1 | 0.000925 | 31.071960 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 339 |18.6777 | 1 | 0.000911 | 31.006622 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 340 |18.7328 | 1 | 0.000902 | 31.566711 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 341 |18.7879 | 1 | 0.000834 | 34.959509 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 342 |18.8430 | 1 | 0.000842 | 34.022732 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 343 |18.8981 | 1 | 0.000891 | 31.951907 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 344 |18.9532 | 1 | 0.000924 | 30.960468 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 345 |19.0083 | 1 | 0.000912 | 30.898630 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 346 |19.0634 | 1 | 0.000914 | 30.985280 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 347 |19.1185 | 1 | 0.000907 | 30.997136 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 348 |19.1736 | 1 | 0.000913 | 30.947927 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 349 |19.2287 | 1 | 0.000922 | 30.926197 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 350 |19.2837 | 1 | 0.000929 | 31.031291 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 351 |19.3388 | 1 | 0.000920 | 31.066194 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ - "| 347 |19.1185 | 1 | 0.000359 | 38.141883 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 348 |19.1736 | 1 | 0.000388 | 35.543387 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 349 |19.2287 | 1 | 0.000384 | 35.859722 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 350 |19.2837 | 1 | 0.000375 | 36.929390 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 351 |19.3388 | 1 | 0.000377 | 36.180960 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 352 |19.3939 | 1 | 0.000364 | 37.933742 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 353 |19.4490 | 1 | 0.000371 | 36.995525 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 354 |19.5041 | 1 | 0.000386 | 35.545846 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 355 |19.5592 | 1 | 0.000388 | 35.628378 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 356 |19.6143 | 1 | 0.000387 | 35.582392 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 357 |19.6694 | 1 | 0.000388 | 35.559669 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 358 |19.7245 | 1 | 0.000387 | 35.656699 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 359 |19.7796 | 1 | 0.000387 | 35.495093 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 360 |19.8347 | 1 | 0.000388 | 35.882711 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 361 |19.8898 | 1 | 0.000373 | 36.684669 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 362 |19.9449 | 1 | 0.000374 | 36.961644 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 363 |20.0000 | 1 | 0.000374 | 36.868427 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 364 |20.0551 | 1 | 0.000387 | 35.622257 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 365 |20.1102 | 1 | 0.000381 | 36.147030 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 366 |20.1653 | 1 | 0.000366 | 37.706172 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 367 |20.2204 | 1 | 0.000386 | 35.734740 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 368 |20.2755 | 1 | 0.000379 | 36.314663 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 369 |20.3306 | 1 | 0.000389 | 35.715487 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 370 |20.3857 | 1 | 0.000373 | 36.823063 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 371 |20.4408 | 1 | 0.000375 | 36.843336 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 372 |20.4959 | 1 | 0.000371 | 37.016015 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 373 |20.5510 | 1 | 0.000384 | 36.872829 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 374 |20.6061 | 1 | 0.000381 | 35.952096 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 375 |20.6612 | 1 | 0.000386 | 35.688584 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 376 |20.7163 | 1 | 0.000370 | 37.488979 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 377 |20.7713 | 1 | 0.000374 | 36.745818 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 378 |20.8264 | 1 | 0.000380 | 36.348014 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 379 |20.8815 | 1 | 0.000357 | 38.004468 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 380 |20.9366 | 1 | 0.000388 | 35.488350 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 381 |20.9917 | 1 | 0.000385 | 35.788104 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 382 |21.0468 | 1 | 0.000378 | 36.528320 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 383 |21.1019 | 1 | 0.000386 | 35.558064 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 384 |21.1570 | 1 | 0.000388 | 35.604617 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 385 |21.2121 | 1 | 0.000386 | 36.004627 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 386 |21.2672 | 1 | 0.000387 | 35.650269 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 387 |21.3223 | 1 | 0.000376 | 36.334532 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 388 |21.3774 | 1 | 0.000385 | 35.575643 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 389 |21.4325 | 1 | 0.000389 | 35.685368 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 390 |21.4876 | 1 | 0.000386 | 36.078773 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 391 |21.5427 | 1 | 0.000382 | 35.660002 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 392 |21.5978 | 1 | 0.000387 | 35.614961 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 393 |21.6529 | 1 | 0.000384 | 35.678329 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 394 |21.7080 | 1 | 0.000387 | 35.669564 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 395 |21.7631 | 1 | 0.000384 | 35.736932 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 396 |21.8182 | 1 | 0.000390 | 35.620417 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 397 |21.8733 | 1 | 0.000390 | 35.622047 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 398 |21.9284 | 1 | 0.000388 | 35.677847 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 399 |21.9835 | 1 | 0.000387 | 35.772093 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 400 |22.0386 | 1 | 0.000390 | 35.534915 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 401 |22.0937 | 1 | 0.000383 | 35.819918 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 402 |22.1488 | 1 | 0.000380 | 36.419453 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 403 |22.2039 | 1 | 0.000388 | 35.593708 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 404 |22.2590 | 1 | 0.000389 | 35.595554 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 405 |22.3140 | 1 | 0.000386 | 35.676154 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 406 |22.3691 | 1 | 0.000388 | 35.602931 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 407 |22.4242 | 1 | 0.000384 | 35.806526 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 408 |22.4793 | 1 | 0.000386 | 35.751935 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 409 |22.5344 | 1 | 0.000388 | 35.694412 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 410 |22.5895 | 1 | 0.000389 | 36.211003 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 411 |22.6446 | 1 | 0.000384 | 35.869718 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 412 |22.6997 | 1 | 0.000389 | 35.704110 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 413 |22.7548 | 1 | 0.000386 | 35.866848 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 414 |22.8099 | 1 | 0.000384 | 35.770937 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 415 |22.8650 | 1 | 0.000381 | 36.103232 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 416 |22.9201 | 1 | 0.000386 | 35.538185 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 417 |22.9752 | 1 | 0.000386 | 35.938821 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 418 |23.0303 | 1 | 0.000382 | 35.772979 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 419 |23.0854 | 1 | 0.000377 | 36.526245 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 420 |23.1405 | 1 | 0.000385 | 35.686211 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 421 |23.1956 | 1 | 0.000386 | 35.631309 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 422 |23.2507 | 1 | 0.000374 | 36.536865 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 423 |23.3058 | 1 | 0.000379 | 35.835702 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 424 |23.3609 | 1 | 0.000388 | 35.650453 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 425 |23.4160 | 1 | 0.000386 | 35.985224 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" + "| 352 |19.3939 | 1 | 0.000915 | 31.021782 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 353 |19.4490 | 1 | 0.000910 | 31.054333 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 354 |19.5041 | 1 | 0.000937 | 31.017431 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 355 |19.5592 | 1 | 0.000914 | 31.036429 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 356 |19.6143 | 1 | 0.000922 | 30.974830 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 357 |19.6694 | 1 | 0.000921 | 30.947570 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 358 |19.7245 | 1 | 0.000913 | 31.119531 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 359 |19.7796 | 1 | 0.000915 | 31.167779 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 360 |19.8347 | 1 | 0.000918 | 31.068536 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 361 |19.8898 | 1 | 0.000911 | 31.031367 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 362 |19.9449 | 1 | 0.000919 | 30.956716 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 363 |20.0000 | 1 | 0.000922 | 30.995727 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 364 |20.0551 | 1 | 0.000914 | 30.973092 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 365 |20.1102 | 1 | 0.000918 | 30.961610 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 366 |20.1653 | 1 | 0.000926 | 30.881730 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 367 |20.2204 | 1 | 0.000908 | 30.987541 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 368 |20.2755 | 1 | 0.000927 | 31.154198 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 369 |20.3306 | 1 | 0.000920 | 30.893291 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 370 |20.3857 | 1 | 0.000925 | 30.981216 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 371 |20.4408 | 1 | 0.000926 | 31.024869 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 372 |20.4959 | 1 | 0.000920 | 31.094704 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 373 |20.5510 | 1 | 0.000924 | 30.931043 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 374 |20.6061 | 1 | 0.000910 | 31.003695 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 375 |20.6612 | 1 | 0.000921 | 30.938825 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 376 |20.7163 | 1 | 0.000913 | 31.182973 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 377 |20.7713 | 1 | 0.000918 | 30.992988 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 378 |20.8264 | 1 | 0.000923 | 30.980134 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 379 |20.8815 | 1 | 0.000918 | 31.031038 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 380 |20.9366 | 1 | 0.000899 | 31.901566 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 381 |20.9917 | 1 | 0.000915 | 31.076764 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 382 |21.0468 | 1 | 0.000911 | 31.072542 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 383 |21.1019 | 1 | 0.000914 | 30.969881 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 384 |21.1570 | 1 | 0.000917 | 30.921061 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 385 |21.2121 | 1 | 0.000939 | 30.948887 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 386 |21.2672 | 1 | 0.000924 | 31.151912 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 387 |21.3223 | 1 | 0.000907 | 31.003044 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 388 |21.3774 | 1 | 0.000915 | 31.097173 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 389 |21.4325 | 1 | 0.000911 | 31.071583 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 390 |21.4876 | 1 | 0.000917 | 30.973833 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 391 |21.5427 | 1 | 0.000917 | 31.150668 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 392 |21.5978 | 1 | 0.000916 | 31.089087 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 393 |21.6529 | 1 | 0.000909 | 31.159542 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 394 |21.7080 | 1 | 0.000915 | 31.040465 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 395 |21.7631 | 1 | 0.000918 | 30.956352 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 396 |21.8182 | 1 | 0.000918 | 30.984192 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 397 |21.8733 | 1 | 0.000919 | 31.130644 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 398 |21.9284 | 1 | 0.000916 | 30.997960 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 399 |21.9835 | 1 | 0.000912 | 31.131888 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 400 |22.0386 | 1 | 0.000949 | 31.186263 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 401 |22.0937 | 1 | 0.000916 | 31.204745 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 402 |22.1488 | 1 | 0.000906 | 31.009868 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 403 |22.2039 | 1 | 0.000912 | 31.036721 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 404 |22.2590 | 1 | 0.000914 | 31.120642 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 405 |22.3140 | 1 | 0.000919 | 30.994664 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 406 |22.3691 | 1 | 0.000919 | 30.961076 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 407 |22.4242 | 1 | 0.000915 | 31.242275 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 408 |22.4793 | 1 | 0.000901 | 31.363461 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 409 |22.5344 | 1 | 0.000910 | 31.323509 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 410 |22.5895 | 1 | 0.000911 | 31.059490 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 411 |22.6446 | 1 | 0.000921 | 30.910846 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 412 |22.6997 | 1 | 0.000932 | 31.133223 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 413 |22.7548 | 1 | 0.000917 | 31.070970 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 414 |22.8099 | 1 | 0.000914 | 30.972951 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 415 |22.8650 | 1 | 0.000918 | 31.069821 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 416 |22.9201 | 1 | 0.000914 | 30.941482 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 417 |22.9752 | 1 | 0.000922 | 31.035067 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 418 |23.0303 | 1 | 0.000919 | 31.025383 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 419 |23.0854 | 1 | 0.000922 | 30.960795 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 420 |23.1405 | 1 | 0.000920 | 30.935715 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 421 |23.1956 | 1 | 0.000921 | 31.048004 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 422 |23.2507 | 1 | 0.000919 | 31.063771 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 423 |23.3058 | 1 | 0.000918 | 31.055843 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 424 |23.3609 | 1 | 0.000913 | 30.966745 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 425 |23.4160 | 1 | 0.000917 | 31.040304 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 426 |23.4711 | 1 | 0.000899 | 31.154555 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 427 |23.5262 | 1 | 0.000924 | 31.061133 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 428 |23.5813 | 1 | 0.000922 | 30.945985 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 429 |23.6364 | 1 | 0.000920 | 31.081685 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 430 |23.6915 | 1 | 0.000944 | 30.971239 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ - "| 426 |23.4711 | 1 | 0.000392 | 35.489623 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 427 |23.5262 | 1 | 0.000389 | 35.608145 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 428 |23.5813 | 1 | 0.000384 | 35.740503 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 429 |23.6364 | 1 | 0.000389 | 35.533001 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 430 |23.6915 | 1 | 0.000384 | 35.683364 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 431 |23.7466 | 1 | 0.000390 | 35.601261 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 432 |23.8017 | 1 | 0.000391 | 35.618575 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 433 |23.8567 | 1 | 0.000378 | 36.598354 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 434 |23.9118 | 1 | 0.000378 | 36.427617 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 435 |23.9669 | 1 | 0.000379 | 36.053304 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 436 |24.0220 | 1 | 0.000377 | 36.117025 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 437 |24.0771 | 1 | 0.000379 | 35.915101 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 438 |24.1322 | 1 | 0.000379 | 36.169325 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 439 |24.1873 | 1 | 0.000382 | 36.040016 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 440 |24.2424 | 1 | 0.000388 | 35.969738 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 441 |24.2975 | 1 | 0.000382 | 36.001195 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 442 |24.3526 | 1 | 0.000388 | 35.664072 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 443 |24.4077 | 1 | 0.000384 | 35.712927 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 444 |24.4628 | 1 | 0.000391 | 35.636432 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 445 |24.5179 | 1 | 0.000389 | 35.651163 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 446 |24.5730 | 1 | 0.000386 | 35.623801 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 447 |24.6281 | 1 | 0.000390 | 35.432490 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 448 |24.6832 | 1 | 0.000386 | 35.826121 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 449 |24.7383 | 1 | 0.000389 | 35.587517 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 450 |24.7934 | 1 | 0.000388 | 35.661466 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 431 |23.7466 | 1 | 0.000909 | 31.095790 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 432 |23.8017 | 1 | 0.000914 | 31.028391 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 433 |23.8567 | 1 | 0.000913 | 30.953656 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 434 |23.9118 | 1 | 0.000917 | 31.025156 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 435 |23.9669 | 1 | 0.000915 | 30.890819 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 436 |24.0220 | 1 | 0.000921 | 31.095835 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 437 |24.0771 | 1 | 0.000907 | 31.297074 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 438 |24.1322 | 1 | 0.000908 | 31.019046 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 439 |24.1873 | 1 | 0.000930 | 30.926273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 440 |24.2424 | 1 | 0.000913 | 30.909393 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 441 |24.2975 | 1 | 0.000915 | 30.939363 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 442 |24.3526 | 1 | 0.000914 | 31.118100 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 443 |24.4077 | 1 | 0.000915 | 31.003708 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 444 |24.4628 | 1 | 0.000904 | 31.023637 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 445 |24.5179 | 1 | 0.000908 | 31.111450 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 446 |24.5730 | 1 | 0.000918 | 30.980093 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 447 |24.6281 | 1 | 0.000906 | 31.211698 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 448 |24.6832 | 1 | 0.000921 | 31.004640 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 449 |24.7383 | 1 | 0.000912 | 31.117989 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 450 |24.7934 | 1 | 0.000909 | 30.893335 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", "\u001b[34m...Finished\u001b[0m\n", - "\u001b[36mFINISHED - Elapsed time = 16723.0401956 seconds\u001b[0m\n", - "\u001b[36mFINISHED - CPU process time = 125522.0910016 seconds\u001b[0m\n" + "\u001b[36mFINISHED - Elapsed time = 14581.6230696 seconds\u001b[0m\n", + "\u001b[36mFINISHED - CPU process time = 108623.9978826 seconds\u001b[0m\n" ] } ], @@ -1056,8 +1073,8 @@ "metadata": {}, "outputs": [], "source": [ - "rho = sharpy_output.settings['StaticCoupledRBM']['aero_solver_settings']['rho'].value\n", - "uinf = sharpy_output.settings['StaticCoupledRBM']['aero_solver_settings']['velocity_field_input']['u_inf'].value\n", + "rho = sharpy_output.settings['StaticCoupled']['aero_solver_settings']['rho'].value\n", + "uinf = sharpy_output.settings['StaticCoupled']['aero_solver_settings']['velocity_field_input']['u_inf'].value\n", "R = np.max(r[0])\n", "Cp = 0\n", "Ct = 0\n", @@ -1138,7 +1155,7 @@ " \n", " \n", " \n", - " \n", " \n", @@ -1146,10 +1163,10 @@ " \n", " \n", + "\" id=\"m71f8e9c9ee\" style=\"stroke:#000000;stroke-width:0.8;\"/>\n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1192,13 +1209,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1238,13 +1255,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1277,13 +1294,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1329,13 +1346,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1390,13 +1407,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1517,7 +1534,7 @@ " \n", " \n", " \n", - " \n", " \n", @@ -1525,10 +1542,10 @@ " \n", " \n", + "\" id=\"m39994ba366\" style=\"stroke:#000000;stroke-width:0.8;\"/>\n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1542,13 +1559,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1562,13 +1579,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1582,13 +1599,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1636,13 +1653,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1760,59 +1777,59 @@ " \n", " \n", " \n", - " \n", " \n", " \n", - " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2138,13 +2155,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2158,13 +2175,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2178,13 +2195,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2198,13 +2215,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2218,13 +2235,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2252,13 +2269,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2273,18 +2290,18 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2294,18 +2311,18 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2315,18 +2332,18 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2336,18 +2353,18 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2357,18 +2374,18 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2396,67 +2413,67 @@ " \n", " \n", " \n", - " \n", " \n", " \n", - " \n", " \n", @@ -2534,10 +2551,10 @@ " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2590,8 +2607,8 @@ "output_type": "stream", "text": [ " OpenFAST SHARPy\n", - "Cp[-] 0.49 0.53\n", - "Ct[-] 0.70 0.74\n" + "Cp[-] 0.49 0.54\n", + "Ct[-] 0.70 0.75\n" ] } ], From 672a1166c26a6526fe04cb1252f6d225a5c45621 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 2 Mar 2021 14:15:38 +0000 Subject: [PATCH 009/253] no_ctypes linuvlm --- sharpy/linear/src/libss.py | 59 ++++++++++++++++++++++++++++ sharpy/linear/src/lin_aeroelastic.py | 27 +++++++------ sharpy/linear/src/linuvlm.py | 7 ++-- 3 files changed, 78 insertions(+), 15 deletions(-) diff --git a/sharpy/linear/src/libss.py b/sharpy/linear/src/libss.py index 85af3babe..5dad1da55 100644 --- a/sharpy/linear/src/libss.py +++ b/sharpy/linear/src/libss.py @@ -499,6 +499,65 @@ def solve_step(self, xn, un): return xn1, yn + def get_mats(self): + + A = np.zeros((self.states, self.states)) + B = np.zeros((self.states, self.inputs)) + C = np.zeros((self.outputs, self.states)) + D = np.zeros((self.outputs, self.inputs)) + + iloc = 0 + for i in range(self.blocks_x): + jloc = 0 + for j in range(self.blocks_x): + if not self.A[i][j] is None: + if type(self.A[i][j]) == libsp.csc_matrix: + A[iloc:iloc+self.S_x[i], jloc:jloc+self.S_x[j]] = self.A[i][j].todense() + else: + A[iloc:iloc+self.S_x[i], jloc:jloc+self.S_x[j]] = self.A[i][j].copy() + jloc += self.S_x[j] + iloc += self.S_x[i] + + iloc = 0 + for i in range(self.blocks_x): + jloc = 0 + for j in range(self.blocks_u): + if not self.B[i][j] is None: + # print(i, j, iloc, jloc, self.S_x[i], self.S_u[j], self.B[i][j].shape) + # print(iloc, iloc+self.S_x[i], jloc, jloc+self.S_u[j]) + if type(self.B[i][j]) == libsp.csc_matrix: + B[iloc:iloc+self.S_x[i], jloc:jloc+self.S_u[j]] = self.B[i][j].todense() + else: + B[iloc:iloc+self.S_x[i], jloc:jloc+self.S_u[j]] = self.B[i][j].copy() + jloc += self.S_u[j] + iloc += self.S_x[i] + + iloc = 0 + for i in range(self.blocks_y): + jloc = 0 + for j in range(self.blocks_x): + if not self.C[i][j] is None: + if type(self.C[i][j]) == libsp.csc_matrix: + C[iloc:iloc+self.S_y[i], jloc:jloc+self.S_x[j]] = self.C[i][j].todense() + else: + C[iloc:iloc+self.S_y[i], jloc:jloc+self.S_x[j]] = self.C[i][j].copy() + jloc += self.S_x[j] + iloc += self.S_y[i] + + iloc = 0 + for i in range(self.blocks_y): + jloc = 0 + for j in range(self.blocks_u): + if not self.D[i][j] is None: + if type(self.D[i][j]) == libsp.csc_matrix: + D[iloc:iloc+self.S_y[i], jloc:jloc+self.S_u[j]] = self.D[i][j].todense() + else: + D[iloc:iloc+self.S_y[i], jloc:jloc+self.S_u[j]] = self.D[i][j].copy() + jloc += self.S_u[j] + iloc += self.S_y[i] + + return A, B, C, D + # ---------------------------------------- Methods for state-space manipulation def project(ss_here,WT,V): ''' diff --git a/sharpy/linear/src/lin_aeroelastic.py b/sharpy/linear/src/lin_aeroelastic.py index 99df86763..838876712 100644 --- a/sharpy/linear/src/lin_aeroelastic.py +++ b/sharpy/linear/src/lin_aeroelastic.py @@ -56,7 +56,8 @@ def __init__(self, data, custom_settings_linear=None, uvlm_block=False, chosen_t sharpy.utils.settings.to_custom_types(settings_here, linuvlm.settings_types_dynamic, - linuvlm.settings_default_dynamic) + linuvlm.settings_default_dynamic, + no_ctype=True) if chosen_ts is None: self.chosen_ts = self.data.ts @@ -69,6 +70,8 @@ def __init__(self, data, custom_settings_linear=None, uvlm_block=False, chosen_t except KeyError: self.rigid_body_motions = False + print("rbm:", self.rigid_body_motions) + try: self.use_euler = settings_here['use_euler'] except KeyError: @@ -81,7 +84,7 @@ def __init__(self, data, custom_settings_linear=None, uvlm_block=False, chosen_t ## ------- ### extract aeroelastic info - self.dt = settings_here['dt'].value + self.dt = settings_here['dt'] ### reference to timestep_info # aero @@ -93,7 +96,7 @@ def __init__(self, data, custom_settings_linear=None, uvlm_block=False, chosen_t # --- backward compatibility try: - rho = settings_here['density'].value + rho = settings_here['density'] except KeyError: warnings.warn( "Key 'density' not found in 'LinearUvlm' solver settings. '\ @@ -102,7 +105,7 @@ def __init__(self, data, custom_settings_linear=None, uvlm_block=False, chosen_t if type(rho) == str: rho = np.float(rho) if hasattr(rho, 'value'): - rho = rho.value + rho = rho self.tsaero.rho = rho # --- backward compatibility @@ -127,22 +130,22 @@ def __init__(self, data, custom_settings_linear=None, uvlm_block=False, chosen_t if uvlm_block: self.linuvlm = linuvlm.DynamicBlock( self.tsaero, - dt=settings_here['dt'].value, + dt=settings_here['dt'], dynamic_settings=settings_here, - RemovePredictor=settings_here['remove_predictor'].value, - UseSparse=settings_here['use_sparse'].value, - integr_order=settings_here['integr_order'].value, + RemovePredictor=settings_here['remove_predictor'], + UseSparse=settings_here['use_sparse'], + integr_order=settings_here['integr_order'], ScalingDict=settings_here['ScalingDict'], for_vel=np.hstack((cga.dot(self.tsstr.for_vel[:3]), cga.dot(self.tsstr.for_vel[3:])))) else: self.linuvlm = linuvlm.Dynamic( self.tsaero, - dt=settings_here['dt'].value, + dt=settings_here['dt'], dynamic_settings=settings_here, - RemovePredictor=settings_here['remove_predictor'].value, - UseSparse=settings_here['use_sparse'].value, - integr_order=settings_here['integr_order'].value, + RemovePredictor=settings_here['remove_predictor'], + UseSparse=settings_here['use_sparse'], + integr_order=settings_here['integr_order'], ScalingDict=settings_here['ScalingDict'], for_vel=np.hstack((cga.dot(self.tsstr.for_vel[:3]), cga.dot(self.tsstr.for_vel[3:])))) diff --git a/sharpy/linear/src/linuvlm.py b/sharpy/linear/src/linuvlm.py index fe3ac75ff..7e23655de 100644 --- a/sharpy/linear/src/linuvlm.py +++ b/sharpy/linear/src/linuvlm.py @@ -102,7 +102,8 @@ def __init__(self, tsdata, custom_settings=None, for_vel=np.zeros((6,))): settings.to_custom_types(settings_here, settings_types_static, - settings_default_static) + settings_default_static, + no_ctype=True) self.vortex_radius = settings_here['vortex_radius'] MS = multisurfaces.MultiAeroGridSurfaces(tsdata, @@ -579,7 +580,7 @@ def __init__(self, tsdata, dt=None, dynamic_settings=None, integr_order=2, warnings.warn('No settings dictionary found. Using default. Individual parsing of settings is deprecated', DeprecationWarning) # Future: remove deprecation warning and make settings the only argument - settings.to_custom_types(self.settings, settings_types_dynamic, settings_default_dynamic) + settings.to_custom_types(self.settings, settings_types_dynamic, settings_default_dynamic, no_ctype=True) self.settings['dt'] = dt self.settings['integr_order'] = integr_order self.settings['remove_predictor'] = RemovePredictor @@ -1747,7 +1748,7 @@ def __init__(self, tsdata, dt=None, warnings.warn('Individual parsing of settings is deprecated. Please use the settings dictionary', DeprecationWarning) - super().__init__(tsdata, vortex_radius, dt, + super().__init__(tsdata, dt, dynamic_settings=dynamic_settings, integr_order=integr_order, RemovePredictor=RemovePredictor, From de143cafac5a30aebe4f0f2b16891ad55af20017 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 2 Mar 2021 14:15:59 +0000 Subject: [PATCH 010/253] comment postprocess LC --- sharpy/structure/utils/lagrangeconstraints.py | 1 + 1 file changed, 1 insertion(+) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 92ec8f62e..b9419e77f 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -1003,6 +1003,7 @@ def staticpost(self, lc_list, MB_beam, MB_tstep): def dynamicpost(self, lc_list, MB_beam, MB_tstep): MB_tstep[self.FoR_body].for_pos[0:3] = np.dot(MB_tstep[self.node_body].cga(), MB_tstep[self.node_body].pos[self.node_number,:]) + MB_tstep[self.node_body].for_pos[0:3] + # MB_tstep[self.FoR_body].for_vel[3:6] = self.rot_vect.copy() return From 3f929157e8379790ea773d0cd14fcf600f7d678f Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 2 Mar 2021 16:46:46 +0000 Subject: [PATCH 011/253] postprocess LC --- sharpy/solvers/nonlinearstatic.py | 4 ++++ sharpy/structure/utils/lagrangeconstraints.py | 13 ++++++++++++- 2 files changed, 16 insertions(+), 1 deletion(-) diff --git a/sharpy/solvers/nonlinearstatic.py b/sharpy/solvers/nonlinearstatic.py index 4815654cb..fc0ec7a8d 100644 --- a/sharpy/solvers/nonlinearstatic.py +++ b/sharpy/solvers/nonlinearstatic.py @@ -30,6 +30,9 @@ class NonLinearStatic(_BaseStructural): settings_types['initial_position'] = 'list(float)' settings_default['initial_position'] = np.array([0.0, 0.0, 0.0]) + + settings_types['initial_velocity'] = 'list(float)' + settings_default['initial_velocity'] = np.array([0., 0., 0., 0., 0., 0.]) settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -48,6 +51,7 @@ def initialise(self, data, custom_settings=None): def run(self): self.data.structure.timestep_info[self.data.ts].for_pos[0:3] = self.settings['initial_position'] + self.data.structure.timestep_info[self.data.ts].for_vel = self.settings['initial_velocity'].copy() xbeamlib.cbeam3_solv_nlnstatic(self.data.structure, self.settings, self.data.ts) self.extract_resultants() return self.data diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index b9419e77f..75927780e 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -1003,7 +1003,18 @@ def staticpost(self, lc_list, MB_beam, MB_tstep): def dynamicpost(self, lc_list, MB_beam, MB_tstep): MB_tstep[self.FoR_body].for_pos[0:3] = np.dot(MB_tstep[self.node_body].cga(), MB_tstep[self.node_body].pos[self.node_number,:]) + MB_tstep[self.node_body].for_pos[0:3] - # MB_tstep[self.FoR_body].for_vel[3:6] = self.rot_vect.copy() + + ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] + node_cga = MB_tstep[self.node_body].cga() + cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem,inode_in_elem,:]) + FoR_cga = MB_tstep[self.FoR_body].cga() + + rot_vect_A = ag.multiply_matrices(FoR_cga.T, + node_cga, + cab, + self.rot_vect) + + MB_tstep[self.FoR_body].for_vel[3:6] = rot_vect_A.copy() return From 1f275139604054d6c52134ad6caa369e3e98806c Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 3 Mar 2021 15:58:24 +0000 Subject: [PATCH 012/253] fix syntax ss --- sharpy/postproc/savedata.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/postproc/savedata.py b/sharpy/postproc/savedata.py index a6d9a6c2f..8a3165154 100644 --- a/sharpy/postproc/savedata.py +++ b/sharpy/postproc/savedata.py @@ -188,7 +188,7 @@ def initialise(self, data, custom_settings=None, caller=None): sharpy.linear.assembler.linearaeroelastic.LinearAeroelastic, sharpy.linear.assembler.linearbeam.LinearBeam, sharpy.linear.assembler.linearuvlm.LinearUVLM, - sharpy.linear.src.libss.ss, + sharpy.linear.src.libss.StateSpace, sharpy.linear.src.lingebm.FlexDynamic,) if self.settings['save_linear_uvlm']: From 84907eed14ad4dd973d4cc43fc182b86ba126f7f Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 4 Mar 2021 08:51:01 +0000 Subject: [PATCH 013/253] fix PID filter --- sharpy/controllers/bladepitchpid.py | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 1b9594ba4..23a841d1d 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -1,5 +1,5 @@ import numpy as np -from scipy.signal import StateSpace, lsim +from control import ss, forced_response import sharpy.utils.controller_interface as controller_interface import sharpy.utils.settings as settings @@ -158,7 +158,7 @@ def initialise(self, in_dict, controller_id=None): else: self.filter_pv = True alpha = np.exp(-self.settings['lp_cut_freq']*self.settings['dt']) - self.filter = StateSpace(alpha, (1-alpha), alpha, (1-alpha), self.settings['dt']) + self.filter = ss(alpha, 1.-alpha, alpha, 1.-alpha, self.settings['dt']) def control(self, data, controlled_state): r""" @@ -183,8 +183,13 @@ def control(self, data, controlled_state): sys_pv = self.compute_system_pv(struct_tstep, data.structure) # Apply filter - if self.filter_pv: - filtered_pv = lsim(self.filter, sys_pv) + if self.filter_pv and (len(self.system_pv) > 1): + nit = len(self.system_pv) + time = np.linspace(0, (nit - 1)*self.settings['dt'], nit) + # print(time.shape, len(self.system_pv)) + T, filtered_pv, xout = forced_response(self.filter, + T=time, + U=self.system_pv) else: filtered_pv = self.system_pv From da1e585bf70959ee54778e85d5ef45bf16a85e42 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 5 Mar 2021 17:08:11 +0000 Subject: [PATCH 014/253] remove rigid states using quat --- sharpy/linear/assembler/linearbeam.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/sharpy/linear/assembler/linearbeam.py b/sharpy/linear/assembler/linearbeam.py index feaf98129..b20576e3e 100644 --- a/sharpy/linear/assembler/linearbeam.py +++ b/sharpy/linear/assembler/linearbeam.py @@ -230,7 +230,10 @@ def assemble(self, t_ref=None): def remove_rigid_states(self): if self.sys.clamped: return - num_rig_dof = 9 + if self.settings['use_euler']: + num_rig_dof = 9 + else: + num_rig_dof = 10 if self.sys.modal: self.ss.A = self.ss.A[num_rig_dof:, num_rig_dof:] From 1eb8f27b5ee307dfc0a786b79afb730e90824eea Mon Sep 17 00:00:00 2001 From: Unknown Date: Fri, 12 Mar 2021 09:40:12 +0000 Subject: [PATCH 015/253] remove value static coupled --- sharpy/solvers/staticcoupled.py | 31 +++++++++++++++--------------- sharpy/structure/utils/xbeamlib.py | 2 +- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/sharpy/solvers/staticcoupled.py b/sharpy/solvers/staticcoupled.py index c0e7a8ef8..4a850ef4a 100644 --- a/sharpy/solvers/staticcoupled.py +++ b/sharpy/solvers/staticcoupled.py @@ -101,7 +101,8 @@ def initialise(self, data, input_dict=None): settings.to_custom_types(self.settings, self.settings_types, self.settings_default, - options=self.settings_options) + options=self.settings_options, + no_ctype=True) self.print_info = self.settings['print_info'] @@ -151,13 +152,13 @@ def cleanup_timestep_info(self): self.data.ts = 0 def run(self): - for i_step in range(self.settings['n_load_steps'].value + 1): - if (i_step == self.settings['n_load_steps'].value and - self.settings['n_load_steps'].value > 0): + for i_step in range(self.settings['n_load_steps'] + 1): + if (i_step == self.settings['n_load_steps'] and + self.settings['n_load_steps'] > 0): break # load step coefficient - if not self.settings['n_load_steps'].value == 0: - load_step_multiplier = (i_step + 1.0)/self.settings['n_load_steps'].value + if not self.settings['n_load_steps'] == 0: + load_step_multiplier = (i_step + 1.0)/self.settings['n_load_steps'] else: load_step_multiplier = 1.0 @@ -165,7 +166,7 @@ def run(self): if i_step > 0: self.increase_ts() - for i_iter in range(self.settings['max_iter'].value): + for i_iter in range(self.settings['max_iter']): # run aero self.data = self.aero_solver.run() @@ -186,7 +187,7 @@ def run(self): self.data.aero.timestep_info[self.data.ts], self.data.structure.timestep_info[self.data.ts], struct_forces, - rho=self.aero_solver.settings['rho'].value) + rho=self.aero_solver.settings['rho']) # Add external forces if self.with_runtime_generators: @@ -202,23 +203,23 @@ def run(self): struct_forces += self.data.structure.timestep_info[self.data.ts].runtime_generated_forces - if not self.settings['relaxation_factor'].value == 0.: + if not self.settings['relaxation_factor'] == 0.: if i_iter == 0: self.previous_force = struct_forces.copy() temp = struct_forces.copy() - struct_forces = ((1.0 - self.settings['relaxation_factor'].value)*struct_forces + - self.settings['relaxation_factor'].value*self.previous_force) + struct_forces = ((1.0 - self.settings['relaxation_factor'])*struct_forces + + self.settings['relaxation_factor']*self.previous_force) self.previous_force = temp # copy force in beam - old_g = self.structural_solver.settings['gravity'].value + old_g = self.structural_solver.settings['gravity'] self.structural_solver.settings['gravity'] = old_g*load_step_multiplier temp1 = load_step_multiplier*(struct_forces + self.data.structure.ini_info.steady_applied_forces) self.data.structure.timestep_info[self.data.ts].steady_applied_forces[:] = temp1 # run beam self.data = self.structural_solver.run() - self.structural_solver.settings['gravity'] = ct.c_double(old_g) + self.structural_solver.settings['gravity'] = old_g (self.data.structure.timestep_info[self.data.ts].total_forces[0:3], self.data.structure.timestep_info[self.data.ts].total_forces[3:6]) = ( self.extract_resultants(self.data.structure.timestep_info[self.data.ts])) @@ -236,7 +237,7 @@ def run(self): return self.data def convergence(self, i_iter, i_step): - if i_iter == self.settings['max_iter'].value - 1: + if i_iter == self.settings['max_iter'] - 1: cout.cout_wrap('StaticCoupled did not converge!', 0) # quit(-1) @@ -279,7 +280,7 @@ def convergence(self, i_iter, i_step): ]) if return_value is None: - if np.abs(self.current_residual - self.previous_residual)/self.initial_residual < self.settings['tolerance'].value: + if np.abs(self.current_residual - self.previous_residual)/self.initial_residual < self.settings['tolerance']: return_value = True else: self.previous_residual = self.current_residual diff --git a/sharpy/structure/utils/xbeamlib.py b/sharpy/structure/utils/xbeamlib.py index 38a58219f..e75088062 100644 --- a/sharpy/structure/utils/xbeamlib.py +++ b/sharpy/structure/utils/xbeamlib.py @@ -1136,7 +1136,7 @@ def cbeam3_asbly_static(beam, tstep, settings, iLoadStep): xbopts.PrintInfo = ct.c_bool(settings['print_info']) # xbopts.Solution = ct.c_int(312) # xbopts.MaxIterations = settings['max_iterations'] - xbopts.NumLoadSteps = ct.c_int(settings['num_load_steps'].value + 1) + xbopts.NumLoadSteps = ct.c_int(settings['num_load_steps'] + 1) # xbopts.NumGauss = ct.c_int(0) # xbopts.DeltaCurved = settings['delta_curved'] # xbopts.MinDelta = settings['min_delta'] From 7b356b0aec3d29b9945287422c6e2315a618f85d Mon Sep 17 00:00:00 2001 From: Unknown Date: Fri, 12 Mar 2021 09:40:34 +0000 Subject: [PATCH 016/253] merge forces in mb --- sharpy/utils/multibody.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index ff634c200..d27c0b837 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -94,6 +94,9 @@ def merge_multibody(MB_tstep, MB_beam, beam, tstep, mb_data_dict, dt): tstep.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) tstep.psi_ddot[ibody_elems,:,:] = MB_tstep[ibody].psi_ddot.astype(dtype=ct.c_double, order='F', copy=True) tstep.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) + tstep.steady_applied_forces[ibody_nodes,:] = MB_tstep[ibody].steady_applied_forces.astype(dtype=ct.c_double, order='F', copy=True) + tstep.unsteady_applied_forces[ibody_nodes,:] = MB_tstep[ibody].unsteady_applied_forces.astype(dtype=ct.c_double, order='F', copy=True) + tstep.runtime_generated_forces[ibody_nodes,:] = MB_tstep[ibody].runtime_generated_forces.astype(dtype=ct.c_double, order='F', copy=True) # TODO: Do I need a change in FoR for the following variables? Maybe for the FoR ones. tstep.forces_constraints_nodes[ibody_nodes,:] = MB_tstep[ibody].forces_constraints_nodes.astype(dtype=ct.c_double, order='F', copy=True) tstep.forces_constraints_FoR[ibody, :] = MB_tstep[ibody].forces_constraints_FoR[ibody, :].astype(dtype=ct.c_double, order='F', copy=True) From 2ef077932044020ea1ba39582e32ef8176105b72 Mon Sep 17 00:00:00 2001 From: Unknown Date: Fri, 12 Mar 2021 09:41:01 +0000 Subject: [PATCH 017/253] all bodies as default in extract resultants --- sharpy/utils/datastructures.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index 1d11d1521..65f1e0b62 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -904,7 +904,7 @@ def whole_structure_to_global_AFoR(self, beam): self.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) - def nodal_b_for_2_a_for(self, nodal, beam, filter=np.array([True]*6), ibody=0): + def nodal_b_for_2_a_for(self, nodal, beam, filter=np.array([True]*6), ibody=None): """ Projects a nodal variable from the local, body-attached frame (B) to the reference A frame. @@ -921,7 +921,7 @@ def nodal_b_for_2_a_for(self, nodal, beam, filter=np.array([True]*6), ibody=0): for i_node in range(self.num_node): # get master elem and i_local_node i_master_elem, i_local_node = beam.node_master_elem[i_node, :] - if beam.body_number[i_master_elem] == ibody: + if ((ibody is None) or (beam.body_number[i_master_elem] == ibody)): crv = self.psi[i_master_elem, i_local_node, :] cab = algebra.crv2rotation(crv) nodal_a[i_node, 0:3] = np.dot(cab, nodal[i_node, 0:3]) @@ -933,7 +933,7 @@ def nodal_b_for_2_a_for(self, nodal, beam, filter=np.array([True]*6), ibody=0): def nodal_type_b_for_2_a_for(self, beam, force_type=['steady', 'unsteady'], filter=np.array([True]*6), - ibody=0): + ibody=None): forces_output = [] for ft in force_type: if ft == 'steady': @@ -946,7 +946,7 @@ def nodal_type_b_for_2_a_for(self, beam, return forces_output - def extract_resultants(self, beam, force_type=['steady', 'unsteady', 'grav'], ibody=0): + def extract_resultants(self, beam, force_type=['steady', 'unsteady', 'grav'], ibody=None): forces_output = [] for ft in force_type: From 74cb3768ad82764bdb5089a3491e83142eb0b4a0 Mon Sep 17 00:00:00 2001 From: Unknown Date: Fri, 12 Mar 2021 10:13:26 +0000 Subject: [PATCH 018/253] update staticuvlm to be used in dynamic --- sharpy/solvers/staticuvlm.py | 46 +++++++++++++++++++++++++++++------- 1 file changed, 38 insertions(+), 8 deletions(-) diff --git a/sharpy/solvers/staticuvlm.py b/sharpy/solvers/staticuvlm.py index 941c5f80b..008e375fd 100644 --- a/sharpy/solvers/staticuvlm.py +++ b/sharpy/solvers/staticuvlm.py @@ -125,7 +125,7 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + settings.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) self.update_step() @@ -135,12 +135,42 @@ def initialise(self, data, custom_settings=None): self.velocity_generator = velocity_generator_type() self.velocity_generator.initialise(self.settings['velocity_field_input']) - def run(self): - if not self.data.aero.timestep_info[self.data.ts].zeta: + def update_grid(self, beam): + self.data.aero.generate_zeta(beam, + self.data.aero.aero_settings, + -1, + beam_ts=-1) + + def update_custom_grid(self, structure_tstep, aero_tstep): + self.data.aero.generate_zeta_timestep_info(structure_tstep, + aero_tstep, + self.data.structure, + self.data.aero.aero_settings, + dt=self.settings['rollup_dt']) + + def run(self, + aero_tstep=None, + structure_tstep=None, + convect_wake=False, + dt=None, + t=None, + unsteady_contribution=False): + + if aero_tstep is None: + aero_tstep = self.data.aero.timestep_info[self.data.ts] + if structure_tstep is None: + structure_tstep = self.data.structure.timestep_info[self.data.ts] + if dt is None: + dt = self.settings['rollup_dt'] + if t is None: + t = self.data.ts*dt + unsteady_contribution = False + convect_wake = False + + if not aero_tstep.zeta: return self.data # generate the wake because the solid shape might change - aero_tstep = self.data.aero.timestep_info[self.data.ts] self.data.aero.wake_shape_generator.generate({'zeta': aero_tstep.zeta, 'zeta_star': aero_tstep.zeta_star, 'gamma': aero_tstep.gamma, @@ -148,12 +178,12 @@ def run(self): 'dist_to_orig': aero_tstep.dist_to_orig}) # generate uext - self.velocity_generator.generate({'zeta': self.data.aero.timestep_info[self.data.ts].zeta, + self.velocity_generator.generate({'zeta': aero_tstep.zeta, 'override': True, - 'for_pos': self.data.structure.timestep_info[self.data.ts].for_pos[0:3]}, - self.data.aero.timestep_info[self.data.ts].u_ext) + 'for_pos': structure_tstep.for_pos[0:3]}, + aero_tstep.u_ext) # grid orientation - uvlmlib.vlm_solver(self.data.aero.timestep_info[self.data.ts], + uvlmlib.vlm_solver(aero_tstep, self.settings) return self.data From 2d1e70f6746f88f1aed3f460b3626df5d73b9ee0 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 12 Mar 2021 10:22:11 +0000 Subject: [PATCH 019/253] remove ctypes --- sharpy/aero/utils/uvlmlib.py | 22 +++++++++++----------- sharpy/solvers/nonlinearstatic.py | 2 +- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/sharpy/aero/utils/uvlmlib.py b/sharpy/aero/utils/uvlmlib.py index 70eb9e3d0..c931b5968 100644 --- a/sharpy/aero/utils/uvlmlib.py +++ b/sharpy/aero/utils/uvlmlib.py @@ -145,18 +145,18 @@ def vlm_solver(ts_info, options): vmopts = VMopts() vmopts.Steady = ct.c_bool(True) vmopts.NumSurfaces = ct.c_uint(ts_info.n_surf) - vmopts.horseshoe = ct.c_bool(options['horseshoe'].value) - vmopts.dt = ct.c_double(options["rollup_dt"].value) - vmopts.n_rollup = ct.c_uint(options["n_rollup"].value) - vmopts.rollup_tolerance = ct.c_double(options["rollup_tolerance"].value) - vmopts.rollup_aic_refresh = ct.c_uint(options['rollup_aic_refresh'].value) - vmopts.NumCores = ct.c_uint(options['num_cores'].value) - vmopts.iterative_solver = ct.c_bool(options['iterative_solver'].value) - vmopts.iterative_tol = ct.c_double(options['iterative_tol'].value) - vmopts.iterative_precond = ct.c_bool(options['iterative_precond'].value) + vmopts.horseshoe = ct.c_bool(options['horseshoe']) + vmopts.dt = ct.c_double(options["rollup_dt"]) + vmopts.n_rollup = ct.c_uint(options["n_rollup"]) + vmopts.rollup_tolerance = ct.c_double(options["rollup_tolerance"]) + vmopts.rollup_aic_refresh = ct.c_uint(options['rollup_aic_refresh']) + vmopts.NumCores = ct.c_uint(options['num_cores']) + vmopts.iterative_solver = ct.c_bool(options['iterative_solver']) + vmopts.iterative_tol = ct.c_double(options['iterative_tol']) + vmopts.iterative_precond = ct.c_bool(options['iterative_precond']) vmopts.cfl1 = ct.c_bool(options['cfl1']) - vmopts.vortex_radius = ct.c_double(options['vortex_radius'].value) - vmopts.vortex_radius_wake_ind = ct.c_double(options['vortex_radius_wake_ind'].value) + vmopts.vortex_radius = ct.c_double(options['vortex_radius']) + vmopts.vortex_radius_wake_ind = ct.c_double(options['vortex_radius_wake_ind']) flightconditions = FlightConditions() flightconditions.rho = options['rho'] diff --git a/sharpy/solvers/nonlinearstatic.py b/sharpy/solvers/nonlinearstatic.py index fc0ec7a8d..ec5354b41 100644 --- a/sharpy/solvers/nonlinearstatic.py +++ b/sharpy/solvers/nonlinearstatic.py @@ -47,7 +47,7 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + settings.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) def run(self): self.data.structure.timestep_info[self.data.ts].for_pos[0:3] = self.settings['initial_position'] From a8798b0b72c2564dbe0e9fa478482f3171715484 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 12 Mar 2021 10:34:04 +0000 Subject: [PATCH 020/253] add_step static uvlm --- sharpy/solvers/staticuvlm.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sharpy/solvers/staticuvlm.py b/sharpy/solvers/staticuvlm.py index 008e375fd..65f518cd9 100644 --- a/sharpy/solvers/staticuvlm.py +++ b/sharpy/solvers/staticuvlm.py @@ -135,6 +135,9 @@ def initialise(self, data, custom_settings=None): self.velocity_generator = velocity_generator_type() self.velocity_generator.initialise(self.settings['velocity_field_input']) + def add_step(self): + self.data.aero.add_timestep() + def update_grid(self, beam): self.data.aero.generate_zeta(beam, self.data.aero.aero_settings, From 55e08497b9467522456c4eb5efa46d19392905df Mon Sep 17 00:00:00 2001 From: Unknown Date: Fri, 12 Mar 2021 16:05:02 +0000 Subject: [PATCH 021/253] InitialAeroelasticLoader --- sharpy/solvers/initialaeroelasticloader.py | 88 ++++++++++++++++++++++ 1 file changed, 88 insertions(+) create mode 100644 sharpy/solvers/initialaeroelasticloader.py diff --git a/sharpy/solvers/initialaeroelasticloader.py b/sharpy/solvers/initialaeroelasticloader.py new file mode 100644 index 000000000..d3a38d0c9 --- /dev/null +++ b/sharpy/solvers/initialaeroelasticloader.py @@ -0,0 +1,88 @@ +import numpy as np +import h5py as h5 + +from sharpy.utils.solver_interface import solver, BaseSolver +import sharpy.utils.settings as settings +import sharpy.utils.algebra as algebra +import sharpy.utils.h5utils as h5utils + +@solver +class InitialAeroelasticLoader(BaseSolver): + r""" + This solver prescribes pos, pos_dot, psi, psi_dot and for_vel + at each time step from a .h5 file + """ + solver_id = 'InitialAeroelasticLoader' + solver_classification = 'loader' + + settings_types = dict() + settings_default = dict() + settings_description = dict() + + settings_types['input_file'] = 'str' + settings_default['input_file'] = None + settings_description['input_file'] = 'Input file containing the simulation data' + + settings_table = settings.SettingsTable() + __doc__ += settings_table.generate(settings_types, settings_default, settings_description) + + def __init__(self): + self.data = None + self.settings = None + self.file_info = None + + def initialise(self, data, custom_settings=None): + + self.data = data + if custom_settings is None: + self.settings = data.settings[self.solver_id] + else: + self.settings = custom_settings + settings.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + no_ctype=True) + # Load simulation data + self.file_info = h5utils.readh5(self.settings['input_file']) + + def run(self, structural_step=None, aero_step=None): + + if structural_step is None: + structural_step = self.data.structure.timestep_info[-1] + if aero_step is None: + aero_step = self.data.aero.timestep_info[-1] + + # Copy structural information + attributes = ['pos', 'pos_dot', 'pos_ddot', + 'psi', 'psi_dot', 'psi_ddot', + 'for_pos', 'for_vel', 'for_acc', + 'mb_FoR_pos', 'mb_FoR_vel', 'mb_FoR_acc', 'mb_quat', + 'runtime_generated_forces', + 'steady_applied_forces', + 'unsteady_applied_forces'] + for att in attributes: + getattr(structural_step, att) = getattr(self.file_info.structure, att) + # structural_step.pos_dot = self.file_info.structure.pos_dot + # structural_step.pos_ddot = self.file_info.structure.pos_ddot + # structural_step.psi = self.file_info.structure.psi + # structural_step.psi_dot = self.file_info.structure.psi_dot + # structural_step.psi_ddot = self.file_info.structure.psi_ddot +# + # structural_step.for_pos = self.file_info.structure.for_pos + # structural_step.for_vel = self.file_info.structure.for_vel + # structural_step.for_acc = self.file_info.structure.for_acc + # structural_step.quat = self.file_info.structure.quat + + # Copy multibody information + # mb_FoR_pos vel acc quat + + # Copy aero information + attributes = ['zeta', 'zeta_star', 'normals', + 'gamma', 'gamma_star', + 'u_ext', 'u_ext_star', + 'dynamic_forces', 'forces',] + # 'dist_to_orig', 'gamma_dot', 'zeta_dot', + for att in attributes: + getattr(aero_step, att) = getattr(self.file_info.aero, att) + + return self.data From 9c7a023f2c604738ac2677c79147404e63f98eb0 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 12 Mar 2021 18:30:52 +0000 Subject: [PATCH 022/253] minor fixes --- sharpy/solvers/initialaeroelasticloader.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/sharpy/solvers/initialaeroelasticloader.py b/sharpy/solvers/initialaeroelasticloader.py index d3a38d0c9..3f530e6ac 100644 --- a/sharpy/solvers/initialaeroelasticloader.py +++ b/sharpy/solvers/initialaeroelasticloader.py @@ -61,7 +61,7 @@ def run(self, structural_step=None, aero_step=None): 'steady_applied_forces', 'unsteady_applied_forces'] for att in attributes: - getattr(structural_step, att) = getattr(self.file_info.structure, att) + getattr(structural_step, att)[...] = getattr(self.file_info.structure, att) # structural_step.pos_dot = self.file_info.structure.pos_dot # structural_step.pos_ddot = self.file_info.structure.pos_ddot # structural_step.psi = self.file_info.structure.psi @@ -83,6 +83,7 @@ def run(self, structural_step=None, aero_step=None): 'dynamic_forces', 'forces',] # 'dist_to_orig', 'gamma_dot', 'zeta_dot', for att in attributes: - getattr(aero_step, att) = getattr(self.file_info.aero, att) + for isurf in range(aero_step.n_surf): + getattr(aero_step, att)[isurf][...] = getattr(self.file_info.aero, att)[isurf] return self.data From 681eff2bca7e55761024b521920821836cf71b5d Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 15 Mar 2021 09:57:58 +0000 Subject: [PATCH 023/253] stride in pickledata and aerogridplot --- sharpy/postproc/aerogridplot.py | 6 +++++- sharpy/postproc/pickledata.py | 14 +++++++------- 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/sharpy/postproc/aerogridplot.py b/sharpy/postproc/aerogridplot.py index 29269e204..6829ebb9a 100644 --- a/sharpy/postproc/aerogridplot.py +++ b/sharpy/postproc/aerogridplot.py @@ -67,6 +67,10 @@ class AerogridPlot(BaseSolver): settings_default['vortex_radius'] = vortex_radius_def settings_description['vortex_radius'] = 'Distance below which inductions are not computed' + settings_types['stride'] = 'int' + settings_default['stride'] = 1 + settings_description['stride'] = 'Number of steps between the execution calls when run online' + table = settings.SettingsTable() __doc__ += table.generate(settings_types, settings_default, settings_description) @@ -112,7 +116,7 @@ def run(self, online=False): self.plot_body() self.plot_wake() cout.cout_wrap('...Finished', 1) - else: + elif (self.data.it % self.settings['stride'] == 0): aero_tsteps = len(self.data.aero.timestep_info) - 1 struct_tsteps = len(self.data.structure.timestep_info) - 1 self.ts = np.max((aero_tsteps, struct_tsteps)) diff --git a/sharpy/postproc/pickledata.py b/sharpy/postproc/pickledata.py index 3c45b6d70..d502c7336 100644 --- a/sharpy/postproc/pickledata.py +++ b/sharpy/postproc/pickledata.py @@ -30,6 +30,10 @@ class PickleData(BaseSolver): settings_types['folder'] = 'str' settings_default['folder'] = './output' settings_description['folder'] = 'Folder to output pickle file' + + settings_types['stride'] = 'int' + settings_default['stride'] = 1 + settings_description['stride'] = 'Number of steps between the execution calls when run online' settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -62,12 +66,8 @@ def initialise(self, data, custom_settings=None, caller=None): self.caller = caller def run(self, online=False): - for it in range(len(self.data.structure.timestep_info)): - tstep_p = self.data.structure.timestep_info[it] - # if tstep_p is not None: - # if not tstep_p.in_global_AFoR: - # tstep_p.whole_structure_to_global_AFoR(self.data.structure) - with open(self.filename, 'wb') as f: - pickle.dump(self.data, f, protocol=pickle.HIGHEST_PROTOCOL) + if ((online and (self.data.it % self.settings['stride'] == 0)) or (not online)): + with open(self.filename, 'wb') as f: + pickle.dump(self.data, f, protocol=pickle.HIGHEST_PROTOCOL) return self.data From 4c9a3a24ef10a331aa674ce784de023f32ba03a1 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 15 Mar 2021 09:59:53 +0000 Subject: [PATCH 024/253] save_wake option in aerogridplot --- sharpy/postproc/aerogridplot.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/sharpy/postproc/aerogridplot.py b/sharpy/postproc/aerogridplot.py index 6829ebb9a..354ec12eb 100644 --- a/sharpy/postproc/aerogridplot.py +++ b/sharpy/postproc/aerogridplot.py @@ -71,6 +71,10 @@ class AerogridPlot(BaseSolver): settings_default['stride'] = 1 settings_description['stride'] = 'Number of steps between the execution calls when run online' + settings_types['save_wake'] = 'bool' + settings_default['save_wake'] = True + settings_description['save_wake'] = 'Plot the wake' + table = settings.SettingsTable() __doc__ += table.generate(settings_types, settings_default, settings_description) @@ -114,14 +118,16 @@ def run(self, online=False): for self.ts in range(self.ts_max): if self.data.structure.timestep_info[self.ts] is not None: self.plot_body() - self.plot_wake() + if self.settings['save_wake']: + self.plot_wake() cout.cout_wrap('...Finished', 1) elif (self.data.it % self.settings['stride'] == 0): aero_tsteps = len(self.data.aero.timestep_info) - 1 struct_tsteps = len(self.data.structure.timestep_info) - 1 self.ts = np.max((aero_tsteps, struct_tsteps)) self.plot_body() - self.plot_wake() + if self.settings['save_wake']: + self.plot_wake() return self.data def plot_body(self): From f740aa34fc7dbf2a15f4f5e4ea0376b099c62357 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 15 Mar 2021 10:56:42 +0000 Subject: [PATCH 025/253] ctype value --- sharpy/postproc/aerogridplot.py | 2 +- sharpy/postproc/pickledata.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/sharpy/postproc/aerogridplot.py b/sharpy/postproc/aerogridplot.py index 354ec12eb..1ccd669cf 100644 --- a/sharpy/postproc/aerogridplot.py +++ b/sharpy/postproc/aerogridplot.py @@ -121,7 +121,7 @@ def run(self, online=False): if self.settings['save_wake']: self.plot_wake() cout.cout_wrap('...Finished', 1) - elif (self.data.it % self.settings['stride'] == 0): + elif (self.data.ts % self.settings['stride'].value == 0): aero_tsteps = len(self.data.aero.timestep_info) - 1 struct_tsteps = len(self.data.structure.timestep_info) - 1 self.ts = np.max((aero_tsteps, struct_tsteps)) diff --git a/sharpy/postproc/pickledata.py b/sharpy/postproc/pickledata.py index d502c7336..2351c1262 100644 --- a/sharpy/postproc/pickledata.py +++ b/sharpy/postproc/pickledata.py @@ -66,7 +66,7 @@ def initialise(self, data, custom_settings=None, caller=None): self.caller = caller def run(self, online=False): - if ((online and (self.data.it % self.settings['stride'] == 0)) or (not online)): + if ((online and (self.data.ts % self.settings['stride'].value == 0)) or (not online)): with open(self.filename, 'wb') as f: pickle.dump(self.data, f, protocol=pickle.HIGHEST_PROTOCOL) From 0894439a30539d0f8bfc24b2d831a8b49dfb07d3 Mon Sep 17 00:00:00 2001 From: Unknown Date: Mon, 15 Mar 2021 16:16:35 +0000 Subject: [PATCH 026/253] fix missing c_double --- sharpy/structure/utils/xbeamlib.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/structure/utils/xbeamlib.py b/sharpy/structure/utils/xbeamlib.py index 47b8f29b1..814f707d0 100644 --- a/sharpy/structure/utils/xbeamlib.py +++ b/sharpy/structure/utils/xbeamlib.py @@ -1209,7 +1209,7 @@ def xbeam_step_coupledrigid(beam, settings, ts, tstep=None, dt=None): xbopts.gravity_dir_x = ct.c_double(settings['gravity_dir'][0]) xbopts.gravity_dir_y = ct.c_double(settings['gravity_dir'][1]) xbopts.gravity_dir_z = ct.c_double(settings['gravity_dir'][2]) - xbopts.relaxation_factor = settings['relaxation_factor'] + xbopts.relaxation_factor = ct.c_double(settings['relaxation_factor']) if dt is None: in_dt = ct.c_double(settings['dt']) From d473ec438bf57f4dbe7e7c6e99edcea023b86ecb Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 18 Mar 2021 15:48:14 +0000 Subject: [PATCH 027/253] fix restart floating forces --- sharpy/generators/floatingforces.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index ad0e4c3ce..7db220cb6 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -832,6 +832,9 @@ def generate(self, params): elif self.settings['method_matrices_freq'] == 'rational_function': # Damping + if self.x0_K[data.ts - 1] is None: + # This loop is needed when computations are restarted + self.x0_K[data.ts - 1] = 0 (T, yout, xout) = forced_response(self.hd_K, T=[0, self.settings['dt']], U=self.qdot[data.ts-1:data.ts+1, :].T, From 0f49176ad537aef6618fe45d71c0ea84386d9387 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 18 Mar 2021 15:48:28 +0000 Subject: [PATCH 028/253] remove .value --- sharpy/postproc/aerogridplot.py | 2 +- sharpy/postproc/pickledata.py | 2 +- sharpy/solvers/dynamiccoupled.py | 8 ++++---- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/sharpy/postproc/aerogridplot.py b/sharpy/postproc/aerogridplot.py index 8baeba6b2..97b73456b 100644 --- a/sharpy/postproc/aerogridplot.py +++ b/sharpy/postproc/aerogridplot.py @@ -121,7 +121,7 @@ def run(self, online=False): if self.settings['save_wake']: self.plot_wake() cout.cout_wrap('...Finished', 1) - elif (self.data.ts % self.settings['stride'].value == 0): + elif (self.data.ts % self.settings['stride'] == 0): aero_tsteps = len(self.data.aero.timestep_info) - 1 struct_tsteps = len(self.data.structure.timestep_info) - 1 self.ts = np.max((aero_tsteps, struct_tsteps)) diff --git a/sharpy/postproc/pickledata.py b/sharpy/postproc/pickledata.py index 2351c1262..b3739da7a 100644 --- a/sharpy/postproc/pickledata.py +++ b/sharpy/postproc/pickledata.py @@ -66,7 +66,7 @@ def initialise(self, data, custom_settings=None, caller=None): self.caller = caller def run(self, online=False): - if ((online and (self.data.ts % self.settings['stride'].value == 0)) or (not online)): + if ((online and (self.data.ts % self.settings['stride'] == 0)) or (not online)): with open(self.filename, 'wb') as f: pickle.dump(self.data, f, protocol=pickle.HIGHEST_PROTOCOL) diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index af5a54634..fb6a71a8c 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -502,11 +502,11 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): # compute unsteady contribution force_coeff = 0.0 unsteady_contribution = False - if self.settings['include_unsteady_force_contribution'].value: - if self.data.ts > self.settings['steps_without_unsteady_force'].value: + if self.settings['include_unsteady_force_contribution']: + if self.data.ts > self.settings['steps_without_unsteady_force']: unsteady_contribution = True - if 0 < self.settings['pseudosteps_ramp_unsteady_force'].value: - force_coeff = k/self.settings['pseudosteps_ramp_unsteady_force'].value + if 0 < self.settings['pseudosteps_ramp_unsteady_force']: + force_coeff = k/self.settings['pseudosteps_ramp_unsteady_force'] else: force_coeff = 1. # Add external forces From df1eb9cb8a1eb8a45f19045fe58d20e40fac74a3 Mon Sep 17 00:00:00 2001 From: Unknown Date: Thu, 18 Mar 2021 15:59:16 +0000 Subject: [PATCH 029/253] generator model --- sharpy/controllers/bladepitchpid.py | 53 +++++++++++++++++++---------- 1 file changed, 35 insertions(+), 18 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 23a841d1d..227ffb3c8 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -42,7 +42,7 @@ class BladePitchPid(controller_interface.BaseController): settings_types['anti_windup_lim'] = 'list(float)' settings_default['anti_windup_lim'] = None settings_description['anti_windup_lim'] = 'Limits of actuation to apply anti windup' - + # Set point parameters settings_types['sp_type'] = 'str' settings_default['sp_type'] = None @@ -57,11 +57,11 @@ class BladePitchPid(controller_interface.BaseController): 'Source used to define the' + ' set point') settings_options['sp_source'] = ['file'] - + settings_types['sp_time_history_file'] = 'str' settings_default['sp_time_history_file'] = None settings_description['sp_time_history_file'] = ('Route and file name of the time ' + - 'history of the desired set point.' + + 'history of the desired set point.' + 'Used for ``sp_source = file``') # Other parameters @@ -81,6 +81,23 @@ class BladePitchPid(controller_interface.BaseController): settings_default['max_pitch_rate'] = 0.1396 settings_description['max_pitch_rate'] = 'Maximum pitch rate [rad/s]' + # Generator and drive train model + settings_types['target_power'] = 'float' + settings_default['target_power'] = 5e6 + settings_description['target_power'] = 'Target power in operation' + + settings_types['GBR'] = 'float' + settings_default['GBR'] = 97. + settings_description['GBR'] = 'Gear box ratio' + + settings_types['inertia_dt'] = 'float' + settings_default['inertia_dt'] = + settings_description['inertia_dt'] = 'Drive train inertia' + + settings_types['newmark_damp'] = 'float' + settings_default['newmark_damp'] = 1e-4 + settings_description['newmark_damp'] = 'Damping of the time integration newmark-beta scheme' + # Output parameters settings_types['write_controller_log'] = 'bool' settings_default['write_controller_log'] = True @@ -132,6 +149,7 @@ def initialise(self, in_dict, controller_id=None): no_ctype=True) self.settings = self.in_dict + self.newmark_damp = 0.5 + self.settings['newmark_damp'] # self.controller_id = controller_id # self.nblades = len(self.settings['blade_num_body']) @@ -181,7 +199,7 @@ def control(self, data, controlled_state): prescribed_sp = self.compute_prescribed_sp(time) sys_pv = self.compute_system_pv(struct_tstep, data.structure) - + # Apply filter if self.filter_pv and (len(self.system_pv) > 1): nit = len(self.system_pv) @@ -205,12 +223,12 @@ def control(self, data, controlled_state): 'I': self.settings['I'], 'D': self.settings['D']}, i_current=data.ts) - + if control_command < -self.settings['max_pitch_rate']: control_command = -self.settings['max_pitch_rate'] elif control_command > self.settings['max_pitch_rate']: control_command = self.settings['max_pitch_rate'] - + # Apply control order # rot_mat = algebra.rotation3d_x(control_command) print("control_command: ", control_command) @@ -254,7 +272,7 @@ def control(self, data, controlled_state): control_command)) return controlled_state - + def compute_prescribed_sp(self, time): """ Compute the set point relevant for the controller @@ -288,7 +306,7 @@ def compute_system_pv(self, struct_tstep, beam): rbm = steady[4] + unsteady[4] + grav[4] self.system_pv.append(rbm) print("rbm: ", rbm) - + return self.system_pv[-1] # def extract_time_history(self, controlled_state): # output = 0.0 @@ -330,17 +348,16 @@ def __exit__(self, *args): # self.log.close() pass + def generator_model(aero_torque, ini_rot_vel, ini_rot_acc): + gen_torque = self.settings['target_power']*ini_rot_vel + delta_rot_acc = (aero_torque - self.settings['GBR']*gen_torque)/self.settings['inertia_dt'] + rot_acc = ini_tor_acc + delta_rot_acc + # Integrate according to newmark-beta scheme + rot_vel = (ini_rot_vel + + (1. - self.newmark_beta)*self.settings['dt'] + + self.newmark_beta*self.settings['dt']*rot_acc) - - - - - - - - - - + return rot_vel, rot_acc From 7c32e4f4f52c50ee901a1c162a80f59096ff93e2 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 19 Mar 2021 09:18:08 +0000 Subject: [PATCH 030/253] default value inertia DT --- sharpy/controllers/bladepitchpid.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 227ffb3c8..f6a7a6709 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -91,7 +91,7 @@ class BladePitchPid(controller_interface.BaseController): settings_description['GBR'] = 'Gear box ratio' settings_types['inertia_dt'] = 'float' - settings_default['inertia_dt'] = + settings_default['inertia_dt'] = 43776046.25 settings_description['inertia_dt'] = 'Drive train inertia' settings_types['newmark_damp'] = 'float' From 0406e0d8270e80f41569d68956540c7bd02c372f Mon Sep 17 00:00:00 2001 From: Unknown Date: Thu, 25 Mar 2021 16:45:34 +0000 Subject: [PATCH 031/253] test commit --- sharpy/controllers/bladepitchpid.py | 1 + 1 file changed, 1 insertion(+) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index f6a7a6709..5997622a9 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -110,6 +110,7 @@ class BladePitchPid(controller_interface.BaseController): settings_description['controller_log_route'] = ( 'Directory where the log will be stored') + #test comment settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, From ab8b08c18eff6df3e44587dd485fea1b6b8b1065 Mon Sep 17 00:00:00 2001 From: Unknown Date: Thu, 25 Mar 2021 16:46:12 +0000 Subject: [PATCH 032/253] revert test commit --- sharpy/controllers/bladepitchpid.py | 1 - 1 file changed, 1 deletion(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 5997622a9..f6a7a6709 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -110,7 +110,6 @@ class BladePitchPid(controller_interface.BaseController): settings_description['controller_log_route'] = ( 'Directory where the log will be stored') - #test comment settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, From 00109fe19b0d0f590abeaa547bca8ab685400f36 Mon Sep 17 00:00:00 2001 From: Unknown Date: Thu, 25 Mar 2021 16:57:54 +0000 Subject: [PATCH 033/253] change to NREL5MW_v02 --- cases/coupled/WindTurbine/generate_rotor.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cases/coupled/WindTurbine/generate_rotor.py b/cases/coupled/WindTurbine/generate_rotor.py index 0c593c5b3..daaee088e 100644 --- a/cases/coupled/WindTurbine/generate_rotor.py +++ b/cases/coupled/WindTurbine/generate_rotor.py @@ -58,7 +58,7 @@ options['separate_blades'] = False excel_description = {} -excel_description['excel_file_name'] = '../../../docs/source/content/example_notebooks/source/type02_db_NREL5MW_v01.xlsx' +excel_description['excel_file_name'] = '../../../docs/source/content/example_notebooks/source/type02_db_NREL5MW_v02.xlsx' excel_description['excel_sheet_parameters'] = 'parameters' excel_description['excel_sheet_structural_blade'] = 'structural_blade' excel_description['excel_sheet_discretization_blade'] = 'discretization_blade' From 71bcc200b7e68d637d50728284209d8768a4cc1e Mon Sep 17 00:00:00 2001 From: Unknown Date: Fri, 26 Mar 2021 10:10:52 +0000 Subject: [PATCH 034/253] copy solver_interface from dev_blade_pitch --- sharpy/utils/solver_interface.py | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/sharpy/utils/solver_interface.py b/sharpy/utils/solver_interface.py index eb671e496..898e4b70b 100644 --- a/sharpy/utils/solver_interface.py +++ b/sharpy/utils/solver_interface.py @@ -100,10 +100,8 @@ def dictionary_of_solvers(print_info=True): import sharpy.postproc dictionary = dict() for solver in dict_of_solvers: - if not solver.lower() == 'SaveData'.lower(): - # TODO: why it does not work for savedata? - init_solver = initialise_solver(solver, print_info) - dictionary[solver] = init_solver.settings_default + init_solver = initialise_solver(solver, print_info) + dictionary[solver] = init_solver.settings_default return dictionary @@ -193,5 +191,3 @@ def output_documentation(route=None): out_file.write(' ./' + solver_type + '/' + k + '\n') except AttributeError: pass - - From 6fe91514903a32ef78ca326bc8832fa0cc9b5aa4 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 26 Mar 2021 14:41:11 +0000 Subject: [PATCH 035/253] return zero in multibody resultants --- sharpy/solvers/nonlineardynamicmultibody.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index a93abef41..2b6243114 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -250,9 +250,9 @@ def integrate_position(self, MB_beam, MB_tstep, dt): else: MB_tstep[ibody].for_pos[0:3] += dt*np.dot(MB_tstep[ibody].cga(),MB_tstep[ibody].for_vel[0:3]) - def extract_resultants(self): + def extract_resultants(self, tstep): # TODO: code - pass + return np.zeros((3)), np.zeros((3)) def compute_forces_constraints(self, MB_beam, MB_tstep, ts, dt, Lambda, Lambda_dot): """ @@ -347,6 +347,7 @@ def run(self, structural_step=None, dt=None): dqdt = np.zeros((self.sys_size + num_LM_eq,), dtype=ct.c_double, order='F') dqddt = np.zeros((self.sys_size + num_LM_eq,), dtype=ct.c_double, order='F') + # TODO: i belive this can move into disp_and_accel2 state as self.Lambda, self.Lambda_dot if not num_LM_eq == 0: Lambda = self.Lambda.astype(dtype=ct.c_double, copy=True, order='F') Lambda_dot = self.Lambda_dot.astype(dtype=ct.c_double, copy=True, order='F') From 1487e4d22946a94da2da70128f752651ba177910 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 28 Mar 2021 17:53:06 +0100 Subject: [PATCH 036/253] wip: fix for conversion --- sharpy/utils/datastructures.py | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index 65f1e0b62..12f7b640b 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -766,8 +766,8 @@ def change_to_local_AFoR(self, for0_pos, for0_vel, quat0): # self.pos_dot[inode,:] = np.dot(Csm,self.pos_dot[inode,:]) - np.dot(CAslaveG,delta_vel_ms[0:3]) self.pos_dot[inode,:] = (np.dot(Csm, self.pos_dot[inode,:]) - np.dot(CAslaveG, delta_vel_ms[0:3]) - - np.dot(algebra.skew(np.dot( CAslaveG, self.for_vel[3:6])), self.pos[inode,:]) + - np.dot(Csm, np.dot(algebra.skew(np.dot(CGAmaster.T, for0_vel[3:6])), pos_previous))) + np.dot(algebra.skew(self.for_vel[3:6]), self.pos[inode,:]) + + np.dot(Csm, np.dot(algebra.skew(for0_vel[3:6]), pos_previous))) self.gravity_forces[inode,0:3] = np.dot(Csm, self.gravity_forces[inode,0:3]) self.gravity_forces[inode,3:6] = np.dot(Csm, self.gravity_forces[inode,3:6]) @@ -807,8 +807,8 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): np.dot(np.transpose(CGAmaster),delta_pos_ms[0:3])) self.pos_dot[inode,:] = (np.dot(np.transpose(Csm),self.pos_dot[inode,:]) + np.dot(np.transpose(CGAmaster),delta_vel_ms[0:3]) + - np.dot(Csm.T, np.dot(algebra.skew(np.dot(CAslaveG, self.for_vel[3:6])), pos_previous)) - - np.dot(algebra.skew(np.dot(CGAmaster.T, for0_vel[3:6])), self.pos[inode,:])) + np.dot(Csm.T, np.dot(algebra.skew(self.for_vel[3:6]), pos_previous)) - + np.dot(algebra.skew(for0_vel[3:6]), self.pos[inode,:])) self.gravity_forces[inode,0:3] = np.dot(Csm.T, self.gravity_forces[inode,0:3]) self.gravity_forces[inode,3:6] = np.dot(Csm.T, self.gravity_forces[inode,3:6]) # np.cross(np.dot(CGAmaster.T, delta_vel_ms[3:6]), pos_previous)) @@ -895,7 +895,6 @@ def whole_structure_to_global_AFoR(self, beam): # Merge tstep self.pos[ibody_nodes,:] = MB_tstep[ibody].pos.astype(dtype=ct.c_double, order='F', copy=True) - # tstep.pos_dot[ibody_nodes,:] = MB_tstep[ibody].pos_dot.astype(dtype=ct.c_double, order='F', copy=True) self.psi[ibody_elems,:,:] = MB_tstep[ibody].psi.astype(dtype=ct.c_double, order='F', copy=True) self.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) From 986f7dc08ed1567ff36d0e1b4c1b3a957e35e399 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 28 Mar 2021 21:27:04 +0100 Subject: [PATCH 037/253] simplify cross3 notation --- sharpy/utils/datastructures.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index 12f7b640b..a998e5565 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -766,8 +766,8 @@ def change_to_local_AFoR(self, for0_pos, for0_vel, quat0): # self.pos_dot[inode,:] = np.dot(Csm,self.pos_dot[inode,:]) - np.dot(CAslaveG,delta_vel_ms[0:3]) self.pos_dot[inode,:] = (np.dot(Csm, self.pos_dot[inode,:]) - np.dot(CAslaveG, delta_vel_ms[0:3]) - - np.dot(algebra.skew(self.for_vel[3:6]), self.pos[inode,:]) + - np.dot(Csm, np.dot(algebra.skew(for0_vel[3:6]), pos_previous))) + algebra.cross3(self.for_vel[3:6]), self.pos[inode,:]) + + np.dot(Csm, algebra.cross3(for0_vel[3:6], pos_previous))) self.gravity_forces[inode,0:3] = np.dot(Csm, self.gravity_forces[inode,0:3]) self.gravity_forces[inode,3:6] = np.dot(Csm, self.gravity_forces[inode,3:6]) @@ -807,8 +807,8 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): np.dot(np.transpose(CGAmaster),delta_pos_ms[0:3])) self.pos_dot[inode,:] = (np.dot(np.transpose(Csm),self.pos_dot[inode,:]) + np.dot(np.transpose(CGAmaster),delta_vel_ms[0:3]) + - np.dot(Csm.T, np.dot(algebra.skew(self.for_vel[3:6]), pos_previous)) - - np.dot(algebra.skew(for0_vel[3:6]), self.pos[inode,:])) + np.dot(Csm.T, algebra.cross3(self.for_vel[3:6], pos_previous)) - + algebra.cross3(for0_vel[3:6], self.pos[inode,:])) self.gravity_forces[inode,0:3] = np.dot(Csm.T, self.gravity_forces[inode,0:3]) self.gravity_forces[inode,3:6] = np.dot(Csm.T, self.gravity_forces[inode,3:6]) # np.cross(np.dot(CGAmaster.T, delta_vel_ms[3:6]), pos_previous)) From e892a83a1b8d0e88c5a71254e4b1d9280c9cb92b Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 29 Mar 2021 19:48:54 +0100 Subject: [PATCH 038/253] pos dot from der and psi dot from equal omega B --- sharpy/utils/datastructures.py | 90 ++++++++++++++++++---------------- 1 file changed, 48 insertions(+), 42 deletions(-) diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index a998e5565..927caff43 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -754,31 +754,35 @@ def change_to_local_AFoR(self, for0_pos, for0_vel, quat0): CGAmaster = algebra.quat2rotation(quat0) Csm = np.dot(CAslaveG, CGAmaster) - delta_vel_ms = np.zeros((6,)) - delta_pos_ms = self.for_pos[0:3] - for0_pos[0:3] - delta_vel_ms[0:3] = np.dot(CAslaveG.T, self.for_vel[0:3]) - np.dot(CGAmaster, for0_vel[0:3]) - delta_vel_ms[3:6] = np.dot(CAslaveG.T, self.for_vel[3:6]) - np.dot(CGAmaster, for0_vel[3:6]) - # Modify position for inode in range(self.pos.shape[0]): - pos_previous = self.pos[inode,:] + np.zeros((3,),) - self.pos[inode,:] = np.dot(Csm,self.pos[inode,:]) - np.dot(CAslaveG,delta_pos_ms[0:3]) - # self.pos_dot[inode,:] = np.dot(Csm,self.pos_dot[inode,:]) - np.dot(CAslaveG,delta_vel_ms[0:3]) - self.pos_dot[inode,:] = (np.dot(Csm, self.pos_dot[inode,:]) - - np.dot(CAslaveG, delta_vel_ms[0:3]) - - algebra.cross3(self.for_vel[3:6]), self.pos[inode,:]) + - np.dot(Csm, algebra.cross3(for0_vel[3:6], pos_previous))) + vel_master = (self.pos_dot[inode,:] + + for0_vel[0:3] + + algebra.cross3(for0_vel[3:6], self.pos[inode, :])) + self.pos[inode, :] = np.dot(Csm,self.pos[inode,:]) + np.dot(CAslaveG, for0_pos[0:3] - self.for_pos[0:3]) + self.pos_dot[inode, :] = (np.dot(Csm, vel_master) - + self.for_vel[0:3] - + algebra.cross3(self.for_vel[3:6], self.pos[inode,:])) - self.gravity_forces[inode,0:3] = np.dot(Csm, self.gravity_forces[inode,0:3]) - self.gravity_forces[inode,3:6] = np.dot(Csm, self.gravity_forces[inode,3:6]) + self.gravity_forces[inode, 0:3] = np.dot(Csm, self.gravity_forces[inode, 0:3]) + self.gravity_forces[inode, 3:6] = np.dot(Csm, self.gravity_forces[inode, 3:6]) # Modify local rotations for ielem in range(self.psi.shape[0]): for inode in range(3): - psi_previous = self.psi[ielem,inode,:] + np.zeros((3,),) - self.psi[ielem,inode,:] = algebra.rotation2crv(np.dot(Csm,algebra.crv2rotation(self.psi[ielem,inode,:]))) - self.psi_dot[ielem, inode, :] = np.dot(np.dot(algebra.crv2tan(self.psi[ielem,inode,:]),Csm), - (np.dot(algebra.crv2tan(psi_previous).T,self.psi_dot[ielem,inode,:]) - np.dot(CGAmaster.T,delta_vel_ms[3:6]))) + # psi_master = self.psi[ielem, inode, :] + np.zeros((3,),) + # self.psi[ielem, inode, :] = np.dot(Csm, self.psi[ielem, inode, :]) + # self.psi_dot[ielem, inode, :] = (np.dot(Csm, self.psi_dot[ielem, inode, :] + algebra.cross3(for0_vel[3:6], psi_master)) - + # algebra.multiply_matrices(CAslaveG, algebra.skew(self.for_vel[3:6]), CGAmaster, psi_master)) + psi_master = self.psi[ielem,inode,:] + np.zeros((3,),) + self.psi[ielem, inode, :] = algebra.rotation2crv(np.dot(Csm,algebra.crv2rotation(self.psi[ielem,inode,:]))) + psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) + cbam = algebra.crv2rotation(psi_master).T + cbas = algebra.crv2rotation(psi_slave).T + tm = algebra.crv2tan(psi_master) + inv_ts = np.linalg.inv(algebra.crv2tan(psi_slave)) + + self.psi_dot[ielem, inode, :] = np.dot(inv_ts, np.dot(tm, self.psi_dot[ielem, inode, :]) + np.dot(cbam, for0_vel[3:6]) - np.dot(cbas, self.for_vel[3:6])) def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): @@ -792,35 +796,37 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): """ # Define the rotation matrices between the different FoR - CAslaveG = algebra.quat2rotation(self.quat).T - CGAmaster = algebra.quat2rotation(quat0) - Csm = np.dot(CAslaveG, CGAmaster) - - delta_vel_ms = np.zeros((6,)) - delta_pos_ms = self.for_pos[0:3] - for0_pos[0:3] - delta_vel_ms[0:3] = np.dot(CAslaveG.T, self.for_vel[0:3]) - np.dot(CGAmaster, for0_vel[0:3]) - delta_vel_ms[3:6] = np.dot(CAslaveG.T, self.for_vel[3:6]) - np.dot(CGAmaster, for0_vel[3:6]) + CGAslave = algebra.quat2rotation(self.quat) + CAmasterG = algebra.quat2rotation(quat0).T + Cms = np.dot(CAmasterG, CGAslave) for inode in range(self.pos.shape[0]): - pos_previous = self.pos[inode,:] + np.zeros((3,),) - self.pos[inode,:] = (np.dot(np.transpose(Csm),self.pos[inode,:]) + - np.dot(np.transpose(CGAmaster),delta_pos_ms[0:3])) - self.pos_dot[inode,:] = (np.dot(np.transpose(Csm),self.pos_dot[inode,:]) + - np.dot(np.transpose(CGAmaster),delta_vel_ms[0:3]) + - np.dot(Csm.T, algebra.cross3(self.for_vel[3:6], pos_previous)) - - algebra.cross3(for0_vel[3:6], self.pos[inode,:])) - self.gravity_forces[inode,0:3] = np.dot(Csm.T, self.gravity_forces[inode,0:3]) - self.gravity_forces[inode,3:6] = np.dot(Csm.T, self.gravity_forces[inode,3:6]) - # np.cross(np.dot(CGAmaster.T, delta_vel_ms[3:6]), pos_previous)) + vel_slave = (self.pos_dot[inode, :] + + self.for_vel[0:3] + + algebra.cross3(self.for_vel[3:6], self.pos[inode, :])) + self.pos[inode, :] = np.dot(Cms, self.pos[inode,:]) + np.dot(CAmasterG, self.for_pos[0:3] - for0_pos[0:3]) + self.pos_dot[inode, :] = (np.dot(Cms, vel_slave) - + for0_vel[0:3] - + algebra.cross3(for0_vel[3:6], self.pos[inode, :])) + + self.gravity_forces[inode, 0:3] = np.dot(Cms, self.gravity_forces[inode, 0:3]) + self.gravity_forces[inode, 3:6] = np.dot(Cms, self.gravity_forces[inode, 3:6]) for ielem in range(self.psi.shape[0]): for inode in range(3): - psi_previous = self.psi[ielem,inode,:] + np.zeros((3,),) - self.psi[ielem,inode,:] = algebra.rotation2crv(np.dot(Csm.T, algebra.crv2rotation(self.psi[ielem,inode,:]))) - self.psi_dot[ielem, inode, :] = np.dot(algebra.crv2tan(self.psi[ielem,inode,:]), - (np.dot(Csm.T, np.dot(algebra.crv2tan(psi_previous).T, self.psi_dot[ielem, inode, :])) + - np.dot(algebra.quat2rotation(quat0).T, delta_vel_ms[3:6]))) - + # psi_slave = self.psi[ielem,inode,:] + np.zeros((3,),) + # self.psi[ielem, inode, :] = np.dot(Cms, self.psi[ielem, inode, :]) + # self.psi_dot[ielem, inode, :] = (np.dot(Cms, self.psi_dot[ielem, inode, :] + algebra.cross3(self.for_vel[3:6], psi_slave)) - + # algebra.multiply_matrices(CAmasterG, algebra.skew(self.for0_vel[3:6]), CGAslave, psi_slave)) + psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) + self.psi[ielem, inode, :] = algebra.rotation2crv(np.dot(Cms,algebra.crv2rotation(self.psi[ielem,inode,:]))) + psi_master = self.psi[ielem,inode,:] + np.zeros((3,),) + cbam = algebra.crv2rotation(psi_master).T + cbas = algebra.crv2rotation(psi_slave).T + ts = algebra.crv2tan(psi_slave) + inv_tm = np.linalg.inv(algebra.crv2tan(psi_master)) + + self.psi_dot[ielem, inode, :] = np.dot(inv_tm, np.dot(ts, self.psi_dot[ielem, inode, :]) + np.dot(cbas, self.for_vel[3:6]) - np.dot(cbam, for0_vel[3:6])) def whole_structure_to_local_AFoR(self, beam): """ From a7ba6ac9388c8e8cedf9c7b9a0ed5e594f90bbb6 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sat, 3 Apr 2021 21:08:02 +0100 Subject: [PATCH 039/253] improve readability --- sharpy/utils/datastructures.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index 927caff43..d41367c93 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -782,7 +782,9 @@ def change_to_local_AFoR(self, for0_pos, for0_vel, quat0): tm = algebra.crv2tan(psi_master) inv_ts = np.linalg.inv(algebra.crv2tan(psi_slave)) - self.psi_dot[ielem, inode, :] = np.dot(inv_ts, np.dot(tm, self.psi_dot[ielem, inode, :]) + np.dot(cbam, for0_vel[3:6]) - np.dot(cbas, self.for_vel[3:6])) + self.psi_dot[ielem, inode, :] = np.dot(inv_ts, (np.dot(tm, self.psi_dot[ielem, inode, :]) + + np.dot(cbam, for0_vel[3:6]) - + np.dot(cbas, self.for_vel[3:6]))) def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): @@ -826,7 +828,9 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): ts = algebra.crv2tan(psi_slave) inv_tm = np.linalg.inv(algebra.crv2tan(psi_master)) - self.psi_dot[ielem, inode, :] = np.dot(inv_tm, np.dot(ts, self.psi_dot[ielem, inode, :]) + np.dot(cbas, self.for_vel[3:6]) - np.dot(cbam, for0_vel[3:6])) + self.psi_dot[ielem, inode, :] = np.dot(inv_tm, (np.dot(ts, self.psi_dot[ielem, inode, :]) + + np.dot(cbas, self.for_vel[3:6]) - + np.dot(cbam, for0_vel[3:6]))) def whole_structure_to_local_AFoR(self, beam): """ From 616ba3b77050485cd70730a98131fca30c1b2ccd Mon Sep 17 00:00:00 2001 From: Unknown Date: Sat, 3 Apr 2021 21:43:25 +0100 Subject: [PATCH 040/253] fix hinge in constant vel (WIP) --- sharpy/structure/utils/lagrangeconstraints.py | 127 ++++++++++++------ 1 file changed, 89 insertions(+), 38 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 4fecb0ac8..332b70cbd 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -609,7 +609,7 @@ def def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, FoR_body, node_body, node_n # Components to be zero Z = np.zeros((2,3)) Z[:, zero_comp] = np.eye(2) - + Bnh[:, FoR_dof+3:FoR_dof+6] += ag.multiply_matrices(Z, cab.T, node_cga.T, FoR_cga) Bnh[:, node_dof+3:node_dof+6] -= ag.multiply_matrices(Z, ag.crv2tan(psi)) Bnh[:, node_FoR_dof+3:node_FoR_dof+6] -= ag.multiply_matrices(Z, cab.T) @@ -705,7 +705,7 @@ def def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, FoR_body, node_body, node_n return ieq -def def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, rot_axisB, rot_vel, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q): +def def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, nonzero_comp, rot_vel, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q): """ This function generates the stiffness and damping matrices and the independent vector associated to a joint that forces the rotation velocity of a FoR with respect to a node @@ -713,7 +713,7 @@ def def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_number See ``LagrangeConstraints`` for the description of variables Args: - rot_axisB (np.ndarray): Rotation axis with respect to the node B FoR + nonzero_comp (int): Component of the rotation axis with respect to the node B FoR which is non-zero rot_vel (float): Rotation velocity node_number (int): number of the "node" within its own body node_body (int): body number of the "node" @@ -723,43 +723,77 @@ def def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_number FoR_dof (int): position of the first degree of freedom associated to the "FoR" """ + ielem, inode_in_elem = MB_beam[node_body].node_master_elem[node_number] num_LM_eq_specific = 1 Bnh = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') B = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') - ielem, inode_in_elem = MB_beam[node_body].node_master_elem[node_number] - Bnh[:, FoR_dof+3:FoR_dof+6] = ag.multiply_matrices(rot_axisB, - ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, - MB_tstep[node_body].cga().T, - MB_tstep[FoR_body].cga()) + # Simplify notation + cab = ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]) + node_cga = MB_tstep[node_body].cga() + FoR_cga = MB_tstep[FoR_body].cga() + FoR_wa = MB_tstep[FoR_body].for_vel[3:6] + + # Components to be zero + Znon = np.zeros((1,3)) + Znon[:, nonzero_comp] = 1 + + Bnh[:, FoR_dof+3:FoR_dof+6] += ag.multiply_matrices(Znon, cab.T, node_cga.T, FoR_cga) # Constrain angular velocities - LM_Q[:sys_size] += scalingFactor*np.dot(np.transpose(Bnh),Lambda_dot[ieq:ieq+num_LM_eq_specific]) - LM_Q[sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*ag.multiply_matrices(rot_axisB, - ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, - MB_tstep[node_body].cga().T, - MB_tstep[FoR_body].cga(), - MB_tstep[FoR_body].for_vel[3:6]) - scalingFactor*rot_vel + LM_Q[:sys_size] += scalingFactor*np.dot(np.transpose(Bnh), Lambda_dot[ieq:ieq+num_LM_eq_specific]) + LM_Q[sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*ag.multiply_matrices(Znon, cab.T, node_cga.T, FoR_cga, FoR_wa) + LM_Q[sys_size+ieq:sys_size+ieq+num_LM_eq_specific] -= scalingFactor*rot_vel LM_C[sys_size+ieq:sys_size+ieq+num_LM_eq_specific,:sys_size] += scalingFactor*Bnh LM_C[:sys_size,sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*np.transpose(Bnh) - if MB_beam[node_body].FoR_movement == 'free': - LM_C[FoR_dof+3:FoR_dof+6,node_FoR_dof+6:node_FoR_dof+10] += scalingFactor*np.dot(MB_tstep[FoR_body].cga().T, - ag.der_Cquat_by_v(MB_tstep[node_body].quat, - ag.multiply_matrices(ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]), - # rot_axisB.T, - rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific]))) + vec = ag.multiply_matrices(node_cga, cab, Znon.T, Lambda_dot[ieq:ieq+num_LM_eq_specific]) + LM_C[FoR_dof+3:FoR_dof+6, FoR_dof+6:FoR_dof+10] += scalingFactor*ag.der_CquatT_by_v(MB_tstep[FoR_body].quat, vec) - LM_C[FoR_dof+3:FoR_dof+6,FoR_dof+6:FoR_dof+10] += scalingFactor*ag.der_CquatT_by_v(MB_tstep[FoR_body].quat, - ag.multiply_matrices(MB_tstep[node_body].cga(), - ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, - rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific])) + if MB_beam[node_body].FoR_movement == 'free': + vec = ag.multiply_matrices(cab, Znon.T, Lambda_dot[ieq:ieq+num_LM_eq_specific]) + LM_C[FoR_dof+3:FoR_dof+6, node_FoR_dof+6:node_FoR_dof+10] += scalingFactor*ag.multiply_matrices(FoR_cga.T, ag.der_Cquat_by_v(MB_tstep[node_body].quat, vec)) - LM_K[FoR_dof+3:FoR_dof+6,node_dof+3:node_dof+6] += scalingFactor*ag.multiply_matrices(MB_tstep[FoR_body].cga().T, - MB_tstep[node_body].cga(), - ag.der_Ccrv_by_v(MB_tstep[node_body].psi[ielem,inode_in_elem,:], - rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific])) + LM_K[FoR_dof+3:FoR_dof+6, node_dof+3:node_dof+6] += scalingFactor*ag.multiply_matrices(FoR_cga.T, node_cga, ag.der_Ccrv_by_v(MB_tstep[node_body].psi[ielem,inode_in_elem,:], + np.dot(Znon.T, Lambda_dot[ieq:ieq+num_LM_eq_specific]))) + + # Bnh = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') + # B = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') +# + # ielem, inode_in_elem = MB_beam[node_body].node_master_elem[node_number] + # Bnh[:, FoR_dof+3:FoR_dof+6] = ag.multiply_matrices(rot_axisB, + # ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, + # MB_tstep[node_body].cga().T, + # MB_tstep[FoR_body].cga()) +# + # # Constrain angular velocities + # LM_Q[:sys_size] += scalingFactor*np.dot(np.transpose(Bnh),Lambda_dot[ieq:ieq+num_LM_eq_specific]) + # LM_Q[sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*ag.multiply_matrices(rot_axisB, + # ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, + # MB_tstep[node_body].cga().T, + # MB_tstep[FoR_body].cga(), + # MB_tstep[FoR_body].for_vel[3:6]) - scalingFactor*rot_vel +# + # LM_C[sys_size+ieq:sys_size+ieq+num_LM_eq_specific,:sys_size] += scalingFactor*Bnh + # LM_C[:sys_size,sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*np.transpose(Bnh) +# + # if MB_beam[node_body].FoR_movement == 'free': + # LM_C[FoR_dof+3:FoR_dof+6,node_FoR_dof+6:node_FoR_dof+10] += scalingFactor*np.dot(MB_tstep[FoR_body].cga().T, + # ag.der_Cquat_by_v(MB_tstep[node_body].quat, + # ag.multiply_matrices(ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]), + # # rot_axisB.T, + # rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific]))) +# + # LM_C[FoR_dof+3:FoR_dof+6,FoR_dof+6:FoR_dof+10] += scalingFactor*ag.der_CquatT_by_v(MB_tstep[FoR_body].quat, + # ag.multiply_matrices(MB_tstep[node_body].cga(), + # ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, + # rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific])) +# + # LM_K[FoR_dof+3:FoR_dof+6,node_dof+3:node_dof+6] += scalingFactor*ag.multiply_matrices(MB_tstep[FoR_body].cga().T, + # MB_tstep[node_body].cga(), + # ag.der_Ccrv_by_v(MB_tstep[node_body].psi[ielem,inode_in_elem,:], + # rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific])) ieq += 1 return ieq @@ -862,9 +896,10 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.rot_dir = 'z' self.zero_comp = np.array([0, 1], dtype=int) else: - self.rot_dir = 'general' - self.indep = [] - + raise NotImplementedError + #self.rot_dir = 'general' + #self.indep = [] + return self._ieq + self._n_eq def staticmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, @@ -928,12 +963,28 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.node_number = MBdict_entry['node_in_body'] self.node_body = MBdict_entry['body'] self.FoR_body = MBdict_entry['body_FoR'] - self.rot_vect = MBdict_entry['rot_vect'] + # self.rot_vect = + self.rot_axisB = ag.unit_vector(MBdict_entry['rot_vect']) + self.rot_vel = np.linalg.norm(MBdict_entry['rot_vect']) self._ieq = ieq self.indep = [] self.scalingFactor = set_value_or_default(MBdict_entry, "scalingFactor", 1.) self.penaltyFactor = set_value_or_default(MBdict_entry, "penaltyFactor", 0.) + if (self.rot_axisB[[1, 2]] == 0).all(): + self.rot_dir = 'x' + self.zero_comp = np.array([1, 2], dtype=int) + self.nozero_comp = 0 + elif (self.rot_axisB[[0, 2]] == 0).all(): + self.rot_dir = 'y' + self.zero_comp = np.array([0, 2], dtype=int) + self.nozero_comp = 1 + elif (self.rot_axisB[[0, 1]] == 0).all(): + self.rot_dir = 'z' + self.zero_comp = np.array([0, 1], dtype=int) + self.nozero_comp = 2 + else: + raise NotImplementedError # self.static_constraint = fully_constrained_node_FoR() # self.static_constraint.initialise(MBdict_entry, ieq) @@ -955,9 +1006,9 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, # Define the equations # ieq = equal_pos_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) - ieq = def_rot_vect_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_vect, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) - # ieq = def_rot_axis_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_axisB, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, self.indep) - # ieq = def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_axisB, self.rot_vel, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + # ieq = def_rot_vect_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_vect, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_axisB, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, self.zero_comp) + ieq = def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.nonzero_comp, self.rot_vel, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) return def staticpost(self, lc_list, MB_beam, MB_tstep): @@ -965,7 +1016,7 @@ def staticpost(self, lc_list, MB_beam, MB_tstep): def dynamicpost(self, lc_list, MB_beam, MB_tstep): MB_tstep[self.FoR_body].for_pos[0:3] = np.dot(MB_tstep[self.node_body].cga(), MB_tstep[self.node_body].pos[self.node_number,:]) + MB_tstep[self.node_body].for_pos[0:3] - + ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] node_cga = MB_tstep[self.node_body].cga() cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem,inode_in_elem,:]) @@ -974,8 +1025,8 @@ def dynamicpost(self, lc_list, MB_beam, MB_tstep): rot_vect_A = ag.multiply_matrices(FoR_cga.T, node_cga, cab, - self.rot_vect) - + self.rot_vect) + MB_tstep[self.FoR_body].for_vel[3:6] = rot_vect_A.copy() return From 75d8e3e08f8f21dc157b7b623893861fad6af88d Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 5 Apr 2021 11:54:43 +0100 Subject: [PATCH 041/253] wip review line 967 --- sharpy/structure/utils/lagrangeconstraints.py | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 332b70cbd..1e2df4acf 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -965,7 +965,7 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.FoR_body = MBdict_entry['body_FoR'] # self.rot_vect = self.rot_axisB = ag.unit_vector(MBdict_entry['rot_vect']) - self.rot_vel = np.linalg.norm(MBdict_entry['rot_vect']) + self.rot_vel = -np.linalg.norm(MBdict_entry['rot_vect']) self._ieq = ieq self.indep = [] self.scalingFactor = set_value_or_default(MBdict_entry, "scalingFactor", 1.) @@ -974,15 +974,15 @@ def initialise(self, MBdict_entry, ieq, print_info=True): if (self.rot_axisB[[1, 2]] == 0).all(): self.rot_dir = 'x' self.zero_comp = np.array([1, 2], dtype=int) - self.nozero_comp = 0 + self.nonzero_comp = 0 elif (self.rot_axisB[[0, 2]] == 0).all(): self.rot_dir = 'y' self.zero_comp = np.array([0, 2], dtype=int) - self.nozero_comp = 1 + self.nonzero_comp = 1 elif (self.rot_axisB[[0, 1]] == 0).all(): self.rot_dir = 'z' self.zero_comp = np.array([0, 1], dtype=int) - self.nozero_comp = 2 + self.nonzero_comp = 2 else: raise NotImplementedError # self.static_constraint = fully_constrained_node_FoR() @@ -1017,17 +1017,17 @@ def staticpost(self, lc_list, MB_beam, MB_tstep): def dynamicpost(self, lc_list, MB_beam, MB_tstep): MB_tstep[self.FoR_body].for_pos[0:3] = np.dot(MB_tstep[self.node_body].cga(), MB_tstep[self.node_body].pos[self.node_number,:]) + MB_tstep[self.node_body].for_pos[0:3] - ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] - node_cga = MB_tstep[self.node_body].cga() - cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem,inode_in_elem,:]) - FoR_cga = MB_tstep[self.FoR_body].cga() + # ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] + # node_cga = MB_tstep[self.node_body].cga() + # cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem,inode_in_elem,:]) + # FoR_cga = MB_tstep[self.FoR_body].cga() - rot_vect_A = ag.multiply_matrices(FoR_cga.T, - node_cga, - cab, - self.rot_vect) + # rot_vect_A = ag.multiply_matrices(FoR_cga.T, + # node_cga, + # cab, + # self.rot_vect) - MB_tstep[self.FoR_body].for_vel[3:6] = rot_vect_A.copy() + # MB_tstep[self.FoR_body].for_vel[3:6] = rot_vect_A.copy() return From 866f273fe5eb98f6c8347c096f47d830f144448f Mon Sep 17 00:00:00 2001 From: Unknown Date: Mon, 5 Apr 2021 13:22:15 +0100 Subject: [PATCH 042/253] raise NotImplementedError for penalty method --- sharpy/structure/utils/lagrangeconstraints.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 1e2df4acf..80bbb666f 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -1805,7 +1805,11 @@ def initialize_constraints(MBdict): # Read the dictionary and create the constraints for iconstraint in range(num_constraints): lc_list.append(lc_from_string(MBdict["constraint_%02d" % iconstraint]['behaviour'])()) - index_eq = lc_list[-1].initialise(MBdict["constraint_%02d" % iconstraint], index_eq) + MBdict_entry = MBdict["constraint_%02d" % iconstraint] + if "penaltyFactor" in MBdict_entry.keys(): + if not MBdict_entry['penaltyFactor'] == 0.: + raise NotImplementedError("Penalty method not completely implemented for Lagrange Constraints") + index_eq = lc_list[-1].initialise(MBdict_entry, index_eq) return lc_list From 37d5414cef368f5663f12e4f9e29f4e6acc9e912 Mon Sep 17 00:00:00 2001 From: Unknown Date: Mon, 5 Apr 2021 13:44:56 +0100 Subject: [PATCH 043/253] Include NotImplementedError and warnings --- sharpy/structure/utils/lagrangeconstraints.py | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 80bbb666f..4bbcfc5e4 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -246,7 +246,11 @@ def equal_pos_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, inode_in_body, no node_dof (int): position of the first degree of freedom associated to the "node" FoR_body (int): body number of the "FoR" FoR_dof (int): position of the first degree of freedom associated to the "FoR" + + Note: this equation constitutes a holonomic constraint which is not currently supported. Check ``equal_lin_vel_node_FoR`` """ + cout.cout_wrap("WARNING: this equation constitutes a holonomic constraint which is not currently supported. Check ``equal_lin_vel_node_FoR``", 3) + num_LM_eq_specific = 3 Bnh = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') B = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') @@ -426,7 +430,10 @@ def def_rot_axis_FoR_wrt_node_general(MB_tstep, MB_beam, FoR_body, node_body, no node_dof (int): position of the first degree of freedom associated to the "node" FoR_body (int): body number of the "FoR" FoR_dof (int): position of the first degree of freedom associated to the "FoR" + + Notes: this function is missing the contribution of the rotation velocity of the reference node. See ``def_rot_axis_FoR_wrt_node_general`` """ + cout.cout_wrap("WARNING: this function is missing the contribution of the rotation velocity of the reference node. See ``def_rot_axis_FoR_wrt_node_general``", 3) ielem, inode_in_elem = MB_beam[node_body].node_master_elem[node_number] @@ -896,7 +903,7 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.rot_dir = 'z' self.zero_comp = np.array([0, 1], dtype=int) else: - raise NotImplementedError + raise NotImplementedError("Hinges should be parallel to the xB, yB or zB of the reference node") #self.rot_dir = 'general' #self.indep = [] @@ -963,9 +970,7 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.node_number = MBdict_entry['node_in_body'] self.node_body = MBdict_entry['body'] self.FoR_body = MBdict_entry['body_FoR'] - # self.rot_vect = self.rot_axisB = ag.unit_vector(MBdict_entry['rot_vect']) - self.rot_vel = -np.linalg.norm(MBdict_entry['rot_vect']) self._ieq = ieq self.indep = [] self.scalingFactor = set_value_or_default(MBdict_entry, "scalingFactor", 1.) @@ -984,7 +989,9 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.zero_comp = np.array([0, 1], dtype=int) self.nonzero_comp = 2 else: - raise NotImplementedError + raise NotImplementedError("Hinges should be parallel to the xB, yB or zB of the reference node") + self.rot_vel = MBdict_entry['rot_vect'][self.nonzero_comp] + # self.static_constraint = fully_constrained_node_FoR() # self.static_constraint.initialise(MBdict_entry, ieq) From c1bad64c45a1c32b2f1e545c26e2d5577b792e84 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 5 Apr 2021 15:41:16 +0100 Subject: [PATCH 044/253] stride savedata and pickledata --- sharpy/postproc/pickledata.py | 7 ++ sharpy/postproc/savedata.py | 183 +++++++++++++++++----------------- 2 files changed, 101 insertions(+), 89 deletions(-) diff --git a/sharpy/postproc/pickledata.py b/sharpy/postproc/pickledata.py index 99f2ca55c..33e0df30d 100644 --- a/sharpy/postproc/pickledata.py +++ b/sharpy/postproc/pickledata.py @@ -48,6 +48,13 @@ def __init__(self): def initialise(self, data, custom_settings=None, caller=None): self.data = data + if custom_settings is None: + self.settings = data.settings[self.solver_id] + else: + self.settings = custom_settings + + settings.to_custom_types(self.settings, + self.settings_types, self.settings_default) self.folder = data.output_folder self.filename = self.folder + self.data.settings['SHARPy']['case']+'.pkl' diff --git a/sharpy/postproc/savedata.py b/sharpy/postproc/savedata.py index f72eaa4d2..26913cf0a 100644 --- a/sharpy/postproc/savedata.py +++ b/sharpy/postproc/savedata.py @@ -90,6 +90,10 @@ class SaveData(BaseSolver): settings_description['format'] = 'Save linear state space to hdf5 ``.h5`` or Matlab ``.mat`` format.' settings_options['format'] = ['h5', 'mat'] + settings_types['stride'] = 'int' + settings_default['stride'] = 1 + settings_description['stride'] = 'Number of steps between the execution calls when run online' + settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options=settings_options) @@ -195,101 +199,102 @@ def run(self, online=False): # you need them on uvlm3d # self.data.aero.timestep_info[-1].generate_ctypes_pointers() - if self.settings['format'] == 'h5': - file_exists = os.path.isfile(self.filename) - hdfile = h5py.File(self.filename, 'a') - - if (online and file_exists): - self.save_timestep(self.data, self.settings, self.data.ts, hdfile) - else: - skip_attr_init = copy.deepcopy(self.settings['skip_attr']) - skip_attr_init.append('timestep_info') - - h5utils.add_as_grp(self.data, hdfile, grpname='data', - ClassesToSave=self.ClassesToSave, SkipAttr=skip_attr_init, - compress_float=self.settings['compress_float']) - - if self.settings['save_struct']: - h5utils.add_as_grp(list(), - hdfile['data']['structure'], - grpname='timestep_info') - if self.settings['save_aero']: - h5utils.add_as_grp(list(), - hdfile['data']['aero'], - grpname='timestep_info') - - for it in range(len(self.data.structure.timestep_info)): - tstep_p = self.data.structure.timestep_info[it] - if tstep_p is not None: - self.save_timestep(self.data, self.settings, it, hdfile) - - hdfile.close() + if ((online and (self.data.ts % self.settings['stride'] == 0)) or (not online)): + if self.settings['format'] == 'h5': + file_exists = os.path.isfile(self.filename) + hdfile = h5py.File(self.filename, 'a') - if self.settings['save_linear_uvlm']: - linhdffile = h5py.File(self.filename.replace('.data.h5', '.uvlmss.h5'), 'a') - h5utils.add_as_grp(self.data.linear.linear_system.uvlm.ss, linhdffile, grpname='ss', - ClassesToSave=self.ClassesToSave, SkipAttr=self.settings['skip_attr'], - compress_float=self.settings['compress_float']) - h5utils.add_as_grp(self.data.linear.linear_system.linearisation_vectors, linhdffile, - grpname='linearisation_vectors', - ClassesToSave=self.ClassesToSave, SkipAttr=self.settings['skip_attr'], - compress_float=self.settings['compress_float']) - linhdffile.close() + if (online and file_exists): + self.save_timestep(self.data, self.settings, self.data.ts, hdfile) + else: + skip_attr_init = copy.deepcopy(self.settings['skip_attr']) + skip_attr_init.append('timestep_info') - if self.settings['save_linear']: - with h5py.File(self.filename_linear, 'a') as linfile: - h5utils.add_as_grp(self.data.linear.linear_system.linearisation_vectors, linfile, - grpname='linearisation_vectors', + h5utils.add_as_grp(self.data, hdfile, grpname='data', + ClassesToSave=self.ClassesToSave, SkipAttr=skip_attr_init, + compress_float=self.settings['compress_float']) + + if self.settings['save_struct']: + h5utils.add_as_grp(list(), + hdfile['data']['structure'], + grpname='timestep_info') + if self.settings['save_aero']: + h5utils.add_as_grp(list(), + hdfile['data']['aero'], + grpname='timestep_info') + + for it in range(len(self.data.structure.timestep_info)): + tstep_p = self.data.structure.timestep_info[it] + if tstep_p is not None: + self.save_timestep(self.data, self.settings, it, hdfile) + + hdfile.close() + + if self.settings['save_linear_uvlm']: + linhdffile = h5py.File(self.filename.replace('.data.h5', '.uvlmss.h5'), 'a') + h5utils.add_as_grp(self.data.linear.linear_system.uvlm.ss, linhdffile, grpname='ss', ClassesToSave=self.ClassesToSave, SkipAttr=self.settings['skip_attr'], compress_float=self.settings['compress_float']) - h5utils.add_as_grp(self.data.linear.ss, linfile, grpname='ss', + h5utils.add_as_grp(self.data.linear.linear_system.linearisation_vectors, linhdffile, + grpname='linearisation_vectors', ClassesToSave=self.ClassesToSave, SkipAttr=self.settings['skip_attr'], compress_float=self.settings['compress_float']) - - if self.settings['save_rom']: - try: - for k, rom in self.data.linear.linear_system.uvlm.rom.items(): - rom.save(self.filename.replace('.data.h5', '_{:s}.rom.h5'.format(k.lower()))) - except AttributeError: - cout.cout_wrap('Could not locate a reduced order model to save') - - elif self.settings['format'] == 'mat': - from scipy.io import savemat - if self.settings['save_linear']: - # reference-forces - linearisation_vectors = self.data.linear.linear_system.linearisation_vectors - - matfilename = self.filename.replace('.data.h5', '.linss.mat') - A, B, C, D = self.data.linear.ss.get_mats() - savedict = {'A': A, - 'B': B, - 'C': C, - 'D': D} - for k, v in linearisation_vectors.items(): - savedict[k] = v - try: - dt = self.data.linear.ss.dt - savedict['dt'] = dt - except AttributeError: - pass - savemat(matfilename, savedict) - - if self.settings['save_linear_uvlm']: - matfilename = self.filename.replace('.data.h5', '.uvlmss.mat') - linearisation_vectors = self.data.linear.linear_system.uvlm.linearisation_vectors - A, B, C, D = self.data.linear.linear_system.uvlm.ss.get_mats() - savedict = {'A': A, - 'B': B, - 'C': C, - 'D': D} - for k, v in linearisation_vectors.items(): - savedict[k] = v - try: - dt = self.data.linear.ss.dt - savedict['dt'] = dt - except AttributeError: - pass - savemat(matfilename, savedict) + linhdffile.close() + + if self.settings['save_linear']: + with h5py.File(self.filename_linear, 'a') as linfile: + h5utils.add_as_grp(self.data.linear.linear_system.linearisation_vectors, linfile, + grpname='linearisation_vectors', + ClassesToSave=self.ClassesToSave, SkipAttr=self.settings['skip_attr'], + compress_float=self.settings['compress_float']) + h5utils.add_as_grp(self.data.linear.ss, linfile, grpname='ss', + ClassesToSave=self.ClassesToSave, SkipAttr=self.settings['skip_attr'], + compress_float=self.settings['compress_float']) + + if self.settings['save_rom']: + try: + for k, rom in self.data.linear.linear_system.uvlm.rom.items(): + rom.save(self.filename.replace('.data.h5', '_{:s}.rom.h5'.format(k.lower()))) + except AttributeError: + cout.cout_wrap('Could not locate a reduced order model to save') + + elif self.settings['format'] == 'mat': + from scipy.io import savemat + if self.settings['save_linear']: + # reference-forces + linearisation_vectors = self.data.linear.linear_system.linearisation_vectors + + matfilename = self.filename.replace('.data.h5', '.linss.mat') + A, B, C, D = self.data.linear.ss.get_mats() + savedict = {'A': A, + 'B': B, + 'C': C, + 'D': D} + for k, v in linearisation_vectors.items(): + savedict[k] = v + try: + dt = self.data.linear.ss.dt + savedict['dt'] = dt + except AttributeError: + pass + savemat(matfilename, savedict) + + if self.settings['save_linear_uvlm']: + matfilename = self.filename.replace('.data.h5', '.uvlmss.mat') + linearisation_vectors = self.data.linear.linear_system.uvlm.linearisation_vectors + A, B, C, D = self.data.linear.linear_system.uvlm.ss.get_mats() + savedict = {'A': A, + 'B': B, + 'C': C, + 'D': D} + for k, v in linearisation_vectors.items(): + savedict[k] = v + try: + dt = self.data.linear.ss.dt + savedict['dt'] = dt + except AttributeError: + pass + savemat(matfilename, savedict) return self.data From 1ae4482c1b63846f7de596c9bf7d5495abd18328 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 6 Apr 2021 11:44:55 +0100 Subject: [PATCH 045/253] include cd multiplier --- sharpy/generators/floatingforces.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index c3f558e8d..758f41972 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -442,6 +442,10 @@ class FloatingForces(generator_interface.BaseGenerator): settings_default['floating_file_name'] = './oc3.floating.h5' settings_description['floating_file_name'] = 'File containing the information about the floating dynamics' + settings_types['cd_multiplier'] = 'float' + settings_default['cd_multiplier'] = 1. + settings_description['cd_multiplier'] = 'Multiply the drag coefficient by this number to increase dissipation' + settings_types['method_matrices_freq'] = 'str' settings_default['method_matrices_freq'] = 'constant' settings_description['method_matrices_freq'] = 'Method to compute frequency-dependent matrices' @@ -566,6 +570,8 @@ def initialise(self, in_dict=None, data=None): self.buoy_rest_mat = self.floating_data['hydrostatics']['buoyancy_restoring_matrix'] # hydrodynamics + self.cd = self.floating_data['hydrodynamics']['CD']*self.settings['cd_multiplier'] + if self.settings['method_matrices_freq'] == 'constant': self.hd_added_mass_const = interp_1st_dim_matrix(self.floating_data['hydrodynamics']['added_mass_matrix'], self.floating_data['hydrodynamics']['ab_freq_rads'], @@ -825,7 +831,7 @@ def generate(self, params): drag_force = (-0.5*self.water_density*np.linalg.norm(vel_g)*vel_g*delta_x* self.floating_data['hydrodynamics']['spar_diameter']* - self.floating_data['hydrodynamics']['CD']) + self.cd) struct_tstep.runtime_generated_forces[inode, 0:3] += np.dot(cbg, drag_force) From 186bd689896f6a136da63c1382c6752b542bf860 Mon Sep 17 00:00:00 2001 From: Unknown Date: Tue, 6 Apr 2021 13:24:02 +0100 Subject: [PATCH 046/253] remove commented lines --- sharpy/solvers/dynamiccoupled.py | 7 ------- 1 file changed, 7 deletions(-) diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index fb6a71a8c..320eb26ca 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -493,12 +493,6 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): structural_kstep, aero_kstep = self.process_controller_output( state) - # print(structural_kstep.quat) - # print(structural_kstep.for_vel) - # print(structural_kstep.for_acc) - # print(self.data.structure.dynamic_input[self.data.ts - 1]['for_vel']) - # print(self.data.structure.dynamic_input[self.data.ts - 1]['for_acc']) - # compute unsteady contribution force_coeff = 0.0 unsteady_contribution = False @@ -592,7 +586,6 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): structural_kstep, force_coeff) - # print(structural_kstep.steady_applied_forces[:, -1]) # relaxation relax_factor = self.relaxation_factor(k) relax(self.data.structure, From a2fad7fea72dfaf82049b67be70251cf610ce805 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 6 Apr 2021 13:36:22 +0100 Subject: [PATCH 047/253] include missing line from merge --- sharpy/generators/floatingforces.py | 1 + 1 file changed, 1 insertion(+) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 7c7bc7fc3..4d73f4269 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -597,6 +597,7 @@ def initialise(self, in_dict=None, data=None): # hydrodynamics self.cd = self.floating_data['hydrodynamics']['CD']*self.settings['cd_multiplier'] + if self.settings['method_matrices_freq'] == 'constant': # self.hd_added_mass_const = interp_1st_dim_matrix(self.floating_data['hydrodynamics']['added_mass_matrix'], # self.floating_data['hydrodynamics']['ab_freq_rads'], # self.settings['matrices_freq']) From 7747c86f43738275bbebbecd5bfdaef5aafcfeaf Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 6 Apr 2021 13:36:38 +0100 Subject: [PATCH 048/253] rm penalty test --- .../multibody/double_pendulum/test_double_pendulum_geradin.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tests/coupled/multibody/double_pendulum/test_double_pendulum_geradin.py b/tests/coupled/multibody/double_pendulum/test_double_pendulum_geradin.py index 2783b8b71..df6ae53db 100644 --- a/tests/coupled/multibody/double_pendulum/test_double_pendulum_geradin.py +++ b/tests/coupled/multibody/double_pendulum/test_double_pendulum_geradin.py @@ -267,7 +267,7 @@ def setUp(self): LC1.body_FoR = 0 LC1.rot_axis_AFoR = np.array([0.0,1.0,0.0]) LC1.scalingFactor = 1e6 - LC1.penaltyFactor = 1e-12 + LC1.penaltyFactor = 0. LC2 = gc.LagrangeConstraint() LC2.behaviour = 'hinge_node_FoR' @@ -276,7 +276,7 @@ def setUp(self): LC2.body_FoR = 1 LC2.rot_axisB = np.array([0.0,1.0,0.0]) LC2.scalingFactor = 1e6 - LC2.penaltyFactor = 1e-12 + LC2.penaltyFactor = 0. LC = [] LC.append(LC1) From a8d7e8736f9cb31637c0c0389279929b1caf0f4d Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 7 Apr 2021 17:42:06 +0100 Subject: [PATCH 049/253] fix interpolation --- sharpy/generators/floatingforces.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 4d73f4269..9b39dd07e 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -658,7 +658,10 @@ def initialise(self, in_dict=None, data=None): interp_x1 = interp1d(self.floating_data['wave_forces']['xi_freq_rads'], self.floating_data['wave_forces']['xi'], - axis=0) + axis=0, + bounds_error=False, + fill_value=(self.floating_data['wave_forces']['xi'][0, ...], + self.floating_data['wave_forces']['xi'][-1, ...])) xi_matrix2 = interp_x1(self.settings['wave_freq']) # xi_matrix2 = interp_x1(self.floating_data['wave_forces']['xi_freq_rads'][2:4]) interp_x2 = interp1d(self.floating_data['wave_forces']['xi_beta_deg']*deg2rad, From e5dc0a834cae44264067f8cfa0ef7fae82c28a8f Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 8 Apr 2021 17:01:29 +0100 Subject: [PATCH 050/253] include forces option and fix quat --- sharpy/solvers/initialaeroelasticloader.py | 22 ++++++++++++++++------ 1 file changed, 16 insertions(+), 6 deletions(-) diff --git a/sharpy/solvers/initialaeroelasticloader.py b/sharpy/solvers/initialaeroelasticloader.py index 3f530e6ac..94fd0a869 100644 --- a/sharpy/solvers/initialaeroelasticloader.py +++ b/sharpy/solvers/initialaeroelasticloader.py @@ -23,6 +23,10 @@ class InitialAeroelasticLoader(BaseSolver): settings_default['input_file'] = None settings_description['input_file'] = 'Input file containing the simulation data' + settings_types['include_forces'] = 'bool' + settings_default['include_forces'] = True + settings_description['include_forces'] = 'Map the forces' + settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -55,11 +59,14 @@ def run(self, structural_step=None, aero_step=None): # Copy structural information attributes = ['pos', 'pos_dot', 'pos_ddot', 'psi', 'psi_dot', 'psi_ddot', - 'for_pos', 'for_vel', 'for_acc', - 'mb_FoR_pos', 'mb_FoR_vel', 'mb_FoR_acc', 'mb_quat', - 'runtime_generated_forces', + 'for_pos', 'for_vel', 'for_acc', 'quat', + 'mb_FoR_pos', 'mb_FoR_vel', 'mb_FoR_acc', 'mb_quat'] + + if self.settings['include_forces']: + attributes.extend(['runtime_generated_forces', 'steady_applied_forces', - 'unsteady_applied_forces'] + 'unsteady_applied_forces']) + for att in attributes: getattr(structural_step, att)[...] = getattr(self.file_info.structure, att) # structural_step.pos_dot = self.file_info.structure.pos_dot @@ -79,9 +86,12 @@ def run(self, structural_step=None, aero_step=None): # Copy aero information attributes = ['zeta', 'zeta_star', 'normals', 'gamma', 'gamma_star', - 'u_ext', 'u_ext_star', - 'dynamic_forces', 'forces',] + 'u_ext', 'u_ext_star',] # 'dist_to_orig', 'gamma_dot', 'zeta_dot', + + if self.settings['include_forces']: + attributes.extend(['dynamic_forces', 'forces',]) + for att in attributes: for isurf in range(aero_step.n_surf): getattr(aero_step, att)[isurf][...] = getattr(self.file_info.aero, att)[isurf] From 4fbcd0ac4e44f96dc1632a5edd7c5176d278bf58 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 9 Apr 2021 10:26:11 +0100 Subject: [PATCH 051/253] clean up --- sharpy/solvers/nonlineardynamicmultibody.py | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 2b6243114..2ad601f4d 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -343,10 +343,6 @@ def run(self, structural_step=None, dt=None): num_LM_eq = self.num_LM_eq # Initialize - q = np.zeros((self.sys_size + num_LM_eq,), dtype=ct.c_double, order='F') - dqdt = np.zeros((self.sys_size + num_LM_eq,), dtype=ct.c_double, order='F') - dqddt = np.zeros((self.sys_size + num_LM_eq,), dtype=ct.c_double, order='F') - # TODO: i belive this can move into disp_and_accel2 state as self.Lambda, self.Lambda_dot if not num_LM_eq == 0: Lambda = self.Lambda.astype(dtype=ct.c_double, copy=True, order='F') @@ -374,6 +370,7 @@ def run(self, structural_step=None, dt=None): # Update positions and velocities Lambda, Lambda_dot = mb.state2disp_and_accel(q, dqdt, dqddt, MB_beam, MB_tstep, num_LM_eq) + if self.settings['write_lm'] and iteration: self.write_lm_cond_num(iteration, Lambda, Lambda_dot, Lambda_ddot, cond_num, cond_num_lm) From 9901725b984e65ee54cac8eed2dc568cc394e25e Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 12 Apr 2021 11:57:49 +0100 Subject: [PATCH 052/253] fix syntax wave forces --- sharpy/generators/floatingforces.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index cacc0284c..03eed69a3 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -919,4 +919,4 @@ def generate(self, params): # Write output if self.settings['write_output']: self.write_output(data.ts, k, mooring_forces, mooring_yaw, hs_f_g, - hd_f_qdot_g, hd_f_qdotdot_g, hd_correct_grav, wave_forces_g[it, :]) + hd_f_qdot_g, hd_f_qdotdot_g, hd_correct_grav, self.wave_forces_g[data.ts, :]) From f92f40843db4d0a1bebbc329b304ade465ba8297 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 12 Apr 2021 11:59:21 +0100 Subject: [PATCH 053/253] move convergence together --- sharpy/solvers/nonlineardynamicmultibody.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 2ad601f4d..36769976f 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -401,7 +401,15 @@ def run(self, structural_step=None, dt=None): else: LM_res = 0.0 if (res < self.settings['min_delta']) and (LM_res < self.settings['min_delta']): + # if (res < self.settings['min_delta']): converged = True + else: + old_Dq = np.max(np.abs(Dq[0:self.sys_size])) + if old_Dq == 0: + print("old_Dq ==0") + old_Dq = 1. + if num_LM_eq: + LM_old_Dq = np.max(np.abs(Dq[self.sys_size:self.sys_size+num_LM_eq])) # Relaxation relax_Dq = np.zeros_like(Dq) @@ -416,10 +424,6 @@ def run(self, structural_step=None, dt=None): if converged: break - if not iteration: - old_Dq = np.max(np.abs(Dq[0:self.sys_size])) - if num_LM_eq: - LM_old_Dq = np.max(np.abs(Dq[self.sys_size:self.sys_size+num_LM_eq])) Lambda, Lambda_dot = mb.state2disp_and_accel(q, dqdt, dqddt, MB_beam, MB_tstep, num_LM_eq) if self.settings['write_lm']: From 63e7b4ffb2e25c493752af4789b004a84be9071f Mon Sep 17 00:00:00 2001 From: Unknown Date: Mon, 12 Apr 2021 12:45:27 +0100 Subject: [PATCH 054/253] Test skip step multibody --- sharpy/solvers/nonlineardynamicmultibody.py | 26 ++++++++++++++++++++- 1 file changed, 25 insertions(+), 1 deletion(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 36769976f..81355d9e5 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -49,6 +49,10 @@ class NonLinearDynamicMultibody(_BaseStructural): settings_default['relax_factor_lm'] = 0. settings_description['relax_factor_lm'] = 'Relaxation factor for Lagrange Multipliers. 0 no relaxation. 1 full relaxation' + settings_types['allow_skip_step'] = 'bool' + settings_default['allow_skip_step'] = False + settings_description['allow_skip_step'] = 'Allow skip step when NaN is found while solving the system' + settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -361,6 +365,7 @@ def run(self, structural_step=None, dt=None): LM_old_Dq = 1.0 converged = False + skip_step = False for iteration in range(self.settings['max_iterations']): # Check if the maximum of iterations has been reached if iteration == self.settings['max_iterations'] - 1: @@ -395,7 +400,13 @@ def run(self, structural_step=None, dt=None): if iteration: res = np.max(np.abs(Dq[0:self.sys_size]))/old_Dq if np.isnan(res): - raise exc.NotConvergedSolver('Multibody res = NaN') + print(old_Dq) + if self.settings['allow_skip_step']: + skip_step = True + cout.cout_wrap("Skipping step", 3) + break + else: + raise exc.NotConvergedSolver('Multibody Dq = NaN') if num_LM_eq: LM_res = np.max(np.abs(Dq[self.sys_size:self.sys_size+num_LM_eq]))/LM_old_Dq else: @@ -430,6 +441,19 @@ def run(self, structural_step=None, dt=None): self.write_lm_cond_num(iteration, Lambda, Lambda_dot, Lambda_ddot, cond_num, cond_num_lm) # end: comment time stepping + if skip_step: + # Use the original time step + MB_beam, MB_tstep = mb.split_multibody( + self.data.structure, + structural_step, + MBdict, + self.data.ts) + # Perform rigid body motions + self.integrate_position(MB_beam, MB_tstep, dt) + for ibody in range(0, len(MB_tstep)): + Temp = np.linalg.inv(np.eye(4) + 0.25*algebra.quadskew(MB_tstep[ibody].for_vel[3:6])*dt) + MB_tstep[ibody].quat = np.dot(Temp, np.dot(np.eye(4) - 0.25*algebra.quadskew(MB_tstep[ibody].for_vel[3:6])*dt, MB_tstep[ibody].quat)) + # End of Newmark-beta iterations # self.integrate_position(MB_beam, MB_tstep, dt) lagrangeconstraints.postprocess(self.lc_list, MB_beam, MB_tstep, "dynamic") From 719f8f3f8fcc140f5ed93943cb94223bd7cd41fe Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 13 Apr 2021 17:35:31 +0100 Subject: [PATCH 055/253] fix node ordering mb --- sharpy/utils/multibody.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index d25c10634..edd6f09cf 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -259,6 +259,6 @@ def get_elems_nodes_list(beam, ibody): """ int_list = np.arange(0, beam.num_elem, 1) ibody_elements = int_list[beam.body_number == ibody] - ibody_nodes = list(set(beam.connectivities[ibody_elements, :].reshape(-1))) - + ibody_nodes = np.sort(np.unique(beam.connectivities[ibody_elements, :].reshape(-1))) + return ibody_elements, ibody_nodes From a39d80517b9ff1ccb1b91011935b4d3394ecab68 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 15 Apr 2021 19:39:46 +0100 Subject: [PATCH 056/253] do not compute psi_dot_local --- sharpy/solvers/nonlineardynamicmultibody.py | 12 +++- sharpy/utils/datastructures.py | 77 ++++++++++++++++----- 2 files changed, 71 insertions(+), 18 deletions(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 81355d9e5..31997fedc 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -329,11 +329,19 @@ def run(self, structural_step=None, dt=None): else: self.settings['dt'] = dt + if self.data.ts == 1: + compute_psi_local = True + print("Computing psi local") + else: + compute_psi_local = False + if self.data.structure.ini_info.in_global_AFoR: - self.data.structure.ini_info.whole_structure_to_local_AFoR(self.data.structure) + self.data.structure.ini_info.whole_structure_to_local_AFoR(self.data.structure, + compute_psi_local) if structural_step.in_global_AFoR: - structural_step.whole_structure_to_local_AFoR(self.data.structure) + structural_step.whole_structure_to_local_AFoR(self.data.structure, + compute_psi_local) self.num_LM_eq = lagrangeconstraints.define_num_LM_eq(self.lc_list) diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index d41367c93..88b5ad19f 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -525,6 +525,8 @@ class StructTimeStepInfo(object): postproc_cell (dict): Variables associated to cells to be postprocessed postproc_node (dict): Variables associated to nodes to be postprocessed + psi_local (np.ndarray): Cartesian Rotation Vector for each node in each element in local FoR + psi_dot_local (np.ndarray): Time derivative of ``psi`` in the local FoR mb_FoR_pos (np.ndarray): Position of the local A FoR of each body ``[num_bodies x 6]`` mb_FoR_vel (np.ndarray): Velocity of the local A FoR of each body ``[num_bodies x 6]`` mb_FoR_acc (np.ndarray): Acceleration of the local A FoR of each body ``[num_bodies x 6]`` @@ -576,6 +578,8 @@ def __init__(self, num_node, num_elem, num_node_elem=3, num_dof=None, num_bodies self.postproc_node = dict() # Multibody + self.psi_local = np.zeros((self.num_elem, num_node_elem, 3), dtype=ct.c_double, order='F') + self.psi_dot_local = np.zeros((self.num_elem, num_node_elem, 3), dtype=ct.c_double, order='F') self.mb_FoR_pos = np.zeros((num_bodies,6), dtype=ct.c_double, order='F') self.mb_FoR_vel = np.zeros((num_bodies,6), dtype=ct.c_double, order='F') self.mb_FoR_acc = np.zeros((num_bodies,6), dtype=ct.c_double, order='F') @@ -627,7 +631,8 @@ def copy(self): copied.postproc_cell = copy.deepcopy(self.postproc_cell) copied.postproc_node = copy.deepcopy(self.postproc_node) - #if not self.mb_quat is None: + copied.psi_local = self.psi_local.astype(dtype=ct.c_double, order='F', copy=True) + copied.psi_dot_local = self.psi_dot_local.astype(dtype=ct.c_double, order='F', copy=True) copied.mb_FoR_pos = self.mb_FoR_pos.astype(dtype=ct.c_double, order='F', copy=True) copied.mb_FoR_vel = self.mb_FoR_vel.astype(dtype=ct.c_double, order='F', copy=True) copied.mb_FoR_acc = self.mb_FoR_acc.astype(dtype=ct.c_double, order='F', copy=True) @@ -711,7 +716,9 @@ def get_body(self, beam, num_dof_ibody, ibody): ibody_StructTimeStepInfo.pos_ddot = self.pos_ddot[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) ibody_StructTimeStepInfo.psi = self.psi[ibody_elems,:,:].astype(dtype=ct.c_double, order='F', copy=True) + ibody_StructTimeStepInfo.psi_local = self.psi_local[ibody_elems,:,:].astype(dtype=ct.c_double, order='F', copy=True) ibody_StructTimeStepInfo.psi_dot = self.psi_dot[ibody_elems,:,:].astype(dtype=ct.c_double, order='F', copy=True) + ibody_StructTimeStepInfo.psi_dot_local = self.psi_dot_local[ibody_elems,:,:].astype(dtype=ct.c_double, order='F', copy=True) ibody_StructTimeStepInfo.psi_ddot = self.psi_ddot[ibody_elems,:,:].astype(dtype=ct.c_double, order='F', copy=True) ibody_StructTimeStepInfo.steady_applied_forces = self.steady_applied_forces[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) @@ -737,6 +744,28 @@ def get_body(self, beam, num_dof_ibody, ibody): return ibody_StructTimeStepInfo + def compute_psi_local_AFoR(self, for0_pos, for0_vel, quat0): + """ + compute_psi_local_AFoR + + Compute psi and psi_dot in the local A frame of reference + + Args: + for0_pos (np.ndarray): Position of the global A FoR + for0_vel (np.ndarray): Velocity of the global A FoR + quat0 (np.ndarray): Quaternion of the global A FoR + """ + + # Define the rotation matrices between the different FoR + CAslaveG = algebra.quat2rotation(self.quat).T + CGAmaster = algebra.quat2rotation(quat0) + Csm = np.dot(CAslaveG, CGAmaster) + + for ielem in range(self.psi.shape[0]): + for inode in range(3): + self.psi_local[ielem, inode, :] = algebra.rotation2crv(np.dot(Csm,algebra.crv2rotation(self.psi[ielem,inode,:]))) + self.psi_dot_local[ielem, inode, :] = np.zeros((3)) + def change_to_local_AFoR(self, for0_pos, for0_vel, quat0): """ change_to_local_AFoR @@ -774,17 +803,20 @@ def change_to_local_AFoR(self, for0_pos, for0_vel, quat0): # self.psi[ielem, inode, :] = np.dot(Csm, self.psi[ielem, inode, :]) # self.psi_dot[ielem, inode, :] = (np.dot(Csm, self.psi_dot[ielem, inode, :] + algebra.cross3(for0_vel[3:6], psi_master)) - # algebra.multiply_matrices(CAslaveG, algebra.skew(self.for_vel[3:6]), CGAmaster, psi_master)) - psi_master = self.psi[ielem,inode,:] + np.zeros((3,),) - self.psi[ielem, inode, :] = algebra.rotation2crv(np.dot(Csm,algebra.crv2rotation(self.psi[ielem,inode,:]))) - psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) - cbam = algebra.crv2rotation(psi_master).T - cbas = algebra.crv2rotation(psi_slave).T - tm = algebra.crv2tan(psi_master) - inv_ts = np.linalg.inv(algebra.crv2tan(psi_slave)) + + # psi_master = self.psi[ielem,inode,:] + np.zeros((3,),) + # self.psi[ielem, inode, :] = algebra.rotation2crv(np.dot(Csm,algebra.crv2rotation(self.psi[ielem,inode,:]))) + # psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) + # cbam = algebra.crv2rotation(psi_master).T + # cbas = algebra.crv2rotation(psi_slave).T + # tm = algebra.crv2tan(psi_master) + # inv_ts = np.linalg.inv(algebra.crv2tan(psi_slave)) - self.psi_dot[ielem, inode, :] = np.dot(inv_ts, (np.dot(tm, self.psi_dot[ielem, inode, :]) + - np.dot(cbam, for0_vel[3:6]) - - np.dot(cbas, self.for_vel[3:6]))) + # self.psi_dot[ielem, inode, :] = np.dot(inv_ts, (np.dot(tm, self.psi_dot[ielem, inode, :]) + + # np.dot(cbam, for0_vel[3:6]) - + # np.dot(cbas, self.for_vel[3:6]))) + self.psi[ielem, inode, :] = self.psi_local[ielem,inode,:].copy() + self.psi_dot[ielem, inode, :] = self.psi_dot_local[ielem, inode, :].copy() def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): @@ -820,19 +852,26 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): # self.psi[ielem, inode, :] = np.dot(Cms, self.psi[ielem, inode, :]) # self.psi_dot[ielem, inode, :] = (np.dot(Cms, self.psi_dot[ielem, inode, :] + algebra.cross3(self.for_vel[3:6], psi_slave)) - # algebra.multiply_matrices(CAmasterG, algebra.skew(self.for0_vel[3:6]), CGAslave, psi_slave)) - psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) + + + self.psi_local[ielem, inode, :] = self.psi[ielem, inode, :].copy() # Copy here the result from the structural computation + self.psi_dot_local[ielem, inode, :] = self.psi_dot[ielem, inode, :].copy() # Copy here the result from the structural computation + + # psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) self.psi[ielem, inode, :] = algebra.rotation2crv(np.dot(Cms,algebra.crv2rotation(self.psi[ielem,inode,:]))) + + # Convert psi_dot_local to psi_dot to be used by the rest of the code psi_master = self.psi[ielem,inode,:] + np.zeros((3,),) cbam = algebra.crv2rotation(psi_master).T - cbas = algebra.crv2rotation(psi_slave).T - ts = algebra.crv2tan(psi_slave) + cbas = algebra.crv2rotation(self.psi_local[ielem, inode, :]).T + ts = algebra.crv2tan(self.psi_local[ielem, inode, :]) inv_tm = np.linalg.inv(algebra.crv2tan(psi_master)) - self.psi_dot[ielem, inode, :] = np.dot(inv_tm, (np.dot(ts, self.psi_dot[ielem, inode, :]) + + self.psi_dot[ielem, inode, :] = np.dot(inv_tm, (np.dot(ts, self.psi_dot_local[ielem, inode, :]) + np.dot(cbas, self.for_vel[3:6]) - np.dot(cbam, for0_vel[3:6]))) - def whole_structure_to_local_AFoR(self, beam): + def whole_structure_to_local_AFoR(self, beam, compute_psi_local=False): """ Same as change_to_local_AFoR but for a multibody structure @@ -853,6 +892,8 @@ def whole_structure_to_local_AFoR(self, beam): for ibody in range(beam.num_bodies): MB_beam[ibody] = beam.get_body(ibody = ibody) MB_tstep[ibody] = self.get_body(beam, MB_beam[ibody].num_dof, ibody = ibody) + if compute_psi_local: + MB_tstep[ibody].compute_psi_local_AFoR(for0_pos, for0_vel, quat0) MB_tstep[ibody].change_to_local_AFoR(for0_pos, for0_vel, quat0) first_dof = 0 @@ -864,10 +905,12 @@ def whole_structure_to_local_AFoR(self, beam): # Merge tstep self.pos[ibody_nodes,:] = MB_tstep[ibody].pos.astype(dtype=ct.c_double, order='F', copy=True) self.psi[ibody_elems,:,:] = MB_tstep[ibody].psi.astype(dtype=ct.c_double, order='F', copy=True) + self.psi_local[ibody_elems,:,:] = MB_tstep[ibody].psi_local.astype(dtype=ct.c_double, order='F', copy=True) self.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) self.pos_dot[ibody_nodes,:] = MB_tstep[ibody].pos_dot.astype(dtype=ct.c_double, order='F', copy=True) self.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) + self.psi_dot_local[ibody_elems,:,:] = MB_tstep[ibody].psi_dot_local.astype(dtype=ct.c_double, order='F', copy=True) # TODO: Do I need a change in FoR for the following variables? Maybe for the FoR ones. # tstep.forces_constraints_nodes[ibody_nodes,:] = MB_tstep[ibody].forces_constraints_nodes.astype(dtype=ct.c_double, order='F', copy=True) @@ -906,11 +949,13 @@ def whole_structure_to_global_AFoR(self, beam): # Merge tstep self.pos[ibody_nodes,:] = MB_tstep[ibody].pos.astype(dtype=ct.c_double, order='F', copy=True) self.psi[ibody_elems,:,:] = MB_tstep[ibody].psi.astype(dtype=ct.c_double, order='F', copy=True) + self.psi_local[ibody_elems,:,:] = MB_tstep[ibody].psi_local.astype(dtype=ct.c_double, order='F', copy=True) self.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) self.pos_dot[ibody_nodes,:] = MB_tstep[ibody].pos_dot.astype(dtype=ct.c_double, order='F', copy=True) self.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) + self.psi_dot_local[ibody_elems,:,:] = MB_tstep[ibody].psi_dot_local.astype(dtype=ct.c_double, order='F', copy=True) def nodal_b_for_2_a_for(self, nodal, beam, filter=np.array([True]*6), ibody=None): From c4768d9f14209156ba8d012cbac8263c69b3b48f Mon Sep 17 00:00:00 2001 From: Unknown Date: Thu, 15 Apr 2021 09:59:40 +0100 Subject: [PATCH 057/253] fix k=0 dynamiccoupled --- sharpy/solvers/dynamiccoupled.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 320eb26ca..f2a0e76cf 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -493,6 +493,7 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): structural_kstep, aero_kstep = self.process_controller_output( state) + k = 0 # compute unsteady contribution force_coeff = 0.0 unsteady_contribution = False @@ -523,7 +524,6 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): controlled_structural_kstep = structural_kstep.copy() controlled_aero_kstep = aero_kstep.copy() - k = 0 for k in range(self.settings['fsi_substeps'] + 1): if (k == self.settings['fsi_substeps'] and self.settings['fsi_substeps']): From fd87f1c640bce09ee6895ec461ab7c4cbae2b909 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 16 Apr 2021 09:19:59 +0100 Subject: [PATCH 058/253] multibody for single body --- sharpy/solvers/nonlineardynamicmultibody.py | 5 +++-- sharpy/utils/multibody.py | 5 +++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 31997fedc..67aeba4c5 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -361,8 +361,9 @@ def run(self, structural_step=None, dt=None): Lambda_dot = self.Lambda_dot.astype(dtype=ct.c_double, copy=True, order='F') Lambda_ddot = self.Lambda_ddot.astype(dtype=ct.c_double, copy=True, order='F') else: - Lambda = 0 - Lambda_dot = 0 + Lambda = np.zeros((1,)) + Lambda_dot = np.zeros((1,)) + Lambda_ddot = np.zeros((1,)) # Predictor step q, dqdt, dqddt = mb.disp_and_accel2state(MB_beam, MB_tstep, Lambda, Lambda_dot, self.sys_size, num_LM_eq) diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index edd6f09cf..3f723d52d 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -185,8 +185,9 @@ def disp_and_accel2state(MB_beam, MB_tstep, Lambda, Lambda_dot, sys_size, num_LM dqddt[first_dof+ibody_num_dof+6:first_dof+ibody_num_dof+10]=dquatdt.astype(dtype=ct.c_double, order='F', copy=True) first_dof += ibody_num_dof + 10 - q[first_dof:] = Lambda.astype(dtype=ct.c_double, order='F', copy=True) - dqdt[first_dof:] = Lambda_dot.astype(dtype=ct.c_double, order='F', copy=True) + if num_LM_eq > 0: + q[first_dof:] = Lambda.astype(dtype=ct.c_double, order='F', copy=True) + dqdt[first_dof:] = Lambda_dot.astype(dtype=ct.c_double, order='F', copy=True) return q, dqdt, dqddt From f1b3de77a7e6d2eb679ba0cf3c38517256d8b312 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 19 Apr 2021 09:19:24 +0100 Subject: [PATCH 059/253] include force coeff in other forces --- sharpy/generators/floatingforces.py | 30 ++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 03eed69a3..b530de807 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -811,7 +811,7 @@ def generate(self, params): horizontal_unit_vec = algebra.unit_vector(fl_to_anchor_G) horizontal_unit_vec[0] = 0. horizontal_unit_vec = algebra.unit_vector(horizontal_unit_vec) - force_fl = hf*horizontal_unit_vec + vf*np.array([-1., 0., 0.]) + force_fl = force_coeff*hf*horizontal_unit_vec + vf*np.array([-1., 0., 0.]) # Move the forces to the mooring node force_cl = np.zeros((6,)) @@ -826,12 +826,12 @@ def generate(self, params): # Yaw moment generated by the mooring system yaw = np.array([self.q[data.ts, 3], 0., 0.]) - mooring_yaw = -self.floating_data['mooring']['yaw_spring_stif']*yaw + mooring_yaw = -force_coeff*self.floating_data['mooring']['yaw_spring_stif']*yaw struct_tstep.runtime_generated_forces[self.mooring_node, 3:6] += np.dot(cbg, mooring_yaw) # Hydrostatic model - hs_f_g = self.buoy_F0 - np.dot(self.buoy_rest_mat, self.q[data.ts, :]) + hs_f_g = self.buoy_F0 - force_coeff*np.dot(self.buoy_rest_mat, self.q[data.ts, :]) if not force_coeff == 0.: hd_f_qdot_g = -np.dot(self.floating_data['hydrodynamics']['additional_damping'], self.qdot[data.ts, :]) @@ -857,22 +857,22 @@ def generate(self, params): else: cout.cout_wrap(("ERROR: Unknown method_matrices_freq %s" % self.settings['method_matrices_freq']), 4) - - # Correct gravity forces if needed - if self.added_mass_in_mass_matrix: - # Correct unreal gravity forces from added mass - gravity_b = np.zeros((6,),) - gravity_b[0:3] = np.dot(cbg, -self.settings['gravity_dir'])*self.settings['gravity'] - hd_correct_grav = -np.dot(self.hd_added_mass_const, gravity_b) - struct_tstep.runtime_generated_forces[self.buoyancy_node, :] += hd_correct_grav - else: - hd_correct_grav = np.zeros((6)) - + else: hd_f_qdot_g = np.zeros((6)) hd_f_qdotdot_g = np.zeros((6)) hd_correct_grav = np.zeros((6)) + # Correct gravity forces if needed + if self.added_mass_in_mass_matrix: + # Correct unreal gravity forces from added mass + gravity_b = np.zeros((6,),) + gravity_b[0:3] = np.dot(cbg, -self.settings['gravity_dir'])*self.settings['gravity'] + hd_correct_grav = -np.dot(self.hd_added_mass_const, gravity_b) + struct_tstep.runtime_generated_forces[self.buoyancy_node, :] += hd_correct_grav + else: + hd_correct_grav = np.zeros((6)) + ielem, inode_in_elem = data.structure.node_master_elem[self.buoyancy_node] cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) cbg = np.dot(cab.T, cga.T) @@ -906,7 +906,7 @@ def generate(self, params): self.floating_data['hydrodynamics']['spar_diameter']* self.cd) - struct_tstep.runtime_generated_forces[inode, 0:3] += np.dot(cbg, drag_force) + struct_tstep.runtime_generated_forces[inode, 0:3] += np.dot(cbg, force_coeff*drag_force) # Wave loading ielem, inode_in_elem = data.structure.node_master_elem[self.wave_forces_node] From 062d589abfbcedc8e211061306ef50b184d745d5 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 19 Apr 2021 09:19:37 +0100 Subject: [PATCH 060/253] move k --- sharpy/solvers/dynamiccoupled.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 320eb26ca..f2a0e76cf 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -493,6 +493,7 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): structural_kstep, aero_kstep = self.process_controller_output( state) + k = 0 # compute unsteady contribution force_coeff = 0.0 unsteady_contribution = False @@ -523,7 +524,6 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): controlled_structural_kstep = structural_kstep.copy() controlled_aero_kstep = aero_kstep.copy() - k = 0 for k in range(self.settings['fsi_substeps'] + 1): if (k == self.settings['fsi_substeps'] and self.settings['fsi_substeps']): From 6290cac339cd1ce373a6ecceb9249441f358b0a3 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 19 Apr 2021 09:20:25 +0100 Subject: [PATCH 061/253] generalised alpha in setting options --- sharpy/solvers/nonlineardynamicmultibody.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 67aeba4c5..7f849e783 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -35,7 +35,7 @@ class NonLinearDynamicMultibody(_BaseStructural): settings_types['time_integrator'] = 'str' settings_default['time_integrator'] = 'NewmarkBeta' settings_description['time_integrator'] = 'Method to perform time integration' - settings_options['time_integrator'] = ['NewmarkBeta'] + settings_options['time_integrator'] = ['NewmarkBeta', 'GeneralisedAlpha'] settings_types['time_integrator_settings'] = 'dict' settings_default['time_integrator_settings'] = dict() @@ -82,7 +82,11 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) + settings.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + self.settings_options, + no_ctype=True) # load info from dyn dictionary self.data.structure.add_unsteady_information( From 675e2cc75b6df3e35911960e96cb3a92455e4456 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 20 Apr 2021 08:55:09 +0100 Subject: [PATCH 062/253] fix bug missing - --- sharpy/structure/models/beam.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/structure/models/beam.py b/sharpy/structure/models/beam.py index e8e6fdb64..0b7bd90f1 100644 --- a/sharpy/structure/models/beam.py +++ b/sharpy/structure/models/beam.py @@ -330,7 +330,7 @@ def add_lumped_mass_to_element(self, i_lumped_node, inertia_tensor, replace=Fals self.elements[i_lumped_master_elem].rbmass[i_lumped_master_node_local, :, :] = ( inertia_tensor) # += necessary in case multiple masses defined per node else: - self.elements[i_lumped_master_elem].rbmass[i_lumped_master_node_local, :, :] = ( + self.elements[i_lumped_master_elem].rbmass[i_lumped_master_node_local, :, :] += ( inertia_tensor) # += necessary in case multiple masses defined per node # def generate_master_structure(self): From 69e5b64ecb775efc526268a851aaebf3e9a63bdb Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 20 Apr 2021 09:46:50 +0100 Subject: [PATCH 063/253] option concentrate spar --- cases/templates/template_wt.py | 316 +++++++++++++++++----------- sharpy/generators/floatingforces.py | 68 ++++-- 2 files changed, 243 insertions(+), 141 deletions(-) diff --git a/cases/templates/template_wt.py b/cases/templates/template_wt.py index b8656e113..633233345 100644 --- a/cases/templates/template_wt.py +++ b/cases/templates/template_wt.py @@ -125,113 +125,166 @@ def spar_from_excel_type04(op_params, excel_sheet_structural_spar = excel_description['excel_sheet_structural_spar'] tol_remove_points = geom_params['tol_remove_points'] - # Generate the spar - SparHeight = gc.read_column_sheet_type01(excel_file_name, - excel_sheet_parameters, - 'SparHeight') - SparBallastMass = gc.read_column_sheet_type01(excel_file_name, + TowerBaseHeight = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, - 'SparBallastMass') - SparBallastDepth = gc.read_column_sheet_type01(excel_file_name, - excel_sheet_parameters, - 'SparBallastDepth') + 'TowerBaseHeight') + + # Generate the spar + if options['concentrate_spar']: + mtower = wt.StructuralInformation.mass_db[0, 0, 0] + + PlatformTotalMass = gc.read_column_sheet_type01(excel_file_name, + excel_sheet_parameters, + 'PlatformTotalMass') + PlatformIrollCM = gc.read_column_sheet_type01(excel_file_name, + excel_sheet_parameters, + 'PlatformIrollCM') + PlatformIpitchCM = gc.read_column_sheet_type01(excel_file_name, + excel_sheet_parameters, + 'PlatformIpitchCM') + PlatformIyawCM = gc.read_column_sheet_type01(excel_file_name, + excel_sheet_parameters, + 'PlatformIyawCM') + PlatformCMbelowSWL = gc.read_column_sheet_type01(excel_file_name, + excel_sheet_parameters, + 'PlatformCMbelowSWL') + + # PlatformIpitch = PlatformIpitchCM + PlatformTotalMass*(PlatformCMbelowSWL + TowerBaseHeight)**2 + # PlatformIroll = PlatformIrollCM + PlatformTotalMass*(PlatformCMbelowSWL + TowerBaseHeight)**2 + + # iner_mat = np.zeros((6,6)) + # iner_mat[0:3, 0:3] = PlatformTotalMass*np.eye(3) + # iner_mat[3, 3] = PlatformIyawCM + # iner_mat[4, 4] = PlatformIpitch + # iner_mat[5, 5] = PlatformIroll + + mpoint = PlatformTotalMass - mtower*TowerBaseHeight + IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**2 + IpitchPoint = PlatformIpitchCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 + IrollPoint = PlatformIrollCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 + iner_mat = np.zeros((6,6)) + iner_mat[0:3, 0:3] = mpoint*np.eye(3) + iner_mat[3, 3] = IyawPoint + iner_mat[4, 4] = IpitchPoint + iner_mat[5, 5] = IrollPoint + + base_stiffness_top = wt.StructuralInformation.stiffness_db[0, :, :] + base_mass_top = wt.StructuralInformation.mass_db[0, :, :] + base_stiffness_bot = 100*base_stiffness_top + base_mass_bot = base_mass_top + + num_lumped_mass_mat = 0 - # Read from excel file - SparHtFract = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparHtFract') - SparMassDen = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparMassDen') - SparFAStif = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparFAStif') - SparSSStif = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparSSStif') - SparGJStif = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparGJStif') - SparEAStif = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparEAStif') - SparFAIner = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparFAIner') - SparSSIner = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparSSIner') - SparFAcgOf = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparFAcgOf') - SparSScgOf = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparSScgOf') - - ElevationSpar = SparHtFract*SparHeight - spar = gc.AeroelasticInformation() - spar.StructuralInformation.num_elem = len(ElevationSpar) - 2 - spar.StructuralInformation.num_node_elem = 3 - spar.StructuralInformation.compute_basic_num_node() + else: + SparHeight = gc.read_column_sheet_type01(excel_file_name, + excel_sheet_parameters, + 'SparHeight') + SparBallastMass = gc.read_column_sheet_type01(excel_file_name, + excel_sheet_parameters, + 'SparBallastMass') + SparBallastDepth = gc.read_column_sheet_type01(excel_file_name, + excel_sheet_parameters, + 'SparBallastDepth') + + # Read from excel file + SparHtFract = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparHtFract') + SparMassDen = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparMassDen') + SparFAStif = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparFAStif') + SparSSStif = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparSSStif') + SparGJStif = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparGJStif') + SparEAStif = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparEAStif') + SparFAIner = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparFAIner') + SparSSIner = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparSSIner') + SparFAcgOf = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparFAcgOf') + SparSScgOf = gc.read_column_sheet_type01(excel_file_name, excel_sheet_structural_spar, 'SparSScgOf') + + ElevationSpar = SparHtFract*SparHeight + spar = gc.AeroelasticInformation() + spar.StructuralInformation.num_elem = len(ElevationSpar) - 2 + spar.StructuralInformation.num_node_elem = 3 + spar.StructuralInformation.compute_basic_num_node() + + # Interpolate excel variables into the correct locations + node_r, elem_r = create_node_radial_pos_from_elem_centres(ElevationSpar, + spar.StructuralInformation.num_node, + spar.StructuralInformation.num_elem, + spar.StructuralInformation.num_node_elem) - # Interpolate excel variables into the correct locations - node_r, elem_r = create_node_radial_pos_from_elem_centres(ElevationSpar, - spar.StructuralInformation.num_node, - spar.StructuralInformation.num_elem, - spar.StructuralInformation.num_node_elem) + # Stiffness + elem_EA = np.interp(elem_r, ElevationSpar, SparEAStif) + elem_EIz = np.interp(elem_r, ElevationSpar, SparSSStif) + elem_EIy = np.interp(elem_r, ElevationSpar, SparFAStif) + elem_GJ = np.interp(elem_r, ElevationSpar, SparGJStif) + # Stiffness: estimate unknown properties + cout.cout_wrap.print_file = False + cout.cout_wrap('WARNING: The poisson cofficient is assumed equal to 0.3', 3) + cout.cout_wrap('WARNING: Cross-section area is used as shear area', 3) + poisson_coef = 0.3 + elem_GAy = elem_EA/2.0/(1.0+poisson_coef) + elem_GAz = elem_EA/2.0/(1.0+poisson_coef) - # Stiffness - elem_EA = np.interp(elem_r, ElevationSpar, SparEAStif) - elem_EIz = np.interp(elem_r, ElevationSpar, SparSSStif) - elem_EIy = np.interp(elem_r, ElevationSpar, SparFAStif) - elem_GJ = np.interp(elem_r, ElevationSpar, SparGJStif) - # Stiffness: estimate unknown properties - cout.cout_wrap.print_file = False - cout.cout_wrap('WARNING: The poisson cofficient is assumed equal to 0.3', 3) - cout.cout_wrap('WARNING: Cross-section area is used as shear area', 3) - poisson_coef = 0.3 - elem_GAy = elem_EA/2.0/(1.0+poisson_coef) - elem_GAz = elem_EA/2.0/(1.0+poisson_coef) + # Inertia + elem_mass_per_unit_length = np.interp(elem_r, ElevationSpar, SparMassDen) + elem_mass_iner_y = np.interp(elem_r, ElevationSpar, SparFAIner) + elem_mass_iner_z = np.interp(elem_r, ElevationSpar, SparSSIner) + # TODO: check yz axis and Flap-edge + elem_pos_cg_B = np.zeros((spar.StructuralInformation.num_elem, 3),) + elem_pos_cg_B[:, 1] = np.interp(elem_r, ElevationSpar, SparSScgOf) + elem_pos_cg_B[:, 2] = np.interp(elem_r, ElevationSpar, SparFAcgOf) - # Inertia - elem_mass_per_unit_length = np.interp(elem_r, ElevationSpar, SparMassDen) - elem_mass_iner_y = np.interp(elem_r, ElevationSpar, SparFAIner) - elem_mass_iner_z = np.interp(elem_r, ElevationSpar, SparSSIner) - # TODO: check yz axis and Flap-edge - elem_pos_cg_B = np.zeros((spar.StructuralInformation.num_elem, 3),) - elem_pos_cg_B[:, 1] = np.interp(elem_r, ElevationSpar, SparSScgOf) - elem_pos_cg_B[:, 2] = np.interp(elem_r, ElevationSpar, SparFAcgOf) + # Stiffness: estimate unknown properties + cout.cout_wrap('WARNING: Using perpendicular axis theorem to compute the inertia around xB', 3) + elem_mass_iner_x = elem_mass_iner_y + elem_mass_iner_z - # Stiffness: estimate unknown properties - cout.cout_wrap('WARNING: Using perpendicular axis theorem to compute the inertia around xB', 3) - elem_mass_iner_x = elem_mass_iner_y + elem_mass_iner_z + # Create the tower + spar.StructuralInformation.create_mass_db_from_vector(elem_mass_per_unit_length, elem_mass_iner_x, elem_mass_iner_y, elem_mass_iner_z, elem_pos_cg_B) + spar.StructuralInformation.create_stiff_db_from_vector(elem_EA, elem_GAy, elem_GAz, elem_GJ, elem_EIy, elem_EIz) - # Create the tower - spar.StructuralInformation.create_mass_db_from_vector(elem_mass_per_unit_length, elem_mass_iner_x, elem_mass_iner_y, elem_mass_iner_z, elem_pos_cg_B) - spar.StructuralInformation.create_stiff_db_from_vector(elem_EA, elem_GAy, elem_GAz, elem_GJ, elem_EIy, elem_EIz) + coordinates = np.zeros((spar.StructuralInformation.num_node, 3),) + coordinates[:, 0] = node_r - coordinates = np.zeros((spar.StructuralInformation.num_node, 3),) - coordinates[:, 0] = node_r + spar.StructuralInformation.generate_1to1_from_vectors( + num_node_elem=spar.StructuralInformation.num_node_elem, + num_node=spar.StructuralInformation.num_node, + num_elem=spar.StructuralInformation.num_elem, + coordinates=coordinates, + stiffness_db=spar.StructuralInformation.stiffness_db, + mass_db=spar.StructuralInformation.mass_db, + frame_of_reference_delta='y_AFoR', + vec_node_structural_twist=np.zeros((spar.StructuralInformation.num_node,),), + num_lumped_mass=1) - spar.StructuralInformation.generate_1to1_from_vectors( - num_node_elem=spar.StructuralInformation.num_node_elem, - num_node=spar.StructuralInformation.num_node, - num_elem=spar.StructuralInformation.num_elem, - coordinates=coordinates, - stiffness_db=spar.StructuralInformation.stiffness_db, - mass_db=spar.StructuralInformation.mass_db, - frame_of_reference_delta='y_AFoR', - vec_node_structural_twist=np.zeros((spar.StructuralInformation.num_node,),), - num_lumped_mass=1) - - spar.StructuralInformation.boundary_conditions[0] = -1 - spar.StructuralInformation.boundary_conditions[-1] = 1 - - # Include ballast mass - dist = np.abs(coordinates[:, 0] + SparBallastDepth) - min_dist = np.amin(dist) - loc_min = np.where(dist == min_dist)[0] - - cout.cout_wrap("Ballast at node %d at position %f" % (loc_min, coordinates[loc_min, 0]), 2) - - spar.StructuralInformation.lumped_mass_nodes[0] = loc_min - spar.StructuralInformation.lumped_mass[0] = SparBallastMass - spar.StructuralInformation.lumped_mass_inertia[0] = np.zeros((3,3)) - spar.StructuralInformation.lumped_mass_position[0] = np.zeros((3,)) - - spar.AerodynamicInformation.set_to_zero(spar.StructuralInformation.num_node_elem, - spar.StructuralInformation.num_node, - spar.StructuralInformation.num_elem) + spar.StructuralInformation.boundary_conditions[0] = -1 + spar.StructuralInformation.boundary_conditions[-1] = 1 + + # Include ballast mass + dist = np.abs(coordinates[:, 0] + SparBallastDepth) + min_dist = np.amin(dist) + loc_min = np.where(dist == min_dist)[0] + + cout.cout_wrap("Ballast at node %d at position %f" % (loc_min, coordinates[loc_min, 0]), 2) + + spar.StructuralInformation.lumped_mass_nodes[0] = loc_min + spar.StructuralInformation.lumped_mass[0] = SparBallastMass + spar.StructuralInformation.lumped_mass_inertia[0] = np.zeros((3,3)) + spar.StructuralInformation.lumped_mass_position[0] = np.zeros((3,)) + + spar.AerodynamicInformation.set_to_zero(spar.StructuralInformation.num_node_elem, + spar.StructuralInformation.num_node, + spar.StructuralInformation.num_elem) + + base_stiffness_bot = spar.StructuralInformation.stiffness_db[-1, :, :] + base_mass_bot = spar.StructuralInformation.mass_db[-1, :, :] + base_stiffness_top = base_stiffness_bot + base_mass_top = base_mass_bot + + num_lumped_mass_mat = 0 # Generate tower base - TowerBaseHeight = gc.read_column_sheet_type01(excel_file_name, - excel_sheet_parameters, - 'TowerBaseHeight') NodesBase = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NodesBase') - base = gc.AeroelasticInformation() base.StructuralInformation.num_node = NodesBase base.StructuralInformation.num_node_elem = 3 @@ -244,17 +297,17 @@ def spar_from_excel_type04(op_params, base_mass_db = np.zeros((base.StructuralInformation.num_elem, 6, 6)) vec_node_structural_twist = np.zeros((base.StructuralInformation.num_node,)) - for ielem in range(base.StructuralInformation.num_elem): - base_stiffness_db[ielem, :, :] = spar.StructuralInformation.stiffness_db[-1, :, :] - base_mass_db[ielem, :, :] = spar.StructuralInformation.mass_db[-1, :, :] # for ielem in range(base.StructuralInformation.num_elem): - # inode_cent = 2*ielem + 1 - # rel_dist_to_spar = node_coord[inode_cent, 0]/TowerBaseHeight - # rel_dist_to_base = (node_coord[-1, 0] - node_coord[inode_cent, 0])/TowerBaseHeight - # base_stiffness_db[ielem, :, :] = (spar.StructuralInformation.stiffness_db[0, :, :]*rel_dist_to_base + - # wt.StructuralInformation.stiffness_db[0, :, :]*rel_dist_to_spar) - # base_mass_db[ielem, :, :] = (spar.StructuralInformation.mass_db[0, :, :]*rel_dist_to_base + - # wt.StructuralInformation.mass_db[0, :, :]*rel_dist_to_spar) + # base_stiffness_db[ielem, :, :] = base_stiffness.copy() + # base_mass_db[ielem, :, :] = base_mass.copy() + for ielem in range(base.StructuralInformation.num_elem): + inode_cent = 2*ielem + 1 + rel_dist_to_bot = node_coord[inode_cent, 0]/TowerBaseHeight + rel_dist_to_top = (node_coord[-1, 0] - node_coord[inode_cent, 0])/TowerBaseHeight + base_stiffness_db[ielem, :, :] = (base_stiffness_bot*rel_dist_to_top + + base_stiffness_top*rel_dist_to_bot) + base_mass_db[ielem, :, :] = (base_mass_bot*rel_dist_to_top + + base_mass_top*rel_dist_to_bot) base.StructuralInformation.generate_1to1_from_vectors( base.StructuralInformation.num_node_elem, @@ -265,7 +318,8 @@ def spar_from_excel_type04(op_params, base_mass_db, 'y_AFoR', vec_node_structural_twist, - num_lumped_mass=0) + num_lumped_mass=0, + num_lumped_mass_mat=num_lumped_mass_mat) base.StructuralInformation.boundary_conditions[0] = 1 base.StructuralInformation.body_number *= 0 @@ -274,24 +328,44 @@ def spar_from_excel_type04(op_params, base.StructuralInformation.num_node, base.StructuralInformation.num_elem) - # Assembly - spar.assembly(base) - spar.remove_duplicated_points(1e-6) - spar.StructuralInformation.body_number *= 0 - nodes_spar = spar.StructuralInformation.num_node + 0 - for inode in range(len(hub_nodes)): - hub_nodes[inode] += nodes_spar - wt.StructuralInformation.coordinates[:, 0] += TowerBaseHeight - spar.assembly(wt) - spar.remove_duplicated_points(1e-6, skip=hub_nodes) - for ielem in range(spar.StructuralInformation.num_elem): - if not spar.StructuralInformation.body_number[ielem] == 0: - spar.StructuralInformation.body_number[ielem] -= 1 - - # Update Lagrange Constraints and Multibody information - # LC[0].node_in_body += nodes_spar - 1 - for ilc in range(len(LC)): - LC[ilc].node_in_body += nodes_spar - 1 + if options['concentrate_spar']: + base.StructuralInformation.lumped_mass_mat_nodes = np.array([0], dtype=int) + base.StructuralInformation.lumped_mass_mat = np.zeros((1, 6, 6)) + base.StructuralInformation.lumped_mass_mat[0, :, :] = iner_mat + + nodes_base = base.StructuralInformation.num_node + 0 + for inode in range(len(hub_nodes)): + hub_nodes[inode] += nodes_base + wt.StructuralInformation.coordinates[:, 0] += TowerBaseHeight + base.assembly(wt) + base.remove_duplicated_points(1e-6, skip=hub_nodes) + for ielem in range(base.StructuralInformation.num_elem): + if not base.StructuralInformation.body_number[ielem] == 0: + base.StructuralInformation.body_number[ielem] -= 1 + for ilc in range(len(LC)): + LC[ilc].node_in_body += nodes_base - 1 + spar = base # Just a rename for the return + else: + # Assembly + spar.assembly(base) + spar.remove_duplicated_points(1e-6) + spar.StructuralInformation.body_number *= 0 + nodes_spar = spar.StructuralInformation.num_node + 0 + for inode in range(len(hub_nodes)): + hub_nodes[inode] += nodes_spar + + wt.StructuralInformation.coordinates[:, 0] += TowerBaseHeight + spar.assembly(wt) + spar.remove_duplicated_points(1e-6, skip=hub_nodes) + for ielem in range(spar.StructuralInformation.num_elem): + if not spar.StructuralInformation.body_number[ielem] == 0: + spar.StructuralInformation.body_number[ielem] -= 1 + + # Update Lagrange Constraints and Multibody information + # LC[0].node_in_body += nodes_spar - 1 + for ilc in range(len(LC)): + LC[ilc].node_in_body += nodes_spar - 1 + MB[0].FoR_movement = 'free' for ibody in range(1, len(MB)): MB[ibody].FoR_position[0] += TowerBaseHeight diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index b530de807..88b7a6f88 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -477,6 +477,10 @@ class FloatingForces(generator_interface.BaseGenerator): settings_default['added_mass_in_mass_matrix'] = True settings_description['added_mass_in_mass_matrix'] = 'Include the platform added mass in the mass matrix of the system' + settings_types['concentrate_spar'] = 'bool' + settings_default['concentrate_spar'] = False + settings_description['concentrate_spar'] = 'Compute CD as if the spar properties were concentrated at the base' + settings_types['method_wave'] = 'str' settings_default['method_wave'] = 'sin' settings_description['method_wave'] = 'Method to compute wave forces' @@ -880,33 +884,57 @@ def generate(self, params): struct_tstep.runtime_generated_forces[self.buoyancy_node, 3:6] += np.dot(cbg, hs_f_g[3:6] + force_coeff*(hd_f_qdot_g[3:6] + hd_f_qdotdot_g[3:6])) # Nonlinear drag coefficeint - for inode in range(self.floating_data['hydrodynamics']['CD_first_node'], self.floating_data['hydrodynamics']['CD_last_node'] + 1): - - ielem, inode_in_elem = data.structure.node_master_elem[inode] + if self.settings['concentrate_spar']: + + ielem, inode_in_elem = data.structure.node_master_elem[self.floating_data['hydrodynamics']['CD_node']] cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) cbg = np.dot(cab.T, cga.T) + + vel_g = np.dot(cga, struct_tstep.for_vel[0:3])*np.array([0., 1., 1.]) + omega_g = np.dot(cga, struct_tstep.for_vel[3:6])*np.array([0., 1., 1.]) + + L = self.floating_data['hydrodynamics']['CD_spar_length'] + avg_dir = algebra.unit_vector(vel_g + 0.5*omega_g*L) + vel_g = algebra.unit_vector(vel_g) + omega_g = algebra.unit_vector(omega_g) + + drag_force = ((vel_g + omega_g*L)**3 - + (vel_g + omega_g*0.)**3)*avg_dir + drag_force *= 0.5*self.water_density*self.cd*self.floating_data['hydrodynamics']['spar_diameter']/3./omega_g + struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 0:3] += np.dot(cbg, force_coeff*drag_force) + + drag_moment = 0.5*vel_g**2*L**2 + (2./3)*vel_g*omega_g*L**3 + 0.25*omega_g**2*L**4 + drag_moment *= 0.5*self.water_density*self.cd*self.floating_data['hydrodynamics']['spar_diameter'] + struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 3:6] += np.dot(cbg, force_coeff*drag_moment) - if inode == 0: - delta_x = 0.5*np.linalg.norm(struct_tstep.pos[1, :] - struct_tstep.pos[0, :]) - elif inode == data.structure.num_node - 1: - delta_x = 0.5*np.linalg.norm(struct_tstep.pos[inode, :] - struct_tstep.pos[inode - 1, :]) - else: - delta_x = 0.5*np.linalg.norm(struct_tstep.pos[inode + 1, :] - struct_tstep.pos[inode - 1, :]) + else: + for inode in range(self.floating_data['hydrodynamics']['CD_first_node'], self.floating_data['hydrodynamics']['CD_last_node'] + 1): + + ielem, inode_in_elem = data.structure.node_master_elem[inode] + cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) + cbg = np.dot(cab.T, cga.T) + + if inode == 0: + delta_x = 0.5*np.linalg.norm(struct_tstep.pos[1, :] - struct_tstep.pos[0, :]) + elif inode == data.structure.num_node - 1: + delta_x = 0.5*np.linalg.norm(struct_tstep.pos[inode, :] - struct_tstep.pos[inode - 1, :]) + else: + delta_x = 0.5*np.linalg.norm(struct_tstep.pos[inode + 1, :] - struct_tstep.pos[inode - 1, :]) - vel_a = (struct_tstep.for_vel[0:3] + - np.cross(struct_tstep.for_vel[3:6], struct_tstep.pos[inode, :]) + - struct_tstep.pos_dot[inode, :]) + vel_a = (struct_tstep.for_vel[0:3] + + np.cross(struct_tstep.for_vel[3:6], struct_tstep.pos[inode, :]) + + struct_tstep.pos_dot[inode, :]) - # Remove velocity along the x axis - vel_b = np.dot(cab.T, vel_a) - vel_b[0] = 0. - vel_g = np.dot(cbg.T, vel_b) + # Remove velocity along the x axis + vel_b = np.dot(cab.T, vel_a) + vel_b[0] = 0. + vel_g = np.dot(cbg.T, vel_b) - drag_force = (-0.5*self.water_density*np.linalg.norm(vel_g)*vel_g*delta_x* - self.floating_data['hydrodynamics']['spar_diameter']* - self.cd) + drag_force = (-0.5*self.water_density*np.linalg.norm(vel_g)*vel_g*delta_x* + self.floating_data['hydrodynamics']['spar_diameter']* + self.cd) - struct_tstep.runtime_generated_forces[inode, 0:3] += np.dot(cbg, force_coeff*drag_force) + struct_tstep.runtime_generated_forces[inode, 0:3] += np.dot(cbg, force_coeff*drag_force) # Wave loading ielem, inode_in_elem = data.structure.node_master_elem[self.wave_forces_node] From bc790d904fc0086c6108c15a6691f4cc547191d6 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 20 Apr 2021 16:18:34 +0100 Subject: [PATCH 064/253] include NodesOverhang --- cases/templates/template_wt.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/cases/templates/template_wt.py b/cases/templates/template_wt.py index 633233345..e84fb6463 100644 --- a/cases/templates/template_wt.py +++ b/cases/templates/template_wt.py @@ -896,6 +896,9 @@ def generate_from_excel_type03(op_params, # Read overhang and nacelle properties from excel file overhang_len = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'overhang') + NodesOverhang = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NodesOverhang') + if NodesOverhang is None: + NodesOverhang = 3 NacelleMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NacMass') NacelleMass_x = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NacMass_x') NacelleMass_z = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NacMass_z') @@ -909,7 +912,6 @@ def generate_from_excel_type03(op_params, else: cout.cout_wrap('WARNING: Nacelle mass placed at tower top', 3) - tower.AerodynamicInformation.set_to_zero(tower.StructuralInformation.num_node_elem, tower.StructuralInformation.num_node, tower.StructuralInformation.num_elem) @@ -921,7 +923,7 @@ def generate_from_excel_type03(op_params, HubMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'HubMass') overhang = gc.AeroelasticInformation() - overhang.StructuralInformation.num_node = 3 + overhang.StructuralInformation.num_node = NodesOverhang overhang.StructuralInformation.num_node_elem = 3 overhang.StructuralInformation.compute_basic_num_elem() node_pos = np.zeros((overhang.StructuralInformation.num_node, 3), ) @@ -930,9 +932,9 @@ def generate_from_excel_type03(op_params, node_pos[:, 2] = np.linspace(0., overhang_len*np.cos(tilt*deg2rad), overhang.StructuralInformation.num_node) # TODO: change the following by real values # Same properties as the last element of the tower - cout.cout_wrap("WARNING: Using the structural properties of the last tower section for the overhang", 3) - oh_mass_per_unit_length = tower.StructuralInformation.mass_db[-1, 0, 0] - oh_mass_iner = tower.StructuralInformation.mass_db[-1, 3, 3] + cout.cout_wrap("WARNING: Using the structural properties (*0.1) of the last tower section for the overhang", 3) + oh_mass_per_unit_length = tower.StructuralInformation.mass_db[-1, 0, 0]/10. + oh_mass_iner = tower.StructuralInformation.mass_db[-1, 3, 3]/10. oh_EA = tower.StructuralInformation.stiffness_db[-1, 0, 0] oh_GA = tower.StructuralInformation.stiffness_db[-1, 1, 1] oh_GJ = tower.StructuralInformation.stiffness_db[-1, 3, 3] From 6b5131e63c8b3bf591305e2678c40decc72b297c Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 20 Apr 2021 16:18:50 +0100 Subject: [PATCH 065/253] fix drag force --- sharpy/generators/floatingforces.py | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 88b7a6f88..d567b2a02 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -895,17 +895,19 @@ def generate(self, params): L = self.floating_data['hydrodynamics']['CD_spar_length'] avg_dir = algebra.unit_vector(vel_g + 0.5*omega_g*L) - vel_g = algebra.unit_vector(vel_g) - omega_g = algebra.unit_vector(omega_g) - - drag_force = ((vel_g + omega_g*L)**3 - - (vel_g + omega_g*0.)**3)*avg_dir - drag_force *= 0.5*self.water_density*self.cd*self.floating_data['hydrodynamics']['spar_diameter']/3./omega_g - struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 0:3] += np.dot(cbg, force_coeff*drag_force) + vel_g = np.linalg.norm(vel_g) + omega_g = np.linalg.norm(omega_g) + + drag_force = np.zeros((6)) + if ((not vel_g == 0) or (not omega_g == 0)): + drag_force[0:3] = ((vel_g + omega_g*L)**3 - + (vel_g + omega_g*0.)**3)*avg_dir + drag_force[0:3] *= 0.5*self.water_density*self.cd*self.floating_data['hydrodynamics']['spar_diameter']/3./omega_g + struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 0:3] += np.dot(cbg, force_coeff*drag_force[0:3]) - drag_moment = 0.5*vel_g**2*L**2 + (2./3)*vel_g*omega_g*L**3 + 0.25*omega_g**2*L**4 - drag_moment *= 0.5*self.water_density*self.cd*self.floating_data['hydrodynamics']['spar_diameter'] - struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 3:6] += np.dot(cbg, force_coeff*drag_moment) + drag_force[3:6] = 0.5*vel_g**2*L**2 + (2./3)*vel_g*omega_g*L**3 + 0.25*omega_g**2*L**4 + drag_force[3:6] *= 0.5*self.water_density*self.cd*self.floating_data['hydrodynamics']['spar_diameter'] + struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 3:6] += np.dot(cbg, force_coeff*drag_force[3:6]) else: for inode in range(self.floating_data['hydrodynamics']['CD_first_node'], self.floating_data['hydrodynamics']['CD_last_node'] + 1): From 52b92978c613281b62eb3fda85194954b7e714c0 Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 21 Apr 2021 16:09:35 +0100 Subject: [PATCH 066/253] change computation of drag in concentrate_spar --- sharpy/generators/floatingforces.py | 91 +++++++++++++---------------- 1 file changed, 42 insertions(+), 49 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index d567b2a02..69d0dcd86 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -885,58 +885,51 @@ def generate(self, params): # Nonlinear drag coefficeint if self.settings['concentrate_spar']: - - ielem, inode_in_elem = data.structure.node_master_elem[self.floating_data['hydrodynamics']['CD_node']] + spar_node_pos = np.linspace(-self.floating_data['hydrodynamics']['CD_spar_length'], 0, 100) + struct_tstep.pos[self.floating_data['hydrodynamics']['CD_node'], :] + spar_node_pos_dot = np.zeros((100)) + else: + spar_node_pos = struct_tstep.pos[self.floating_data['hydrodynamics']['CD_first_node'] : self.floating_data['hydrodynamics']['CD_last_node'] + 1, :] + spar_node_pos_dot = struct_tstep.pos_dot[self.floating_data['hydrodynamics']['CD_first_node'] : self.floating_data['hydrodynamics']['CD_last_node'] + 1, :] + + total_drag_force = np.zeros((6)) + for inode in range(len(spar_node_pos)): + + if self.settings['concentrate_spar']: + ielem, inode_in_elem = data.structure.node_master_elem[inode + self.floating_data['hydrodynamics']['CD_node']] + else: + ielem, inode_in_elem = data.structure.node_master_elem[inode + self.floating_data['hydrodynamics']['CD_first_node']] cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) cbg = np.dot(cab.T, cga.T) - - vel_g = np.dot(cga, struct_tstep.for_vel[0:3])*np.array([0., 1., 1.]) - omega_g = np.dot(cga, struct_tstep.for_vel[3:6])*np.array([0., 1., 1.]) - - L = self.floating_data['hydrodynamics']['CD_spar_length'] - avg_dir = algebra.unit_vector(vel_g + 0.5*omega_g*L) - vel_g = np.linalg.norm(vel_g) - omega_g = np.linalg.norm(omega_g) - - drag_force = np.zeros((6)) - if ((not vel_g == 0) or (not omega_g == 0)): - drag_force[0:3] = ((vel_g + omega_g*L)**3 - - (vel_g + omega_g*0.)**3)*avg_dir - drag_force[0:3] *= 0.5*self.water_density*self.cd*self.floating_data['hydrodynamics']['spar_diameter']/3./omega_g - struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 0:3] += np.dot(cbg, force_coeff*drag_force[0:3]) - - drag_force[3:6] = 0.5*vel_g**2*L**2 + (2./3)*vel_g*omega_g*L**3 + 0.25*omega_g**2*L**4 - drag_force[3:6] *= 0.5*self.water_density*self.cd*self.floating_data['hydrodynamics']['spar_diameter'] - struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 3:6] += np.dot(cbg, force_coeff*drag_force[3:6]) - - else: - for inode in range(self.floating_data['hydrodynamics']['CD_first_node'], self.floating_data['hydrodynamics']['CD_last_node'] + 1): - ielem, inode_in_elem = data.structure.node_master_elem[inode] - cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) - cbg = np.dot(cab.T, cga.T) - - if inode == 0: - delta_x = 0.5*np.linalg.norm(struct_tstep.pos[1, :] - struct_tstep.pos[0, :]) - elif inode == data.structure.num_node - 1: - delta_x = 0.5*np.linalg.norm(struct_tstep.pos[inode, :] - struct_tstep.pos[inode - 1, :]) - else: - delta_x = 0.5*np.linalg.norm(struct_tstep.pos[inode + 1, :] - struct_tstep.pos[inode - 1, :]) - - vel_a = (struct_tstep.for_vel[0:3] + - np.cross(struct_tstep.for_vel[3:6], struct_tstep.pos[inode, :]) + - struct_tstep.pos_dot[inode, :]) - - # Remove velocity along the x axis - vel_b = np.dot(cab.T, vel_a) - vel_b[0] = 0. - vel_g = np.dot(cbg.T, vel_b) - - drag_force = (-0.5*self.water_density*np.linalg.norm(vel_g)*vel_g*delta_x* - self.floating_data['hydrodynamics']['spar_diameter']* - self.cd) - - struct_tstep.runtime_generated_forces[inode, 0:3] += np.dot(cbg, force_coeff*drag_force) + if inode == 0: + delta_x = 0.5*np.linalg.norm(spar_node_pos[1, :] - spar_node_pos[0, :]) + elif inode == len(spar_node_pos) - 1: + delta_x = 0.5*np.linalg.norm(spar_node_pos[inode, :] - spar_node_pos[inode - 1, :]) + else: + delta_x = 0.5*np.linalg.norm(spar_node_pos[inode + 1, :] - spar_node_pos[inode - 1, :]) + + vel_a = (struct_tstep.for_vel[0:3] + + np.cross(struct_tstep.for_vel[3:6], spar_node_pos[inode, :]) + + spar_node_pos_dot[inode, :]) + + # Remove velocity along the x axis + vel_b = np.dot(cab.T, vel_a) + vel_b[0] = 0. + vel_g = np.dot(cbg.T, vel_b) + + drag_force = (-0.5*self.water_density*np.linalg.norm(vel_g)*vel_g*delta_x* + self.floating_data['hydrodynamics']['spar_diameter']* + self.cd) + + r = spar_node_pos[inode, :] - struct_tstep[self.floating_data['hydrodynamics']['CD_node'], :] + drag_moment = np.corss(r, drag_force) + total_drag_force[0:3] += drag_force + total_drag_force[3:6] += drag_moment + if self.settings['concentrate_spar']: + struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 0:3] += np.dot(cbg, force_coeff*drag_force) + struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 3:6] += np.dot(cbg, force_coeff*drag_moment) + else: + struct_tstep.runtime_generated_forces[inode + self.floating_data['hydrodynamics']['CD_first_node'], 0:3] += np.dot(cbg, force_coeff*drag_force) # Wave loading ielem, inode_in_elem = data.structure.node_master_elem[self.wave_forces_node] From 68a6c10cc70e823d9c29891bd6349524a696477c Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 21 Apr 2021 16:09:58 +0100 Subject: [PATCH 067/253] fix computation platform properties --- cases/templates/template_wt.py | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/cases/templates/template_wt.py b/cases/templates/template_wt.py index e84fb6463..414e52efb 100644 --- a/cases/templates/template_wt.py +++ b/cases/templates/template_wt.py @@ -132,7 +132,8 @@ def spar_from_excel_type04(op_params, # Generate the spar if options['concentrate_spar']: mtower = wt.StructuralInformation.mass_db[0, 0, 0] - + iyawtower = wt.StructuralInformation.mass_db[0, 3, 3] + PlatformTotalMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'PlatformTotalMass') @@ -159,11 +160,18 @@ def spar_from_excel_type04(op_params, # iner_mat[5, 5] = PlatformIroll mpoint = PlatformTotalMass - mtower*TowerBaseHeight - IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**2 - IpitchPoint = PlatformIpitchCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 - IrollPoint = PlatformIrollCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 + # IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**2 + # IpitchPoint = PlatformIpitchCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 + # IrollPoint = PlatformIrollCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 + IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**3 - iyawtower + IpitchPoint = PlatformIpitchCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**3 + IrollPoint = PlatformIrollCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**3 + xpoint = (PlatformTotalMass*PlatformCMbelowSWL + 0.5*mtower*TowerBaseHeight**2)/mpoint + iner_mat = np.zeros((6,6)) iner_mat[0:3, 0:3] = mpoint*np.eye(3) + iner_mat[0:3, 3:6] = -mpoint*algebra.skew(np.array([-xpoint, 0, 0])) + iner_mat[3:6, 0:3] = -iner_mat[0:3, 3:6] iner_mat[3, 3] = IyawPoint iner_mat[4, 4] = IpitchPoint iner_mat[5, 5] = IrollPoint @@ -932,6 +940,9 @@ def generate_from_excel_type03(op_params, node_pos[:, 2] = np.linspace(0., overhang_len*np.cos(tilt*deg2rad), overhang.StructuralInformation.num_node) # TODO: change the following by real values # Same properties as the last element of the tower + # cout.cout_wrap("WARNING: Using the structural properties of the last tower section for the overhang", 3) + # oh_mass_per_unit_length = tower.StructuralInformation.mass_db[-1, 0, 0] + # oh_mass_iner = tower.StructuralInformation.mass_db[-1, 3, 3] cout.cout_wrap("WARNING: Using the structural properties (*0.1) of the last tower section for the overhang", 3) oh_mass_per_unit_length = tower.StructuralInformation.mass_db[-1, 0, 0]/10. oh_mass_iner = tower.StructuralInformation.mass_db[-1, 3, 3]/10. From d8b610dbd79990b8a728a591205c947785dbd4ca Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 21 Apr 2021 16:10:35 +0100 Subject: [PATCH 068/253] remove force_coeff from some forces --- sharpy/generators/floatingforces.py | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 69d0dcd86..fff38a647 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -815,7 +815,7 @@ def generate(self, params): horizontal_unit_vec = algebra.unit_vector(fl_to_anchor_G) horizontal_unit_vec[0] = 0. horizontal_unit_vec = algebra.unit_vector(horizontal_unit_vec) - force_fl = force_coeff*hf*horizontal_unit_vec + vf*np.array([-1., 0., 0.]) + force_fl = hf*horizontal_unit_vec + vf*np.array([-1., 0., 0.]) # Move the forces to the mooring node force_cl = np.zeros((6,)) @@ -830,12 +830,12 @@ def generate(self, params): # Yaw moment generated by the mooring system yaw = np.array([self.q[data.ts, 3], 0., 0.]) - mooring_yaw = -force_coeff*self.floating_data['mooring']['yaw_spring_stif']*yaw + mooring_yaw = -self.floating_data['mooring']['yaw_spring_stif']*yaw struct_tstep.runtime_generated_forces[self.mooring_node, 3:6] += np.dot(cbg, mooring_yaw) # Hydrostatic model - hs_f_g = self.buoy_F0 - force_coeff*np.dot(self.buoy_rest_mat, self.q[data.ts, :]) + hs_f_g = self.buoy_F0 - np.dot(self.buoy_rest_mat, self.q[data.ts, :]) if not force_coeff == 0.: hd_f_qdot_g = -np.dot(self.floating_data['hydrodynamics']['additional_damping'], self.qdot[data.ts, :]) @@ -865,7 +865,6 @@ def generate(self, params): else: hd_f_qdot_g = np.zeros((6)) hd_f_qdotdot_g = np.zeros((6)) - hd_correct_grav = np.zeros((6)) # Correct gravity forces if needed if self.added_mass_in_mass_matrix: From 0833080ce4909c8fbe4dcd7da0d498b270f7a509 Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 21 Apr 2021 17:17:23 +0100 Subject: [PATCH 069/253] write drag and minor fixes --- sharpy/generators/floatingforces.py | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index fff38a647..7e5e8ff7b 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -707,7 +707,7 @@ def initialise(self, in_dict=None, data=None): def write_output(self, ts, k, mooring, mooring_yaw, hydrostatic, - hydrodynamic_qdot, hydrodynamic_qdotdot, hd_correct_grav, waves): + hydrodynamic_qdot, hydrodynamic_qdotdot, hd_correct_grav, drag, waves): output = dict() output['ts'] = ts @@ -721,6 +721,7 @@ def write_output(self, ts, k, mooring, mooring_yaw, hydrostatic, output['hydrodynamic_qdot'] = hydrodynamic_qdot output['hydrodynamic_qdotdot'] = hydrodynamic_qdotdot output['hydrodynamic_correct_grav'] = hd_correct_grav + output['drag'] = drag output['waves'] = waves fid = h5.File(self.log_filename, 'a') @@ -744,6 +745,7 @@ def write_output(self, ts, k, mooring, mooring_yaw, hydrostatic, print("hydrodynamic_qdot: ", hydrodynamic_qdot) print("hydrodynamic_qdotdot: ", hydrodynamic_qdotdot) print("hydrodynamic_correct_grav: ", hd_correct_grav) + print("drag: ", drag) print("waves: ", waves) return @@ -884,8 +886,9 @@ def generate(self, params): # Nonlinear drag coefficeint if self.settings['concentrate_spar']: - spar_node_pos = np.linspace(-self.floating_data['hydrodynamics']['CD_spar_length'], 0, 100) + struct_tstep.pos[self.floating_data['hydrodynamics']['CD_node'], :] - spar_node_pos_dot = np.zeros((100)) + spar_node_pos = np.zeros((100, 3)) + struct_tstep.pos[self.floating_data['hydrodynamics']['CD_node'], :] + spar_node_pos[:, 0] += np.linspace(-self.floating_data['hydrodynamics']['CD_spar_length'], 0, 100) + spar_node_pos_dot = np.zeros((100, 3)) else: spar_node_pos = struct_tstep.pos[self.floating_data['hydrodynamics']['CD_first_node'] : self.floating_data['hydrodynamics']['CD_last_node'] + 1, :] spar_node_pos_dot = struct_tstep.pos_dot[self.floating_data['hydrodynamics']['CD_first_node'] : self.floating_data['hydrodynamics']['CD_last_node'] + 1, :] @@ -920,8 +923,8 @@ def generate(self, params): self.floating_data['hydrodynamics']['spar_diameter']* self.cd) - r = spar_node_pos[inode, :] - struct_tstep[self.floating_data['hydrodynamics']['CD_node'], :] - drag_moment = np.corss(r, drag_force) + r = spar_node_pos[inode, :] - struct_tstep.pos[self.floating_data['hydrodynamics']['CD_node'], :] + drag_moment = np.cross(r, drag_force) total_drag_force[0:3] += drag_force total_drag_force[3:6] += drag_moment if self.settings['concentrate_spar']: @@ -941,4 +944,4 @@ def generate(self, params): # Write output if self.settings['write_output']: self.write_output(data.ts, k, mooring_forces, mooring_yaw, hs_f_g, - hd_f_qdot_g, hd_f_qdotdot_g, hd_correct_grav, self.wave_forces_g[data.ts, :]) + hd_f_qdot_g, hd_f_qdotdot_g, hd_correct_grav, total_drag_force, self.wave_forces_g[data.ts, :]) From 817723ad9f22608b78d16ea428de1a7e7ce1176c Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 22 Apr 2021 10:15:36 +0100 Subject: [PATCH 070/253] add controllers and generators to default values --- sharpy/utils/controller_interface.py | 9 ++-- sharpy/utils/generate_cases.py | 80 +++++----------------------- 2 files changed, 19 insertions(+), 70 deletions(-) diff --git a/sharpy/utils/controller_interface.py b/sharpy/utils/controller_interface.py index b382ed2eb..aeff6fbc9 100644 --- a/sharpy/utils/controller_interface.py +++ b/sharpy/utils/controller_interface.py @@ -47,17 +47,18 @@ def controller_list_from_path(cwd): return files -def initialise_controller(controller_name): - cout.cout_wrap('Generating an instance of %s' % controller_name, 2) +def initialise_controller(controller_name, print_info=True): + if print_info: + cout.cout_wrap('Generating an instance of %s' % controller_name, 2) cls_type = controller_from_string(controller_name) controller = cls_type() return controller -def dictionary_of_controllers(): +def dictionary_of_controllers(print_info=True): import sharpy.controllers dictionary = dict() for controller in dict_of_controllers: - init_controller = initialise_controller(controller) + init_controller = initialise_controller(controller, print_info=print_info) dictionary[controller] = init_controller.settings_default return dictionary diff --git a/sharpy/utils/generate_cases.py b/sharpy/utils/generate_cases.py index 9d36be63f..80d4aebe4 100644 --- a/sharpy/utils/generate_cases.py +++ b/sharpy/utils/generate_cases.py @@ -28,6 +28,7 @@ import sharpy.utils.algebra as algebra import sharpy.utils.solver_interface as solver_interface import sharpy.utils.generator_interface as generator_interface +import sharpy.utils.controller_interface as controller_interface import sharpy.structure.utils.lagrangeconstraints as lagrangeconstraints import sharpy.utils.cout_utils as cout @@ -1685,39 +1686,17 @@ def set_default_values(self): """ self.solvers = dict() - # cout.start_writer() - aux_names = solver_interface.dictionary_of_solvers(print_info=False) - # cout.finish_writer() - aux_names.update(generator_interface.dictionary_of_generators(print_info=False)) + aux_solvers = solver_interface.dictionary_of_solvers(print_info=False) + aux_solvers.update(generator_interface.dictionary_of_generators(print_info=False)) + aux_solvers.update(controller_interface.dictionary_of_controllers(print_info=False)) - # TODO: I am sure this can be done in a better way - for solver in aux_names: + for solver in aux_solvers: if solver == 'PreSharpy': solver_name = 'SHARPy' else: solver_name = solver - self.solvers[solver_name] = {} - try: - aux_solver = solver_interface.solver_from_string(solver) - except: - aux_solver = generator_interface.generator_from_string(solver) - # TODO: remove this try/except when generators are rewriten as solvers with class attributes instead of instance attributes - aux_solver.__init__(aux_solver) - - if aux_solver.settings_default == {}: - aux_solver.__init__(aux_solver) - - for key, value in aux_solver.settings_default.items(): - self.solvers[solver_name][key] = deepcopy(value) - - # # MAIN - # self.solvers['SHARPy'] = {'flow': '', - # 'case': 'default_case_name', - # 'route': '', - # 'write_screen': 'on', - # 'write_log': 'off', - # 'log_folder': './output', - # 'log_file': 'log'} + self.solvers[solver_name] = deepcopy(aux_solvers[solver]) + def check(self): @@ -1729,6 +1708,7 @@ def check(self): if key not in default.solvers[solver]: raise RuntimeError(("solver '%s' has no key named '%s'" % (solver, key))) + def define_num_steps(self, num_steps): """ define_num_steps @@ -1739,44 +1719,12 @@ def define_num_steps(self, num_steps): num_steps (int): number of steps """ - solver_names = solver_interface.dictionary_of_solvers(print_info=False) - for solver in solver_names: - if not solver == 'PreSharpy': - if 'n_time_steps' in self.solvers[solver]: - self.solvers[solver]['n_time_steps'] = num_steps - if 'num_steps' in self.solvers[solver]: - self.solvers[solver]['num_steps'] = num_steps - - # TODO:Maybe it would be convenient to use the same name for all the solvers - # try: - # self.solvers["DynamicCoupled"]['n_time_steps'] = num_steps - # except KeyError: - # pass - # # self.solvers["DynamicPrescribedCoupled"]['n_time_steps'] = num_steps - # try: - # self.solvers["StepUvlm"]['n_time_steps'] = num_steps - # except KeyError: - # pass - # try: - # self.solvers['NonLinearDynamicMultibody']['num_steps'] = num_steps - # except KeyError: - # pass - # try: - # self.solvers['NonLinearDynamicCoupledStep']['num_steps'] = num_steps - # except KeyError: - # pass - # try: - # self.solvers['NonLinearDynamicPrescribedStep']['num_steps'] = num_steps - # except KeyError: - # pass - # try: - # self.solvers['RigidDynamicPrescribedStep']['num_steps'] = num_steps - # except KeyError: - # pass - # try: - # self.solvers['SteadyHelicoidalWake']['n_time_steps'] = num_steps - # except KeyError: - # pass + for solver in self.solvers: + if 'n_time_steps' in self.solvers[solver]: + self.solvers[solver]['n_time_steps'] = num_steps + if 'num_steps' in self.solvers[solver]: + self.solvers[solver]['num_steps'] = num_steps + def define_uinf(self, unit_vector, norm): """ From f3451ae3d954f96c29f931cb25efebdd653a9d84 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 22 Apr 2021 12:13:16 +0100 Subject: [PATCH 071/253] fix variable all dicts --- sharpy/utils/generate_cases.py | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 deletions(-) diff --git a/sharpy/utils/generate_cases.py b/sharpy/utils/generate_cases.py index 80d4aebe4..b956d68f2 100644 --- a/sharpy/utils/generate_cases.py +++ b/sharpy/utils/generate_cases.py @@ -315,6 +315,16 @@ def list_methods(class_instance, print_info=True, clean=True): return list +def set_variable_dict(dictionary, variable, set_value): + + if variable in dictionary: + dictionary[variable] = set_value + + for key, value in dictionary.items(): + if isinstance(value, dict): + set_variable_dict(value, variable, set_value) + + ###################################################################### ############### STRUCTURAL INFORMATION ############################# ###################################################################### @@ -1750,7 +1760,8 @@ def define_uinf(self, unit_vector, norm): # self.solvers['StepUvlm']['velocity_field_input'] = {'u_inf': norm, # 'u_inf_direction': unit_vector} - def set_variable_all_dicts(self, variable, value): + + def set_variable_all_dicts(self, variable, set_value): """ set_variable_all_dicts @@ -1758,11 +1769,9 @@ def set_variable_all_dicts(self, variable, value): Args: variable (str): variable name - value ( ): value + set_value ( ): value """ - for solver in self.solvers: - if variable in self.solvers[solver]: - self.solvers[solver][variable] = value + set_variable_dict(self.solvers, variable, set_value) def generate_solver_file(self): """ From 04834772a05f54400d31d319179d97c2c0cefec5 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 22 Apr 2021 18:10:35 +0100 Subject: [PATCH 072/253] fix yaw inertia computation --- cases/templates/template_wt.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/cases/templates/template_wt.py b/cases/templates/template_wt.py index 414e52efb..4c1c7103a 100644 --- a/cases/templates/template_wt.py +++ b/cases/templates/template_wt.py @@ -132,7 +132,6 @@ def spar_from_excel_type04(op_params, # Generate the spar if options['concentrate_spar']: mtower = wt.StructuralInformation.mass_db[0, 0, 0] - iyawtower = wt.StructuralInformation.mass_db[0, 3, 3] PlatformTotalMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, @@ -163,7 +162,7 @@ def spar_from_excel_type04(op_params, # IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**2 # IpitchPoint = PlatformIpitchCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 # IrollPoint = PlatformIrollCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 - IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**3 - iyawtower + IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**3 IpitchPoint = PlatformIpitchCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**3 IrollPoint = PlatformIrollCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**3 xpoint = (PlatformTotalMass*PlatformCMbelowSWL + 0.5*mtower*TowerBaseHeight**2)/mpoint From 36e2b97726bc1f3aa66979603c1192fffc2830f5 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sat, 24 Apr 2021 12:37:14 +0100 Subject: [PATCH 073/253] additional damping --- sharpy/generators/floatingforces.py | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 7e5e8ff7b..eb120521b 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -460,6 +460,14 @@ class FloatingForces(generator_interface.BaseGenerator): settings_default['cd_multiplier'] = 1. settings_description['cd_multiplier'] = 'Multiply the drag coefficient by this number to increase dissipation' + settings_types['add_damp_diag'] = 'list(float)' + settings_default['add_damp_diag'] = [0., 0., 0., 0., 0., 0.] + settings_description['add_damp_diag'] = 'Diagonal terms to include in the additional damping matrix' + + settings_types['add_damp_ts'] = 'int' + settings_default['add_damp_ts'] = 0 + settings_description['add_damp_ts'] = 'Timesteps in which ``add_damp_diag`` will be used' + settings_types['method_matrices_freq'] = 'str' settings_default['method_matrices_freq'] = 'constant' settings_description['method_matrices_freq'] = 'Method to compute frequency-dependent matrices' @@ -840,7 +848,10 @@ def generate(self, params): hs_f_g = self.buoy_F0 - np.dot(self.buoy_rest_mat, self.q[data.ts, :]) if not force_coeff == 0.: - hd_f_qdot_g = -np.dot(self.floating_data['hydrodynamics']['additional_damping'], self.qdot[data.ts, :]) + add_damp = self.floating_data['hydrodynamics']['additional_damping'].copy() + if data.ts < self.settings['add_damp_ts']: + add_damp += np.diag(self.settings['add_damp_diag']) + hd_f_qdot_g = -np.dot(add_damp, self.qdot[data.ts, :]) if ((self.settings['method_matrices_freq'] == 'constant') or (data.ts < self.settings['steps_constant_matrices'])): From 5a98f26b6c78119bf7f3fa915ba4f23c99aae82e Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 25 Apr 2021 13:57:15 +0100 Subject: [PATCH 074/253] shape check initial aeroelastic loader --- sharpy/solvers/initialaeroelasticloader.py | 31 +++++++++++----------- 1 file changed, 16 insertions(+), 15 deletions(-) diff --git a/sharpy/solvers/initialaeroelasticloader.py b/sharpy/solvers/initialaeroelasticloader.py index 94fd0a869..78266db43 100644 --- a/sharpy/solvers/initialaeroelasticloader.py +++ b/sharpy/solvers/initialaeroelasticloader.py @@ -5,6 +5,8 @@ import sharpy.utils.settings as settings import sharpy.utils.algebra as algebra import sharpy.utils.h5utils as h5utils +import sharpy.utils.exceptions as exceptions + @solver class InitialAeroelasticLoader(BaseSolver): @@ -68,20 +70,13 @@ def run(self, structural_step=None, aero_step=None): 'unsteady_applied_forces']) for att in attributes: - getattr(structural_step, att)[...] = getattr(self.file_info.structure, att) - # structural_step.pos_dot = self.file_info.structure.pos_dot - # structural_step.pos_ddot = self.file_info.structure.pos_ddot - # structural_step.psi = self.file_info.structure.psi - # structural_step.psi_dot = self.file_info.structure.psi_dot - # structural_step.psi_ddot = self.file_info.structure.psi_ddot -# - # structural_step.for_pos = self.file_info.structure.for_pos - # structural_step.for_vel = self.file_info.structure.for_vel - # structural_step.for_acc = self.file_info.structure.for_acc - # structural_step.quat = self.file_info.structure.quat - - # Copy multibody information - # mb_FoR_pos vel acc quat + new_attr = getattr(structural_step, att) + db_attr = getattr(self.file_info.structure, att) + if new_attr.shape == db_attr.shape: + new_attr[...] = db_attr + else: + error_msg = "Non matching shapes in attribute %s" % att + exceptions.NotValidInputFile(error_msg) # Copy aero information attributes = ['zeta', 'zeta_star', 'normals', @@ -94,6 +89,12 @@ def run(self, structural_step=None, aero_step=None): for att in attributes: for isurf in range(aero_step.n_surf): - getattr(aero_step, att)[isurf][...] = getattr(self.file_info.aero, att)[isurf] + new_attr = getattr(aero_step, att)[isurf] + db_attr = getattr(self.file_info.aero, att)[isurf] + if new_attr.shape == db_attr.shape: + new_attr[...] = db_attr + else: + error_msg = "Non matching shapes in attribute %s" % att + exceptions.NotValidInputFile(error_msg) return self.data From 060704a739b783d3c519b051708d820ca81a91ad Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 25 Apr 2021 13:57:50 +0100 Subject: [PATCH 075/253] comment out zero initialisation mb --- sharpy/utils/multibody.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index 3f723d52d..b002717e4 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -41,13 +41,13 @@ def split_multibody(beam, tstep, mb_data_dict, ts): ibody_beam.FoR_movement = mb_data_dict['body_%02d' % ibody]['FoR_movement'] - if ts == 1: - ibody_beam.ini_info.pos_dot *= 0 - ibody_beam.timestep_info.pos_dot *= 0 - ibody_tstep.pos_dot *= 0 - ibody_beam.ini_info.psi_dot *= 0 - ibody_beam.timestep_info.psi_dot *= 0 - ibody_tstep.psi_dot *= 0 + #if ts == 1: + # ibody_beam.ini_info.pos_dot *= 0 + # ibody_beam.timestep_info.pos_dot *= 0 + # ibody_tstep.pos_dot *= 0 + # ibody_beam.ini_info.psi_dot *= 0 + # ibody_beam.timestep_info.psi_dot *= 0 + # ibody_tstep.psi_dot *= 0 MB_beam.append(ibody_beam) MB_tstep.append(ibody_tstep) From 89ccc4cc3b8a6fd1610e7d0b14864f87c38a4cb3 Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 28 Apr 2021 13:10:49 +0100 Subject: [PATCH 076/253] fix node CD concentrate spar --- sharpy/generators/floatingforces.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index eb120521b..97d2e4857 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -934,7 +934,10 @@ def generate(self, params): self.floating_data['hydrodynamics']['spar_diameter']* self.cd) - r = spar_node_pos[inode, :] - struct_tstep.pos[self.floating_data['hydrodynamics']['CD_node'], :] + if self.settings['concentrate_spar']: + r = spar_node_pos[inode, :] - struct_tstep.pos[self.floating_data['hydrodynamics']['CD_node'], :] + else: + r = spar_node_pos[inode, :] - struct_tstep.pos[self.floating_data['hydrostatics']['node'], :] drag_moment = np.cross(r, drag_force) total_drag_force[0:3] += drag_force total_drag_force[3:6] += drag_moment From 25bdb0615b202632998e819826f2dbe03887fb9f Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 28 Apr 2021 13:50:41 +0100 Subject: [PATCH 077/253] zero init and rigid bodies --- sharpy/solvers/nonlineardynamicmultibody.py | 49 ++++++++++++++++++++- 1 file changed, 48 insertions(+), 1 deletion(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 7f849e783..f6cf740a8 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -9,6 +9,7 @@ import sharpy.utils.cout_utils as cout import sharpy.structure.utils.xbeamlib as xbeamlib import sharpy.utils.multibody as mb +import sharpy.utils.algebra as algebra import sharpy.structure.utils.lagrangeconstraints as lagrangeconstraints import sharpy.utils.exceptions as exc @@ -53,6 +54,14 @@ class NonLinearDynamicMultibody(_BaseStructural): settings_default['allow_skip_step'] = False settings_description['allow_skip_step'] = 'Allow skip step when NaN is found while solving the system' + settings_types['rigid_bodies'] = 'bool' + settings_default['rigid_bodies'] = False + settings_description['rigid_bodies'] = 'Set to zero the changes in flexible degrees of freedom (not very efficient)' + + settings_types['zero_ini_dot_ddot'] = 'bool' + settings_default['zero_ini_dot_ddot'] = False + settings_description['zero_ini_dot_ddot'] = 'Set to zero the position and crv derivatives at the first time step' + settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -149,6 +158,20 @@ def define_sys_size(self): if (MBdict['body_%02d' % ibody]['FoR_movement'] == 'free'): self.sys_size += 10 + def define_rigid_dofs(self, MB_beam): + + self.n_rigid_dofs = 0 + self.rigid_dofs = [] + + first_dof = 0 + for ibody in range(len(MB_beam)): + last_dof = first_dof + MB_beam[ibody].num_dof.value + if MB_beam[ibody].FoR_movement == 'free': + self.n_rigid_dofs += 10 + self.rigid_dofs += (np.arange(10, dtype=int) + last_dof).tolist() + last_dof += 10 + first_dof = last_dof + 0 + def assembly_MB_eq_system(self, MB_beam, MB_tstep, ts, dt, Lambda, Lambda_dot, MBdict): """ This function generates the matrix and vector associated to the linear system to solve a structural iteration @@ -347,6 +370,16 @@ def run(self, structural_step=None, dt=None): structural_step.whole_structure_to_local_AFoR(self.data.structure, compute_psi_local) + if self.data.ts == 1 and self.settings['zero_ini_dot_ddot']: + self.data.structure.ini_info.pos_dot *= 0. + self.data.structure.ini_info.pos_ddot *= 0. + self.data.structure.ini_info.psi_dot *= 0. + self.data.structure.ini_info.psi_ddot *= 0. + structural_step.pos_dot *= 0. + structural_step.pos_ddot *= 0. + structural_step.psi_dot *= 0. + structural_step.psi_ddot *= 0. + self.num_LM_eq = lagrangeconstraints.define_num_LM_eq(self.lc_list) MB_beam, MB_tstep = mb.split_multibody( @@ -355,6 +388,8 @@ def run(self, structural_step=None, dt=None): MBdict, self.data.ts) + self.define_rigid_dofs(MB_beam) + # Lagrange multipliers parameters num_LM_eq = self.num_LM_eq @@ -407,7 +442,19 @@ def run(self, structural_step=None, dt=None): cond_num = np.linalg.cond(Asys[:self.sys_size, :self.sys_size]) cond_num_lm = np.linalg.cond(Asys) - Dq = np.linalg.solve(Asys, -Q) + if self.settings['rigid_bodies']: + rigid_LM_dofs = self.rigid_dofs + (np.arange(self.num_LM_eq, dtype=int) + self.sys_size).tolist() + # rigid_Asys = np.zeros((self.n_rigid_dofs + self.num_LM_eq, self.n_rigid_dofsi + self.num_LM_eq)) + # rigid_Q = np.zeros((self.n_rigid_dofs + self.num_LM_eq,)) + + rigid_Asys = Asys[np.ix_(rigid_LM_dofs, rigid_LM_dofs)].copy() + rigid_Q = Q[rigid_LM_dofs].copy() + rigid_Dq = np.linalg.solve(rigid_Asys, -rigid_Q) + Dq = np.zeros((self.sys_size + self.num_LM_eq)) + Dq[rigid_LM_dofs] = rigid_Dq.copy() + + else: + Dq = np.linalg.solve(Asys, -Q) # Evaluate convergence if iteration: From dbb642029ca39e862389a3ec2f92d9f79b04705c Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 28 Apr 2021 18:16:31 +0100 Subject: [PATCH 078/253] include option no overhang beam --- cases/templates/template_wt.py | 120 ++++++++++-------- sharpy/structure/utils/lagrangeconstraints.py | 13 +- sharpy/utils/generate_cases.py | 45 +++++++ 3 files changed, 123 insertions(+), 55 deletions(-) diff --git a/cases/templates/template_wt.py b/cases/templates/template_wt.py index 4c1c7103a..b45697bc1 100644 --- a/cases/templates/template_wt.py +++ b/cases/templates/template_wt.py @@ -901,11 +901,7 @@ def generate_from_excel_type03(op_params, tower.StructuralInformation.boundary_conditions = np.zeros((tower.StructuralInformation.num_node), dtype = int) tower.StructuralInformation.boundary_conditions[0] = 1 - # Read overhang and nacelle properties from excel file - overhang_len = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'overhang') - NodesOverhang = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NodesOverhang') - if NodesOverhang is None: - NodesOverhang = 3 + # Nacelle properties from excel file NacelleMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NacMass') NacelleMass_x = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NacMass_x') NacelleMass_z = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NacMass_z') @@ -923,39 +919,39 @@ def generate_from_excel_type03(op_params, tower.StructuralInformation.num_node, tower.StructuralInformation.num_elem) - # Assembly overhang with the tower - # numberOfBlades = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NumBl') + # Overhang tilt = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'ShftTilt')*deg2rad - # cone = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'Cone')*deg2rad - HubMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'HubMass') - - overhang = gc.AeroelasticInformation() - overhang.StructuralInformation.num_node = NodesOverhang - overhang.StructuralInformation.num_node_elem = 3 - overhang.StructuralInformation.compute_basic_num_elem() - node_pos = np.zeros((overhang.StructuralInformation.num_node, 3), ) - node_pos[:, 0] += tower.StructuralInformation.coordinates[-1, 0] - node_pos[:, 0] += np.linspace(0., -overhang_len*np.sin(tilt*deg2rad), overhang.StructuralInformation.num_node) - node_pos[:, 2] = np.linspace(0., overhang_len*np.cos(tilt*deg2rad), overhang.StructuralInformation.num_node) - # TODO: change the following by real values - # Same properties as the last element of the tower - # cout.cout_wrap("WARNING: Using the structural properties of the last tower section for the overhang", 3) - # oh_mass_per_unit_length = tower.StructuralInformation.mass_db[-1, 0, 0] - # oh_mass_iner = tower.StructuralInformation.mass_db[-1, 3, 3] - cout.cout_wrap("WARNING: Using the structural properties (*0.1) of the last tower section for the overhang", 3) - oh_mass_per_unit_length = tower.StructuralInformation.mass_db[-1, 0, 0]/10. - oh_mass_iner = tower.StructuralInformation.mass_db[-1, 3, 3]/10. - oh_EA = tower.StructuralInformation.stiffness_db[-1, 0, 0] - oh_GA = tower.StructuralInformation.stiffness_db[-1, 1, 1] - oh_GJ = tower.StructuralInformation.stiffness_db[-1, 3, 3] - oh_EI = tower.StructuralInformation.stiffness_db[-1, 4, 4] - if not HubMass is None: - num_lumped_mass_overhang = 1 + if not tilt == 0.: + raise NonImplementedError("Non-zero tilt not supported") + NodesOverhang = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NodesOverhang') + overhang_len = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'overhang') + if NodesOverhang == 0: + with_overhang = False else: - cout.cout_wrap('WARNING: HubMass not found', 3) - num_lumped_mass_overhang = 0 - - overhang.StructuralInformation.generate_uniform_sym_beam(node_pos, + with_overhang = True + + overhang = gc.AeroelasticInformation() + overhang.StructuralInformation.num_node = NodesOverhang + overhang.StructuralInformation.num_node_elem = 3 + overhang.StructuralInformation.compute_basic_num_elem() + node_pos = np.zeros((overhang.StructuralInformation.num_node, 3), ) + node_pos[:, 0] += tower.StructuralInformation.coordinates[-1, 0] + node_pos[:, 0] += np.linspace(0., -overhang_len*np.sin(tilt*deg2rad), overhang.StructuralInformation.num_node) + node_pos[:, 2] = np.linspace(0., overhang_len*np.cos(tilt*deg2rad), overhang.StructuralInformation.num_node) + # TODO: change the following by real values + # Same properties as the last element of the tower + # cout.cout_wrap("WARNING: Using the structural properties of the last tower section for the overhang", 3) + # oh_mass_per_unit_length = tower.StructuralInformation.mass_db[-1, 0, 0] + # oh_mass_iner = tower.StructuralInformation.mass_db[-1, 3, 3] + cout.cout_wrap("WARNING: Using the structural properties (*0.1) of the last tower section for the overhang", 3) + oh_mass_per_unit_length = tower.StructuralInformation.mass_db[-1, 0, 0]/10. + oh_mass_iner = tower.StructuralInformation.mass_db[-1, 3, 3]/10. + oh_EA = tower.StructuralInformation.stiffness_db[-1, 0, 0] + oh_GA = tower.StructuralInformation.stiffness_db[-1, 1, 1] + oh_GJ = tower.StructuralInformation.stiffness_db[-1, 3, 3] + oh_EI = tower.StructuralInformation.stiffness_db[-1, 4, 4] + + overhang.StructuralInformation.generate_uniform_sym_beam(node_pos, oh_mass_per_unit_length, oh_mass_iner, oh_EA, @@ -964,25 +960,38 @@ def generate_from_excel_type03(op_params, oh_EI, num_node_elem=3, y_BFoR='y_AFoR', - num_lumped_mass=num_lumped_mass_overhang) - - overhang.StructuralInformation.boundary_conditions = np.zeros((overhang.StructuralInformation.num_node), dtype=int) - overhang.StructuralInformation.boundary_conditions[-1] = -1 - - if not HubMass is None: - # Include hub mass - overhang.StructuralInformation.lumped_mass_nodes = np.array([overhang.StructuralInformation.num_node - 1], dtype=int) - overhang.StructuralInformation.lumped_mass = np.array([HubMass], dtype=float) + num_lumped_mass=0) + + overhang.StructuralInformation.boundary_conditions[-1] = -1 - overhang.AerodynamicInformation.set_to_zero(overhang.StructuralInformation.num_node_elem, + overhang.AerodynamicInformation.set_to_zero(overhang.StructuralInformation.num_node_elem, overhang.StructuralInformation.num_node, overhang.StructuralInformation.num_elem) - tower.assembly(overhang) - tower.remove_duplicated_points(tol_remove_points) + tower.assembly(overhang) + tower.remove_duplicated_points(tol_remove_points) + tower.StructuralInformation.body_number *= 0 + for inode in range(len(hub_nodes)): hub_nodes[inode] += tower.StructuralInformation.num_node - tower.StructuralInformation.body_number *= 0 + + # Hub mass + HubMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'HubMass') + if HubMass is not None: + if with_overhang: + tower.StructuralInformation.add_lumped_mass(tower.StructuralInformation.num_node -1, + HubMass, + inertia=np.zeros((3, 3)), + pos=np.zeros((3))) + else: + n_hub_nodes = len(hub_nodes) + for inode_hub in range(n_hub_nodes): + rotor.StructuralInformation.add_lumped_mass(hub_nodes[inode_hub], + HubMass/n_hub_nodes, + inertia=np.zeros((3, 3)), + pos=np.zeros((3))) + else: + cout.cout_wrap('WARNING: HubMass not found', 3) ###################################################################### ## WIND TURBINE @@ -990,6 +999,8 @@ def generate_from_excel_type03(op_params, # Assembly the whole case wt = tower.copy() hub_position = tower.StructuralInformation.coordinates[-1, :] + if not with_overhang: + hub_position += np.array([0., 0., overhang_len]) rotor.StructuralInformation.coordinates += hub_position wt.assembly(rotor) @@ -1008,7 +1019,12 @@ def generate_from_excel_type03(op_params, LC1.node_in_body = tower.StructuralInformation.num_node - 1 LC1.body = 0 LC1.body_FoR = iblade + 1 - LC1.rot_vect = np.array([-1., 0., 0.])*rotation_velocity + if with_overhang: + LC1.rot_vect = np.array([-1., 0., 0.])*rotation_velocity + LC1.rel_posB = np.zeros((3)) + else: + LC1.rot_vect = np.array([0., 0., 1.])*rotation_velocity + LC1.rel_posB = np.array([0., 0., overhang_len]) LC.append(LC1) # Define the multibody infromation for the tower and the rotor @@ -1026,9 +1042,7 @@ def generate_from_excel_type03(op_params, for iblade in range(numberOfBlades): MB2 = gc.BodyInformation() MB2.body_number = iblade + 1 - MB2.FoR_position = np.array([tower.StructuralInformation.coordinates[-1, 0], - tower.StructuralInformation.coordinates[-1, 1], tower.StructuralInformation.coordinates[-1, 2], - 0.0, 0.0, 0.0]) + MB2.FoR_position = np.concatenate((hub_position, np.zeros((3)))) MB2.FoR_velocity = np.array([0., 0., 0., 0., 0., rotation_velocity]) MB2.FoR_acceleration = np.zeros((6,),) MB2.FoR_movement = 'free' diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 4bbcfc5e4..7d58a2d3b 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -955,11 +955,12 @@ class hinge_node_FoR_constant_vel(BaseLagrangeConstraint): node_body (int): body number of the "node" FoR_body (int): body number of the "FoR" rot_vect (np.ndarray): Rotation velocity vector in the node B FoR + rel_posB (np.ndarray): Relative position between the node and the frame of reference in the node B FoR """ _lc_id = 'hinge_node_FoR_constant_vel' def __init__(self): - self.required_parameters = ['node_in_body', 'body', 'body_FoR', 'rot_vect'] + self.required_parameters = ['node_in_body', 'body', 'body_FoR', 'rot_vect', 'rel_posB'] self._n_eq = 6 def get_n_eq(self): @@ -971,6 +972,7 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.node_body = MBdict_entry['body'] self.FoR_body = MBdict_entry['body_FoR'] self.rot_axisB = ag.unit_vector(MBdict_entry['rot_vect']) + self.rel_posB = MBdict_entry['rel_posB'] self._ieq = ieq self.indep = [] self.scalingFactor = set_value_or_default(MBdict_entry, "scalingFactor", 1.) @@ -1022,7 +1024,14 @@ def staticpost(self, lc_list, MB_beam, MB_tstep): return def dynamicpost(self, lc_list, MB_beam, MB_tstep): - MB_tstep[self.FoR_body].for_pos[0:3] = np.dot(MB_tstep[self.node_body].cga(), MB_tstep[self.node_body].pos[self.node_number,:]) + MB_tstep[self.node_body].for_pos[0:3] + + ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] + node_cga = MB_tstep[self.node_body].cga() + cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem, inode_in_elem, :]) + + MB_tstep[self.FoR_body].for_pos[0:3] = (np.dot(node_cga, + MB_tstep[self.node_body].pos[self.node_number,:] + np.dot(cab, self.rel_posB)) + + MB_tstep[self.node_body].for_pos[0:3]) # ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] # node_cga = MB_tstep[self.node_body].cga() diff --git a/sharpy/utils/generate_cases.py b/sharpy/utils/generate_cases.py index b956d68f2..1c59ba34a 100644 --- a/sharpy/utils/generate_cases.py +++ b/sharpy/utils/generate_cases.py @@ -325,6 +325,19 @@ def set_variable_dict(dictionary, variable, set_value): set_variable_dict(value, variable, set_value) +def define_or_concatenate(variable, value, axis=0): + """ + if variable is None, value is assigned + If variable is an array, value is concatenated along axis + """ + if variable is None: + variable = value + else: + variable = np.concatenate((variable, value), axis=axis) + + return variable + + ###################################################################### ############### STRUCTURAL INFORMATION ############################# ###################################################################### @@ -838,6 +851,38 @@ def generate_uniform_beam(self, self.boundary_conditions = np.zeros((self.num_node), dtype=int) + def add_lumped_mass(self, node, mass=None, inertia=None, pos=None, mat=None): + """ + Add lumped mass to structure + + node(int): Node where the lumped mass is to be placed + + For lumped masses: + mass(float): Mass + inertia(np.array): 3x3 inertia matrix + pos(np.array): 3 coordinates of the mass position + + For lumped masses described as a 6x6 matrix: + mat(np.array): 6x6 mass and inertia matrix + """ + + if (mass is not None) and (inertia is not None): + if pos is None: + pos = np.zeros((3)) + if mat is not None: + raise ValueError("mass, inertia and mat cannot be defined at the same time") + + self.lumped_mass_nodes = define_or_concatenate(self.lumped_mass_nodes, np.array([node]), axis=0) + self.lumped_mass = define_or_concatenate(self.lumped_mass, np.array([mass]), axis=0) + self.lumped_mass_inertia = define_or_concatenate(self.lumped_mass_inertia, np.array([inertia]), axis=0) + self.lumped_mass_position = define_or_concatenate(self.lumped_mass_position, np.array([pos]), axis=0) + + elif (mat is not None): + + self.lumped_mass_mat_nodes = define_or_concatenate(self.lumped_mass_mat_nodes, np.array([node]), axis=0) + self.lumped_mass_mat = define_or_concatenate(self.lumped_mass_mat, np.array([mat]), axis=0) + + def assembly_structures(self, *args): """ assembly_structures From c2783ba8df4d33501abf617443034f564526e100 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 29 Apr 2021 19:10:24 +0100 Subject: [PATCH 079/253] update fully constrained WIP --- sharpy/structure/utils/lagrangeconstraints.py | 47 +++++++------------ 1 file changed, 16 insertions(+), 31 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 7d58a2d3b..9b1be384f 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -1417,7 +1417,7 @@ class fully_constrained_node_FoR(BaseLagrangeConstraint): _lc_id = 'fully_constrained_node_FoR' def __init__(self): - self.required_parameters = ['node_in_body', 'body', 'body_FoR'] + self.required_parameters = ['node_in_body', 'body', 'body_FoR', 'rel_posB'] self._n_eq = 6 def get_n_eq(self): @@ -1425,10 +1425,11 @@ def get_n_eq(self): def initialise(self, MBdict_entry, ieq, print_info=True): - cout.cout_wrap("WARNING: do not use fully_constrained_node_FoR. It is outdated. Definetly not working if 'body' has velocity", 3) + # cout.cout_wrap("WARNING: do not use fully_constrained_node_FoR. It is outdated. Definetly not working if 'body' has velocity", 3) self.node_number = MBdict_entry['node_in_body'] self.node_body = MBdict_entry['body'] self.FoR_body = MBdict_entry['body_FoR'] + self.rel_posB = MBdict_entry['rel_posB'] self._ieq = ieq self.scalingFactor = set_value_or_default(MBdict_entry, "scalingFactor", 1.) self.penaltyFactor = set_value_or_default(MBdict_entry, "penaltyFactor", 0.) @@ -1441,47 +1442,31 @@ def staticmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, sys_size, dt, Lambda, Lambda_dot): - num_LM_eq_specific = self._n_eq - Bnh = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') - B = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') + # Define the position of the first degree of freedom associated to the node node_dof = define_node_dof(MB_beam, self.node_body, self.node_number) + node_FoR_dof = define_FoR_dof(MB_beam, self.node_body) FoR_dof = define_FoR_dof(MB_beam, self.FoR_body) ieq = self._ieq - # Option with non holonomic constraints - # BC for linear velocities - Bnh[:3, node_dof:node_dof+3] = -1.0*np.eye(3) - quat = ag.quat_bound(MB_tstep[self.FoR_body].quat) - Bnh[:3, FoR_dof:FoR_dof+3] = ag.quat2rotation(quat) - - # BC for angular velocities - Bnh[3:6,FoR_dof+3:FoR_dof+6] = -1.0*ag.quat2rotation(quat) - ielem, inode_in_elem = MB_beam[0].node_master_elem[self.node_number] - Bnh[3:6,node_dof+3:node_dof+6] = ag.crv2tan(MB_tstep[0].psi[ielem, inode_in_elem, :]) - - LM_C[sys_size+ieq:sys_size+ieq+num_LM_eq_specific,:sys_size] += self.scalingFactor*Bnh - LM_C[:sys_size,sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += self.scalingFactor*np.transpose(Bnh) - - LM_Q[:sys_size] += self.scalingFactor*np.dot(np.transpose(Bnh),Lambda_dot[ieq:ieq+num_LM_eq_specific]) - LM_Q[sys_size+ieq:sys_size+ieq+3] += -self.scalingFactor*MB_tstep[0].pos_dot[-1,:] + np.dot(ag.quat2rotation(quat),MB_tstep[1].for_vel[0:3]) - LM_Q[sys_size+ieq+3:sys_size+ieq+6] += self.scalingFactor*(np.dot(ag.crv2tan(MB_tstep[0].psi[ielem, inode_in_elem, :]),MB_tstep[0].psi_dot[ielem, inode_in_elem, :]) - - np.dot(ag.quat2rotation(quat), MB_tstep[self.FoR_body].for_vel[3:6])) - - #LM_K[FoR_dof:FoR_dof+3,FoR_dof+6:FoR_dof+10] = ag.der_CquatT_by_v(MB_tstep[body_FoR].quat,Lambda_dot) - LM_C[FoR_dof:FoR_dof+3,FoR_dof+6:FoR_dof+10] += self.scalingFactor*ag.der_CquatT_by_v(quat,Lambda_dot[ieq:ieq+3]) - LM_C[FoR_dof+3:FoR_dof+6,FoR_dof+6:FoR_dof+10] -= self.scalingFactor*ag.der_CquatT_by_v(quat,Lambda_dot[ieq+3:ieq+6]) - - LM_K[node_dof+3:node_dof+6,node_dof+3:node_dof+6] += self.scalingFactor*ag.der_TanT_by_xv(MB_tstep[0].psi[ielem, inode_in_elem, :],Lambda_dot[ieq+3:ieq+6]) + # Define the equations + ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, np.array([1., 0., 0.]), self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, [1, 2]) + ieq = def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, 0, 0., self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) - ieq += 6 return def staticpost(self, lc_list, MB_beam, MB_tstep): return def dynamicpost(self, lc_list, MB_beam, MB_tstep): - # MB_tstep[self.FoR_body].for_pos[0:3] = np.dot(ag.quat2rotation(MB_tstep[self.node_body].quat), MB_tstep[self.node_body].pos[self.node_number,:]) + MB_tstep[self.node_body].for_pos[0:3] + ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] + node_cga = MB_tstep[self.node_body].cga() + cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem, inode_in_elem, :]) + + MB_tstep[self.FoR_body].for_pos[0:3] = (np.dot(node_cga, + MB_tstep[self.node_body].pos[self.node_number,:] + np.dot(cab, self.rel_posB)) + + MB_tstep[self.node_body].for_pos[0:3]) return From 761b03e02590da5e21f25f8107261acb57ed858a Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 29 Apr 2021 19:14:20 +0100 Subject: [PATCH 080/253] rename function --- sharpy/structure/utils/lagrangeconstraints.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 9b1be384f..6d951687e 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -712,7 +712,7 @@ def def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, FoR_body, node_body, node_n return ieq -def def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, nonzero_comp, rot_vel, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q): +def def_rot_vel_mod_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, nonzero_comp, rot_vel, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q): """ This function generates the stiffness and damping matrices and the independent vector associated to a joint that forces the rotation velocity of a FoR with respect to a node @@ -808,7 +808,7 @@ def def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_number def def_rot_vect_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, rot_vect, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q): """ This function fixes the rotation velocity VECTOR of a FOR equal to a velocity vector defined in the B FoR of a node - This function is a new implementation that combines and simplifies the use of 'def_rot_vel_FoR_wrt_node' and 'def_rot_axis_FoR_wrt_node' together + This function is a new implementation that combines and simplifies the use of 'def_rot_vel_mod_FoR_wrt_node' and 'def_rot_axis_FoR_wrt_node' together """ num_LM_eq_specific = 3 @@ -1017,7 +1017,7 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) # ieq = def_rot_vect_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_vect, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) ieq = def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_axisB, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, self.zero_comp) - ieq = def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.nonzero_comp, self.rot_vel, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = def_rot_vel_mod_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.nonzero_comp, self.rot_vel, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) return def staticpost(self, lc_list, MB_beam, MB_tstep): @@ -1452,7 +1452,7 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, # Define the equations ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) ieq = def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, np.array([1., 0., 0.]), self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, [1, 2]) - ieq = def_rot_vel_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, 0, 0., self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = def_rot_vel_mod_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, 0, 0., self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) return From ad306b983de801ed118d7bc443172c8829399098 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 30 Apr 2021 08:56:37 +0100 Subject: [PATCH 081/253] fix hub nodes --- cases/templates/template_wt.py | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/cases/templates/template_wt.py b/cases/templates/template_wt.py index b45697bc1..9263e1dc5 100644 --- a/cases/templates/template_wt.py +++ b/cases/templates/template_wt.py @@ -116,7 +116,6 @@ def spar_from_excel_type04(op_params, geom_params, excel_description, options) - # Remove base clam wt.StructuralInformation.boundary_conditions[0] = 0 @@ -180,7 +179,7 @@ def spar_from_excel_type04(op_params, base_stiffness_bot = 100*base_stiffness_top base_mass_bot = base_mass_top - num_lumped_mass_mat = 0 + num_lumped_mass_mat = 1 else: SparHeight = gc.read_column_sheet_type01(excel_file_name, @@ -971,9 +970,6 @@ def generate_from_excel_type03(op_params, tower.assembly(overhang) tower.remove_duplicated_points(tol_remove_points) tower.StructuralInformation.body_number *= 0 - - for inode in range(len(hub_nodes)): - hub_nodes[inode] += tower.StructuralInformation.num_node # Hub mass HubMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'HubMass') @@ -993,6 +989,9 @@ def generate_from_excel_type03(op_params, else: cout.cout_wrap('WARNING: HubMass not found', 3) + for inode in range(len(hub_nodes)): + hub_nodes[inode] += tower.StructuralInformation.num_node + ###################################################################### ## WIND TURBINE ###################################################################### From e8f529f5b583192523a1e1a7d30754b7c1dffc5a Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 30 Apr 2021 08:57:59 +0100 Subject: [PATCH 082/253] change convergence mb --- sharpy/solvers/nonlineardynamicmultibody.py | 65 ++++++++++++--------- 1 file changed, 38 insertions(+), 27 deletions(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index f6cf740a8..8a9274bd2 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -456,31 +456,13 @@ def run(self, structural_step=None, dt=None): else: Dq = np.linalg.solve(Asys, -Q) - # Evaluate convergence - if iteration: - res = np.max(np.abs(Dq[0:self.sys_size]))/old_Dq - if np.isnan(res): - print(old_Dq) - if self.settings['allow_skip_step']: - skip_step = True - cout.cout_wrap("Skipping step", 3) - break - else: - raise exc.NotConvergedSolver('Multibody Dq = NaN') - if num_LM_eq: - LM_res = np.max(np.abs(Dq[self.sys_size:self.sys_size+num_LM_eq]))/LM_old_Dq - else: - LM_res = 0.0 - if (res < self.settings['min_delta']) and (LM_res < self.settings['min_delta']): - # if (res < self.settings['min_delta']): - converged = True - else: - old_Dq = np.max(np.abs(Dq[0:self.sys_size])) - if old_Dq == 0: - print("old_Dq ==0") - old_Dq = 1. - if num_LM_eq: - LM_old_Dq = np.max(np.abs(Dq[self.sys_size:self.sys_size+num_LM_eq])) + #if (not np.isnan(Dq).any()) and (not (Dq == 0.).all()): + # msg = ("k:%d pos_min:%d min:%e pos_max:%d max:%e" % (iteration, + # np.where(Dq == np.min(Dq))[0], + # np.min(Dq), + # np.where(Dq == np.max(Dq))[0], + # np.max(Dq))) + # print(msg) # Relaxation relax_Dq = np.zeros_like(Dq) @@ -492,9 +474,38 @@ def run(self, structural_step=None, dt=None): # Corrector step self.time_integrator.corrector(q, dqdt, dqddt, relax_Dq) - if converged: - break + # Reference values for convergence + if iteration == 0: + old_Dq = np.max(np.abs(Dq[0:self.sys_size])) + if num_LM_eq: + LM_old_Dq = np.max(np.abs(Dq[self.sys_size:self.sys_size+num_LM_eq])) + else: + LM_old_Dq = 0. + # Change the reference values + if old_Dq == 0: + old_Dq = 1. + if LM_old_Dq == 0: + LM_old_Dq = 1. + # Evaluate convergence + res = np.max(np.abs(Dq[0:self.sys_size]))/old_Dq + if np.isnan(res): + print(old_Dq) + if self.settings['allow_skip_step']: + skip_step = True + cout.cout_wrap("Skipping step", 3) + break + else: + raise exc.NotConvergedSolver('Multibody Dq = NaN') + if num_LM_eq: + LM_res = np.max(np.abs(Dq[self.sys_size:self.sys_size+num_LM_eq]))/LM_old_Dq + else: + LM_res = 0.0 + + if (res < self.settings['min_delta']) and (LM_res < self.settings['min_delta']): + # if (res < self.settings['min_delta']): + converged = True + break Lambda, Lambda_dot = mb.state2disp_and_accel(q, dqdt, dqddt, MB_beam, MB_tstep, num_LM_eq) if self.settings['write_lm']: From 5f4f8d3805c1e5bd3f79100b32b6b57c00da4015 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 30 Apr 2021 08:59:47 +0100 Subject: [PATCH 083/253] lumped mass mat in split mb --- sharpy/structure/models/beam.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/sharpy/structure/models/beam.py b/sharpy/structure/models/beam.py index 0b7bd90f1..755afcdb4 100644 --- a/sharpy/structure/models/beam.py +++ b/sharpy/structure/models/beam.py @@ -580,6 +580,18 @@ def get_body(self, ibody): ibody_beam.lumped_mass_position = np.concatenate((ibody_beam.lumped_mass_position ,np.array([self.lumped_mass_position[inode]])), axis=0) ibody_beam.n_lumped_mass += 1 + if not self.lumped_mass_mat is None: + is_first = True + for inode in range(len(self.lumped_mass_mat_nodes)): + if self.lumped_mass_mat_nodes[inode] in ibody_nodes: + if is_first: + is_first = False + ibody_beam.lumped_mass_mat_nodes = int_list_nodes[ibody_nodes == self.lumped_mass_mat_nodes[inode]] + ibody_beam.lumped_mass_mat = np.array([self.lumped_mass_mat[inode, :, :]]) + else: + ibody_beam.lumped_mass_mat_nodes = np.concatenate((ibody_beam.lumped_mass_mat_nodes , int_list_nodes[ibody_nodes == self.lumped_mass_mat_nodes[inode]]), axis=0) + ibody_beam.lumped_mass_mat = np.concatenate((ibody_beam.lumped_mass_mat ,np.array([self.lumped_mass_mat[inode, :, :]])), axis=0) + ibody_beam.steady_app_forces = self.steady_app_forces[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) ibody_beam.num_bodies = 1 From 743ad802ddf38841dfc281672fb8930d73fc9834 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 30 Apr 2021 09:00:19 +0100 Subject: [PATCH 084/253] equal rot vel node FoR --- sharpy/structure/utils/lagrangeconstraints.py | 61 ++++++++++++++++++- 1 file changed, 59 insertions(+), 2 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 6d951687e..89532f01d 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -413,6 +413,64 @@ def equal_lin_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, return ieq +def equal_rot_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q): + """ + This function generates the stiffness and damping matrices and the independent vector associated to a constraint that + imposes equal rotation velocities between a node and a frame of reference + + See ``LagrangeConstraints`` for the description of variables + + Args: + node_number (int): number of the "node" within its own body + node_body (int): body number of the "node" + node_FoR_dof (int): position of the first degree of freedom of the FoR to which the "node" belongs + node_dof (int): position of the first degree of freedom associated to the "node" + FoR_body (int): body number of the "FoR" + FoR_dof (int): position of the first degree of freedom associated to the "FoR" + """ + + num_LM_eq_specific = 3 + Bnh = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') + + # Simplify notation + ielem, inode_in_elem = MB_beam[node_body].node_master_elem[node_number] + node_cga = MB_tstep[node_body].cga() + node_FoR_wa = MB_tstep[node_body].for_vel[3:6] + psi = MB_tstep[node_body].psi[ielem,inode_in_elem,:] + cab = ag.crv2rotation(psi) + tan = ag.crv2tan(psi) + + FoR_cga = MB_tstep[FoR_body].cga() + FoR_wa = MB_tstep[FoR_body].for_vel[3:6] + + Bnh[:, node_dof+3:node_dof+6] += tan.copy() + Bnh[:, FoR_dof+3:FoR_dof+6] -= ag.multiply_matrices(cab.T, node_cga.T, FoR_cga) + if MB_beam[node_body].FoR_movement == 'free': + Bnh[:, node_FoR_dof+3:node_FoR_dof+6] += cab.T + + LM_C[sys_size+ieq:sys_size+ieq+num_LM_eq_specific,:sys_size] += scalingFactor*Bnh + LM_C[:sys_size,sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*np.transpose(Bnh) + + LM_Q[:sys_size] += scalingFactor*np.dot(np.transpose(Bnh), Lambda_dot[ieq:ieq+num_LM_eq_specific]) + LM_Q[sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*(np.dot(tan, MB_tstep[node_body].psi_dot[ielem, inode_in_elem, :]) + + np.dot(cab.T, node_FoR_wa) - + ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, FoR_wa)) + + LM_K[node_dof+3:node_dof+6, node_dof+3:node_dof+6] += scalingFactor*ag.der_TanT_by_xv(psi, Lambda_dot[ieq:ieq+num_LM_eq_specific]) + if MB_beam[node_body].FoR_movement == 'free': + LM_K[node_FoR_dof+3:node_FoR_dof+6, node_dof+3:node_dof+6] += scalingFactor*ag.der_Ccrv_by_v(psi, Lambda_dot[ieq:ieq+num_LM_eq_specific]) + + LM_K[FoR_dof+3:FoR_dof+6, node_dof+3:node_dof+6] -= scalingFactor*ag.der_Ccrv_by_v(psi, + ag.multiply_matrices(node_cga, FoR_cga.T, Lambda_dot[ieq:ieq+num_LM_eq_specific])) + + LM_C[FoR_dof+3:FoR_dof+6, node_FoR_dof+6:node_FoR_dof+10] -= scalingFactor*np.dot(cab, ag.der_Cquat_by_v(MB_tstep[node_body].quat, + np.dot(FoR_cga.T, Lambda_dot[ieq:ieq+num_LM_eq_specific]))) + LM_C[FoR_dof+3:FoR_dof+6, FoR_dof+6:FoR_dof+10] -= scalingFactor*ag.multiply_matrices(cab, node_cga, ag.der_CquatT_by_v(MB_tstep[FoR_body].quat, + Lambda_dot[ieq:ieq+num_LM_eq_specific])) + + ieq += 3 + return ieq + def def_rot_axis_FoR_wrt_node_general(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, rot_axisB, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q, indep): """ This function generates the stiffness and damping matrices and the independent vector associated to a joint that @@ -1451,8 +1509,7 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, # Define the equations ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) - ieq = def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, np.array([1., 0., 0.]), self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, [1, 2]) - ieq = def_rot_vel_mod_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, 0, 0., self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = equal_rot_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) return From a49d925487bc07666ca43fe5e471ee845f3ffe16 Mon Sep 17 00:00:00 2001 From: Unknown Date: Mon, 3 May 2021 20:04:54 +0100 Subject: [PATCH 085/253] simplify multibody functions --- sharpy/solvers/nonlineardynamicmultibody.py | 66 ++++--- sharpy/structure/models/beam.py | 4 +- sharpy/utils/datastructures.py | 194 ++++++++++---------- sharpy/utils/multibody.py | 28 ++- 4 files changed, 154 insertions(+), 138 deletions(-) diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 8a9274bd2..73a380d77 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -61,7 +61,7 @@ class NonLinearDynamicMultibody(_BaseStructural): settings_types['zero_ini_dot_ddot'] = 'bool' settings_default['zero_ini_dot_ddot'] = False settings_description['zero_ini_dot_ddot'] = 'Set to zero the position and crv derivatives at the first time step' - + settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -162,8 +162,8 @@ def define_rigid_dofs(self, MB_beam): self.n_rigid_dofs = 0 self.rigid_dofs = [] - - first_dof = 0 + + first_dof = 0 for ibody in range(len(MB_beam)): last_dof = first_dof + MB_beam[ibody].num_dof.value if MB_beam[ibody].FoR_movement == 'free': @@ -194,7 +194,6 @@ def assembly_MB_eq_system(self, MB_beam, MB_tstep, ts, dt, Lambda, Lambda_dot, M MB_Asys (np.ndarray): Matrix of the systems of equations MB_Q (np.ndarray): Vector of the systems of equations """ - self.num_LM_eq = lagrangeconstraints.define_num_LM_eq(self.lc_list) MB_M = np.zeros((self.sys_size, self.sys_size), dtype=ct.c_double, order='F') MB_C = np.zeros((self.sys_size, self.sys_size), dtype=ct.c_double, order='F') @@ -356,31 +355,19 @@ def run(self, structural_step=None, dt=None): else: self.settings['dt'] = dt - if self.data.ts == 1: - compute_psi_local = True - print("Computing psi local") - else: - compute_psi_local = False - - if self.data.structure.ini_info.in_global_AFoR: - self.data.structure.ini_info.whole_structure_to_local_AFoR(self.data.structure, - compute_psi_local) - - if structural_step.in_global_AFoR: - structural_step.whole_structure_to_local_AFoR(self.data.structure, - compute_psi_local) + #if self.data.ts == 1: + # compute_psi_local = True + # print("Computing psi local") + #else: + # compute_psi_local = False - if self.data.ts == 1 and self.settings['zero_ini_dot_ddot']: - self.data.structure.ini_info.pos_dot *= 0. - self.data.structure.ini_info.pos_ddot *= 0. - self.data.structure.ini_info.psi_dot *= 0. - self.data.structure.ini_info.psi_ddot *= 0. - structural_step.pos_dot *= 0. - structural_step.pos_ddot *= 0. - structural_step.psi_dot *= 0. - structural_step.psi_ddot *= 0. - - self.num_LM_eq = lagrangeconstraints.define_num_LM_eq(self.lc_list) + #if self.data.structure.ini_info.in_global_AFoR: + # self.data.structure.ini_info.whole_structure_to_local_AFoR(self.data.structure, + # compute_psi_local) +# + #if structural_step.in_global_AFoR: + # structural_step.whole_structure_to_local_AFoR(self.data.structure, + # compute_psi_local) MB_beam, MB_tstep = mb.split_multibody( self.data.structure, @@ -389,10 +376,21 @@ def run(self, structural_step=None, dt=None): self.data.ts) self.define_rigid_dofs(MB_beam) - - # Lagrange multipliers parameters num_LM_eq = self.num_LM_eq + if self.data.ts == 1 and self.settings['zero_ini_dot_ddot']: + for ibody in range(len(MB_tstep)): + MB_beam[ibody].ini_info.pos_dot *= 0. + MB_beam[ibody].ini_info.pos_ddot *= 0. + MB_beam[ibody].ini_info.psi_dot *= 0. + MB_beam[ibody].ini_info.psi_dot_local *= 0. + MB_beam[ibody].ini_info.psi_ddot *= 0. + MB_tstep[ibody].pos_dot *= 0. + MB_tstep[ibody].pos_ddot *= 0. + MB_tstep[ibody].psi_dot *= 0. + MB_tstep[ibody].psi_dot_local *= 0. + MB_tstep[ibody].psi_ddot *= 0. + # Initialize # TODO: i belive this can move into disp_and_accel2 state as self.Lambda, self.Lambda_dot if not num_LM_eq == 0: @@ -452,7 +450,7 @@ def run(self, structural_step=None, dt=None): rigid_Dq = np.linalg.solve(rigid_Asys, -rigid_Q) Dq = np.zeros((self.sys_size + self.num_LM_eq)) Dq[rigid_LM_dofs] = rigid_Dq.copy() - + else: Dq = np.linalg.solve(Asys, -Q) @@ -501,7 +499,7 @@ def run(self, structural_step=None, dt=None): LM_res = np.max(np.abs(Dq[self.sys_size:self.sys_size+num_LM_eq]))/LM_old_Dq else: LM_res = 0.0 - + if (res < self.settings['min_delta']) and (LM_res < self.settings['min_delta']): # if (res < self.settings['min_delta']): converged = True @@ -534,8 +532,8 @@ def run(self, structural_step=None, dt=None): xbeamlib.cbeam3_correct_gravity_forces(MB_beam[ibody], MB_tstep[ibody], self.settings) mb.merge_multibody(MB_tstep, MB_beam, self.data.structure, structural_step, MBdict, dt) - if not structural_step.in_global_AFoR: - structural_step.whole_structure_to_global_AFoR(self.data.structure) + # if not structural_step.in_global_AFoR: + # structural_step.whole_structure_to_global_AFoR(self.data.structure) self.Lambda = Lambda.astype(dtype=ct.c_double, copy=True, order='F') self.Lambda_dot = Lambda_dot.astype(dtype=ct.c_double, copy=True, order='F') diff --git a/sharpy/structure/models/beam.py b/sharpy/structure/models/beam.py index 755afcdb4..cb6b71680 100644 --- a/sharpy/structure/models/beam.py +++ b/sharpy/structure/models/beam.py @@ -112,8 +112,8 @@ def generate(self, in_data, settings): # connectivity information self.connectivities = in_data['connectivities'].astype(dtype=ct.c_int, order='F') - self.global_nodes_num = list(set(self.connectivities.reshape(-1))) - self.global_elems_num = np.arange(0, self.num_elem, 1) + self.global_nodes_num = np.sort(np.unique(beam.connectivities[ibody_elements, :].reshape(-1))) + self.global_elems_num = np.arange(self.num_elem) # stiffness data self.elem_stiffness = in_data['elem_stiffness'].copy() diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index 88b5ad19f..44f3e7279 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -803,15 +803,15 @@ def change_to_local_AFoR(self, for0_pos, for0_vel, quat0): # self.psi[ielem, inode, :] = np.dot(Csm, self.psi[ielem, inode, :]) # self.psi_dot[ielem, inode, :] = (np.dot(Csm, self.psi_dot[ielem, inode, :] + algebra.cross3(for0_vel[3:6], psi_master)) - # algebra.multiply_matrices(CAslaveG, algebra.skew(self.for_vel[3:6]), CGAmaster, psi_master)) - - # psi_master = self.psi[ielem,inode,:] + np.zeros((3,),) + + # psi_master = self.psi[ielem,inode,:] + np.zeros((3,),) # self.psi[ielem, inode, :] = algebra.rotation2crv(np.dot(Csm,algebra.crv2rotation(self.psi[ielem,inode,:]))) - # psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) + # psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) # cbam = algebra.crv2rotation(psi_master).T # cbas = algebra.crv2rotation(psi_slave).T # tm = algebra.crv2tan(psi_master) # inv_ts = np.linalg.inv(algebra.crv2tan(psi_slave)) - + # self.psi_dot[ielem, inode, :] = np.dot(inv_ts, (np.dot(tm, self.psi_dot[ielem, inode, :]) + # np.dot(cbam, for0_vel[3:6]) - # np.dot(cbas, self.for_vel[3:6]))) @@ -842,7 +842,7 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): self.pos_dot[inode, :] = (np.dot(Cms, vel_slave) - for0_vel[0:3] - algebra.cross3(for0_vel[3:6], self.pos[inode, :])) - + self.gravity_forces[inode, 0:3] = np.dot(Cms, self.gravity_forces[inode, 0:3]) self.gravity_forces[inode, 3:6] = np.dot(Cms, self.gravity_forces[inode, 3:6]) @@ -852,12 +852,12 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): # self.psi[ielem, inode, :] = np.dot(Cms, self.psi[ielem, inode, :]) # self.psi_dot[ielem, inode, :] = (np.dot(Cms, self.psi_dot[ielem, inode, :] + algebra.cross3(self.for_vel[3:6], psi_slave)) - # algebra.multiply_matrices(CAmasterG, algebra.skew(self.for0_vel[3:6]), CGAslave, psi_slave)) - + self.psi_local[ielem, inode, :] = self.psi[ielem, inode, :].copy() # Copy here the result from the structural computation self.psi_dot_local[ielem, inode, :] = self.psi_dot[ielem, inode, :].copy() # Copy here the result from the structural computation - - # psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) + + # psi_slave = self.psi[ielem, inode, :] + np.zeros((3,),) self.psi[ielem, inode, :] = algebra.rotation2crv(np.dot(Cms,algebra.crv2rotation(self.psi[ielem,inode,:]))) # Convert psi_dot_local to psi_dot to be used by the rest of the code @@ -866,96 +866,96 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): cbas = algebra.crv2rotation(self.psi_local[ielem, inode, :]).T ts = algebra.crv2tan(self.psi_local[ielem, inode, :]) inv_tm = np.linalg.inv(algebra.crv2tan(psi_master)) - + self.psi_dot[ielem, inode, :] = np.dot(inv_tm, (np.dot(ts, self.psi_dot_local[ielem, inode, :]) + np.dot(cbas, self.for_vel[3:6]) - np.dot(cbam, for0_vel[3:6]))) - def whole_structure_to_local_AFoR(self, beam, compute_psi_local=False): - """ - Same as change_to_local_AFoR but for a multibody structure - - Args: - beam(sharpy.structure.models.beam.Beam): Beam structure of ``PreSharpy`` - """ - if not self.in_global_AFoR: - raise NotImplementedError("Wrong managing of FoR") - - self.in_global_AFoR = False - quat0 = self.quat.astype(dtype=ct.c_double, order='F', copy=True) - for0_pos = self.for_pos.astype(dtype=ct.c_double, order='F', copy=True) - for0_vel = self.for_vel.astype(dtype=ct.c_double, order='F', copy=True) - - MB_beam = [None]*beam.num_bodies - MB_tstep = [None]*beam.num_bodies - - for ibody in range(beam.num_bodies): - MB_beam[ibody] = beam.get_body(ibody = ibody) - MB_tstep[ibody] = self.get_body(beam, MB_beam[ibody].num_dof, ibody = ibody) - if compute_psi_local: - MB_tstep[ibody].compute_psi_local_AFoR(for0_pos, for0_vel, quat0) - MB_tstep[ibody].change_to_local_AFoR(for0_pos, for0_vel, quat0) - - first_dof = 0 - for ibody in range(beam.num_bodies): - # Renaming for clarity - ibody_elems = MB_beam[ibody].global_elems_num - ibody_nodes = MB_beam[ibody].global_nodes_num - - # Merge tstep - self.pos[ibody_nodes,:] = MB_tstep[ibody].pos.astype(dtype=ct.c_double, order='F', copy=True) - self.psi[ibody_elems,:,:] = MB_tstep[ibody].psi.astype(dtype=ct.c_double, order='F', copy=True) - self.psi_local[ibody_elems,:,:] = MB_tstep[ibody].psi_local.astype(dtype=ct.c_double, order='F', copy=True) - self.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) - - self.pos_dot[ibody_nodes,:] = MB_tstep[ibody].pos_dot.astype(dtype=ct.c_double, order='F', copy=True) - self.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) - self.psi_dot_local[ibody_elems,:,:] = MB_tstep[ibody].psi_dot_local.astype(dtype=ct.c_double, order='F', copy=True) - - # TODO: Do I need a change in FoR for the following variables? Maybe for the FoR ones. - # tstep.forces_constraints_nodes[ibody_nodes,:] = MB_tstep[ibody].forces_constraints_nodes.astype(dtype=ct.c_double, order='F', copy=True) - # tstep.forces_constraints_FoR[ibody, :] = MB_tstep[ibody].forces_constraints_FoR[ibody, :].astype(dtype=ct.c_double, order='F', copy=True) - - def whole_structure_to_global_AFoR(self, beam): - """ - Same as change_to_global_AFoR but for a multibody structure - - Args: - beam(sharpy.structure.models.beam.Beam): Beam structure of ``PreSharpy`` - """ - if self.in_global_AFoR: - raise NotImplementedError("Wrong managing of FoR") - - self.in_global_AFoR = True - - MB_beam = [None]*beam.num_bodies - MB_tstep = [None]*beam.num_bodies - quat0 = self.quat.astype(dtype=ct.c_double, order='F', copy=True) - for0_pos = self.for_pos.astype(dtype=ct.c_double, order='F', copy=True) - for0_vel = self.for_vel.astype(dtype=ct.c_double, order='F', copy=True) - - for ibody in range(beam.num_bodies): - MB_beam[ibody] = beam.get_body(ibody = ibody) - MB_tstep[ibody] = self.get_body(beam, MB_beam[ibody].num_dof, ibody = ibody) - MB_tstep[ibody].change_to_global_AFoR(for0_pos, for0_vel, quat0) - - - first_dof = 0 - for ibody in range(beam.num_bodies): - # Renaming for clarity - ibody_elems = MB_beam[ibody].global_elems_num - ibody_nodes = MB_beam[ibody].global_nodes_num - - # Merge tstep - self.pos[ibody_nodes,:] = MB_tstep[ibody].pos.astype(dtype=ct.c_double, order='F', copy=True) - self.psi[ibody_elems,:,:] = MB_tstep[ibody].psi.astype(dtype=ct.c_double, order='F', copy=True) - self.psi_local[ibody_elems,:,:] = MB_tstep[ibody].psi_local.astype(dtype=ct.c_double, order='F', copy=True) - self.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', - copy=True) - - self.pos_dot[ibody_nodes,:] = MB_tstep[ibody].pos_dot.astype(dtype=ct.c_double, order='F', copy=True) - self.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) - self.psi_dot_local[ibody_elems,:,:] = MB_tstep[ibody].psi_dot_local.astype(dtype=ct.c_double, order='F', copy=True) + # def whole_structure_to_local_AFoR(self, beam, compute_psi_local=False): + # """ + # Same as change_to_local_AFoR but for a multibody structure + # + # Args: + # beam(sharpy.structure.models.beam.Beam): Beam structure of ``PreSharpy`` + # """ + # if not self.in_global_AFoR: + # raise NotImplementedError("Wrong managing of FoR") + # + # self.in_global_AFoR = False + # quat0 = self.quat.astype(dtype=ct.c_double, order='F', copy=True) + # for0_pos = self.for_pos.astype(dtype=ct.c_double, order='F', copy=True) + # for0_vel = self.for_vel.astype(dtype=ct.c_double, order='F', copy=True) + # + # MB_beam = [None]*beam.num_bodies + # MB_tstep = [None]*beam.num_bodies + # + # for ibody in range(beam.num_bodies): + # MB_beam[ibody] = beam.get_body(ibody = ibody) + # MB_tstep[ibody] = self.get_body(beam, MB_beam[ibody].num_dof, ibody = ibody) + # if compute_psi_local: + # MB_tstep[ibody].compute_psi_local_AFoR(for0_pos, for0_vel, quat0) + # MB_tstep[ibody].change_to_local_AFoR(for0_pos, for0_vel, quat0) + # + # first_dof = 0 + # for ibody in range(beam.num_bodies): + # # Renaming for clarity + # ibody_elems = MB_beam[ibody].global_elems_num + # ibody_nodes = MB_beam[ibody].global_nodes_num + # + # # Merge tstep + # self.pos[ibody_nodes,:] = MB_tstep[ibody].pos.astype(dtype=ct.c_double, order='F', copy=True) + # self.psi[ibody_elems,:,:] = MB_tstep[ibody].psi.astype(dtype=ct.c_double, order='F', copy=True) + # self.psi_local[ibody_elems,:,:] = MB_tstep[ibody].psi_local.astype(dtype=ct.c_double, order='F', copy=True) + # self.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) + # + # self.pos_dot[ibody_nodes,:] = MB_tstep[ibody].pos_dot.astype(dtype=ct.c_double, order='F', copy=True) + # self.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) + # self.psi_dot_local[ibody_elems,:,:] = MB_tstep[ibody].psi_dot_local.astype(dtype=ct.c_double, order='F', copy=True) + # + # # TODO: Do I need a change in FoR for the following variables? Maybe for the FoR ones. + # # tstep.forces_constraints_nodes[ibody_nodes,:] = MB_tstep[ibody].forces_constraints_nodes.astype(dtype=ct.c_double, order='F', copy=True) + # # tstep.forces_constraints_FoR[ibody, :] = MB_tstep[ibody].forces_constraints_FoR[ibody, :].astype(dtype=ct.c_double, order='F', copy=True) + + # def whole_structure_to_global_AFoR(self, beam): + # """ + # Same as change_to_global_AFoR but for a multibody structure + # + # Args: + # beam(sharpy.structure.models.beam.Beam): Beam structure of ``PreSharpy`` + # """ + # if self.in_global_AFoR: + # raise NotImplementedError("Wrong managing of FoR") + # + # self.in_global_AFoR = True + # + # MB_beam = [None]*beam.num_bodies + # MB_tstep = [None]*beam.num_bodies + # quat0 = self.quat.astype(dtype=ct.c_double, order='F', copy=True) + # for0_pos = self.for_pos.astype(dtype=ct.c_double, order='F', copy=True) + # for0_vel = self.for_vel.astype(dtype=ct.c_double, order='F', copy=True) + # + # for ibody in range(beam.num_bodies): + # MB_beam[ibody] = beam.get_body(ibody = ibody) + # MB_tstep[ibody] = self.get_body(beam, MB_beam[ibody].num_dof, ibody = ibody) + # MB_tstep[ibody].change_to_global_AFoR(for0_pos, for0_vel, quat0) + # + # + # first_dof = 0 + # for ibody in range(beam.num_bodies): + # # Renaming for clarity + # ibody_elems = MB_beam[ibody].global_elems_num + # ibody_nodes = MB_beam[ibody].global_nodes_num + # + # # Merge tstep + # self.pos[ibody_nodes,:] = MB_tstep[ibody].pos.astype(dtype=ct.c_double, order='F', copy=True) + # self.psi[ibody_elems,:,:] = MB_tstep[ibody].psi.astype(dtype=ct.c_double, order='F', copy=True) + # self.psi_local[ibody_elems,:,:] = MB_tstep[ibody].psi_local.astype(dtype=ct.c_double, order='F', copy=True) + # self.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', + # copy=True) + # + # self.pos_dot[ibody_nodes,:] = MB_tstep[ibody].pos_dot.astype(dtype=ct.c_double, order='F', copy=True) + # self.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) + # self.psi_dot_local[ibody_elems,:,:] = MB_tstep[ibody].psi_dot_local.astype(dtype=ct.c_double, order='F', copy=True) def nodal_b_for_2_a_for(self, nodal, beam, filter=np.array([True]*6), ibody=None): @@ -980,10 +980,10 @@ def nodal_b_for_2_a_for(self, nodal, beam, filter=np.array([True]*6), ibody=None cab = algebra.crv2rotation(crv) nodal_a[i_node, 0:3] = np.dot(cab, nodal[i_node, 0:3]) nodal_a[i_node, 3:6] = np.dot(cab, nodal[i_node, 3:6]) - nodal_a *= filter + nodal_a *= filter return nodal_a - + def nodal_type_b_for_2_a_for(self, beam, force_type=['steady', 'unsteady'], filter=np.array([True]*6), @@ -1011,7 +1011,7 @@ def extract_resultants(self, beam, force_type=['steady', 'unsteady', 'grav'], ib fa = self.gravity_forces.copy() elif ft == 'unsteady': fa = self.nodal_type_b_for_2_a_for(beam, force_type=['unsteady'], ibody=ibody)[0] - + for i_node in range(beam.num_node): totals += fa[i_node, :] totals[3:6] += algebra.cross3(self.pos[i_node, :], diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index b002717e4..fa2d5c3c9 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -33,6 +33,10 @@ def split_multibody(beam, tstep, mb_data_dict, ts): MB_beam = [] MB_tstep = [] + quat0 = tstep.quat.astype(dtype=ct.c_double, order='F', copy=True) + for0_pos = tstep.for_pos.astype(dtype=ct.c_double, order='F', copy=True) + for0_vel = tstep.for_vel.astype(dtype=ct.c_double, order='F', copy=True) + for ibody in range(beam.num_bodies): ibody_beam = None ibody_tstep = None @@ -41,6 +45,11 @@ def split_multibody(beam, tstep, mb_data_dict, ts): ibody_beam.FoR_movement = mb_data_dict['body_%02d' % ibody]['FoR_movement'] + if ts == 1: + ibody_beam.compute_psi_local_AFoR(for0_pos, for0_vel, quat0) + ibody_tstep.compute_psi_local_AFoR(for0_pos, for0_vel, quat0) + ibody_beam.ini_info.change_to_local_AFoR(for0_pos, for0_vel, quat0) + ibody_tstep.change_to_local_AFoR(for0_pos, for0_vel, quat0) #if ts == 1: # ibody_beam.ini_info.pos_dot *= 0 # ibody_beam.timestep_info.pos_dot *= 0 @@ -77,6 +86,13 @@ def merge_multibody(MB_tstep, MB_beam, beam, tstep, mb_data_dict, dt): update_mb_dB_before_merge(tstep, MB_tstep) + quat0 = tstep[0].quat.astype(dtype=ct.c_double, order='F', copy=True) + for0_pos = tstep[0].for_pos.astype(dtype=ct.c_double, order='F', copy=True) + for0_vel = tstep[0].for_vel.astype(dtype=ct.c_double, order='F', copy=True) + + for ibody in range(beam.num_bodies): + MB_tstep[ibody].change_to_global_AFoR(for0_pos, for0_vel, quat0) + first_dof = 0 for ibody in range(beam.num_bodies): # Renaming for clarity @@ -88,7 +104,9 @@ def merge_multibody(MB_tstep, MB_beam, beam, tstep, mb_data_dict, dt): tstep.pos_dot[ibody_nodes,:] = MB_tstep[ibody].pos_dot.astype(dtype=ct.c_double, order='F', copy=True) tstep.pos_ddot[ibody_nodes,:] = MB_tstep[ibody].pos_ddot.astype(dtype=ct.c_double, order='F', copy=True) tstep.psi[ibody_elems,:,:] = MB_tstep[ibody].psi.astype(dtype=ct.c_double, order='F', copy=True) + tstep.psi_local[ibody_elems,:,:] = MB_tstep[ibody].psi_local.astype(dtype=ct.c_double, order='F', copy=True) tstep.psi_dot[ibody_elems,:,:] = MB_tstep[ibody].psi_dot.astype(dtype=ct.c_double, order='F', copy=True) + tstep.psi_dot_local[ibody_elems,:,:] = MB_tstep[ibody].psi_dot_local.astype(dtype=ct.c_double, order='F', copy=True) tstep.psi_ddot[ibody_elems,:,:] = MB_tstep[ibody].psi_ddot.astype(dtype=ct.c_double, order='F', copy=True) tstep.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) tstep.steady_applied_forces[ibody_nodes,:] = MB_tstep[ibody].steady_applied_forces.astype(dtype=ct.c_double, order='F', copy=True) @@ -151,7 +169,7 @@ def disp_and_accel2state(MB_beam, MB_tstep, Lambda, Lambda_dot, sys_size, num_LM MB_tstep (list(:class:`~sharpy.utils.datastructures.StructTimeStepInfo`)): each entry represents a body Lambda(np.ndarray): Lagrange multipliers of holonomic constraints Lambda_dot(np.ndarray): Lagrange multipliers of non-holonomic constraints - + sys_size(int): number of degrees of freedom of the system of equations not accounting for lagrange multipliers num_LM_eq(int): Number of equations associated to the Lagrange Multipliers @@ -205,9 +223,9 @@ def state2disp_and_accel(q, dqdt, dqddt, MB_beam, MB_tstep, num_LM_eq): q(np.ndarray): Vector of states dqdt(np.ndarray): Time derivatives of states dqddt(np.ndarray): Second time derivatives of states - + num_LM_eq(int): Number of equations associated to the Lagrange Multipliers - + Lambda(np.ndarray): Lagrange multipliers of holonomic constraints Lambda_dot(np.ndarray): Lagrange multipliers of non-holonomic constraints @@ -258,8 +276,8 @@ def get_elems_nodes_list(beam, ibody): ibody_nodes (list): List of nodes that belong the ``ibody`` """ - int_list = np.arange(0, beam.num_elem, 1) + int_list = np.arange(beam.num_elem) ibody_elements = int_list[beam.body_number == ibody] ibody_nodes = np.sort(np.unique(beam.connectivities[ibody_elements, :].reshape(-1))) - + return ibody_elements, ibody_nodes From 1405be9a161cc8ca2ce5f9e77e75bcda829ae875 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 3 May 2021 20:23:22 +0100 Subject: [PATCH 086/253] minor bugs --- sharpy/structure/models/beam.py | 2 +- sharpy/utils/multibody.py | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/sharpy/structure/models/beam.py b/sharpy/structure/models/beam.py index cb6b71680..66c27a57e 100644 --- a/sharpy/structure/models/beam.py +++ b/sharpy/structure/models/beam.py @@ -112,8 +112,8 @@ def generate(self, in_data, settings): # connectivity information self.connectivities = in_data['connectivities'].astype(dtype=ct.c_int, order='F') - self.global_nodes_num = np.sort(np.unique(beam.connectivities[ibody_elements, :].reshape(-1))) self.global_elems_num = np.arange(self.num_elem) + self.global_nodes_num = np.arange(self.num_node) # stiffness data self.elem_stiffness = in_data['elem_stiffness'].copy() diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index fa2d5c3c9..9563411b2 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -46,7 +46,7 @@ def split_multibody(beam, tstep, mb_data_dict, ts): ibody_beam.FoR_movement = mb_data_dict['body_%02d' % ibody]['FoR_movement'] if ts == 1: - ibody_beam.compute_psi_local_AFoR(for0_pos, for0_vel, quat0) + ibody_beam.ini_info.compute_psi_local_AFoR(for0_pos, for0_vel, quat0) ibody_tstep.compute_psi_local_AFoR(for0_pos, for0_vel, quat0) ibody_beam.ini_info.change_to_local_AFoR(for0_pos, for0_vel, quat0) ibody_tstep.change_to_local_AFoR(for0_pos, for0_vel, quat0) @@ -86,9 +86,9 @@ def merge_multibody(MB_tstep, MB_beam, beam, tstep, mb_data_dict, dt): update_mb_dB_before_merge(tstep, MB_tstep) - quat0 = tstep[0].quat.astype(dtype=ct.c_double, order='F', copy=True) - for0_pos = tstep[0].for_pos.astype(dtype=ct.c_double, order='F', copy=True) - for0_vel = tstep[0].for_vel.astype(dtype=ct.c_double, order='F', copy=True) + quat0 = MB_tstep[0].quat.astype(dtype=ct.c_double, order='F', copy=True) + for0_pos = MB_tstep[0].for_pos.astype(dtype=ct.c_double, order='F', copy=True) + for0_vel = MB_tstep[0].for_vel.astype(dtype=ct.c_double, order='F', copy=True) for ibody in range(beam.num_bodies): MB_tstep[ibody].change_to_global_AFoR(for0_pos, for0_vel, quat0) From 1d13753183023b112bbcd5773aa67a40b7694616 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 4 May 2021 11:37:10 +0100 Subject: [PATCH 087/253] fix bug several masses same node --- sharpy/generators/floatingforces.py | 7 +++++++ sharpy/structure/models/beam.py | 4 ++-- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 97d2e4857..3ecf4f64d 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -635,6 +635,13 @@ def initialise(self, in_dict=None, data=None): self.added_mass_in_mass_matrix = self.settings['added_mass_in_mass_matrix'] if self.added_mass_in_mass_matrix: + if data.structure.lumped_mass_mat is None: + data_structure.lumped_mass_mat_nodes = np.array([self.buoyancy_node]) + data_structure.lumped_mass_mat = np.array([self.hd_added_mass_const]) + else: + data.structure.lumped_mass_mat_nodes = np.concatenate((data.structure.lumped_mass_mat_nodes, np.array([self.buoyancy_node])), axis=0) + data.structure.lumped_mass_mat = np.concatenate((data.structure.lumped_mass_mat, np.array([self.hd_added_mass_const])), axis=0) + data.structure.add_lumped_mass_to_element(self.buoyancy_node, self.hd_added_mass_const) data.structure.generate_fortran() diff --git a/sharpy/structure/models/beam.py b/sharpy/structure/models/beam.py index 66c27a57e..f9239add0 100644 --- a/sharpy/structure/models/beam.py +++ b/sharpy/structure/models/beam.py @@ -451,7 +451,7 @@ def generate_fortran(self): for elem in self.elements: for inode in range(elem.n_nodes): if elem.rbmass is not None: - rbmass_temp[elem.ielem, inode, :, :] = elem.rbmass[inode, :, :] + rbmass_temp[elem.ielem, inode, :, :] += elem.rbmass[inode, :, :] self.fortran['rbmass'] = rbmass_temp.astype(dtype=ct.c_double, order='F') if self.settings['unsteady']: @@ -625,7 +625,7 @@ def get_body(self, ibody): ibody_beam.generate_master_structure() - if ibody_beam.lumped_mass is not None: + if ibody_beam.lumped_mass is not None or ibody_beam.lumped_mass_mat is not None: ibody_beam.lump_masses() ibody_beam.generate_fortran() From 2e417025fb264ff6d362942db56e6be501f5eec4 Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 5 May 2021 11:50:41 +0100 Subject: [PATCH 088/253] fix split ini info --- sharpy/utils/multibody.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index 9563411b2..db2d696d5 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -37,6 +37,10 @@ def split_multibody(beam, tstep, mb_data_dict, ts): for0_pos = tstep.for_pos.astype(dtype=ct.c_double, order='F', copy=True) for0_vel = tstep.for_vel.astype(dtype=ct.c_double, order='F', copy=True) + ini_quat0 = beam.ini_info.quat.astype(dtype=ct.c_double, order='F', copy=True) + ini_for0_pos = beam.ini_info.for_pos.astype(dtype=ct.c_double, order='F', copy=True) + ini_for0_vel = beam.ini_info.for_vel.astype(dtype=ct.c_double, order='F', copy=True) + for ibody in range(beam.num_bodies): ibody_beam = None ibody_tstep = None @@ -45,10 +49,10 @@ def split_multibody(beam, tstep, mb_data_dict, ts): ibody_beam.FoR_movement = mb_data_dict['body_%02d' % ibody]['FoR_movement'] + ibody_beam.ini_info.compute_psi_local_AFoR(ini_for0_pos, ini_for0_vel, ini_quat0) + ibody_beam.ini_info.change_to_local_AFoR(ini_for0_pos, ini_for0_vel, ini_quat0) if ts == 1: - ibody_beam.ini_info.compute_psi_local_AFoR(for0_pos, for0_vel, quat0) ibody_tstep.compute_psi_local_AFoR(for0_pos, for0_vel, quat0) - ibody_beam.ini_info.change_to_local_AFoR(for0_pos, for0_vel, quat0) ibody_tstep.change_to_local_AFoR(for0_pos, for0_vel, quat0) #if ts == 1: # ibody_beam.ini_info.pos_dot *= 0 From 59a06332677bab56d9245ee5db5b76b4685b736c Mon Sep 17 00:00:00 2001 From: Unknown Date: Wed, 5 May 2021 18:36:22 +0100 Subject: [PATCH 089/253] runtime steady and unsteady forces --- sharpy/generators/floatingforces.py | 99 +++++++++++----------- sharpy/solvers/dynamiccoupled.py | 71 ++++++++-------- sharpy/solvers/initialaeroelasticloader.py | 3 +- sharpy/solvers/staticcoupled.py | 6 +- sharpy/utils/datastructures.py | 13 ++- sharpy/utils/multibody.py | 5 +- 6 files changed, 99 insertions(+), 98 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 3ecf4f64d..7acf3c2e9 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -42,7 +42,7 @@ def compute_xf_zf(hf, vf, l, w, EA, cb): if not cb == 0.: xf += cb*w/2/EA*(-lb**2 + (lb - hf/cb/w)*np.maximum((lb - hf/cb/w), 0)) zf = hf/w*(root1 - 1) + vf**2/2/EA/w - + return xf, zf @@ -463,11 +463,11 @@ class FloatingForces(generator_interface.BaseGenerator): settings_types['add_damp_diag'] = 'list(float)' settings_default['add_damp_diag'] = [0., 0., 0., 0., 0., 0.] settings_description['add_damp_diag'] = 'Diagonal terms to include in the additional damping matrix' - + settings_types['add_damp_ts'] = 'int' settings_default['add_damp_ts'] = 0 settings_description['add_damp_ts'] = 'Timesteps in which ``add_damp_diag`` will be used' - + settings_types['method_matrices_freq'] = 'str' settings_default['method_matrices_freq'] = 'constant' settings_description['method_matrices_freq'] = 'Method to compute frequency-dependent matrices' @@ -488,7 +488,7 @@ class FloatingForces(generator_interface.BaseGenerator): settings_types['concentrate_spar'] = 'bool' settings_default['concentrate_spar'] = False settings_description['concentrate_spar'] = 'Compute CD as if the spar properties were concentrated at the base' - + settings_types['method_wave'] = 'str' settings_default['method_wave'] = 'sin' settings_description['method_wave'] = 'Method to compute wave forces' @@ -610,7 +610,7 @@ def initialise(self, in_dict=None, data=None): # hydrodynamics self.cd = self.floating_data['hydrodynamics']['CD']*self.settings['cd_multiplier'] - if self.settings['method_matrices_freq'] == 'constant': + if self.settings['method_matrices_freq'] == 'constant': # self.hd_added_mass_const = interp_1st_dim_matrix(self.floating_data['hydrodynamics']['added_mass_matrix'], # self.floating_data['hydrodynamics']['ab_freq_rads'], # self.settings['matrices_freq']) @@ -641,7 +641,7 @@ def initialise(self, in_dict=None, data=None): else: data.structure.lumped_mass_mat_nodes = np.concatenate((data.structure.lumped_mass_mat_nodes, np.array([self.buoyancy_node])), axis=0) data.structure.lumped_mass_mat = np.concatenate((data.structure.lumped_mass_mat, np.array([self.hd_added_mass_const])), axis=0) - + data.structure.add_lumped_mass_to_element(self.buoyancy_node, self.hd_added_mass_const) data.structure.generate_fortran() @@ -793,7 +793,6 @@ def generate(self, params): data = params['data'] struct_tstep = params['struct_tstep'] aero_tstep = params['aero_tstep'] - force_coeff = params['force_coeff'] k = params['fsi_substep'] # Update dof vector @@ -842,65 +841,63 @@ def generate(self, params): r_fairlead_G = fairlead_pos_G - mooring_node_pos_G force_cl[3:6] = np.cross(r_fairlead_G, force_fl) - struct_tstep.runtime_generated_forces[self.mooring_node, 0:3] += np.dot(cbg, force_cl[0:3]) - struct_tstep.runtime_generated_forces[self.mooring_node, 3:6] += np.dot(cbg, force_cl[3:6]) + struct_tstep.runtime_unsteady_forces[self.mooring_node, 0:3] += np.dot(cbg, force_cl[0:3]) + struct_tstep.runtime_unsteady_forces[self.mooring_node, 3:6] += np.dot(cbg, force_cl[3:6]) # Yaw moment generated by the mooring system yaw = np.array([self.q[data.ts, 3], 0., 0.]) mooring_yaw = -self.floating_data['mooring']['yaw_spring_stif']*yaw - struct_tstep.runtime_generated_forces[self.mooring_node, 3:6] += np.dot(cbg, + struct_tstep.runtime_unsteady_forces[self.mooring_node, 3:6] += np.dot(cbg, mooring_yaw) # Hydrostatic model - hs_f_g = self.buoy_F0 - np.dot(self.buoy_rest_mat, self.q[data.ts, :]) - - if not force_coeff == 0.: - add_damp = self.floating_data['hydrodynamics']['additional_damping'].copy() - if data.ts < self.settings['add_damp_ts']: - add_damp += np.diag(self.settings['add_damp_diag']) - hd_f_qdot_g = -np.dot(add_damp, self.qdot[data.ts, :]) - - if ((self.settings['method_matrices_freq'] == 'constant') or - (data.ts < self.settings['steps_constant_matrices'])): - hd_f_qdot_g -= np.dot(self.hd_damping_const, self.qdot[data.ts, :]) - hd_f_qdotdot_g = np.zeros((6)) - - elif self.settings['method_matrices_freq'] == 'rational_function': - # Damping - if self.x0_K[data.ts - 1] is None: - # This loop is needed when computations are restarted - self.x0_K[data.ts - 1] = 0 - (T, yout, xout) = forced_response(self.hd_K, - T=[0, self.settings['dt']], - U=self.qdot[data.ts-1:data.ts+1, :].T, - X0=self.x0_K[data.ts-1]) - # transpose=True) - self.x0_K[data.ts] = xout[:, 1] - hd_f_qdot_g -= yout[:, 1] - hd_f_qdotdot_g = np.zeros((6)) + hs_f_g = - np.dot(self.buoy_rest_mat, self.q[data.ts, :]) - else: - cout.cout_wrap(("ERROR: Unknown method_matrices_freq %s" % self.settings['method_matrices_freq']), 4) - - else: - hd_f_qdot_g = np.zeros((6)) + add_damp = self.floating_data['hydrodynamics']['additional_damping'].copy() + if data.ts < self.settings['add_damp_ts']: + add_damp += np.diag(self.settings['add_damp_diag']) + hd_f_qdot_g = -np.dot(add_damp, self.qdot[data.ts, :]) + + if ((self.settings['method_matrices_freq'] == 'constant') or + (data.ts < self.settings['steps_constant_matrices'])): + hd_f_qdot_g -= np.dot(self.hd_damping_const, self.qdot[data.ts, :]) hd_f_qdotdot_g = np.zeros((6)) + elif self.settings['method_matrices_freq'] == 'rational_function': + # Damping + if self.x0_K[data.ts - 1] is None: + # This loop is needed when computations are restarted + self.x0_K[data.ts - 1] = 0 + (T, yout, xout) = forced_response(self.hd_K, + T=[0, self.settings['dt']], + U=self.qdot[data.ts-1:data.ts+1, :].T, + X0=self.x0_K[data.ts-1]) + # transpose=True) + self.x0_K[data.ts] = xout[:, 1] + hd_f_qdot_g -= yout[:, 1] + hd_f_qdotdot_g = np.zeros((6)) + + else: + cout.cout_wrap(("ERROR: Unknown method_matrices_freq %s" % self.settings['method_matrices_freq']), 4) + # Correct gravity forces if needed if self.added_mass_in_mass_matrix: # Correct unreal gravity forces from added mass gravity_b = np.zeros((6,),) gravity_b[0:3] = np.dot(cbg, -self.settings['gravity_dir'])*self.settings['gravity'] hd_correct_grav = -np.dot(self.hd_added_mass_const, gravity_b) - struct_tstep.runtime_generated_forces[self.buoyancy_node, :] += hd_correct_grav + struct_tstep.runtime_steady_forces[self.buoyancy_node, :] += hd_correct_grav else: hd_correct_grav = np.zeros((6)) ielem, inode_in_elem = data.structure.node_master_elem[self.buoyancy_node] cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) cbg = np.dot(cab.T, cga.T) - struct_tstep.runtime_generated_forces[self.buoyancy_node, 0:3] += np.dot(cbg, hs_f_g[0:3] + force_coeff*(hd_f_qdot_g[0:3] + hd_f_qdotdot_g[0:3])) - struct_tstep.runtime_generated_forces[self.buoyancy_node, 3:6] += np.dot(cbg, hs_f_g[3:6] + force_coeff*(hd_f_qdot_g[3:6] + hd_f_qdotdot_g[3:6])) + + struct_tstep.runtime_steady_forces[self.buoyancy_node, 0:3] += np.dot(cbg, self.buoy_F0[0:3]) + struct_tstep.runtime_steady_forces[self.buoyancy_node, 3:6] += np.dot(cbg, self.buoy_F0[3:6]) + struct_tstep.runtime_unsteady_forces[self.buoyancy_node, 0:3] += np.dot(cbg, hs_f_g[0:3] + hd_f_qdot_g[0:3] + hd_f_qdotdot_g[0:3]) + struct_tstep.runtime_unsteady_forces[self.buoyancy_node, 3:6] += np.dot(cbg, hs_f_g[3:6] + hd_f_qdot_g[3:6] + hd_f_qdotdot_g[3:6]) # Nonlinear drag coefficeint if self.settings['concentrate_spar']: @@ -910,10 +907,10 @@ def generate(self, params): else: spar_node_pos = struct_tstep.pos[self.floating_data['hydrodynamics']['CD_first_node'] : self.floating_data['hydrodynamics']['CD_last_node'] + 1, :] spar_node_pos_dot = struct_tstep.pos_dot[self.floating_data['hydrodynamics']['CD_first_node'] : self.floating_data['hydrodynamics']['CD_last_node'] + 1, :] - + total_drag_force = np.zeros((6)) for inode in range(len(spar_node_pos)): - + if self.settings['concentrate_spar']: ielem, inode_in_elem = data.structure.node_master_elem[inode + self.floating_data['hydrodynamics']['CD_node']] else: @@ -949,18 +946,18 @@ def generate(self, params): total_drag_force[0:3] += drag_force total_drag_force[3:6] += drag_moment if self.settings['concentrate_spar']: - struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 0:3] += np.dot(cbg, force_coeff*drag_force) - struct_tstep.runtime_generated_forces[self.floating_data['hydrodynamics']['CD_node'], 3:6] += np.dot(cbg, force_coeff*drag_moment) + struct_tstep.runtime_unsteady_forces[self.floating_data['hydrodynamics']['CD_node'], 0:3] += np.dot(cbg, drag_force) + struct_tstep.runtime_unsteady_forces[self.floating_data['hydrodynamics']['CD_node'], 3:6] += np.dot(cbg, drag_moment) else: - struct_tstep.runtime_generated_forces[inode + self.floating_data['hydrodynamics']['CD_first_node'], 0:3] += np.dot(cbg, force_coeff*drag_force) + struct_tstep.runtime_unsteady_forces[inode + self.floating_data['hydrodynamics']['CD_first_node'], 0:3] += np.dot(cbg, drag_force) # Wave loading ielem, inode_in_elem = data.structure.node_master_elem[self.wave_forces_node] cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) cbg = np.dot(cab.T, cga.T) - struct_tstep.runtime_generated_forces[self.wave_forces_node, 0:3] += np.dot(cbg, force_coeff*self.wave_forces_g[data.ts, 0:3]) - struct_tstep.runtime_generated_forces[self.wave_forces_node, 3:6] += np.dot(cbg, force_coeff*self.wave_forces_g[data.ts, 3:6]) + struct_tstep.runtime_unsteady_forces[self.wave_forces_node, 0:3] += np.dot(cbg, self.wave_forces_g[data.ts, 0:3]) + struct_tstep.runtime_unsteady_forces[self.wave_forces_node, 3:6] += np.dot(cbg, self.wave_forces_g[data.ts, 3:6]) # Write output if self.settings['write_output']: diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index f2a0e76cf..7adb3bb8a 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -493,25 +493,14 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): structural_kstep, aero_kstep = self.process_controller_output( state) - k = 0 - # compute unsteady contribution - force_coeff = 0.0 - unsteady_contribution = False - if self.settings['include_unsteady_force_contribution']: - if self.data.ts > self.settings['steps_without_unsteady_force']: - unsteady_contribution = True - if 0 < self.settings['pseudosteps_ramp_unsteady_force']: - force_coeff = k/self.settings['pseudosteps_ramp_unsteady_force'] - else: - force_coeff = 1. # Add external forces if self.with_runtime_generators: - structural_kstep.runtime_generated_forces.fill(0.) + structural_kstep.runtime_steady_forces.fill(0.) + structural_kstep.runtime_unsteady_forces.fill(0.) params = dict() params['data'] = self.data params['struct_tstep'] = structural_kstep params['aero_tstep'] = aero_kstep - params['force_coeff'] = force_coeff params['fsi_substep'] = -1 for id, runtime_generator in self.runtime_generators.items(): runtime_generator.generate(params) @@ -552,15 +541,16 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): else: force_coeff = 1. - previous_runtime_generated_forces = structural_kstep.runtime_generated_forces.astype(dtype=ct.c_double, order='F', copy=True) + previous_runtime_steady_forces = structural_kstep.runtime_steady_forces.astype(dtype=ct.c_double, order='F', copy=True) + previous_runtime_unsteady_forces = structural_kstep.runtime_unsteady_forces.astype(dtype=ct.c_double, order='F', copy=True) # Add external forces if self.with_runtime_generators: - structural_kstep.runtime_generated_forces.fill(0.) + structural_kstep.runtime_steady_forces.fill(0.) + structural_kstep.runtime_unsteady_forces.fill(0.) params = dict() params['data'] = self.data params['struct_tstep'] = structural_kstep params['aero_tstep'] = aero_kstep - params['force_coeff'] = force_coeff params['fsi_substep'] = k for id, runtime_generator in self.runtime_generators.items(): runtime_generator.generate(params) @@ -575,8 +565,10 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): previous_kstep = structural_kstep.copy() structural_kstep = controlled_structural_kstep.copy() - structural_kstep.runtime_generated_forces = previous_kstep.runtime_generated_forces.astype(dtype=ct.c_double, order='F', copy=True) - previous_kstep.runtime_generated_forces = previous_runtime_generated_forces.astype(dtype=ct.c_double, order='F', copy=True) + structural_kstep.runtime_steady_forces = previous_kstep.runtime_steady_forces.astype(dtype=ct.c_double, order='F', copy=True) + structural_kstep.runtime_unsteady_forces = previous_kstep.runtime_unsteady_forces.astype(dtype=ct.c_double, order='F', copy=True) + previous_kstep.runtime_steady_forces = previous_runtime_steady_forces.astype(dtype=ct.c_double, order='F', copy=True) + previous_kstep.runtime_unsteady_forces = previous_runtime_unsteady_forces.astype(dtype=ct.c_double, order='F', copy=True) # move the aerodynamic surface according the the structural one self.aero_solver.update_custom_grid(structural_kstep, @@ -705,7 +697,8 @@ def convergence(self, k, tstep, previous_tstep, if self.base_dqdt == 0: self.base_dqdt = 1. if with_runtime_generators: - self.base_res_forces = np.linalg.norm(tstep.runtime_generated_forces) + self.base_res_forces = np.linalg.norm(tstep.runtime_steady_forces + + tstep.runtime_unsteady_forces) if self.base_res_forces == 0: self.base_res_forces = 1. return False @@ -723,9 +716,11 @@ def convergence(self, k, tstep, previous_tstep, self.base_dqdt) if with_runtime_generators: - res_forces = (np.linalg.norm(tstep.runtime_generated_forces - - previous_tstep.runtime_generated_forces)/ - self.base_res_forces) + res_forces = (np.linalg.norm(tstep.runtime_steady_forces - + previous_tstep.runtime_steady_forces + + tstep.runtime_unsteady_forces - + previous_tstep.runtime_unsteady_forces)/ + self.base_res_forces) else: res_forces = 0. @@ -760,7 +755,7 @@ def map_forces(self, aero_kstep, structural_kstep, unsteady_forces_coeff=1.0): self.data.structure.connectivities, structural_kstep.cag(), self.data.aero.aero_dict) - dynamic_struct_forces = unsteady_forces_coeff*mapping.aero2struct_force_mapping( + dynamic_struct_forces = mapping.aero2struct_force_mapping( aero_kstep.dynamic_forces, self.data.aero.struct2aero_mapping, aero_kstep.zeta, @@ -782,18 +777,18 @@ def map_forces(self, aero_kstep, structural_kstep, unsteady_forces_coeff=1.0): # structural_kstep, # dynamic_struct_forces) - # prescribed forces + aero forces - structural_kstep.steady_applied_forces = ( - (struct_forces + self.data.structure.ini_info.steady_applied_forces). - astype(dtype=ct.c_double, order='F', copy=True)) - try: - structural_kstep.unsteady_applied_forces = ( - (dynamic_struct_forces + self.data.structure.dynamic_input[max(self.data.ts - 1, 0)]['dynamic_forces'] + - structural_kstep.runtime_generated_forces). - astype(dtype=ct.c_double, order='F', copy=True)) - except KeyError: - structural_kstep.unsteady_applied_forces = (dynamic_struct_forces + - structural_kstep.runtime_generated_forces) + # prescribed forces + aero forces + runtime generated + structural_kstep.steady_applied_forces += struct_forces + structural_kstep.steady_applied_forces += self.data.structure.ini_info.steady_applied_forces + structural_kstep.steady_applied_forces += structural_kstep.runtime_steady_forces + + structural_kstep.unsteady_applied_forces += dynamic_struct_forces + if len(self.data.structure.dynamic_input) > 0: + structural_kstep.unsteady_applied_forces += self.data.structure.dynamic_input[max(self.data.ts - 1, 0)]['dynamic_forces'] + structural_kstep.unsteady_applied_forces += structural_kstep.runtime_unsteady_forces + + # Apply unsteady force coefficient + structural_kstep.unsteady_applied_forces *= unsteady_forces_coeff def relaxation_factor(self, k): initial = self.settings['relaxation_factor'] @@ -850,8 +845,10 @@ def relax(beam, timestep, previous_timestep, coeff): coeff*previous_timestep.steady_applied_forces) timestep.unsteady_applied_forces = ((1.0 - coeff)*timestep.unsteady_applied_forces + coeff*previous_timestep.unsteady_applied_forces) - timestep.runtime_generated_forces = ((1.0 - coeff)*timestep.runtime_generated_forces + - coeff*previous_timestep.runtime_generated_forces) + timestep.runtime_steady_forces = ((1.0 - coeff)*timestep.runtime_steady_forces + + coeff*previous_timestep.runtime_steady_forces) + timestep.runtime_unsteady_forces = ((1.0 - coeff)*timestep.runtime_unsteady_forces + + coeff*previous_timestep.runtime_unsteady_forces) def normalise_quaternion(tstep): diff --git a/sharpy/solvers/initialaeroelasticloader.py b/sharpy/solvers/initialaeroelasticloader.py index 78266db43..d9458e52f 100644 --- a/sharpy/solvers/initialaeroelasticloader.py +++ b/sharpy/solvers/initialaeroelasticloader.py @@ -65,7 +65,8 @@ def run(self, structural_step=None, aero_step=None): 'mb_FoR_pos', 'mb_FoR_vel', 'mb_FoR_acc', 'mb_quat'] if self.settings['include_forces']: - attributes.extend(['runtime_generated_forces', + attributes.extend(['runtime_steady_forces', + 'runtime_unsteady_forces', 'steady_applied_forces', 'unsteady_applied_forces']) diff --git a/sharpy/solvers/staticcoupled.py b/sharpy/solvers/staticcoupled.py index 4a850ef4a..405c86796 100644 --- a/sharpy/solvers/staticcoupled.py +++ b/sharpy/solvers/staticcoupled.py @@ -191,17 +191,17 @@ def run(self): # Add external forces if self.with_runtime_generators: - self.data.structure.timestep_info[self.data.ts].runtime_generated_forces.fill(0.) + self.data.structure.timestep_info[self.data.ts].runtime_steady_forces.fill(0.) + self.data.structure.timestep_info[self.data.ts].runtime_unsteady_forces.fill(0.) params = dict() params['data'] = self.data params['struct_tstep'] = self.data.structure.timestep_info[self.data.ts] params['aero_tstep'] = self.data.aero.timestep_info[self.data.ts] - params['force_coeff'] = 0. params['fsi_substep'] = -i_iter for id, runtime_generator in self.runtime_generators.items(): runtime_generator.generate(params) - struct_forces += self.data.structure.timestep_info[self.data.ts].runtime_generated_forces + struct_forces += self.data.structure.timestep_info[self.data.ts].runtime_steady_forces if not self.settings['relaxation_factor'] == 0.: if i_iter == 0: diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index 44f3e7279..d020d4e9d 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -511,7 +511,9 @@ class StructTimeStepInfo(object): ``[num_nodes x 6]``. Expressed in B FoR unsteady_applied_forces (np.ndarray): Forces applied to the structure associated to time derivatives ``[num_node x 6]``. Expressed in B FoR - runtime_generated_forces (np.ndarray): Forces generated at runtime through runtime generators + runtime_steady_forces (np.ndarray): Steady forces generated at runtime through runtime generators + ``[num_node x 6]``. Expressed in B FoR + runtime_unsteady_forces (np.ndarray): Unsteady forces generated at runtime through runtime generators ``[num_node x 6]``. Expressed in B FoR gravity_forces (np.ndarray): Gravity forces at nodes ``[num_node x 6]``. Expressed in A FoR @@ -562,7 +564,8 @@ def __init__(self, num_node, num_elem, num_node_elem=3, num_dof=None, num_bodies self.steady_applied_forces = np.zeros((self.num_node, 6), dtype=ct.c_double, order='F') self.unsteady_applied_forces = np.zeros((self.num_node, 6), dtype=ct.c_double, order='F') - self.runtime_generated_forces = np.zeros((self.num_node, 6), dtype=ct.c_double, order='F') + self.runtime_steady_forces = np.zeros((self.num_node, 6), dtype=ct.c_double, order='F') + self.runtime_unsteady_forces = np.zeros((self.num_node, 6), dtype=ct.c_double, order='F') self.gravity_forces = np.zeros((self.num_node, 6), dtype=ct.c_double, order='F') self.total_gravity_forces = np.zeros((6,), dtype=ct.c_double, order='F') self.total_forces = np.zeros((6,), dtype=ct.c_double, order='F') @@ -619,7 +622,8 @@ def copy(self): copied.steady_applied_forces = self.steady_applied_forces.astype(dtype=ct.c_double, order='F', copy=True) copied.unsteady_applied_forces = self.unsteady_applied_forces.astype(dtype=ct.c_double, order='F', copy=True) - copied.runtime_generated_forces = self.runtime_generated_forces.astype(dtype=ct.c_double, order='F', copy=True) + copied.runtime_steady_forces = self.runtime_steady_forces.astype(dtype=ct.c_double, order='F', copy=True) + copied.runtime_unsteady_forces = self.runtime_unsteady_forces.astype(dtype=ct.c_double, order='F', copy=True) copied.gravity_forces = self.gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) copied.total_gravity_forces = self.total_gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) copied.total_forces = self.total_forces.astype(dtype=ct.c_double, order='F', copy=True) @@ -723,7 +727,8 @@ def get_body(self, beam, num_dof_ibody, ibody): ibody_StructTimeStepInfo.steady_applied_forces = self.steady_applied_forces[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) ibody_StructTimeStepInfo.unsteady_applied_forces = self.unsteady_applied_forces[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) - ibody_StructTimeStepInfo.runtime_generated_forces = self.runtime_generated_forces[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) + ibody_StructTimeStepInfo.runtime_steady_forces = self.runtime_steady_forces[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) + ibody_StructTimeStepInfo.runtime_unsteady_forces = self.runtime_unsteady_forces[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) ibody_StructTimeStepInfo.gravity_forces = self.gravity_forces[ibody_nodes,:].astype(dtype=ct.c_double, order='F', copy=True) ibody_StructTimeStepInfo.total_gravity_forces = self.total_gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index db2d696d5..9fd31ad62 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -40,7 +40,7 @@ def split_multibody(beam, tstep, mb_data_dict, ts): ini_quat0 = beam.ini_info.quat.astype(dtype=ct.c_double, order='F', copy=True) ini_for0_pos = beam.ini_info.for_pos.astype(dtype=ct.c_double, order='F', copy=True) ini_for0_vel = beam.ini_info.for_vel.astype(dtype=ct.c_double, order='F', copy=True) - + for ibody in range(beam.num_bodies): ibody_beam = None ibody_tstep = None @@ -115,7 +115,8 @@ def merge_multibody(MB_tstep, MB_beam, beam, tstep, mb_data_dict, dt): tstep.gravity_forces[ibody_nodes,:] = MB_tstep[ibody].gravity_forces.astype(dtype=ct.c_double, order='F', copy=True) tstep.steady_applied_forces[ibody_nodes,:] = MB_tstep[ibody].steady_applied_forces.astype(dtype=ct.c_double, order='F', copy=True) tstep.unsteady_applied_forces[ibody_nodes,:] = MB_tstep[ibody].unsteady_applied_forces.astype(dtype=ct.c_double, order='F', copy=True) - tstep.runtime_generated_forces[ibody_nodes,:] = MB_tstep[ibody].runtime_generated_forces.astype(dtype=ct.c_double, order='F', copy=True) + tstep.runtime_steady_forces[ibody_nodes,:] = MB_tstep[ibody].runtime_steady_forces.astype(dtype=ct.c_double, order='F', copy=True) + tstep.runtime_unsteady_forces[ibody_nodes,:] = MB_tstep[ibody].runtime_unsteady_forces.astype(dtype=ct.c_double, order='F', copy=True) # TODO: Do I need a change in FoR for the following variables? Maybe for the FoR ones. tstep.forces_constraints_nodes[ibody_nodes,:] = MB_tstep[ibody].forces_constraints_nodes.astype(dtype=ct.c_double, order='F', copy=True) tstep.forces_constraints_FoR[ibody, :] = MB_tstep[ibody].forces_constraints_FoR[ibody, :].astype(dtype=ct.c_double, order='F', copy=True) From 2264c10bf2223c9cfb55c349a96173965c7b93c1 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 10 May 2021 18:01:32 +0100 Subject: [PATCH 090/253] fix bug in quat2euler --- sharpy/utils/algebra.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sharpy/utils/algebra.py b/sharpy/utils/algebra.py index 80a371090..8e88a0b2f 100644 --- a/sharpy/utils/algebra.py +++ b/sharpy/utils/algebra.py @@ -898,9 +898,9 @@ def quat2euler(quat): if np.abs(delta) > 0.9 * 0.5: warn('Warning, approaching singularity. Delta {:.3f} for singularity at Delta=0.5'.format(np.abs(delta))) - yaw = np.arctan(2*(q0*q3+q1*q2)/(1-2*(q2**2+q3**2))) + yaw = np.arctan2(2*(q0*q3+q1*q2), (1-2*(q2**2+q3**2))) pitch = np.arcsin(2*delta) - roll = np.arctan(2*(q0*q1+q2*q3)/(1-2*(q1**2+q2**2))) + roll = np.arctan2(2*(q0*q1+q2*q3), (1-2*(q1**2+q2**2))) return np.array([roll, pitch, yaw]) From bf41ff3f680b352b70336c523a8a1e15f05b2f18 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 13 May 2021 20:58:48 +0100 Subject: [PATCH 091/253] fix readh5 in restart cases --- sharpy/utils/h5utils.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/sharpy/utils/h5utils.py b/sharpy/utils/h5utils.py index 2adbd0631..0b7447b19 100644 --- a/sharpy/utils/h5utils.py +++ b/sharpy/utils/h5utils.py @@ -161,7 +161,10 @@ def read_group(Grp): Hinst = list(Grp['_as_array'][()]) else: N = len(MainLev) - 1 - for nn in range(N): + list_ts = MainLev.copy() + list_ts.remove('_read_as') + list_ts = np.sort(np.unique(np.array(list_ts, dtype=np.int))) + for nn in list_ts: name = '%.5d' % nn ### extract value if type(Grp[name]) is h5._hl.group.Group: From 5c4f7b3068c99b4ba362b803d50b4d4e30626d82 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 13 May 2021 21:00:16 +0100 Subject: [PATCH 092/253] fix bug syntax, constant added mass and no gravity --- sharpy/generators/floatingforces.py | 31 +++++++++++++++++------------ 1 file changed, 18 insertions(+), 13 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 7acf3c2e9..a78ff34c6 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -444,6 +444,10 @@ class FloatingForces(generator_interface.BaseGenerator): settings_default['water_density'] = 1025 # kg/m3 settings_description['water_density'] = 'Water density' + settings_types['gravity_on'] = 'bool' + settings_default['gravity_on'] = True + settings_description['gravity_on'] = 'Flag to include gravitational forces' + settings_types['gravity'] = 'float' settings_default['gravity'] = 9.81 settings_description['gravity'] = 'Gravity' @@ -590,15 +594,16 @@ def initialise(self, in_dict=None, data=None): self.hf_prev = [None]*self.n_mooring_lines self.vf_prev = [None]*self.n_mooring_lines - theta = 2.*np.pi/self.n_mooring_lines - R = algebra.rotation3d_x(theta) - self.anchor_pos[0, 0] = -self.floating_data['mooring']['anchor_depth'] - self.anchor_pos[0, 2] = self.floating_data['mooring']['anchor_radius'] - self.fairlead_pos_A[0, 0] = -self.floating_data['mooring']['fairlead_depth'] - self.fairlead_pos_A[0, 2] = self.floating_data['mooring']['fairlead_radius'] - for imoor in range(1, self.n_mooring_lines): - self.anchor_pos[imoor, :] = np.dot(R, self.anchor_pos[imoor - 1, :]) - self.fairlead_pos_A[imoor, :] = np.dot(R, self.fairlead_pos_A[imoor - 1, :]) + if self.n_mooring_lines > 0: + theta = 2.*np.pi/self.n_mooring_lines + R = algebra.rotation3d_x(theta) + self.anchor_pos[0, 0] = -self.floating_data['mooring']['anchor_depth'] + self.anchor_pos[0, 2] = self.floating_data['mooring']['anchor_radius'] + self.fairlead_pos_A[0, 0] = -self.floating_data['mooring']['fairlead_depth'] + self.fairlead_pos_A[0, 2] = self.floating_data['mooring']['fairlead_radius'] + for imoor in range(1, self.n_mooring_lines): + self.anchor_pos[imoor, :] = np.dot(R, self.anchor_pos[imoor - 1, :]) + self.fairlead_pos_A[imoor, :] = np.dot(R, self.fairlead_pos_A[imoor - 1, :]) # Hydrostatics self.buoyancy_node = self.floating_data['hydrostatics']['node'] @@ -636,8 +641,8 @@ def initialise(self, in_dict=None, data=None): self.added_mass_in_mass_matrix = self.settings['added_mass_in_mass_matrix'] if self.added_mass_in_mass_matrix: if data.structure.lumped_mass_mat is None: - data_structure.lumped_mass_mat_nodes = np.array([self.buoyancy_node]) - data_structure.lumped_mass_mat = np.array([self.hd_added_mass_const]) + data.structure.lumped_mass_mat_nodes = np.array([self.buoyancy_node]) + data.structure.lumped_mass_mat = np.array([self.hd_added_mass_const]) else: data.structure.lumped_mass_mat_nodes = np.concatenate((data.structure.lumped_mass_mat_nodes, np.array([self.buoyancy_node])), axis=0) data.structure.lumped_mass_mat = np.concatenate((data.structure.lumped_mass_mat, np.array([self.hd_added_mass_const])), axis=0) @@ -861,7 +866,7 @@ def generate(self, params): if ((self.settings['method_matrices_freq'] == 'constant') or (data.ts < self.settings['steps_constant_matrices'])): hd_f_qdot_g -= np.dot(self.hd_damping_const, self.qdot[data.ts, :]) - hd_f_qdotdot_g = np.zeros((6)) + hd_f_qdotdot_g = -np.dot(self.hd_added_mass_const, self.qdotdot[data.ts, :]) elif self.settings['method_matrices_freq'] == 'rational_function': # Damping @@ -881,7 +886,7 @@ def generate(self, params): cout.cout_wrap(("ERROR: Unknown method_matrices_freq %s" % self.settings['method_matrices_freq']), 4) # Correct gravity forces if needed - if self.added_mass_in_mass_matrix: + if self.added_mass_in_mass_matrix and self.settings['gravity_on']: # Correct unreal gravity forces from added mass gravity_b = np.zeros((6,),) gravity_b[0:3] = np.dot(cbg, -self.settings['gravity_dir'])*self.settings['gravity'] From e6cab3d974de88f616021dfbc3885c670c37ca50 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 16 May 2021 11:03:43 +0100 Subject: [PATCH 093/253] fix read h5 --- sharpy/utils/h5utils.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sharpy/utils/h5utils.py b/sharpy/utils/h5utils.py index 0b7447b19..927af014c 100644 --- a/sharpy/utils/h5utils.py +++ b/sharpy/utils/h5utils.py @@ -164,6 +164,9 @@ def read_group(Grp): list_ts = MainLev.copy() list_ts.remove('_read_as') list_ts = np.sort(np.unique(np.array(list_ts, dtype=np.int))) + if len(list_ts > 0): + for nn in range(list_ts[0] - 1): + Hinst.append('NoneType') for nn in list_ts: name = '%.5d' % nn ### extract value From 122e4dc2e19d9b983d3d129398d949ad29f01b75 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 16 May 2021 11:04:02 +0100 Subject: [PATCH 094/253] comment test added mass --- sharpy/generators/floatingforces.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index a78ff34c6..773caaeed 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -881,6 +881,14 @@ def generate(self, params): self.x0_K[data.ts] = xout[:, 1] hd_f_qdot_g -= yout[:, 1] hd_f_qdotdot_g = np.zeros((6)) + #(T, yout, xout) = forced_response(self.hd_K, + # T=[0, self.settings['dt']], + # U=self.qdotdot[data.ts-1:data.ts+1, :].T, + # X0=self.x0_K[data.ts-1]) + # # transpose=True) + #self.x0_K[data.ts] = xout[:, 1] + #hd_f_qdot_g -= np.zeros((6)) + #hd_f_qdotdot_g = -yout[:, 1] else: cout.cout_wrap(("ERROR: Unknown method_matrices_freq %s" % self.settings['method_matrices_freq']), 4) From 519c9dc5ca6be71966e8b19d0f744feeee08fcac Mon Sep 17 00:00:00 2001 From: Unknown Date: Sun, 16 May 2021 11:19:35 +0100 Subject: [PATCH 095/253] new sine velocity lagrangeconstraint --- sharpy/structure/utils/lagrangeconstraints.py | 83 ++++++++++++++++++- 1 file changed, 81 insertions(+), 2 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 89532f01d..c076e994c 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -459,7 +459,7 @@ def equal_rot_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, LM_K[node_dof+3:node_dof+6, node_dof+3:node_dof+6] += scalingFactor*ag.der_TanT_by_xv(psi, Lambda_dot[ieq:ieq+num_LM_eq_specific]) if MB_beam[node_body].FoR_movement == 'free': LM_K[node_FoR_dof+3:node_FoR_dof+6, node_dof+3:node_dof+6] += scalingFactor*ag.der_Ccrv_by_v(psi, Lambda_dot[ieq:ieq+num_LM_eq_specific]) - + LM_K[FoR_dof+3:FoR_dof+6, node_dof+3:node_dof+6] -= scalingFactor*ag.der_Ccrv_by_v(psi, ag.multiply_matrices(node_cga, FoR_cga.T, Lambda_dot[ieq:ieq+num_LM_eq_specific])) @@ -1082,7 +1082,7 @@ def staticpost(self, lc_list, MB_beam, MB_tstep): return def dynamicpost(self, lc_list, MB_beam, MB_tstep): - + ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] node_cga = MB_tstep[self.node_body].cga() cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem, inode_in_elem, :]) @@ -1652,6 +1652,85 @@ def staticpost(self, lc_list, MB_beam, MB_tstep): def dynamicpost(self, lc_list, MB_beam, MB_tstep): return + +@lagrangeconstraint +class zero_lin_vel_sine_rot_vel_FoR(BaseLagrangeConstraint): + __doc__ = """ + zero_lin_vel_sine_rot_vel_FoR + + Zero linear velocity and sinusoidal rotation velocity FoR + + See ``LagrangeConstraints`` for the description of variables + + Attributes: + FoR_body (int): body number of the "FoR" + vel_amp (float): Rotation velocity amplitude + omega (float): Frequency of the sinusoidally-varying rotation velocity + xyz (string): Axis with the sine velocity + """ + _lc_id = 'zero_lin_vel_sine_rot_vel_FoR' + + def __init__(self): + self.required_parameters = ['FoR_body', 'vel_amp', 'omega', 'xyz'] + self._n_eq = 6 + + def get_n_eq(self): + return self._n_eq + + def initialise(self, MBdict_entry, ieq, print_info=True): + + self.FoR_body = MBdict_entry['FoR_body'] + self.vel_amp = MBdict_entry['vel_amp'] + self.omega = MBdict_entry['omega'] + if MBdict_entry['xyz'] == 'x': + self.xyz_index = 0 + elif MBdict_entry['xyz'] == 'y': + self.xyz_index = 1 + elif MBdict_entry['xyz'] == 'z': + self.xyz_index = 2 + else: + raise NotImplementedError("FoR rotation velocity shouldd be parallel to x, y or z") + self._ieq = ieq + self.scalingFactor = set_value_or_default(MBdict_entry, "scalingFactor", 1.) + self.penaltyFactor = set_value_or_default(MBdict_entry, "penaltyFactor", 0.) + + return self._ieq + self._n_eq + + def staticmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, + sys_size, dt, Lambda, Lambda_dot): + return + + def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, + sys_size, dt, Lambda, Lambda_dot): + num_LM_eq_specific = self._n_eq + Bnh = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order='F') + B = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order='F') + + # Define the position of the first degree of freedom associated to the FoR + FoR_dof = define_FoR_dof(MB_beam, self.FoR_body) + ieq = self._ieq + + vel = np.zeros((6)) + vel[3 + self.xyz_index] = vel_amp*np.sin(omega*ts*dt) + + Bnh[:num_LM_eq_specific, FoR_dof:FoR_dof+6] = np.eye(6) + + LM_C[sys_size + ieq:sys_size + ieq + num_LM_eq_specific, :sys_size] += self.scalingFactor * Bnh + LM_C[:sys_size, sys_size + ieq:sys_size + ieq + num_LM_eq_specific] += self.scalingFactor * np.transpose(Bnh) + + LM_Q[:sys_size] += self.scalingFactor * np.dot(np.transpose(Bnh), Lambda_dot[ieq:ieq + num_LM_eq_specific]) + LM_Q[sys_size + ieq:sys_size + ieq + num_LM_eq_specific] += self.scalingFactor*(MB_tstep[self.FoR_body].for_vel - vel) + + ieq += 6 + return + + def staticpost(self, lc_list, MB_beam, MB_tstep): + return + + def dynamicpost(self, lc_list, MB_beam, MB_tstep): + return + + @lagrangeconstraint class lin_vel_node_wrtA(BaseLagrangeConstraint): __doc__ = """ From 25d04e4e68574d98efcf7d5934f1a3954bd52161 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 16 May 2021 11:38:53 +0100 Subject: [PATCH 096/253] missing self --- sharpy/structure/utils/lagrangeconstraints.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index c076e994c..ed1ad2cba 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -1711,7 +1711,7 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, ieq = self._ieq vel = np.zeros((6)) - vel[3 + self.xyz_index] = vel_amp*np.sin(omega*ts*dt) + vel[3 + self.xyz_index] = self.vel_amp*np.sin(self.omega*ts*dt) Bnh[:num_LM_eq_specific, FoR_dof:FoR_dof+6] = np.eye(6) From 93d090848d046fda7695f13917a649781393b46b Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 16 May 2021 11:57:26 +0100 Subject: [PATCH 097/253] rigid mb convergence in dc --- sharpy/solvers/dynamiccoupled.py | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 7adb3bb8a..1ffada6f2 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -616,8 +616,8 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): if self.convergence(k, structural_kstep, previous_kstep, - self.settings['structural_solver'].lower(), - self.settings['aero_solver'].lower(), + self.structural_solver, + self.aero_solver, self.with_runtime_generators): # move the aerodynamic surface according to the structural one self.aero_solver.update_custom_grid( @@ -704,7 +704,7 @@ def convergence(self, k, tstep, previous_tstep, return False # Check the special case of no aero and no runtime generators - if aero_solver.lower() == "noaero" and not with_runtime_generators: + if aero_solver.solver_id.lower() == "noaero" and not with_runtime_generators: return True # relative residuals @@ -731,8 +731,13 @@ def convergence(self, k, tstep, previous_tstep, return False # convergence + rigid_solver = False + if "rigid" in struct_solver.solver_id.lower(): + rigid_solver = True + elif "NonLinearDynamicMultibody" == struct_solver.solver_id.lower() and struct_solver.settings['rigid_bodies']: + rigid_solver = True if k > self.settings['minimum_steps'] - 1: - if self.res < self.settings['fsi_tolerance'] or "rigid" in struct_solver.lower(): + if self.res < self.settings['fsi_tolerance'] or rigid_solver: if self.res_dqdt < self.settings['fsi_tolerance']: if res_forces < self.settings['fsi_tolerance']: return True From 05602d1fe9403801ac7f373883dc8fbdef511b47 Mon Sep 17 00:00:00 2001 From: Unknown Date: Thu, 27 May 2021 10:16:11 +0100 Subject: [PATCH 098/253] update UVLM --- lib/UVLM | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lib/UVLM b/lib/UVLM index f23ef25ad..75d2ee917 160000 --- a/lib/UVLM +++ b/lib/UVLM @@ -1 +1 @@ -Subproject commit f23ef25adb00914c4e87392358d89c1a2752ae7f +Subproject commit 75d2ee917c04987c68583fa86c181360a674fb71 From f1c80df0ffcb5bc91686add7920a85103011a4cb Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 27 May 2021 16:22:31 +0100 Subject: [PATCH 099/253] update wind turbine jupyter --- .../example_notebooks/wind_turbine.ipynb | 1387 ++++++++--------- 1 file changed, 657 insertions(+), 730 deletions(-) diff --git a/docs/source/content/example_notebooks/wind_turbine.ipynb b/docs/source/content/example_notebooks/wind_turbine.ipynb index 76380d17e..1ec905ee3 100644 --- a/docs/source/content/example_notebooks/wind_turbine.ipynb +++ b/docs/source/content/example_notebooks/wind_turbine.ipynb @@ -208,7 +208,7 @@ "options['separate_blades'] = False \n", " \n", "excel_description = {} \n", - "excel_description['excel_file_name'] = 'source/type02_db_NREL5MW_v01.xlsx' \n", + "excel_description['excel_file_name'] = 'source/type02_db_NREL5MW_v02.xlsx' \n", "excel_description['excel_sheet_parameters'] = 'parameters' \n", "excel_description['excel_sheet_structural_blade'] = 'structural_blade' \n", "excel_description['excel_sheet_discretization_blade'] = 'discretization_blade' \n", @@ -381,54 +381,10 @@ " License available at /~https://github.com/imperialcollegelondon/sharpy\u001b[0m\n", "\u001b[36mRunning SHARPy from /home/arturo/code/sharpy/docs/source/content/example_notebooks\u001b[0m\n", "\u001b[36mSHARPy being run is in /home/arturo/code/sharpy\u001b[0m\n", - "\u001b[36mThe branch being run is dev_blade_pitch\u001b[0m\n", - "\u001b[36mThe version and commit hash are: v1.2-240-g308515ad-308515ad\u001b[0m\n", - "\u001b[36mThe available solvers on this session are:\u001b[0m\n", - "\u001b[36m_BaseStructural \u001b[0m\n", - "\u001b[36mAerogridLoader \u001b[0m\n", - "\u001b[36mBeamLoader \u001b[0m\n", - "\u001b[36mDynamicCoupled \u001b[0m\n", - "\u001b[36mDynamicUVLM \u001b[0m\n", - "\u001b[36mLinDynamicSim \u001b[0m\n", - "\u001b[36mLinearAssembler \u001b[0m\n", - "\u001b[36mModal \u001b[0m\n", - "\u001b[36mNoAero \u001b[0m\n", - "\u001b[36mNonLinearDynamic \u001b[0m\n", - "\u001b[36mNonLinearDynamicCoupledStep \u001b[0m\n", - "\u001b[36mNonLinearDynamicMultibody \u001b[0m\n", - "\u001b[36mNonLinearDynamicPrescribedStep \u001b[0m\n", - "\u001b[36mNonLinearStatic \u001b[0m\n", - "\u001b[36mNonLinearStaticMultibody \u001b[0m\n", - "\u001b[36mNoStructural \u001b[0m\n", - "\u001b[36mPrescribedUvlm \u001b[0m\n", - "\u001b[36mRigidDynamicCoupledStep \u001b[0m\n", - "\u001b[36mRigidDynamicPrescribedStep \u001b[0m\n", - "\u001b[36mStaticCoupled \u001b[0m\n", - "\u001b[36mStaticTrim \u001b[0m\n", - "\u001b[36mStaticUvlm \u001b[0m\n", - "\u001b[36mStepLinearUVLM \u001b[0m\n", - "\u001b[36mStepUvlm \u001b[0m\n", - "\u001b[36m_BaseTimeIntegrator \u001b[0m\n", - "\u001b[36mNewmarkBeta \u001b[0m\n", - "\u001b[36mGeneralisedAlpha \u001b[0m\n", - "\u001b[36mTrim \u001b[0m\n", - "\u001b[36mFrequencyResponse \u001b[0m\n", - "\u001b[36mWriteVariablesTime \u001b[0m\n", - "\u001b[36mBeamPlot \u001b[0m\n", - "\u001b[36mLiftDistribution \u001b[0m\n", - "\u001b[36mAeroForcesCalculator \u001b[0m\n", - "\u001b[36mCreateSnapshot \u001b[0m\n", - "\u001b[36mCleanup \u001b[0m\n", - "\u001b[36mAsymptoticStability \u001b[0m\n", - "\u001b[36mUDPout \u001b[0m\n", - "\u001b[36mPickleData \u001b[0m\n", - "\u001b[36mPreSharpy \u001b[0m\n", - "\u001b[36mSaveData \u001b[0m\n", - "\u001b[36mSaveParametricCase \u001b[0m\n", - "\u001b[36mStallCheck \u001b[0m\n", - "\u001b[36mBeamLoads \u001b[0m\n", - "\u001b[36mPlotFlowField \u001b[0m\n", - "\u001b[36mAerogridPlot \u001b[0m\n", + "\u001b[36mThe branch being run is dev_blade_pitch_v2\u001b[0m\n", + "\u001b[36mThe version and commit hash are: v1.2.1-546-g05602d1f-05602d1f\u001b[0m\n", + "SHARPy output folder set\u001b[0m\n", + "\u001b[34m\t./output//rotor/\u001b[0m\n", "\u001b[36mGenerating an instance of BeamLoader\u001b[0m\n", "\u001b[36mGenerating an instance of AerogridLoader\u001b[0m\n", "Variable shear_direction has no assigned value in the settings file.\u001b[0m\n", @@ -440,15 +396,15 @@ "Variable h_corr has no assigned value in the settings file.\u001b[0m\n", "\u001b[34m will default to the value: 1.0\u001b[0m\n", "\u001b[34mThe aerodynamic grid contains 3 surfaces\u001b[0m\n", - "\u001b[34m Surface 0, M=8, N=48\u001b[0m\n", - " Wake 0, M=450, N=48\u001b[0m\n", - "\u001b[34m Surface 1, M=8, N=48\u001b[0m\n", - " Wake 1, M=450, N=48\u001b[0m\n", - "\u001b[34m Surface 2, M=8, N=48\u001b[0m\n", - " Wake 2, M=450, N=48\u001b[0m\n", - " In total: 1152 bound panels\u001b[0m\n", - " In total: 64800 wake panels\u001b[0m\n", - " Total number of panels = 65952\u001b[0m\n", + "\u001b[34m Surface 0, M=8, N=26\u001b[0m\n", + " Wake 0, M=450, N=26\u001b[0m\n", + "\u001b[34m Surface 1, M=8, N=26\u001b[0m\n", + " Wake 1, M=450, N=26\u001b[0m\n", + "\u001b[34m Surface 2, M=8, N=26\u001b[0m\n", + " Wake 2, M=450, N=26\u001b[0m\n", + " In total: 624 bound panels\u001b[0m\n", + " In total: 35100 wake panels\u001b[0m\n", + " Total number of panels = 35724\u001b[0m\n", "\u001b[36mGenerating an instance of StaticCoupled\u001b[0m\n", "\u001b[36mGenerating an instance of RigidDynamicPrescribedStep\u001b[0m\n", "\u001b[36mGenerating an instance of StaticUvlm\u001b[0m\n", @@ -458,8 +414,8 @@ "|=====|=====|============|==========|==========|==========|==========|==========|==========|\u001b[0m\n", "|iter |step | log10(res) | Fx | Fy | Fz | Mx | My | Mz |\u001b[0m\n", "|=====|=====|============|==========|==========|==========|==========|==========|==========|\u001b[0m\n", - "| 0 | 0 | 0.00000 | -0.0000 | 0.0000 |58835.1377| -0.0000 | 0.0000 |6121580.8013|\u001b[0m\n", - "| 1 | 0 | -inf | -0.0000 | 0.0000 |58835.1377| -0.0000 | 0.0000 |6121580.8013|\u001b[0m\n", + "| 0 | 0 | 0.00000 | -0.0000 | 0.0000 |21927.8250| 0.0000 | -0.0000 |5962997.5361|\u001b[0m\n", + "| 1 | 0 | -inf | -0.0000 | 0.0000 |21927.8250| 0.0000 | -0.0000 |5962997.5361|\u001b[0m\n", "\u001b[36mGenerating an instance of DynamicCoupled\u001b[0m\n", "\u001b[36mGenerating an instance of RigidDynamicPrescribedStep\u001b[0m\n", "\u001b[36mGenerating an instance of StepUvlm\u001b[0m\n", @@ -473,495 +429,459 @@ "|=======|========|======|==============|==============|==============|==============|==============|\u001b[0m\n", "| ts | t | iter | struc ratio | iter time | residual vel | FoR_vel(x) | FoR_vel(z) |\u001b[0m\n", "|=======|========|======|==============|==============|==============|==============|==============|\u001b[0m\n", - "| 1 | 0.0551 | 1 | 0.000892 | 32.003247 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 2 | 0.1102 | 1 | 0.000829 | 34.424959 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 3 | 0.1653 | 1 | 0.000897 | 31.674002 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 4 | 0.2204 | 1 | 0.000917 | 30.999806 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 5 | 0.2755 | 1 | 0.000910 | 31.273636 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 6 | 0.3306 | 1 | 0.000907 | 31.360496 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 7 | 0.3857 | 1 | 0.000927 | 30.898685 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 8 | 0.4408 | 1 | 0.000922 | 31.080507 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 9 | 0.4959 | 1 | 0.000917 | 31.008975 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 10 | 0.5510 | 1 | 0.000913 | 31.051142 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 11 | 0.6061 | 1 | 0.000916 | 30.973677 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 12 | 0.6612 | 1 | 0.000922 | 30.960834 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 13 | 0.7163 | 1 | 0.000897 | 31.733305 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 14 | 0.7713 | 1 | 0.000917 | 30.951755 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 15 | 0.8264 | 1 | 0.000918 | 30.906685 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 16 | 0.8815 | 1 | 0.000896 | 32.725117 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 17 | 0.9366 | 1 | 0.000824 | 34.665609 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 18 | 0.9917 | 1 | 0.000887 | 32.271645 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 19 | 1.0468 | 1 | 0.000892 | 32.066907 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 20 | 1.1019 | 1 | 0.000891 | 32.330094 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 21 | 1.1570 | 1 | 0.000900 | 31.906545 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 22 | 1.2121 | 1 | 0.000904 | 31.585152 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 23 | 1.2672 | 1 | 0.000923 | 32.065384 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 24 | 1.3223 | 1 | 0.000900 | 31.655170 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 25 | 1.3774 | 1 | 0.000872 | 32.705481 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 26 | 1.4325 | 1 | 0.000866 | 32.846920 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 27 | 1.4876 | 1 | 0.000905 | 31.668165 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 28 | 1.5427 | 1 | 0.000883 | 32.061146 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 29 | 1.5978 | 1 | 0.000887 | 32.765074 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 30 | 1.6529 | 1 | 0.000861 | 33.212694 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 31 | 1.7080 | 1 | 0.000878 | 32.706162 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 32 | 1.7631 | 1 | 0.000808 | 35.254301 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 33 | 1.8182 | 1 | 0.000914 | 31.894184 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 34 | 1.8733 | 1 | 0.000897 | 31.895611 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 35 | 1.9284 | 1 | 0.000900 | 31.743104 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "| 36 | 1.9835 | 1 | 0.000907 | 31.382207 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 37 | 2.0386 | 1 | 0.000889 | 31.995525 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 38 | 2.0937 | 1 | 0.000896 | 31.669265 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 39 | 2.1488 | 1 | 0.000892 | 32.021120 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 40 | 2.2039 | 1 | 0.000895 | 32.341717 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 41 | 2.2590 | 1 | 0.000909 | 31.194986 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 42 | 2.3140 | 1 | 0.000913 | 31.075842 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 43 | 2.3691 | 1 | 0.000905 | 31.220793 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 44 | 2.4242 | 1 | 0.000865 | 32.660052 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 45 | 2.4793 | 1 | 0.000913 | 31.252726 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 46 | 2.5344 | 1 | 0.000717 | 39.589737 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 47 | 2.5895 | 1 | 0.000689 | 43.339545 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 48 | 2.6446 | 1 | 0.000654 | 43.501825 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 49 | 2.6997 | 1 | 0.000888 | 32.114099 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 50 | 2.7548 | 1 | 0.000894 | 31.591624 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 51 | 2.8099 | 1 | 0.000911 | 31.120782 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 52 | 2.8650 | 1 | 0.000918 | 31.005261 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 53 | 2.9201 | 1 | 0.000923 | 30.937075 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 54 | 2.9752 | 1 | 0.000920 | 31.006048 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 55 | 3.0303 | 1 | 0.000926 | 30.934778 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 56 | 3.0854 | 1 | 0.000910 | 31.056369 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 57 | 3.1405 | 1 | 0.000933 | 31.085487 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 58 | 3.1956 | 1 | 0.000925 | 30.989723 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 59 | 3.2507 | 1 | 0.000932 | 30.994836 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 60 | 3.3058 | 1 | 0.000916 | 31.033034 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 61 | 3.3609 | 1 | 0.000918 | 30.934751 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 62 | 3.4160 | 1 | 0.000928 | 30.999680 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 63 | 3.4711 | 1 | 0.000911 | 30.978938 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 64 | 3.5262 | 1 | 0.000926 | 30.976717 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 65 | 3.5813 | 1 | 0.000907 | 31.276748 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 66 | 3.6364 | 1 | 0.000911 | 31.264278 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 67 | 3.6915 | 1 | 0.000915 | 31.093838 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 68 | 3.7466 | 1 | 0.000924 | 31.082399 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 69 | 3.8017 | 1 | 0.000919 | 30.964752 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 70 | 3.8567 | 1 | 0.000863 | 33.050274 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 71 | 3.9118 | 1 | 0.000915 | 31.032668 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 72 | 3.9669 | 1 | 0.000912 | 30.922833 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 73 | 4.0220 | 1 | 0.000918 | 30.893852 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 74 | 4.0771 | 1 | 0.000971 | 31.148592 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 75 | 4.1322 | 1 | 0.000920 | 30.974765 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 76 | 4.1873 | 1 | 0.000904 | 31.115302 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 77 | 4.2424 | 1 | 0.000919 | 31.070263 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 78 | 4.2975 | 1 | 0.000932 | 30.954521 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 79 | 4.3526 | 1 | 0.000902 | 31.636753 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 80 | 4.4077 | 1 | 0.000887 | 32.539172 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 81 | 4.4628 | 1 | 0.000820 | 34.997592 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 82 | 4.5179 | 1 | 0.000650 | 45.337859 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 83 | 4.5730 | 1 | 0.000657 | 43.207602 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 84 | 4.6281 | 1 | 0.000898 | 31.524481 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 85 | 4.6832 | 1 | 0.000921 | 31.117602 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 86 | 4.7383 | 1 | 0.000832 | 34.343085 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 87 | 4.7934 | 1 | 0.000624 | 46.383277 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 88 | 4.8485 | 1 | 0.000673 | 43.034549 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 89 | 4.9036 | 1 | 0.000809 | 35.412812 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 90 | 4.9587 | 1 | 0.000972 | 31.025067 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 91 | 5.0138 | 1 | 0.000917 | 31.065905 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 92 | 5.0689 | 1 | 0.000910 | 31.646625 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 93 | 5.1240 | 1 | 0.000684 | 41.495273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 94 | 5.1791 | 1 | 0.000672 | 42.896018 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 95 | 5.2342 | 1 | 0.000721 | 39.449060 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 96 | 5.2893 | 1 | 0.000914 | 31.205017 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 97 | 5.3444 | 1 | 0.000920 | 30.984492 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 98 | 5.3994 | 1 | 0.000924 | 30.922404 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 99 | 5.4545 | 1 | 0.000912 | 30.943627 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 100 | 5.5096 | 1 | 0.000909 | 31.230726 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 101 | 5.5647 | 1 | 0.000908 | 31.102787 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 102 | 5.6198 | 1 | 0.000917 | 31.079339 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 103 | 5.6749 | 1 | 0.000917 | 31.224959 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 104 | 5.7300 | 1 | 0.000918 | 30.897047 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 105 | 5.7851 | 1 | 0.000919 | 30.946830 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 106 | 5.8402 | 1 | 0.000929 | 31.049852 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 107 | 5.8953 | 1 | 0.000957 | 30.911006 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 108 | 5.9504 | 1 | 0.000936 | 31.019474 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 109 | 6.0055 | 1 | 0.000917 | 31.004980 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 110 | 6.0606 | 1 | 0.000924 | 31.007143 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 111 | 6.1157 | 1 | 0.000912 | 31.071975 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 112 | 6.1708 | 1 | 0.000912 | 30.917326 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 113 | 6.2259 | 1 | 0.000915 | 30.961683 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 114 | 6.2810 | 1 | 0.000909 | 31.010302 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "| 115 | 6.3361 | 1 | 0.000937 | 31.016248 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 116 | 6.3912 | 1 | 0.000916 | 30.918273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 117 | 6.4463 | 1 | 0.000919 | 31.072337 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 118 | 6.5014 | 1 | 0.000916 | 31.076478 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 119 | 6.5565 | 1 | 0.000915 | 30.992306 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 120 | 6.6116 | 1 | 0.000906 | 31.038977 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 121 | 6.6667 | 1 | 0.000920 | 30.893811 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 122 | 6.7218 | 1 | 0.000918 | 31.017417 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 123 | 6.7769 | 1 | 0.000919 | 30.938301 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 124 | 6.8320 | 1 | 0.000918 | 30.992443 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 125 | 6.8871 | 1 | 0.000927 | 30.876471 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 126 | 6.9421 | 1 | 0.000926 | 31.022833 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 127 | 6.9972 | 1 | 0.000957 | 31.079162 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 128 | 7.0523 | 1 | 0.000930 | 30.912956 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 129 | 7.1074 | 1 | 0.000917 | 30.920774 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 130 | 7.1625 | 1 | 0.000926 | 30.889295 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 131 | 7.2176 | 1 | 0.000928 | 30.952314 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 132 | 7.2727 | 1 | 0.000928 | 30.948958 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 133 | 7.3278 | 1 | 0.000933 | 30.914106 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 134 | 7.3829 | 1 | 0.000946 | 30.961606 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 135 | 7.4380 | 1 | 0.000909 | 31.023403 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 136 | 7.4931 | 1 | 0.000915 | 31.114690 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 137 | 7.5482 | 1 | 0.000934 | 30.938297 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 138 | 7.6033 | 1 | 0.000924 | 30.948950 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 139 | 7.6584 | 1 | 0.000918 | 31.025968 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 140 | 7.7135 | 1 | 0.000915 | 31.038340 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 141 | 7.7686 | 1 | 0.000922 | 30.895676 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 142 | 7.8237 | 1 | 0.000911 | 30.999057 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 143 | 7.8788 | 1 | 0.000908 | 30.910233 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 144 | 7.9339 | 1 | 0.000919 | 31.004791 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 145 | 7.9890 | 1 | 0.000922 | 30.905117 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 146 | 8.0441 | 1 | 0.000930 | 30.995744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 147 | 8.0992 | 1 | 0.000921 | 30.923201 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 148 | 8.1543 | 1 | 0.000917 | 30.989188 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 149 | 8.2094 | 1 | 0.000907 | 31.033752 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 150 | 8.2645 | 1 | 0.000912 | 31.093257 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 151 | 8.3196 | 1 | 0.000919 | 30.918701 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 152 | 8.3747 | 1 | 0.000923 | 30.913795 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 153 | 8.4298 | 1 | 0.000937 | 30.977022 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 154 | 8.4848 | 1 | 0.000916 | 31.022006 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 155 | 8.5399 | 1 | 0.000922 | 30.903273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 156 | 8.5950 | 1 | 0.001047 | 31.571999 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 157 | 8.6501 | 1 | 0.000945 | 30.975473 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 158 | 8.7052 | 1 | 0.000917 | 30.915441 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 159 | 8.7603 | 1 | 0.000913 | 30.937728 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 160 | 8.8154 | 1 | 0.000915 | 30.942585 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 161 | 8.8705 | 1 | 0.000916 | 30.966433 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 162 | 8.9256 | 1 | 0.000913 | 30.941522 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 163 | 8.9807 | 1 | 0.000918 | 30.932131 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 164 | 9.0358 | 1 | 0.000914 | 30.935404 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 165 | 9.0909 | 1 | 0.000907 | 30.975778 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 166 | 9.1460 | 1 | 0.000918 | 30.856382 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 167 | 9.2011 | 1 | 0.000919 | 30.987064 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 168 | 9.2562 | 1 | 0.000924 | 30.910973 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 169 | 9.3113 | 1 | 0.000922 | 30.918958 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 170 | 9.3664 | 1 | 0.000919 | 30.954364 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 171 | 9.4215 | 1 | 0.000886 | 32.110778 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 172 | 9.4766 | 1 | 0.000908 | 31.343746 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 173 | 9.5317 | 1 | 0.000938 | 30.921140 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 174 | 9.5868 | 1 | 0.000947 | 31.042633 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 175 | 9.6419 | 1 | 0.000918 | 30.901971 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 176 | 9.6970 | 1 | 0.000917 | 31.145731 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 177 | 9.7521 | 1 | 0.000875 | 32.249622 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 178 | 9.8072 | 1 | 0.000912 | 30.969236 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 179 | 9.8623 | 1 | 0.000914 | 31.004783 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 180 | 9.9174 | 1 | 0.000937 | 30.933874 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 181 | 9.9725 | 1 | 0.000911 | 31.110613 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 182 |10.0275 | 1 | 0.000939 | 31.085973 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 183 |10.0826 | 1 | 0.000925 | 30.870848 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 184 |10.1377 | 1 | 0.000923 | 30.926473 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 185 |10.1928 | 1 | 0.000916 | 31.146158 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 186 |10.2479 | 1 | 0.000917 | 30.947480 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 187 |10.3030 | 1 | 0.000923 | 30.908379 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 188 |10.3581 | 1 | 0.000954 | 31.005452 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 189 |10.4132 | 1 | 0.000926 | 31.012259 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 190 |10.4683 | 1 | 0.000928 | 30.888091 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 191 |10.5234 | 1 | 0.000922 | 31.017826 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 192 |10.5785 | 1 | 0.000937 | 30.900784 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 193 |10.6336 | 1 | 0.000912 | 31.008140 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "| 194 |10.6887 | 1 | 0.000924 | 30.905508 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 195 |10.7438 | 1 | 0.000957 | 31.092918 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 196 |10.7989 | 1 | 0.000922 | 30.984259 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 197 |10.8540 | 1 | 0.000912 | 30.918213 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 198 |10.9091 | 1 | 0.000918 | 30.906566 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 199 |10.9642 | 1 | 0.000920 | 30.978359 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 200 |11.0193 | 1 | 0.000921 | 30.990309 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 201 |11.0744 | 1 | 0.000922 | 30.998848 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 202 |11.1295 | 1 | 0.000919 | 30.988585 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 203 |11.1846 | 1 | 0.000967 | 30.932929 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 204 |11.2397 | 1 | 0.000961 | 31.166006 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 205 |11.2948 | 1 | 0.000923 | 30.916330 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 206 |11.3499 | 1 | 0.000918 | 31.015378 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 207 |11.4050 | 1 | 0.000920 | 30.935401 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 208 |11.4601 | 1 | 0.000919 | 30.982654 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 209 |11.5152 | 1 | 0.000897 | 31.874632 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 210 |11.5702 | 1 | 0.000908 | 31.118416 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 211 |11.6253 | 1 | 0.000931 | 31.217766 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 212 |11.6804 | 1 | 0.000903 | 31.346483 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 213 |11.7355 | 1 | 0.000920 | 30.971118 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 214 |11.7906 | 1 | 0.000929 | 31.000595 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 215 |11.8457 | 1 | 0.000915 | 30.969266 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 216 |11.9008 | 1 | 0.000913 | 31.803210 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 217 |11.9559 | 1 | 0.000913 | 31.008861 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 218 |12.0110 | 1 | 0.000912 | 30.917057 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 219 |12.0661 | 1 | 0.000905 | 31.483228 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 220 |12.1212 | 1 | 0.000925 | 30.923689 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 221 |12.1763 | 1 | 0.000916 | 30.942301 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 222 |12.2314 | 1 | 0.000918 | 30.963086 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 223 |12.2865 | 1 | 0.000900 | 31.521071 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 224 |12.3416 | 1 | 0.000925 | 30.931045 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 225 |12.3967 | 1 | 0.000906 | 31.197149 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 226 |12.4518 | 1 | 0.000913 | 31.144852 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 227 |12.5069 | 1 | 0.000895 | 31.983333 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 228 |12.5620 | 1 | 0.000900 | 31.542461 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 229 |12.6171 | 1 | 0.000920 | 31.045717 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 230 |12.6722 | 1 | 0.000897 | 31.491388 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 231 |12.7273 | 1 | 0.000918 | 30.903177 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 232 |12.7824 | 1 | 0.000915 | 31.084838 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 233 |12.8375 | 1 | 0.000920 | 30.906922 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 234 |12.8926 | 1 | 0.000912 | 31.119419 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 235 |12.9477 | 1 | 0.000881 | 31.875403 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 236 |13.0028 | 1 | 0.000889 | 31.890126 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 237 |13.0579 | 1 | 0.000916 | 30.947009 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 238 |13.1129 | 1 | 0.000903 | 31.104523 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 239 |13.1680 | 1 | 0.000908 | 31.200449 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 240 |13.2231 | 1 | 0.000918 | 31.005172 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 241 |13.2782 | 1 | 0.000923 | 31.013511 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 242 |13.3333 | 1 | 0.000917 | 31.053680 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 243 |13.3884 | 1 | 0.000918 | 30.949748 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 244 |13.4435 | 1 | 0.000897 | 31.708627 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 245 |13.4986 | 1 | 0.000896 | 31.703804 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 246 |13.5537 | 1 | 0.000936 | 30.964896 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 247 |13.6088 | 1 | 0.000916 | 31.018459 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 248 |13.6639 | 1 | 0.000906 | 31.030132 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 249 |13.7190 | 1 | 0.000697 | 40.540772 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 250 |13.7741 | 1 | 0.000939 | 30.990541 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 251 |13.8292 | 1 | 0.000930 | 31.189301 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 252 |13.8843 | 1 | 0.000908 | 31.074319 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 253 |13.9394 | 1 | 0.000926 | 30.931407 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 254 |13.9945 | 1 | 0.000908 | 30.975691 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 255 |14.0496 | 1 | 0.000921 | 30.952020 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 256 |14.1047 | 1 | 0.000922 | 30.929284 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 257 |14.1598 | 1 | 0.000924 | 30.884744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 258 |14.2149 | 1 | 0.000910 | 30.982695 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 259 |14.2700 | 1 | 0.000924 | 30.994780 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 260 |14.3251 | 1 | 0.000914 | 31.057176 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 261 |14.3802 | 1 | 0.000924 | 30.977462 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 262 |14.4353 | 1 | 0.000910 | 30.970187 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 263 |14.4904 | 1 | 0.000925 | 30.897495 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 264 |14.5455 | 1 | 0.000919 | 30.917634 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 265 |14.6006 | 1 | 0.000910 | 31.083578 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 266 |14.6556 | 1 | 0.000912 | 31.073436 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 267 |14.7107 | 1 | 0.000904 | 31.496094 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 268 |14.7658 | 1 | 0.000912 | 30.973318 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 269 |14.8209 | 1 | 0.000921 | 31.001805 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 270 |14.8760 | 1 | 0.000921 | 31.058672 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 271 |14.9311 | 1 | 0.000919 | 30.941234 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 272 |14.9862 | 1 | 0.000915 | 31.067117 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "| 273 |15.0413 | 1 | 0.000914 | 30.991765 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 274 |15.0964 | 1 | 0.000910 | 31.124020 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 275 |15.1515 | 1 | 0.000937 | 31.242097 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 276 |15.2066 | 1 | 0.000923 | 30.869329 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 277 |15.2617 | 1 | 0.000913 | 31.004095 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 278 |15.3168 | 1 | 0.000920 | 30.970996 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 279 |15.3719 | 1 | 0.000927 | 30.917484 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 280 |15.4270 | 1 | 0.000911 | 30.892718 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 281 |15.4821 | 1 | 0.000914 | 30.960543 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 282 |15.5372 | 1 | 0.000913 | 30.893237 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 283 |15.5923 | 1 | 0.000921 | 31.036962 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 284 |15.6474 | 1 | 0.000916 | 31.041628 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 285 |15.7025 | 1 | 0.000919 | 30.893108 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 286 |15.7576 | 1 | 0.000922 | 30.907060 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 287 |15.8127 | 1 | 0.000907 | 31.154682 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 288 |15.8678 | 1 | 0.000917 | 31.055366 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 289 |15.9229 | 1 | 0.000908 | 31.073641 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 290 |15.9780 | 1 | 0.000909 | 30.925398 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 291 |16.0331 | 1 | 0.000931 | 30.933038 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 292 |16.0882 | 1 | 0.000932 | 30.883366 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 293 |16.1433 | 1 | 0.000925 | 30.974573 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 294 |16.1983 | 1 | 0.000926 | 30.920426 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 295 |16.2534 | 1 | 0.000909 | 30.992082 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 296 |16.3085 | 1 | 0.000910 | 31.053425 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 297 |16.3636 | 1 | 0.000919 | 30.943481 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 298 |16.4187 | 1 | 0.000920 | 31.073522 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 299 |16.4738 | 1 | 0.000912 | 31.017014 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 300 |16.5289 | 1 | 0.000913 | 30.950815 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 301 |16.5840 | 1 | 0.000919 | 30.873358 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 302 |16.6391 | 1 | 0.000917 | 30.949980 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 303 |16.6942 | 1 | 0.000912 | 31.149671 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 304 |16.7493 | 1 | 0.000683 | 41.283571 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 305 |16.8044 | 1 | 0.000657 | 42.893068 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 306 |16.8595 | 1 | 0.000662 | 43.174875 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 307 |16.9146 | 1 | 0.000881 | 32.450967 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 308 |16.9697 | 1 | 0.000915 | 31.021247 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 309 |17.0248 | 1 | 0.000921 | 30.962266 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 310 |17.0799 | 1 | 0.000920 | 30.990332 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 311 |17.1350 | 1 | 0.000917 | 30.915749 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 312 |17.1901 | 1 | 0.000917 | 30.961650 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 313 |17.2452 | 1 | 0.000903 | 30.992689 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 314 |17.3003 | 1 | 0.000925 | 31.008350 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 315 |17.3554 | 1 | 0.000904 | 31.472609 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 316 |17.4105 | 1 | 0.000909 | 31.018433 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 317 |17.4656 | 1 | 0.000913 | 31.128679 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 318 |17.5207 | 1 | 0.000916 | 31.038997 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 319 |17.5758 | 1 | 0.000909 | 30.992505 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 320 |17.6309 | 1 | 0.000915 | 30.903055 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 321 |17.6860 | 1 | 0.000919 | 31.084218 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 322 |17.7410 | 1 | 0.000908 | 31.119063 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 323 |17.7961 | 1 | 0.000910 | 31.273114 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 324 |17.8512 | 1 | 0.000921 | 30.880844 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 325 |17.9063 | 1 | 0.000910 | 31.029546 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 326 |17.9614 | 1 | 0.000916 | 30.941567 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 327 |18.0165 | 1 | 0.000913 | 31.233166 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 328 |18.0716 | 1 | 0.000929 | 30.970063 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 329 |18.1267 | 1 | 0.000912 | 31.140351 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 330 |18.1818 | 1 | 0.000908 | 31.050875 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 331 |18.2369 | 1 | 0.000909 | 31.189776 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 332 |18.2920 | 1 | 0.000914 | 30.987210 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 333 |18.3471 | 1 | 0.000959 | 31.032436 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 334 |18.4022 | 1 | 0.000915 | 31.036937 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 335 |18.4573 | 1 | 0.000916 | 31.051169 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 336 |18.5124 | 1 | 0.000923 | 30.913584 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 337 |18.5675 | 1 | 0.000924 | 30.979053 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 338 |18.6226 | 1 | 0.000925 | 31.071960 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 339 |18.6777 | 1 | 0.000911 | 31.006622 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 340 |18.7328 | 1 | 0.000902 | 31.566711 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 341 |18.7879 | 1 | 0.000834 | 34.959509 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 342 |18.8430 | 1 | 0.000842 | 34.022732 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 343 |18.8981 | 1 | 0.000891 | 31.951907 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 344 |18.9532 | 1 | 0.000924 | 30.960468 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 345 |19.0083 | 1 | 0.000912 | 30.898630 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 346 |19.0634 | 1 | 0.000914 | 30.985280 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 347 |19.1185 | 1 | 0.000907 | 30.997136 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 348 |19.1736 | 1 | 0.000913 | 30.947927 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 349 |19.2287 | 1 | 0.000922 | 30.926197 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 350 |19.2837 | 1 | 0.000929 | 31.031291 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 351 |19.3388 | 1 | 0.000920 | 31.066194 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "| 352 |19.3939 | 1 | 0.000915 | 31.021782 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 353 |19.4490 | 1 | 0.000910 | 31.054333 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 354 |19.5041 | 1 | 0.000937 | 31.017431 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 355 |19.5592 | 1 | 0.000914 | 31.036429 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 356 |19.6143 | 1 | 0.000922 | 30.974830 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 357 |19.6694 | 1 | 0.000921 | 30.947570 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 358 |19.7245 | 1 | 0.000913 | 31.119531 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 359 |19.7796 | 1 | 0.000915 | 31.167779 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 360 |19.8347 | 1 | 0.000918 | 31.068536 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 361 |19.8898 | 1 | 0.000911 | 31.031367 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 362 |19.9449 | 1 | 0.000919 | 30.956716 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 363 |20.0000 | 1 | 0.000922 | 30.995727 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 364 |20.0551 | 1 | 0.000914 | 30.973092 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 365 |20.1102 | 1 | 0.000918 | 30.961610 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 366 |20.1653 | 1 | 0.000926 | 30.881730 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 367 |20.2204 | 1 | 0.000908 | 30.987541 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 368 |20.2755 | 1 | 0.000927 | 31.154198 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 369 |20.3306 | 1 | 0.000920 | 30.893291 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 370 |20.3857 | 1 | 0.000925 | 30.981216 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 371 |20.4408 | 1 | 0.000926 | 31.024869 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 372 |20.4959 | 1 | 0.000920 | 31.094704 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 373 |20.5510 | 1 | 0.000924 | 30.931043 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 374 |20.6061 | 1 | 0.000910 | 31.003695 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 375 |20.6612 | 1 | 0.000921 | 30.938825 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 376 |20.7163 | 1 | 0.000913 | 31.182973 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 377 |20.7713 | 1 | 0.000918 | 30.992988 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 378 |20.8264 | 1 | 0.000923 | 30.980134 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 379 |20.8815 | 1 | 0.000918 | 31.031038 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 380 |20.9366 | 1 | 0.000899 | 31.901566 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 381 |20.9917 | 1 | 0.000915 | 31.076764 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 382 |21.0468 | 1 | 0.000911 | 31.072542 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 383 |21.1019 | 1 | 0.000914 | 30.969881 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 384 |21.1570 | 1 | 0.000917 | 30.921061 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 385 |21.2121 | 1 | 0.000939 | 30.948887 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 386 |21.2672 | 1 | 0.000924 | 31.151912 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 387 |21.3223 | 1 | 0.000907 | 31.003044 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 388 |21.3774 | 1 | 0.000915 | 31.097173 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 389 |21.4325 | 1 | 0.000911 | 31.071583 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 390 |21.4876 | 1 | 0.000917 | 30.973833 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 391 |21.5427 | 1 | 0.000917 | 31.150668 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 392 |21.5978 | 1 | 0.000916 | 31.089087 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 393 |21.6529 | 1 | 0.000909 | 31.159542 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 394 |21.7080 | 1 | 0.000915 | 31.040465 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 395 |21.7631 | 1 | 0.000918 | 30.956352 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 396 |21.8182 | 1 | 0.000918 | 30.984192 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 397 |21.8733 | 1 | 0.000919 | 31.130644 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 398 |21.9284 | 1 | 0.000916 | 30.997960 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 399 |21.9835 | 1 | 0.000912 | 31.131888 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 400 |22.0386 | 1 | 0.000949 | 31.186263 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 401 |22.0937 | 1 | 0.000916 | 31.204745 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 402 |22.1488 | 1 | 0.000906 | 31.009868 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 403 |22.2039 | 1 | 0.000912 | 31.036721 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 404 |22.2590 | 1 | 0.000914 | 31.120642 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 405 |22.3140 | 1 | 0.000919 | 30.994664 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 406 |22.3691 | 1 | 0.000919 | 30.961076 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 407 |22.4242 | 1 | 0.000915 | 31.242275 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 408 |22.4793 | 1 | 0.000901 | 31.363461 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 409 |22.5344 | 1 | 0.000910 | 31.323509 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 410 |22.5895 | 1 | 0.000911 | 31.059490 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 411 |22.6446 | 1 | 0.000921 | 30.910846 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 412 |22.6997 | 1 | 0.000932 | 31.133223 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 413 |22.7548 | 1 | 0.000917 | 31.070970 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 414 |22.8099 | 1 | 0.000914 | 30.972951 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 415 |22.8650 | 1 | 0.000918 | 31.069821 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 416 |22.9201 | 1 | 0.000914 | 30.941482 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 417 |22.9752 | 1 | 0.000922 | 31.035067 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 418 |23.0303 | 1 | 0.000919 | 31.025383 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 419 |23.0854 | 1 | 0.000922 | 30.960795 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 420 |23.1405 | 1 | 0.000920 | 30.935715 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 421 |23.1956 | 1 | 0.000921 | 31.048004 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 422 |23.2507 | 1 | 0.000919 | 31.063771 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 423 |23.3058 | 1 | 0.000918 | 31.055843 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 424 |23.3609 | 1 | 0.000913 | 30.966745 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 425 |23.4160 | 1 | 0.000917 | 31.040304 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 426 |23.4711 | 1 | 0.000899 | 31.154555 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 427 |23.5262 | 1 | 0.000924 | 31.061133 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 428 |23.5813 | 1 | 0.000922 | 30.945985 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 429 |23.6364 | 1 | 0.000920 | 31.081685 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 430 |23.6915 | 1 | 0.000944 | 30.971239 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "| 431 |23.7466 | 1 | 0.000909 | 31.095790 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 432 |23.8017 | 1 | 0.000914 | 31.028391 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 433 |23.8567 | 1 | 0.000913 | 30.953656 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 434 |23.9118 | 1 | 0.000917 | 31.025156 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 435 |23.9669 | 1 | 0.000915 | 30.890819 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 436 |24.0220 | 1 | 0.000921 | 31.095835 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 437 |24.0771 | 1 | 0.000907 | 31.297074 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 438 |24.1322 | 1 | 0.000908 | 31.019046 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 439 |24.1873 | 1 | 0.000930 | 30.926273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 440 |24.2424 | 1 | 0.000913 | 30.909393 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 441 |24.2975 | 1 | 0.000915 | 30.939363 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 442 |24.3526 | 1 | 0.000914 | 31.118100 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 443 |24.4077 | 1 | 0.000915 | 31.003708 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 444 |24.4628 | 1 | 0.000904 | 31.023637 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 445 |24.5179 | 1 | 0.000908 | 31.111450 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 446 |24.5730 | 1 | 0.000918 | 30.980093 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 447 |24.6281 | 1 | 0.000906 | 31.211698 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 448 |24.6832 | 1 | 0.000921 | 31.004640 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 449 |24.7383 | 1 | 0.000912 | 31.117989 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", - "| 450 |24.7934 | 1 | 0.000909 | 30.893335 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 1 | 0.0551 | 1 | 0.001471 | 11.072773 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 2 | 0.1102 | 1 | 0.001529 | 11.094774 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 3 | 0.1653 | 1 | 0.001487 | 11.017530 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 4 | 0.2204 | 1 | 0.001487 | 11.053551 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 5 | 0.2755 | 1 | 0.001495 | 10.972424 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 6 | 0.3306 | 1 | 0.001496 | 10.951425 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 7 | 0.3857 | 1 | 0.001492 | 11.018625 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 8 | 0.4408 | 1 | 0.001476 | 11.044770 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 9 | 0.4959 | 1 | 0.001478 | 11.122489 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 10 | 0.5510 | 1 | 0.001500 | 10.997606 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 11 | 0.6061 | 1 | 0.001481 | 11.076450 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 12 | 0.6612 | 1 | 0.001513 | 10.976762 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 13 | 0.7163 | 1 | 0.001489 | 11.056770 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 14 | 0.7713 | 1 | 0.001473 | 11.147662 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 15 | 0.8264 | 1 | 0.001485 | 11.047932 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 16 | 0.8815 | 1 | 0.001500 | 10.984375 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 17 | 0.9366 | 1 | 0.001492 | 10.999334 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 18 | 0.9917 | 1 | 0.001492 | 11.036468 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 19 | 1.0468 | 1 | 0.001490 | 10.989860 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 20 | 1.1019 | 1 | 0.001487 | 10.981977 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 21 | 1.1570 | 1 | 0.001480 | 11.026050 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 22 | 1.2121 | 1 | 0.001501 | 10.964416 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 23 | 1.2672 | 1 | 0.001483 | 11.061231 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 24 | 1.3223 | 1 | 0.001502 | 11.026285 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 25 | 1.3774 | 1 | 0.001497 | 10.937541 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 26 | 1.4325 | 1 | 0.001464 | 11.216671 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 27 | 1.4876 | 1 | 0.001489 | 11.077631 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 28 | 1.5427 | 1 | 0.001487 | 11.029765 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 29 | 1.5978 | 1 | 0.001484 | 11.057365 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 30 | 1.6529 | 1 | 0.001499 | 10.988523 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 31 | 1.7080 | 1 | 0.001480 | 11.082585 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 32 | 1.7631 | 1 | 0.001493 | 11.026814 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 33 | 1.8182 | 1 | 0.001500 | 10.964227 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 34 | 1.8733 | 1 | 0.001496 | 11.070894 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 35 | 1.9284 | 1 | 0.001499 | 10.991359 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 36 | 1.9835 | 1 | 0.001493 | 10.956692 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 37 | 2.0386 | 1 | 0.001489 | 11.022953 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 38 | 2.0937 | 1 | 0.001493 | 11.002933 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 39 | 2.1488 | 1 | 0.001494 | 10.971854 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 40 | 2.2039 | 1 | 0.001499 | 10.956611 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 41 | 2.2590 | 1 | 0.001484 | 11.020658 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 42 | 2.3140 | 1 | 0.001484 | 11.016274 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 43 | 2.3691 | 1 | 0.001490 | 11.171444 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 44 | 2.4242 | 1 | 0.001496 | 10.975332 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 45 | 2.4793 | 1 | 0.001479 | 11.094840 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 46 | 2.5344 | 1 | 0.001484 | 11.060059 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 47 | 2.5895 | 1 | 0.001329 | 12.309849 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 48 | 2.6446 | 1 | 0.001455 | 11.269876 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 49 | 2.6997 | 1 | 0.001489 | 11.076657 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 50 | 2.7548 | 1 | 0.001496 | 10.998456 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 51 | 2.8099 | 1 | 0.001471 | 11.215534 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 52 | 2.8650 | 1 | 0.001494 | 10.981076 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 53 | 2.9201 | 1 | 0.001476 | 11.089418 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 54 | 2.9752 | 1 | 0.001482 | 10.973016 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 55 | 3.0303 | 1 | 0.001469 | 11.115966 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 56 | 3.0854 | 1 | 0.001458 | 11.172810 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 57 | 3.1405 | 1 | 0.001496 | 10.984580 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 58 | 3.1956 | 1 | 0.001451 | 11.196615 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 59 | 3.2507 | 1 | 0.001498 | 10.961545 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 60 | 3.3058 | 1 | 0.001492 | 11.053819 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 61 | 3.3609 | 1 | 0.001492 | 11.066293 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 62 | 3.4160 | 1 | 0.001489 | 11.025009 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 63 | 3.4711 | 1 | 0.001485 | 10.999920 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 64 | 3.5262 | 1 | 0.001505 | 10.973439 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 65 | 3.5813 | 1 | 0.001495 | 10.981763 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 66 | 3.6364 | 1 | 0.001481 | 10.997240 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 67 | 3.6915 | 1 | 0.001489 | 11.030007 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 68 | 3.7466 | 1 | 0.001487 | 10.977346 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 69 | 3.8017 | 1 | 0.001490 | 11.086072 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 70 | 3.8567 | 1 | 0.001478 | 11.027897 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 71 | 3.9118 | 1 | 0.001492 | 10.997195 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 72 | 3.9669 | 1 | 0.001476 | 11.129629 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 73 | 4.0220 | 1 | 0.001491 | 10.996616 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 74 | 4.0771 | 1 | 0.001513 | 10.996785 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 75 | 4.1322 | 1 | 0.001487 | 11.010984 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 76 | 4.1873 | 1 | 0.001504 | 10.960333 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 77 | 4.2424 | 1 | 0.001483 | 11.062480 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 78 | 4.2975 | 1 | 0.001502 | 10.999189 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 79 | 4.3526 | 1 | 0.001504 | 10.989805 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 80 | 4.4077 | 1 | 0.001499 | 10.986292 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 81 | 4.4628 | 1 | 0.001471 | 11.064248 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 82 | 4.5179 | 1 | 0.001478 | 11.030763 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 83 | 4.5730 | 1 | 0.001423 | 11.418318 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 84 | 4.6281 | 1 | 0.001513 | 10.934981 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 85 | 4.6832 | 1 | 0.001477 | 10.947891 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 86 | 4.7383 | 1 | 0.001449 | 11.337449 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 87 | 4.7934 | 1 | 0.001446 | 11.356113 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 88 | 4.8485 | 1 | 0.001493 | 11.006986 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 89 | 4.9036 | 1 | 0.001508 | 10.995290 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 90 | 4.9587 | 1 | 0.001519 | 10.961908 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 91 | 5.0138 | 1 | 0.001511 | 11.004637 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 92 | 5.0689 | 1 | 0.001493 | 11.060139 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 93 | 5.1240 | 1 | 0.001475 | 11.108975 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 94 | 5.1791 | 1 | 0.001501 | 10.946505 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 95 | 5.2342 | 1 | 0.001504 | 10.936386 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 96 | 5.2893 | 1 | 0.001486 | 10.994701 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 97 | 5.3444 | 1 | 0.001483 | 11.023811 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 98 | 5.3994 | 1 | 0.001494 | 10.979126 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 99 | 5.4545 | 1 | 0.001481 | 11.163518 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 100 | 5.5096 | 1 | 0.001479 | 11.047313 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 101 | 5.5647 | 1 | 0.001473 | 11.060119 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 102 | 5.6198 | 1 | 0.001486 | 11.053105 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 103 | 5.6749 | 1 | 0.001486 | 11.092742 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 104 | 5.7300 | 1 | 0.001477 | 11.137425 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 105 | 5.7851 | 1 | 0.001491 | 11.010371 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 106 | 5.8402 | 1 | 0.001496 | 10.990369 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 107 | 5.8953 | 1 | 0.001473 | 11.243003 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 108 | 5.9504 | 1 | 0.001388 | 11.929604 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 109 | 6.0055 | 1 | 0.001458 | 11.222341 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 110 | 6.0606 | 1 | 0.001499 | 11.021925 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 111 | 6.1157 | 1 | 0.001489 | 10.988726 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 112 | 6.1708 | 1 | 0.001464 | 11.127002 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 113 | 6.2259 | 1 | 0.001490 | 10.982098 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 114 | 6.2810 | 1 | 0.001490 | 11.058744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 115 | 6.3361 | 1 | 0.001501 | 11.036917 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 116 | 6.3912 | 1 | 0.001487 | 11.093127 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 117 | 6.4463 | 1 | 0.001511 | 10.986041 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 118 | 6.5014 | 1 | 0.001473 | 11.067499 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 119 | 6.5565 | 1 | 0.001495 | 10.978576 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 120 | 6.6116 | 1 | 0.001497 | 11.027401 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 121 | 6.6667 | 1 | 0.001487 | 11.056618 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 122 | 6.7218 | 1 | 0.001492 | 10.946566 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 123 | 6.7769 | 1 | 0.001492 | 10.977270 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 124 | 6.8320 | 1 | 0.001466 | 11.212596 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 125 | 6.8871 | 1 | 0.001493 | 10.996106 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 126 | 6.9421 | 1 | 0.001480 | 11.018607 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 127 | 6.9972 | 1 | 0.001509 | 10.976320 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 128 | 7.0523 | 1 | 0.001329 | 12.417034 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 129 | 7.1074 | 1 | 0.001510 | 10.938081 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 130 | 7.1625 | 1 | 0.001496 | 10.964072 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 131 | 7.2176 | 1 | 0.001497 | 11.006588 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 132 | 7.2727 | 1 | 0.001493 | 11.018465 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 133 | 7.3278 | 1 | 0.001493 | 11.030553 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 134 | 7.3829 | 1 | 0.001490 | 11.034491 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 135 | 7.4380 | 1 | 0.001493 | 10.942718 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 136 | 7.4931 | 1 | 0.001485 | 11.063141 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 137 | 7.5482 | 1 | 0.001490 | 10.940797 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 138 | 7.6033 | 1 | 0.001496 | 11.094267 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 139 | 7.6584 | 1 | 0.001476 | 11.092305 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 140 | 7.7135 | 1 | 0.001489 | 10.999871 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 141 | 7.7686 | 1 | 0.001486 | 10.969563 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 142 | 7.8237 | 1 | 0.001485 | 11.045270 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 143 | 7.8788 | 1 | 0.001493 | 10.999192 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 144 | 7.9339 | 1 | 0.001498 | 11.051950 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 145 | 7.9890 | 1 | 0.001489 | 11.134410 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 146 | 8.0441 | 1 | 0.001474 | 11.101941 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 147 | 8.0992 | 1 | 0.001480 | 11.063681 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 148 | 8.1543 | 1 | 0.001486 | 10.946801 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 149 | 8.2094 | 1 | 0.001484 | 11.076774 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 150 | 8.2645 | 1 | 0.001480 | 11.143664 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 151 | 8.3196 | 1 | 0.001509 | 10.947056 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 152 | 8.3747 | 1 | 0.001447 | 11.226169 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 153 | 8.4298 | 1 | 0.001479 | 11.063754 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 154 | 8.4848 | 1 | 0.001484 | 10.961506 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 155 | 8.5399 | 1 | 0.001497 | 11.050401 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 156 | 8.5950 | 1 | 0.001503 | 11.018204 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 157 | 8.6501 | 1 | 0.001472 | 11.145519 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 158 | 8.7052 | 1 | 0.001486 | 11.037257 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 159 | 8.7603 | 1 | 0.001492 | 11.036405 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 160 | 8.8154 | 1 | 0.001480 | 11.015381 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 161 | 8.8705 | 1 | 0.001498 | 10.979052 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 162 | 8.9256 | 1 | 0.001496 | 11.051611 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 163 | 8.9807 | 1 | 0.001486 | 11.052557 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 164 | 9.0358 | 1 | 0.001491 | 11.034617 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 165 | 9.0909 | 1 | 0.001488 | 11.049273 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 166 | 9.1460 | 1 | 0.001491 | 11.085268 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 167 | 9.2011 | 1 | 0.001503 | 10.958939 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 168 | 9.2562 | 1 | 0.001497 | 11.062020 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 169 | 9.3113 | 1 | 0.001518 | 10.996845 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 170 | 9.3664 | 1 | 0.001470 | 11.209611 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 171 | 9.4215 | 1 | 0.001477 | 11.023668 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 172 | 9.4766 | 1 | 0.001481 | 11.090508 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 173 | 9.5317 | 1 | 0.001512 | 10.958598 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 174 | 9.5868 | 1 | 0.001472 | 11.093911 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 175 | 9.6419 | 1 | 0.001495 | 11.022321 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 176 | 9.6970 | 1 | 0.001497 | 10.963686 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 177 | 9.7521 | 1 | 0.001495 | 11.014677 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 178 | 9.8072 | 1 | 0.001494 | 10.971079 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 179 | 9.8623 | 1 | 0.001478 | 11.075295 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 180 | 9.9174 | 1 | 0.001492 | 10.967837 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 181 | 9.9725 | 1 | 0.001502 | 11.002055 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 182 |10.0275 | 1 | 0.001478 | 11.256881 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 183 |10.0826 | 1 | 0.001503 | 10.965836 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 184 |10.1377 | 1 | 0.001492 | 11.003513 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 185 |10.1928 | 1 | 0.001499 | 11.033890 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 186 |10.2479 | 1 | 0.001477 | 11.086396 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 187 |10.3030 | 1 | 0.001494 | 11.022237 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 188 |10.3581 | 1 | 0.001488 | 11.065405 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 189 |10.4132 | 1 | 0.001479 | 11.172747 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 190 |10.4683 | 1 | 0.001488 | 11.135500 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 191 |10.5234 | 1 | 0.001485 | 10.995766 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 192 |10.5785 | 1 | 0.001494 | 10.953639 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 193 |10.6336 | 1 | 0.001492 | 11.006385 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 194 |10.6887 | 1 | 0.001384 | 11.898180 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 195 |10.7438 | 1 | 0.001505 | 10.971906 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 196 |10.7989 | 1 | 0.001506 | 10.982670 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 197 |10.8540 | 1 | 0.001324 | 12.325860 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 198 |10.9091 | 1 | 0.001502 | 11.026861 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 199 |10.9642 | 1 | 0.001505 | 10.987199 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 200 |11.0193 | 1 | 0.001488 | 11.061289 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 201 |11.0744 | 1 | 0.001489 | 11.049199 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 202 |11.1295 | 1 | 0.001501 | 10.973437 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 203 |11.1846 | 1 | 0.001500 | 10.937448 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 204 |11.2397 | 1 | 0.001499 | 10.940185 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 205 |11.2948 | 1 | 0.001506 | 10.956871 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 206 |11.3499 | 1 | 0.001496 | 10.959225 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 207 |11.4050 | 1 | 0.001380 | 11.911324 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 208 |11.4601 | 1 | 0.001505 | 10.983367 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 209 |11.5152 | 1 | 0.001483 | 11.116040 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 210 |11.5702 | 1 | 0.001499 | 10.946843 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 211 |11.6253 | 1 | 0.001495 | 11.007702 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 212 |11.6804 | 1 | 0.001484 | 11.036537 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 213 |11.7355 | 1 | 0.001501 | 10.962850 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 214 |11.7906 | 1 | 0.001458 | 11.231765 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 215 |11.8457 | 1 | 0.001500 | 10.974388 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 216 |11.9008 | 1 | 0.001502 | 10.971881 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 217 |11.9559 | 1 | 0.001484 | 11.094227 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 218 |12.0110 | 1 | 0.001465 | 11.285769 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 219 |12.0661 | 1 | 0.001472 | 11.138884 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 220 |12.1212 | 1 | 0.001462 | 11.085258 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 221 |12.1763 | 1 | 0.001506 | 10.962956 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 222 |12.2314 | 1 | 0.001481 | 11.063845 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 223 |12.2865 | 1 | 0.001490 | 10.940562 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 224 |12.3416 | 1 | 0.001487 | 11.074080 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 225 |12.3967 | 1 | 0.001500 | 10.966088 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 226 |12.4518 | 1 | 0.001503 | 10.940730 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 227 |12.5069 | 1 | 0.001500 | 10.983767 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 228 |12.5620 | 1 | 0.001495 | 11.087621 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 229 |12.6171 | 1 | 0.001491 | 11.030768 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 230 |12.6722 | 1 | 0.001501 | 10.986019 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 231 |12.7273 | 1 | 0.001471 | 11.210606 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 232 |12.7824 | 1 | 0.001496 | 10.989540 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 233 |12.8375 | 1 | 0.001479 | 10.991125 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 234 |12.8926 | 1 | 0.001484 | 10.997315 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 235 |12.9477 | 1 | 0.001495 | 10.981242 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 236 |13.0028 | 1 | 0.001494 | 11.034151 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 237 |13.0579 | 1 | 0.001521 | 11.393696 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 238 |13.1129 | 1 | 0.001483 | 11.187673 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 239 |13.1680 | 1 | 0.001476 | 11.165030 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 240 |13.2231 | 1 | 0.001461 | 11.121420 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 241 |13.2782 | 1 | 0.001497 | 11.077922 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 242 |13.3333 | 1 | 0.001472 | 11.274707 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 243 |13.3884 | 1 | 0.001477 | 11.087600 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 244 |13.4435 | 1 | 0.001469 | 11.061153 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 245 |13.4986 | 1 | 0.001449 | 11.292755 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 246 |13.5537 | 1 | 0.001495 | 11.001245 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 247 |13.6088 | 1 | 0.001493 | 11.024726 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 248 |13.6639 | 1 | 0.001480 | 10.968597 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 249 |13.7190 | 1 | 0.001478 | 11.008988 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 250 |13.7741 | 1 | 0.001464 | 11.120604 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 251 |13.8292 | 1 | 0.001494 | 10.976703 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 252 |13.8843 | 1 | 0.001464 | 11.173856 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 253 |13.9394 | 1 | 0.001478 | 11.182188 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 254 |13.9945 | 1 | 0.001474 | 11.138903 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 255 |14.0496 | 1 | 0.001498 | 10.998538 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 256 |14.1047 | 1 | 0.001490 | 10.959735 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 257 |14.1598 | 1 | 0.001497 | 11.015843 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 258 |14.2149 | 1 | 0.001442 | 11.296236 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 259 |14.2700 | 1 | 0.001470 | 11.035043 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 260 |14.3251 | 1 | 0.001499 | 11.025067 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 261 |14.3802 | 1 | 0.001483 | 11.032883 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 262 |14.4353 | 1 | 0.001450 | 11.225693 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 263 |14.4904 | 1 | 0.001490 | 11.049877 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 264 |14.5455 | 1 | 0.001500 | 10.961913 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 265 |14.6006 | 1 | 0.001468 | 11.227395 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 266 |14.6556 | 1 | 0.001500 | 10.950821 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 267 |14.7107 | 1 | 0.001496 | 11.034819 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 268 |14.7658 | 1 | 0.001478 | 11.039118 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 269 |14.8209 | 1 | 0.001480 | 11.054862 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 270 |14.8760 | 1 | 0.001499 | 10.966170 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 271 |14.9311 | 1 | 0.001492 | 11.013549 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 272 |14.9862 | 1 | 0.001487 | 11.063011 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 273 |15.0413 | 1 | 0.001494 | 11.025787 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 274 |15.0964 | 1 | 0.001492 | 11.056323 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 275 |15.1515 | 1 | 0.001502 | 11.017958 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 276 |15.2066 | 1 | 0.001498 | 10.993303 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 277 |15.2617 | 1 | 0.001492 | 11.045624 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 278 |15.3168 | 1 | 0.001488 | 11.001706 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 279 |15.3719 | 1 | 0.001501 | 11.019076 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 280 |15.4270 | 1 | 0.001482 | 10.980229 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 281 |15.4821 | 1 | 0.001500 | 10.990641 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 282 |15.5372 | 1 | 0.001482 | 11.039660 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 283 |15.5923 | 1 | 0.001506 | 10.960431 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 284 |15.6474 | 1 | 0.001483 | 11.035762 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 285 |15.7025 | 1 | 0.001483 | 10.972536 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 286 |15.7576 | 1 | 0.001497 | 11.078446 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 287 |15.8127 | 1 | 0.001494 | 11.003910 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 288 |15.8678 | 1 | 0.001524 | 10.954572 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 289 |15.9229 | 1 | 0.001468 | 11.170064 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 290 |15.9780 | 1 | 0.001466 | 11.078832 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 291 |16.0331 | 1 | 0.001500 | 10.965774 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 292 |16.0882 | 1 | 0.001492 | 10.988034 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 293 |16.1433 | 1 | 0.001498 | 11.034559 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 294 |16.1983 | 1 | 0.001485 | 10.967131 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 295 |16.2534 | 1 | 0.001480 | 11.102506 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 296 |16.3085 | 1 | 0.001504 | 10.998471 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 297 |16.3636 | 1 | 0.001499 | 10.959420 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 298 |16.4187 | 1 | 0.001483 | 11.099791 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 299 |16.4738 | 1 | 0.001493 | 10.974991 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 300 |16.5289 | 1 | 0.001487 | 10.989717 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 301 |16.5840 | 1 | 0.001484 | 11.069229 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 302 |16.6391 | 1 | 0.001503 | 10.985806 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 303 |16.6942 | 1 | 0.001496 | 11.041107 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 304 |16.7493 | 1 | 0.001487 | 10.991144 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 305 |16.8044 | 1 | 0.001492 | 11.005035 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 306 |16.8595 | 1 | 0.001488 | 11.087163 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 307 |16.9146 | 1 | 0.001491 | 11.002862 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 308 |16.9697 | 1 | 0.001519 | 11.018252 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 309 |17.0248 | 1 | 0.001489 | 11.030986 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 310 |17.0799 | 1 | 0.001509 | 11.001859 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 311 |17.1350 | 1 | 0.001492 | 11.019300 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 312 |17.1901 | 1 | 0.001488 | 11.036436 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 313 |17.2452 | 1 | 0.001493 | 11.046922 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 314 |17.3003 | 1 | 0.001485 | 10.976898 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 315 |17.3554 | 1 | 0.001497 | 10.941875 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 316 |17.4105 | 1 | 0.001497 | 11.056621 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 317 |17.4656 | 1 | 0.001471 | 11.117604 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 318 |17.5207 | 1 | 0.001469 | 11.168160 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 319 |17.5758 | 1 | 0.001476 | 11.020628 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 320 |17.6309 | 1 | 0.001490 | 11.020211 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 321 |17.6860 | 1 | 0.001488 | 11.010496 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 322 |17.7410 | 1 | 0.001475 | 11.125369 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 323 |17.7961 | 1 | 0.001494 | 10.955690 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 324 |17.8512 | 1 | 0.001493 | 11.078510 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 325 |17.9063 | 1 | 0.001362 | 12.022863 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 326 |17.9614 | 1 | 0.001489 | 11.021870 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 327 |18.0165 | 1 | 0.001463 | 11.139775 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 328 |18.0716 | 1 | 0.001475 | 11.015395 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 329 |18.1267 | 1 | 0.001475 | 10.995628 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 330 |18.1818 | 1 | 0.001490 | 11.037015 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 331 |18.2369 | 1 | 0.001489 | 10.994272 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 332 |18.2920 | 1 | 0.001485 | 11.023925 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 333 |18.3471 | 1 | 0.001465 | 11.131615 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 334 |18.4022 | 1 | 0.001481 | 10.996215 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 335 |18.4573 | 1 | 0.001493 | 11.042847 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 336 |18.5124 | 1 | 0.001493 | 11.153712 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 337 |18.5675 | 1 | 0.001497 | 10.981005 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 338 |18.6226 | 1 | 0.001490 | 10.993124 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 339 |18.6777 | 1 | 0.001498 | 10.970379 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 340 |18.7328 | 1 | 0.001492 | 10.992345 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 341 |18.7879 | 1 | 0.001492 | 10.998224 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 342 |18.8430 | 1 | 0.001523 | 10.982035 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 343 |18.8981 | 1 | 0.001485 | 11.054384 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 344 |18.9532 | 1 | 0.001486 | 11.027520 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 345 |19.0083 | 1 | 0.001482 | 11.016985 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 346 |19.0634 | 1 | 0.001484 | 11.169659 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 347 |19.1185 | 1 | 0.001476 | 11.164135 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 348 |19.1736 | 1 | 0.001499 | 10.963815 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 349 |19.2287 | 1 | 0.001481 | 11.041115 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 350 |19.2837 | 1 | 0.001478 | 11.025983 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 351 |19.3388 | 1 | 0.001504 | 10.984140 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 352 |19.3939 | 1 | 0.001478 | 11.033161 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 353 |19.4490 | 1 | 0.001490 | 11.040692 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 354 |19.5041 | 1 | 0.001479 | 11.018249 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 355 |19.5592 | 1 | 0.001471 | 10.995813 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 356 |19.6143 | 1 | 0.001478 | 11.009744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 357 |19.6694 | 1 | 0.001489 | 11.012060 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 358 |19.7245 | 1 | 0.001487 | 11.043458 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 359 |19.7796 | 1 | 0.001492 | 10.996924 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 360 |19.8347 | 1 | 0.001486 | 10.997914 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 361 |19.8898 | 1 | 0.001462 | 11.193126 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 362 |19.9449 | 1 | 0.001476 | 11.131790 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 363 |20.0000 | 1 | 0.001456 | 11.255347 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 364 |20.0551 | 1 | 0.001443 | 11.262457 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 365 |20.1102 | 1 | 0.001442 | 11.282331 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 366 |20.1653 | 1 | 0.001460 | 11.133270 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 367 |20.2204 | 1 | 0.001461 | 11.137590 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 368 |20.2755 | 1 | 0.001458 | 11.279287 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 369 |20.3306 | 1 | 0.001473 | 11.155934 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 370 |20.3857 | 1 | 0.001480 | 11.140440 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 371 |20.4408 | 1 | 0.001464 | 11.196868 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 372 |20.4959 | 1 | 0.001473 | 11.196430 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 373 |20.5510 | 1 | 0.001467 | 11.166742 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 374 |20.6061 | 1 | 0.001488 | 11.095840 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 375 |20.6612 | 1 | 0.001456 | 11.119288 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 376 |20.7163 | 1 | 0.001514 | 10.997535 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 377 |20.7713 | 1 | 0.001500 | 10.973636 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 378 |20.8264 | 1 | 0.001485 | 11.041631 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 379 |20.8815 | 1 | 0.001474 | 11.054704 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 380 |20.9366 | 1 | 0.001505 | 10.956344 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 381 |20.9917 | 1 | 0.001485 | 11.037928 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 382 |21.0468 | 1 | 0.001494 | 11.004072 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 383 |21.1019 | 1 | 0.001460 | 11.191711 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 384 |21.1570 | 1 | 0.001464 | 11.213192 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 385 |21.2121 | 1 | 0.001297 | 12.715977 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 386 |21.2672 | 1 | 0.001473 | 11.214244 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 387 |21.3223 | 1 | 0.001488 | 11.175076 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 388 |21.3774 | 1 | 0.001477 | 11.140157 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 389 |21.4325 | 1 | 0.001476 | 11.217773 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 390 |21.4876 | 1 | 0.001487 | 11.070076 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 391 |21.5427 | 1 | 0.001476 | 11.079977 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 392 |21.5978 | 1 | 0.001497 | 10.963420 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 393 |21.6529 | 1 | 0.001492 | 10.965270 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 394 |21.7080 | 1 | 0.001499 | 11.031488 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 395 |21.7631 | 1 | 0.001379 | 11.928026 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 396 |21.8182 | 1 | 0.001474 | 11.124487 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 397 |21.8733 | 1 | 0.001482 | 11.037149 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 398 |21.9284 | 1 | 0.001491 | 11.062619 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 399 |21.9835 | 1 | 0.001483 | 11.227740 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 400 |22.0386 | 1 | 0.001460 | 11.253708 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 401 |22.0937 | 1 | 0.001474 | 11.210907 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 402 |22.1488 | 1 | 0.001483 | 11.119041 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 403 |22.2039 | 1 | 0.001490 | 11.014906 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 404 |22.2590 | 1 | 0.001499 | 10.956471 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 405 |22.3140 | 1 | 0.001468 | 11.109550 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 406 |22.3691 | 1 | 0.001490 | 10.982853 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 407 |22.4242 | 1 | 0.001478 | 11.193154 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 408 |22.4793 | 1 | 0.001498 | 11.031459 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 409 |22.5344 | 1 | 0.001508 | 10.978516 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 410 |22.5895 | 1 | 0.001481 | 11.028180 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 411 |22.6446 | 1 | 0.001492 | 11.037275 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 412 |22.6997 | 1 | 0.001483 | 10.967960 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 413 |22.7548 | 1 | 0.001493 | 10.990911 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 414 |22.8099 | 1 | 0.001484 | 11.067482 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 415 |22.8650 | 1 | 0.001486 | 10.987234 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 416 |22.9201 | 1 | 0.001453 | 11.105183 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 417 |22.9752 | 1 | 0.001484 | 11.019325 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 418 |23.0303 | 1 | 0.001489 | 11.033711 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 419 |23.0854 | 1 | 0.001486 | 10.961752 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 420 |23.1405 | 1 | 0.001488 | 11.020402 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 421 |23.1956 | 1 | 0.001485 | 10.985927 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 422 |23.2507 | 1 | 0.001484 | 11.122986 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 423 |23.3058 | 1 | 0.001488 | 11.010117 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 424 |23.3609 | 1 | 0.001494 | 11.027276 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 425 |23.4160 | 1 | 0.001498 | 11.002853 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 426 |23.4711 | 1 | 0.001504 | 10.948009 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 427 |23.5262 | 1 | 0.001537 | 10.965587 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 428 |23.5813 | 1 | 0.001480 | 11.023513 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 429 |23.6364 | 1 | 0.001495 | 11.016430 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 430 |23.6915 | 1 | 0.001498 | 10.990407 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 431 |23.7466 | 1 | 0.001482 | 11.029547 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 432 |23.8017 | 1 | 0.001489 | 11.028503 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 433 |23.8567 | 1 | 0.001494 | 10.994521 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 434 |23.9118 | 1 | 0.001497 | 11.033860 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 435 |23.9669 | 1 | 0.001472 | 11.085127 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 436 |24.0220 | 1 | 0.001519 | 10.940756 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 437 |24.0771 | 1 | 0.001477 | 11.058848 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 438 |24.1322 | 1 | 0.001479 | 11.067911 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 439 |24.1873 | 1 | 0.001488 | 11.029004 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 440 |24.2424 | 1 | 0.001497 | 10.977903 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 441 |24.2975 | 1 | 0.001486 | 11.038936 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 442 |24.3526 | 1 | 0.001492 | 11.042946 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 443 |24.4077 | 1 | 0.001492 | 10.970813 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 444 |24.4628 | 1 | 0.001486 | 11.023437 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 445 |24.5179 | 1 | 0.001504 | 10.981979 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 446 |24.5730 | 1 | 0.001487 | 10.943550 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 447 |24.6281 | 1 | 0.001504 | 10.990585 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 448 |24.6832 | 1 | 0.001488 | 11.020756 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 449 |24.7383 | 1 | 0.001502 | 11.020719 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", + "| 450 |24.7934 | 1 | 0.001490 | 10.944653 | 0.000000 | 0.000000e+00 | 0.000000e+00 |\u001b[0m\n", "\u001b[34m...Finished\u001b[0m\n", - "\u001b[36mFINISHED - Elapsed time = 14581.6230696 seconds\u001b[0m\n", - "\u001b[36mFINISHED - CPU process time = 108623.9978826 seconds\u001b[0m\n" + "\u001b[36mFINISHED - Elapsed time = 5192.1956986 seconds\u001b[0m\n", + "\u001b[36mFINISHED - CPU process time = 38238.0321676 seconds\u001b[0m\n" ] } ], @@ -1073,8 +993,8 @@ "metadata": {}, "outputs": [], "source": [ - "rho = sharpy_output.settings['StaticCoupled']['aero_solver_settings']['rho'].value\n", - "uinf = sharpy_output.settings['StaticCoupled']['aero_solver_settings']['velocity_field_input']['u_inf'].value\n", + "rho = sharpy_output.settings['StaticCoupled']['aero_solver_settings']['rho']\n", + "uinf = sharpy_output.settings['StaticCoupled']['aero_solver_settings']['velocity_field_input']['u_inf']\n", "R = np.max(r[0])\n", "Cp = 0\n", "Ct = 0\n", @@ -1155,7 +1075,7 @@ " \n", " \n", " \n", - " \n", " \n", @@ -1163,10 +1083,10 @@ " \n", " \n", + "\" id=\"m6e3d9edeb4\" style=\"stroke:#000000;stroke-width:0.8;\"/>\n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1209,13 +1129,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1255,13 +1175,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1294,13 +1214,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1346,13 +1266,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1407,13 +1327,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1534,7 +1454,7 @@ " \n", " \n", " \n", - " \n", " \n", @@ -1542,10 +1462,10 @@ " \n", " \n", + "\" id=\"m60ac5f1668\" style=\"stroke:#000000;stroke-width:0.8;\"/>\n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1559,13 +1479,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1579,13 +1499,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1599,13 +1519,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1653,13 +1573,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -1777,59 +1697,39 @@ " \n", " \n", " \n", - " \n", " \n", " \n", - " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2155,13 +2055,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2175,13 +2075,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2195,13 +2095,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2215,13 +2115,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2235,13 +2135,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2269,13 +2169,13 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2290,39 +2190,39 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", - " \n", - " \n", + " \n", + " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", - " \n", - " \n", + " \n", + " \n", " \n", " \n", " \n", @@ -2332,18 +2232,18 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", - " \n", - " \n", + " \n", + " \n", " \n", " \n", " \n", @@ -2353,47 +2253,94 @@ " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", - " \n", - " \n", + " \n", + " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", " \n", " \n", - " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", - " \n", - " \n", + " \n", + " \n", + " \n", + " \n", + " \n", " \n", " \n", - " \n", - " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", @@ -2412,68 +2359,48 @@ " \n", " \n", " \n", - " \n", - " \n", + " \n", " \n", - " \n", - " \n", + " \n", " \n", @@ -2551,10 +2478,10 @@ " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", - " \n", + " \n", " \n", " \n", " \n", From bf5d29f706fc3c68956f9320b8a15409f4464719 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 28 May 2021 11:46:25 +0100 Subject: [PATCH 100/253] fix vtu extension in files with . --- sharpy/postproc/aerogridplot.py | 10 ++++++---- sharpy/postproc/beamplot.py | 3 ++- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/sharpy/postproc/aerogridplot.py b/sharpy/postproc/aerogridplot.py index f1fa9a5c5..11b297ab3 100644 --- a/sharpy/postproc/aerogridplot.py +++ b/sharpy/postproc/aerogridplot.py @@ -151,8 +151,9 @@ def plot_body(self): for i_surf in range(aero_tstep.n_surf): filename = (self.body_filename + '_' + - '%02u_' % i_surf + - '%06u' % self.ts) + ('%02u_' % i_surf) + + ('%06u' % self.ts) + + '.vtu') dims = aero_tstep.dimensions[i_surf, :] point_data_dim = (dims[0]+1)*(dims[1]+1) # + (dims_star[0]+1)*(dims_star[1]+1) @@ -271,8 +272,9 @@ def plot_wake(self): for i_surf in range(self.data.aero.timestep_info[self.ts].n_surf): filename = (self.wake_filename + '_' + - '%02u_' % i_surf + - '%06u' % self.ts) + ('%02u_' % i_surf) + + ('%06u' % self.ts) + + '.vtu') dims_star = self.data.aero.timestep_info[self.ts].dimensions_star[i_surf, :].copy() dims_star[0] -= self.settings['minus_m_star'] diff --git a/sharpy/postproc/beamplot.py b/sharpy/postproc/beamplot.py index ff832aa6c..28f3c5b65 100644 --- a/sharpy/postproc/beamplot.py +++ b/sharpy/postproc/beamplot.py @@ -112,7 +112,8 @@ def plot(self, online): def write_beam(self, it): it_filename = (self.filename + - '%06u' % it) + ('%06u' % it) + + '.vtu') num_nodes = self.data.structure.num_node num_elem = self.data.structure.num_elem From 632fef904baee5715a464527ca991a8c39523010 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 28 May 2021 12:01:39 +0100 Subject: [PATCH 101/253] remove folder setting --- tests/linear/control_surfaces/test_control_surfaces.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/linear/control_surfaces/test_control_surfaces.py b/tests/linear/control_surfaces/test_control_surfaces.py index 15db3f36b..c384025b1 100644 --- a/tests/linear/control_surfaces/test_control_surfaces.py +++ b/tests/linear/control_surfaces/test_control_surfaces.py @@ -212,7 +212,7 @@ def setup(self): 'minus_m_star': 0}, } } - ws.config['PickleData'] = {'folder': self.route_test_dir + '/output/'} + ws.config['PickleData'] = {} ws.config.write() From 784c49ad04fb4a6297e77749d2d9fd505401dd21 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 28 May 2021 12:16:02 +0100 Subject: [PATCH 102/253] remove write screen --- tests/linear/derivatives/test_stabilityderivatives.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/linear/derivatives/test_stabilityderivatives.py b/tests/linear/derivatives/test_stabilityderivatives.py index 1bde06bac..5ff7bd918 100644 --- a/tests/linear/derivatives/test_stabilityderivatives.py +++ b/tests/linear/derivatives/test_stabilityderivatives.py @@ -77,7 +77,7 @@ def run_sharpy(self, alpha_deg, flow, target_system, not_run=False): ws.config['SHARPy'] = { 'flow': flow, 'case': ws.case_name, 'route': ws.route, - 'write_screen': 'on', 'write_log': 'on', + 'write_screen': 'off', 'write_log': 'on', 'log_folder': self.route_test_dir + '/output/', 'log_file': ws.case_name + '.log'} From 9f81d691133f2c50abeaf382f67507861dfe83fc Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 28 May 2021 12:23:30 +0100 Subject: [PATCH 103/253] update savedata from dev_remove_istates --- sharpy/postproc/savedata.py | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/sharpy/postproc/savedata.py b/sharpy/postproc/savedata.py index 26913cf0a..a236afba9 100644 --- a/sharpy/postproc/savedata.py +++ b/sharpy/postproc/savedata.py @@ -272,11 +272,9 @@ def run(self, online=False): 'D': D} for k, v in linearisation_vectors.items(): savedict[k] = v - try: - dt = self.data.linear.ss.dt + dt = self.data.linear.ss.dt + if dt is not None: savedict['dt'] = dt - except AttributeError: - pass savemat(matfilename, savedict) if self.settings['save_linear_uvlm']: @@ -289,11 +287,9 @@ def run(self, online=False): 'D': D} for k, v in linearisation_vectors.items(): savedict[k] = v - try: - dt = self.data.linear.ss.dt + dt = self.data.linear.linear_system.uvlm.ss.dt + if dt is not None: savedict['dt'] = dt - except AttributeError: - pass savemat(matfilename, savedict) return self.data From 6df789a3491663cca235fee162df764ed292fd1b Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 28 May 2021 12:32:14 +0100 Subject: [PATCH 104/253] nodal_b_for_2_a_for --- sharpy/postproc/aeroforcescalculator.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sharpy/postproc/aeroforcescalculator.py b/sharpy/postproc/aeroforcescalculator.py index c54581f36..481213877 100644 --- a/sharpy/postproc/aeroforcescalculator.py +++ b/sharpy/postproc/aeroforcescalculator.py @@ -129,11 +129,11 @@ def calculate_forces(self): except AttributeError: unsteady_forces_b = self.map_forces_beam_dof(self.ts, unsteady_force) - steady_forces_a = self.data.structure.nodal_b_for_2_a_for(steady_forces_b, - self.data.structure.timestep_info[self.ts]) + steady_forces_a = self.data.structure.timestep_info[self.ts].nodal_b_for_2_a_for(steady_forces_b, + self.data.structure) - unsteady_forces_a = self.data.structure.nodal_b_for_2_a_for(unsteady_forces_b, - self.data.structure.timestep_info[self.ts]) + unsteady_forces_a = self.data.structure.timestep_info[self.ts].nodal_b_for_2_a_for(unsteady_forces_b, + self.data.structure) # Express total forces in A frame self.data.aero.timestep_info[self.ts].total_steady_body_forces = np.sum(steady_forces_a, axis=0) From e7675bff9545608782e337519b55e152b769b14c Mon Sep 17 00:00:00 2001 From: Unknown Date: Wed, 2 Jun 2021 18:10:53 +0100 Subject: [PATCH 105/253] fix aeroforces ts --- sharpy/postproc/aeroforcescalculator.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sharpy/postproc/aeroforcescalculator.py b/sharpy/postproc/aeroforcescalculator.py index 6400ad862..a12293226 100644 --- a/sharpy/postproc/aeroforcescalculator.py +++ b/sharpy/postproc/aeroforcescalculator.py @@ -137,11 +137,11 @@ def calculate_forces(self, ts): except KeyError: unsteady_forces_b = self.map_forces_beam_dof(ts, unsteady_force) - steady_forces_a = self.data.structure.timestep_info[self.ts].nodal_b_for_2_a_for(steady_forces_b, - self.data.structure) + steady_forces_a = self.data.structure.timestep_info[ts].nodal_b_for_2_a_for(steady_forces_b, + self.data.structure) - unsteady_forces_a = self.data.structure.timestep_info[self.ts].nodal_b_for_2_a_for(unsteady_forces_b, - self.data.structure) + unsteady_forces_a = self.data.structure.timestep_info[ts].nodal_b_for_2_a_for(unsteady_forces_b, + self.data.structure) # Express total forces in A frame self.data.aero.timestep_info[ts].total_steady_body_forces = np.sum(steady_forces_a, axis=0) From 42cc2a09471400e0261486ec2d4e894f96b0ff06 Mon Sep 17 00:00:00 2001 From: Unknown Date: Wed, 2 Jun 2021 18:24:32 +0100 Subject: [PATCH 106/253] remove unsteady setting aeroforcescalculator --- tests/linear/derivatives/test_stabilityderivatives.py | 5 ++--- tests/linear/gusts/test_external_gust.py | 1 - tests/linear/horten/test_horten.py | 1 - 3 files changed, 2 insertions(+), 5 deletions(-) diff --git a/tests/linear/derivatives/test_stabilityderivatives.py b/tests/linear/derivatives/test_stabilityderivatives.py index 5ff7bd918..29f134ad1 100644 --- a/tests/linear/derivatives/test_stabilityderivatives.py +++ b/tests/linear/derivatives/test_stabilityderivatives.py @@ -144,8 +144,7 @@ def run_sharpy(self, alpha_deg, flow, target_system, not_run=False): ws.config['AeroForcesCalculator'] = {'write_text_file': 'on', # 'text_file_name': ws.case_name + '_aeroforces.csv', - 'screen_output': 'on', - 'unsteady': 'off'} + 'screen_output': 'on'} ws.config['BeamPlot'] = {'include_rbm': 'off', 'include_applied_forces': 'on'} @@ -370,7 +369,7 @@ def run_case(self, target_system): ref_case_name)) linss_data = scio.loadmat(self.route_test_dir + '/output/{:s}/savedata/{:s}.linss.mat'.format(ref_case_name, ref_case_name)) - + # Steady State transfer function if target_system == 'aerodynamic': A, B, C, D = linuvlm_data['A'], linuvlm_data['B'], linuvlm_data['C'], linuvlm_data['D'] diff --git a/tests/linear/gusts/test_external_gust.py b/tests/linear/gusts/test_external_gust.py index ec1577990..9ce4992ac 100644 --- a/tests/linear/gusts/test_external_gust.py +++ b/tests/linear/gusts/test_external_gust.py @@ -106,7 +106,6 @@ def generate_sharpy(alpha=0., case_name='hale_static', case_route='./', **kwargs settings['AeroForcesCalculator'] = {'write_text_file': 'on', 'text_file_name': 'aeroforces.txt', 'screen_output': 'on', - 'unsteady': 'off', 'coefficients': True, 'q_ref': 0.5 * rho * u_inf ** 2, 'S_ref': 12.809, diff --git a/tests/linear/horten/test_horten.py b/tests/linear/horten/test_horten.py index 62de0d655..dc4b43314 100644 --- a/tests/linear/horten/test_horten.py +++ b/tests/linear/horten/test_horten.py @@ -158,7 +158,6 @@ def run_rom_convergence(case_name, case_route='./cases/', output_folder='./outpu settings['AeroForcesCalculator'] = {'write_text_file': 'off', 'text_file_name': ws.case_name + '_aeroforces.csv', 'screen_output': 'on', - 'unsteady': 'off', 'coefficients': True, 'q_ref': 0.5 * ws.rho * ws.u_inf ** 2, 'S_ref': 12.809, From a219efb8580596bc77b193d50ad274a8a9a4c46a Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 4 Jun 2021 10:37:37 +0100 Subject: [PATCH 107/253] restoring forces to steady --- sharpy/generators/floatingforces.py | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 8739fa2ff..f78727622 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -635,7 +635,6 @@ def initialise(self, in_dict=None, data=None): axis=0) self.hd_damping_const = interp_d(self.settings['matrices_freq']) - elif self.settings['method_matrices_freq'] == 'rational_function': self.hd_added_mass_const = self.floating_data['hydrodynamics']['added_mass_matrix'][-1, :, :] self.hd_damping_const = self.floating_data['hydrodynamics']['damping_matrix'][-1, :, :] @@ -909,10 +908,10 @@ def generate(self, params): cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) cbg = np.dot(cab.T, cga.T) - struct_tstep.runtime_steady_forces[self.buoyancy_node, 0:3] += np.dot(cbg, self.buoy_F0[0:3]) - struct_tstep.runtime_steady_forces[self.buoyancy_node, 3:6] += np.dot(cbg, self.buoy_F0[3:6]) - struct_tstep.runtime_unsteady_forces[self.buoyancy_node, 0:3] += np.dot(cbg, hs_f_g[0:3] + hd_f_qdot_g[0:3] + hd_f_qdotdot_g[0:3]) - struct_tstep.runtime_unsteady_forces[self.buoyancy_node, 3:6] += np.dot(cbg, hs_f_g[3:6] + hd_f_qdot_g[3:6] + hd_f_qdotdot_g[3:6]) + struct_tstep.runtime_steady_forces[self.buoyancy_node, 0:3] += np.dot(cbg, self.buoy_F0[0:3] + hs_f_g[0:3]) + struct_tstep.runtime_steady_forces[self.buoyancy_node, 3:6] += np.dot(cbg, self.buoy_F0[3:6] + hs_f_g[3:6]) + struct_tstep.runtime_unsteady_forces[self.buoyancy_node, 0:3] += np.dot(cbg, hd_f_qdot_g[0:3] + hd_f_qdotdot_g[0:3]) + struct_tstep.runtime_unsteady_forces[self.buoyancy_node, 3:6] += np.dot(cbg, hd_f_qdot_g[3:6] + hd_f_qdotdot_g[3:6]) # Nonlinear drag coefficeint if self.settings['concentrate_spar']: From 96812b451b6bf92c0c4272c620a844a5998b0975 Mon Sep 17 00:00:00 2001 From: Unknown Date: Tue, 8 Jun 2021 17:01:29 +0100 Subject: [PATCH 108/253] update blade pitch control --- sharpy/controllers/bladepitchpid.py | 160 +++++++++++------- sharpy/solvers/dynamiccoupled.py | 12 +- sharpy/structure/utils/lagrangeconstraints.py | 118 ++++++++++++- 3 files changed, 222 insertions(+), 68 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index f6a7a6709..bf22dc923 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -40,8 +40,9 @@ class BladePitchPid(controller_interface.BaseController): settings_description['lp_cut_freq'] = 'Cutting frequency of the low pass filter of the process value. Choose 0 for no filter' settings_types['anti_windup_lim'] = 'list(float)' - settings_default['anti_windup_lim'] = None - settings_description['anti_windup_lim'] = 'Limits of actuation to apply anti windup' + settings_default['anti_windup_lim'] = [-1., -1.] + settings_description['anti_windup_lim'] = ('Limits of actuation to apply anti windup.' + + 'Use the same number to deactivate.') # Set point parameters settings_types['sp_type'] = 'str' @@ -49,21 +50,25 @@ class BladePitchPid(controller_interface.BaseController): settings_description['sp_type'] = ( 'Quantity used to define the' + ' set point') - settings_options['sp_type'] = ['rbm', 'pitch'] + settings_options['sp_type'] = ['rbm', 'pitch', 'torque'] settings_types['sp_source'] = 'str' settings_default['sp_source'] = None settings_description['sp_source'] = ( 'Source used to define the' + ' set point') - settings_options['sp_source'] = ['file'] + settings_options['sp_source'] = ['file', 'const'] settings_types['sp_time_history_file'] = 'str' - settings_default['sp_time_history_file'] = None + settings_default['sp_time_history_file'] = '' settings_description['sp_time_history_file'] = ('Route and file name of the time ' + 'history of the desired set point.' + 'Used for ``sp_source = file``') + settings_types['sp_const'] = 'float' + settings_default['sp_const'] = 0. + settings_description['sp_const'] = 'Constant set point. Only used for ``sp_source`` = `const ``' + # Other parameters settings_types['dt'] = 'float' settings_default['dt'] = None @@ -81,10 +86,14 @@ class BladePitchPid(controller_interface.BaseController): settings_default['max_pitch_rate'] = 0.1396 settings_description['max_pitch_rate'] = 'Maximum pitch rate [rad/s]' + settings_types['min_pitch'] = 'float' + settings_default['min_pitch'] = 0. + settings_description['min_pitch'] = 'Minimum pitch [rad]' + # Generator and drive train model - settings_types['target_power'] = 'float' - settings_default['target_power'] = 5e6 - settings_description['target_power'] = 'Target power in operation' + settings_types['variable_speed'] = 'bool' + settings_default['variable_speed'] = True + settings_description['variable_speed'] = 'Allow the change in the rotor velocity' settings_types['GBR'] = 'float' settings_default['GBR'] = 97. @@ -94,6 +103,10 @@ class BladePitchPid(controller_interface.BaseController): settings_default['inertia_dt'] = 43776046.25 settings_description['inertia_dt'] = 'Drive train inertia' + settings_types['target_gen_torque'] = 'float' + settings_default['target_gen_torque'] = 3945990.325 + settings_description['target_gen_torque'] = 'Generator torque' + settings_types['newmark_damp'] = 'float' settings_default['newmark_damp'] = 1e-4 settings_description['newmark_damp'] = 'Damping of the time integration newmark-beta scheme' @@ -149,7 +162,7 @@ def initialise(self, in_dict, controller_id=None): no_ctype=True) self.settings = self.in_dict - self.newmark_damp = 0.5 + self.settings['newmark_damp'] + self.newmark_beta = 0.5 + self.settings['newmark_damp'] # self.controller_id = controller_id # self.nblades = len(self.settings['blade_num_body']) @@ -169,7 +182,8 @@ def initialise(self, in_dict, controller_id=None): self.settings['D'], self.settings['dt']) - self.controller_implementation.set_anti_windup_lim(self.settings['anti_windup_lim']) + if not self.settings['anti_windup_lim'][0] == self.settings['anti_windup_lim'][1]: + self.controller_implementation.set_anti_windup_lim(self.settings['anti_windup_lim']) if self.settings['lp_cut_freq'] == 0.: self.filter_pv = False @@ -195,10 +209,22 @@ def control(self, data, controlled_state): """ struct_tstep = controlled_state['structural'] aero_tstep = controlled_state['aero'] + if not "info" in controlled_state: + controlled_state['info'] = dict() time = self.settings['dt']*data.ts + # Compute the rotor velocity + torque = self.compute_torque(data.structure, struct_tstep) + if self.settings['variable_speed']: + rotor_vel, rotor_acc = self.drive_train_model(torque, + struct_tstep.mb_FoR_vel[self.settings['blade_num_body'][0], 3:6], + struct_tstep.mb_FoR_acc[self.settings['blade_num_body'][0], 3:6]) + controlled_state['info']['rotor_vel'] = rotor_vel + + # System set point prescribed_sp = self.compute_prescribed_sp(time) - sys_pv = self.compute_system_pv(struct_tstep, data.structure) + # System process value + sys_pv = self.compute_system_pv(struct_tstep, data.structure, torque=torque) # Apply filter if self.filter_pv and (len(self.system_pv) > 1): @@ -224,29 +250,45 @@ def control(self, data, controlled_state): 'D': self.settings['D']}, i_current=data.ts) - if control_command < -self.settings['max_pitch_rate']: - control_command = -self.settings['max_pitch_rate'] - elif control_command > self.settings['max_pitch_rate']: - control_command = self.settings['max_pitch_rate'] + # Limit pitch and pitch rate + current_pitch = algebra.quat2euler(struct_tstep.mb_quat[self.settings['blade_num_body'][0]])[0] + target_pitch = current_pitch + control_command + target_pitch = max(target_pitch, self.settings['min_pitch']) + pitch_rate = (target_pitch - current_pitch)/self.settings['dt'] + if pitch_rate < -self.settings['max_pitch_rate']: + pitch_rate = -self.settings['max_pitch_rate'] + elif pitch_rate > self.settings['max_pitch_rate']: + pitch_rate = self.settings['max_pitch_rate'] + delta_pitch = pitch_rate*self.settings['dt'] + controlled_state['info']['pitch_vel'] = pitch_rate # Apply control order # rot_mat = algebra.rotation3d_x(control_command) - print("control_command: ", control_command) + # print("control_command: ", control_command) # print("init euler: ", algebra.quat2euler(struct_tstep.quat)) change_quat = False if change_quat: - quat = algebra.rotate_quaternion(struct_tstep.quat, control_command*np.array([1., 0., 0.])) - # print("final euler: ", algebra.quat2euler(quat)) - # euler = np.array([prescribed_sp[0], 0., 0.]) - struct_tstep.quat = quat + for ibody in self.settings['blade_num_body']: + quat = algebra.rotate_quaternion(struct_tstep.mb_quat[ibody, :], + delta_pitch*np.array([1., 0., 0.])) + # print("final euler: ", algebra.quat2euler(quat)) + # euler = np.array([prescribed_sp[0], 0., 0.]) + struct_tstep.mb_quat[ibody, :] = quat.copy() + if ibody == 0: + struct_tstep.quat = quat.copy() change_vel = True if change_vel: # struct_tstep.for_vel[3] = control_command/self.settings['dt'] # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] # struct_tstep.for_vel[3] = np.sign(control_command)*self.settings['max_pitch_rate'] # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] - struct_tstep.for_vel[3] = control_command - struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] + for ibody in self.settings['blade_num_body']: + struct_tstep.mb_FoR_vel[ibody, 3] = pitch_rate + struct_tstep.mb_FoR_acc[ibody, 3] = (data.structure.timestep_info[data.ts - 1].mb_FoR_vel[ibody, 3] - + struct_tstep.mb_FoR_vel[ibody, 3])/self.settings['dt'] + if ibody == 0: + struct_tstep.for_vel[3] = struct_tstep.mb_FoR_vel[ibody, 3] + struct_tstep.for_acc[3] = struct_tstep.mb_FoR_acc[ibody, 3] data.structure.dynamic_input[data.ts - 1]['for_vel'] = struct_tstep.for_vel.copy() data.structure.dynamic_input[data.ts - 1]['for_acc'] = struct_tstep.for_acc.copy() @@ -270,6 +312,7 @@ def control(self, data, controlled_state): detail[1], detail[2], control_command)) + return controlled_state @@ -281,23 +324,19 @@ def compute_prescribed_sp(self, time): sp = np.interp(time, self.prescribed_sp_time_history[:, 0], self.prescribed_sp_time_history[:, 1]) - # vel = np.interp(time, - # self.prescribed_sp_time_history[:, 0], - # self.prescribed_sp_time_history[:, 2]) - # acc = np.interp(time, - # self.prescribed_sp_time_history[:, 0], - # self.prescribed_sp_time_history[:, 3]) - # self.prescribed_sp.append(np.array([pitch, vel, acc])) self.prescribed_sp.append(sp) + elif self.settings['sp_source'] == 'const': + self.prescribed_sp.append(self.settings['sp_const']) + return self.prescribed_sp[-1] - def compute_system_pv(self, struct_tstep, beam): + def compute_system_pv(self, struct_tstep, beam, **kwargs): """ Compute the process value relevant for the controller """ if self.settings['sp_type'] == 'pitch': - pitch = algebra.quat2euler(struct_tstep.quat)[0] + pitch = algebra.quat2euler(struct_tstep.mb_quat[self.settings['blade_num_body'][0]])[0] self.system_pv.append(pitch) elif self.settings['sp_type'] == 'rbm': steady, unsteady, grav = struct_tstep.extract_resultants(beam, force_type=['steady', 'unsteady', 'gravity'], @@ -305,35 +344,11 @@ def compute_system_pv(self, struct_tstep, beam): # rbm = np.linalg.norm(steady[3:6] + unsteady[3:6] + grav[3:6]) rbm = steady[4] + unsteady[4] + grav[4] self.system_pv.append(rbm) - print("rbm: ", rbm) + # print("rbm: ", rbm) + elif self.settings['sp_type'] == 'torque': + self.system_pv.append(kwargs['torque']) return self.system_pv[-1] - # def extract_time_history(self, controlled_state): - # output = 0.0 - # if self.settings['input_type'] == 'pitch': - # step = controlled_state['structural'] - # euler = step.euler_angles() - - # output = euler[1] - # elif self.settings['input_type'] == 'roll': - # step = controlled_state['structural'] - # euler = step.euler_angles() - - # output = euler[0] - # elif 'pos_z(' in self.settings['input_type']: - # node_str = self.settings['input_type'] - # node_str = node_str.replace('pos(', '') - # node_str = node_str.replace(')', '') - # node = int(node_str) - # step = controlled_state['structural'] - # pos = step.pos[node, :] - - # output = pos[2] - # else: - # raise NotImplementedError( - # "input_type {} is not yet implemented in extract_time_history()" - # .format(self.settings['input_type'])) - # return output def controller_wrapper(self, required_input, @@ -348,12 +363,13 @@ def __exit__(self, *args): # self.log.close() pass - def generator_model(aero_torque, ini_rot_vel, ini_rot_acc): + def drive_train_model(self, torque, ini_rot_vel, ini_rot_acc): - gen_torque = self.settings['target_power']*ini_rot_vel + # Assuming contant generator torque demand + gen_torque = self.settings['target_gen_torque'] - delta_rot_acc = (aero_torque - self.settings['GBR']*gen_torque)/self.settings['inertia_dt'] - rot_acc = ini_tor_acc + delta_rot_acc + delta_rot_acc = (torque - self.settings['GBR']*gen_torque)/self.settings['inertia_dt'] + rot_acc = ini_rot_acc + delta_rot_acc # Integrate according to newmark-beta scheme rot_vel = (ini_rot_vel + @@ -361,3 +377,23 @@ def generator_model(aero_torque, ini_rot_vel, ini_rot_acc): self.newmark_beta*self.settings['dt']*rot_acc) return rot_vel, rot_acc + + def compute_torque(self, beam, struct_tstep): + # Compute total forces + total_forces = np.zeros((6)) + for ibody in self.settings['blade_num_body']: + steady, unsteady, grav = struct_tstep.extract_resultants(beam, + force_type=['steady', 'unsteady', 'grav'], + ibody=ibody) + total_forces += steady + unsteady + grav + + # Compute equivalent forces at hub position + hub_elem = np.where(beam.body_number == self.settings['blade_num_body'][0])[0][0] + hub_node = beam.connectivities[hub_elem, 0] + hub_pos = struct_tstep.pos[hub_node, :] + + hub_forces = np.zeros((6)) + hub_forces[0:3] = total_forces[0:3].copy() + hub_forces[3:6] = total_forces[3:6] + np.cross(hub_pos, total_forces[0:3]) + + return hub_forces[5] diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 1b9acb482..1b168fcfd 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -393,13 +393,23 @@ def process_controller_output(self, controlled_state): self.settings['dt']/( self.settings['structural_substeps'] + 1)) - if info_k == 'structural_solver': + elif info_k == 'structural_solver': if info_v is not None: self.structural_solver = solver_interface.initialise_solver( info['structural_solver']) self.structural_solver.initialise( self.data, self.settings['structural_solver_settings']) + elif info_k == 'rotor_vel': + for lc in self.structural_solver.lc_list: + if lc._lc_id == 'hinge_node_FoR_pitch': + lc.set_rotor_vel(info_v) + + elif info_k == 'pitch_vel': + for lc in self.structural_solver.lc_list: + if lc._lc_id == 'hinge_node_FoR_pitch': + lc.set_pitch_vel(info_v) + return controlled_state['structural'], controlled_state['aero'] def run(self): diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index ed1ad2cba..a3877d3c0 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -413,7 +413,7 @@ def equal_lin_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, return ieq -def equal_rot_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q): +def rel_rot_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_vel=np.zeros((3))): """ This function generates the stiffness and damping matrices and the independent vector associated to a constraint that imposes equal rotation velocities between a node and a frame of reference @@ -427,6 +427,7 @@ def equal_rot_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_dof (int): position of the first degree of freedom associated to the "node" FoR_body (int): body number of the "FoR" FoR_dof (int): position of the first degree of freedom associated to the "FoR" + rel_vel (np.array): relative velocity FoR-node """ num_LM_eq_specific = 3 @@ -454,7 +455,7 @@ def equal_rot_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, LM_Q[:sys_size] += scalingFactor*np.dot(np.transpose(Bnh), Lambda_dot[ieq:ieq+num_LM_eq_specific]) LM_Q[sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*(np.dot(tan, MB_tstep[node_body].psi_dot[ielem, inode_in_elem, :]) + np.dot(cab.T, node_FoR_wa) - - ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, FoR_wa)) + ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, FoR_wa) - rel_vel) LM_K[node_dof+3:node_dof+6, node_dof+3:node_dof+6] += scalingFactor*ag.der_TanT_by_xv(psi, Lambda_dot[ieq:ieq+num_LM_eq_specific]) if MB_beam[node_body].FoR_movement == 'free': @@ -1029,13 +1030,13 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.node_number = MBdict_entry['node_in_body'] self.node_body = MBdict_entry['body'] self.FoR_body = MBdict_entry['body_FoR'] - self.rot_axisB = ag.unit_vector(MBdict_entry['rot_vect']) self.rel_posB = MBdict_entry['rel_posB'] self._ieq = ieq self.indep = [] self.scalingFactor = set_value_or_default(MBdict_entry, "scalingFactor", 1.) self.penaltyFactor = set_value_or_default(MBdict_entry, "penaltyFactor", 0.) + self.rot_axisB = ag.unit_vector(MBdict_entry['rot_vect']) if (self.rot_axisB[[1, 2]] == 0).all(): self.rot_dir = 'x' self.zero_comp = np.array([1, 2], dtype=int) @@ -1050,13 +1051,24 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.nonzero_comp = 2 else: raise NotImplementedError("Hinges should be parallel to the xB, yB or zB of the reference node") - self.rot_vel = MBdict_entry['rot_vect'][self.nonzero_comp] + self.set_rot_vel(MBdict_entry['rot_vect'][self.nonzero_comp]) + + self.pitch_vel = set_value_or_default(MBdict_entry, "pitch_vel", 0.) # self.static_constraint = fully_constrained_node_FoR() # self.static_constraint.initialise(MBdict_entry, ieq) return self._ieq + self._n_eq + + def set_rot_vel(self, rot_vel): + self.rot_vel = rot_vel + + + def set_pitch_vel(self, pitch_vel): + self.pitch_vel = pitch_vel + + def staticmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, sys_size, dt, Lambda, Lambda_dot): return @@ -1105,6 +1117,102 @@ def dynamicpost(self, lc_list, MB_beam, MB_tstep): return +@lagrangeconstraint +class hinge_node_FoR_pitch(BaseLagrangeConstraint): + __doc__ = """ + hinge_node_FoR_pitch + + This constraint forces a hinge behaviour between a node and a FoR and + a rotation velocity at the joint + + See ``LagrangeConstraints`` for the description of variables + + Attributes: + node_number (int): number of the "node" within its own body + node_body (int): body number of the "node" + FoR_body (int): body number of the "FoR" + rot_vect (np.ndarray): Rotation velocity vector in the node B FoR + rel_posB (np.ndarray): Relative position between the node and the frame of reference in the node B FoR + """ + _lc_id = 'hinge_node_FoR_pitch' + + def __init__(self): + self.required_parameters = ['node_in_body', 'body', 'body_FoR', 'rotor_vel', 'rel_posB'] + self._n_eq = 6 + + def get_n_eq(self): + return self._n_eq + + def initialise(self, MBdict_entry, ieq, print_info=True): + + self.node_number = MBdict_entry['node_in_body'] + self.node_body = MBdict_entry['body'] + self.FoR_body = MBdict_entry['body_FoR'] + self.rel_posB = MBdict_entry['rel_posB'] + self._ieq = ieq + self.indep = [] + self.scalingFactor = set_value_or_default(MBdict_entry, "scalingFactor", 1.) + self.penaltyFactor = set_value_or_default(MBdict_entry, "penaltyFactor", 0.) + + self.set_rotor_vel(MBdict_entry['rotor_vel']) + pitch_vel = set_value_or_default(MBdict_entry, "pitch_vel", np.zeros((3))) + self.set_pitch_vel(pitch_vel) + + return self._ieq + self._n_eq + + + def set_rotor_vel(self, rotor_vel): + self.rotor_vel = rotor_vel + + + def set_pitch_vel(self, pitch_vel): + self.pitch_vel = pitch_vel + + + def staticmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, + sys_size, dt, Lambda, Lambda_dot): + return + + def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, + sys_size, dt, Lambda, Lambda_dot): + + # Define the position of the first degree of freedom associated to the node + node_dof = define_node_dof(MB_beam, self.node_body, self.node_number) + node_FoR_dof = define_FoR_dof(MB_beam, self.node_body) + FoR_dof = define_FoR_dof(MB_beam, self.FoR_body) + ieq = self._ieq + + # Compute relative velocity + ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] + node_cga = MB_tstep[self.node_body].cga() + cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem, inode_in_elem, :]) + FoR_cga = MB_tstep[self.FoR_body].cga() + + rel_vel = np.array([0., 0., self.rotor_vel]) + rel_vel += ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, + np.array([self.pitch_vel, 0., 0.])) + + # Define the equations + ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = rel_rot_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_vel=rel_vel) + return + + def staticpost(self, lc_list, MB_beam, MB_tstep): + return + + def dynamicpost(self, lc_list, MB_beam, MB_tstep): + + ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] + node_cga = MB_tstep[self.node_body].cga() + cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem, inode_in_elem, :]) + + MB_tstep[self.FoR_body].for_pos[0:3] = (np.dot(node_cga, + MB_tstep[self.node_body].pos[self.node_number,:] + np.dot(cab, self.rel_posB)) + + MB_tstep[self.node_body].for_pos[0:3]) + + return + + @lagrangeconstraint class spherical_node_FoR(BaseLagrangeConstraint): __doc__ = """ @@ -1509,7 +1617,7 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, # Define the equations ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) - ieq = equal_rot_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = rel_rot_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_vel=np.zeros((3))) return From fa14f1ad5263b2447de403b0b7180f1488e6fbea Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 10 Jun 2021 18:07:44 +0100 Subject: [PATCH 109/253] fix pitch LC --- sharpy/structure/utils/lagrangeconstraints.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index a3877d3c0..e98e7e850 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -455,7 +455,7 @@ def rel_rot_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, no LM_Q[:sys_size] += scalingFactor*np.dot(np.transpose(Bnh), Lambda_dot[ieq:ieq+num_LM_eq_specific]) LM_Q[sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*(np.dot(tan, MB_tstep[node_body].psi_dot[ielem, inode_in_elem, :]) + np.dot(cab.T, node_FoR_wa) - - ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, FoR_wa) - rel_vel) + ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, FoR_wa) + rel_vel) LM_K[node_dof+3:node_dof+6, node_dof+3:node_dof+6] += scalingFactor*ag.der_TanT_by_xv(psi, Lambda_dot[ieq:ieq+num_LM_eq_specific]) if MB_beam[node_body].FoR_movement == 'free': @@ -1155,7 +1155,7 @@ def initialise(self, MBdict_entry, ieq, print_info=True): self.penaltyFactor = set_value_or_default(MBdict_entry, "penaltyFactor", 0.) self.set_rotor_vel(MBdict_entry['rotor_vel']) - pitch_vel = set_value_or_default(MBdict_entry, "pitch_vel", np.zeros((3))) + pitch_vel = set_value_or_default(MBdict_entry, "pitch_vel", 0.) self.set_pitch_vel(pitch_vel) return self._ieq + self._n_eq From 8d49b642b83cca6bf85004290d75120c3701fe32 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 10 Jun 2021 19:22:42 +0100 Subject: [PATCH 110/253] fix log file SHARPy --- sharpy/presharpy/presharpy.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/sharpy/presharpy/presharpy.py b/sharpy/presharpy/presharpy.py index 98c9c44da..d025c6616 100644 --- a/sharpy/presharpy/presharpy.py +++ b/sharpy/presharpy/presharpy.py @@ -62,6 +62,10 @@ class PreSharpy(object): settings_description['log_folder'] = 'A folder with the case name will be created at this directory ' \ 'containing the SHARPy log and output folders' + settings_types['log_file'] = 'str' + settings_default['log_file'] = 'log' + settings_description['log_file'] = 'Name of the log file' + settings_types['save_settings'] = 'bool' settings_default['save_settings'] = False settings_description['save_settings'] = 'Save a copy of the settings to a ``.sharpy`` file in the output ' \ @@ -79,9 +83,6 @@ def __init__(self, in_settings=None): self.ts = 0 - self.settings_types['log_file'] = 'str' - self.settings_default['log_file'] = 'log' - if self._settings: self.settings = in_settings self.settings['SHARPy']['flow'] = self.settings['SHARPy']['flow'] From 81bf12b0a1d644811fe003615197e060319fc9e1 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sun, 13 Jun 2021 13:20:55 +0100 Subject: [PATCH 111/253] improvements blade pitch WIP --- sharpy/controllers/bladepitchpid.py | 127 +++++++++++++++++++--------- 1 file changed, 89 insertions(+), 38 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index bf22dc923..f5ecf127d 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -50,7 +50,7 @@ class BladePitchPid(controller_interface.BaseController): settings_description['sp_type'] = ( 'Quantity used to define the' + ' set point') - settings_options['sp_type'] = ['rbm', 'pitch', 'torque'] + settings_options['sp_type'] = ['rbm', 'pitch', 'rotor_vel'] settings_types['sp_source'] = 'str' settings_default['sp_source'] = None @@ -90,10 +90,14 @@ class BladePitchPid(controller_interface.BaseController): settings_default['min_pitch'] = 0. settings_description['min_pitch'] = 'Minimum pitch [rad]' + settings_types['nocontrol_steps'] = 'int' + settings_default['nocontrol_steps'] = -1 + settings_description['nocontrol_steps'] = 'Time steps without control action' + # Generator and drive train model - settings_types['variable_speed'] = 'bool' - settings_default['variable_speed'] = True - settings_description['variable_speed'] = 'Allow the change in the rotor velocity' + #settings_types['variable_speed'] = 'bool' + #settings_default['variable_speed'] = True + #settings_description['variable_speed'] = 'Allow the change in the rotor velocity' settings_types['GBR'] = 'float' settings_default['GBR'] = 97. @@ -103,9 +107,9 @@ class BladePitchPid(controller_interface.BaseController): settings_default['inertia_dt'] = 43776046.25 settings_description['inertia_dt'] = 'Drive train inertia' - settings_types['target_gen_torque'] = 'float' - settings_default['target_gen_torque'] = 3945990.325 - settings_description['target_gen_torque'] = 'Generator torque' + settings_types['target_gen_power'] = 'float' + settings_default['target_gen_power'] = 3945990.325 + settings_description['target_gen_power'] = 'Generator power' settings_types['newmark_damp'] = 'float' settings_default['newmark_damp'] = 1e-4 @@ -169,8 +173,8 @@ def initialise(self, in_dict, controller_id=None): if self.settings['write_controller_log']: self.log = open(self.settings['controller_log_route'] + '/' + self.controller_id + '.dat', 'w+') - self.log.write(('#'+ 1*'{:>2},' + 6*'{:>12},' + '{:>12}\n'). - format('tstep', 'time', 'Ref. state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control')) + self.log.write(('#'+ 1*'{:>2},' + 9*'{:>12},' + '{:>12}\n'). + format('tstep', 'time', 'ref_state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control', 'gen_torque', 'rotor_vel', 'pitch_vel')) self.log.flush() # save input time history @@ -192,6 +196,8 @@ def initialise(self, in_dict, controller_id=None): alpha = np.exp(-self.settings['lp_cut_freq']*self.settings['dt']) self.filter = ss(alpha, 1.-alpha, alpha, 1.-alpha, self.settings['dt']) + self.pitch = 0. + def control(self, data, controlled_state): r""" Main routine of the controller. @@ -211,21 +217,34 @@ def control(self, data, controlled_state): aero_tstep = controlled_state['aero'] if not "info" in controlled_state: controlled_state['info'] = dict() + time = self.settings['dt']*data.ts # Compute the rotor velocity - torque = self.compute_torque(data.structure, struct_tstep) - if self.settings['variable_speed']: - rotor_vel, rotor_acc = self.drive_train_model(torque, - struct_tstep.mb_FoR_vel[self.settings['blade_num_body'][0], 3:6], - struct_tstep.mb_FoR_acc[self.settings['blade_num_body'][0], 3:6]) - controlled_state['info']['rotor_vel'] = rotor_vel + aero_torque = self.compute_aero_torque(data.structure, struct_tstep) + # if self.settings['variable_speed']: + if True: + rotor_vel, rotor_acc = self.drive_train_model(aero_torque, + struct_tstep.mb_FoR_vel[self.settings['blade_num_body'][0], 5], + struct_tstep.mb_FoR_acc[self.settings['blade_num_body'][0], 5]) + else: + rotor_vel = self.settings['sp_const'] + rotor_acc = 0. # System set point prescribed_sp = self.compute_prescribed_sp(time) # System process value - sys_pv = self.compute_system_pv(struct_tstep, data.structure, torque=torque) - + sys_pv = self.compute_system_pv(struct_tstep, + data.structure, + rotor_vel=rotor_vel) + + if data.ts < self.settings['nocontrol_steps']: + sys_pv = prescribed_sp + self.system_pv[-1] = sys_pv + return controlled_state + else: + controlled_state['info']['rotor_vel'] = rotor_vel + # Apply filter if self.filter_pv and (len(self.system_pv) > 1): nit = len(self.system_pv) @@ -249,17 +268,34 @@ def control(self, data, controlled_state): 'I': self.settings['I'], 'D': self.settings['D']}, i_current=data.ts) - + control_command *= -1. # Limit pitch and pitch rate - current_pitch = algebra.quat2euler(struct_tstep.mb_quat[self.settings['blade_num_body'][0]])[0] - target_pitch = current_pitch + control_command - target_pitch = max(target_pitch, self.settings['min_pitch']) - pitch_rate = (target_pitch - current_pitch)/self.settings['dt'] + # current_pitch = algebra.quat2euler(struct_tstep.mb_quat[self.settings['blade_num_body'][0]])[0] + # print(control_command, current_pitch) + # target_pitch = current_pitch + control_command + # target_pitch = max(target_pitch, self.settings['min_pitch']) + # pitch_rate = (target_pitch - current_pitch)/self.settings['dt'] + pitch_rate = control_command/self.settings['dt'] + if pitch_rate < -self.settings['max_pitch_rate']: pitch_rate = -self.settings['max_pitch_rate'] elif pitch_rate > self.settings['max_pitch_rate']: pitch_rate = self.settings['max_pitch_rate'] - delta_pitch = pitch_rate*self.settings['dt'] + # delta_pitch = pitch_rate*self.settings['dt'] + # if control_command > 0.: + # pitch_rate = self.settings['max_pitch_rate'] + # elif control_command < 0.: + # pitch_rate = -self.settings['max_pitch_rate'] + # else: + # pitch_rate = 0. + # pitch_rate = 0. + + next_pitch = self.pitch + pitch_rate*self.settings['dt'] + if next_pitch < 0.: + pitch_rate = 0. + next_pitch = 0. + self.pitch = next_pitch + controlled_state['info']['pitch_vel'] = pitch_rate # Apply control order @@ -276,7 +312,7 @@ def control(self, data, controlled_state): struct_tstep.mb_quat[ibody, :] = quat.copy() if ibody == 0: struct_tstep.quat = quat.copy() - change_vel = True + change_vel = False if change_vel: # struct_tstep.for_vel[3] = control_command/self.settings['dt'] # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] @@ -302,8 +338,12 @@ def control(self, data, controlled_state): # controlled_state['aero'].control_surface_deflection = ( # np.array(self.settings['controlled_surfaces_coeff'])*control_command) + print("gen torque [MNm]:", aero_torque/self.settings['GBR']*1e-6, + "rotor_vel:", rotor_vel, + "pitch_vel:", pitch_rate, + "control_c:", control_command) self.log.write(('{:>6d},' - + 6*'{:>12.6f},' + + 9*'{:>12.6f},' + '{:>12.6f}\n').format(data.ts, data.ts*self.settings['dt'], self.prescribed_sp[-1], @@ -311,8 +351,10 @@ def control(self, data, controlled_state): detail[0], detail[1], detail[2], - control_command)) - + control_command, + aero_torque/self.settings['GBR'], + rotor_vel, + pitch_rate)) return controlled_state @@ -345,8 +387,8 @@ def compute_system_pv(self, struct_tstep, beam, **kwargs): rbm = steady[4] + unsteady[4] + grav[4] self.system_pv.append(rbm) # print("rbm: ", rbm) - elif self.settings['sp_type'] == 'torque': - self.system_pv.append(kwargs['torque']) + elif self.settings['sp_type'] == 'rotor_vel': + self.system_pv.append(kwargs['rotor_vel']) return self.system_pv[-1] @@ -363,29 +405,38 @@ def __exit__(self, *args): # self.log.close() pass - def drive_train_model(self, torque, ini_rot_vel, ini_rot_acc): + def drive_train_model(self, aero_torque, ini_rot_vel, ini_rot_acc): # Assuming contant generator torque demand - gen_torque = self.settings['target_gen_torque'] + print(ini_rot_vel) + gen_torque = self.settings['target_gen_power']/self.settings['GBR']/ini_rot_vel + + print("aero_torque", aero_torque) + print("gen_torque", gen_torque*self.settings['GBR']) + print("error_torque", (aero_torque - gen_torque*self.settings['GBR'])/aero_torque*100) - delta_rot_acc = (torque - self.settings['GBR']*gen_torque)/self.settings['inertia_dt'] - rot_acc = ini_rot_acc + delta_rot_acc + rot_acc = (aero_torque - self.settings['GBR']*gen_torque)/self.settings['inertia_dt'] + # rot_acc = ini_rot_acc + delta_rot_acc # Integrate according to newmark-beta scheme - rot_vel = (ini_rot_vel + - (1. - self.newmark_beta)*self.settings['dt'] + - self.newmark_beta*self.settings['dt']*rot_acc) + # rot_vel = (ini_rot_vel + + # (1. - self.newmark_beta)*self.settings['dt']*ini_rot_acc + + # self.newmark_beta*self.settings['dt']*rot_acc) + rot_vel = ini_rot_vel + rot_acc*self.settings['dt'] + print("rot vel acc", rot_vel, rot_acc) return rot_vel, rot_acc + # return ini_rot_vel, ini_rot_acc - def compute_torque(self, beam, struct_tstep): + def compute_aero_torque(self, beam, struct_tstep): # Compute total forces total_forces = np.zeros((6)) for ibody in self.settings['blade_num_body']: steady, unsteady, grav = struct_tstep.extract_resultants(beam, force_type=['steady', 'unsteady', 'grav'], ibody=ibody) - total_forces += steady + unsteady + grav + # total_forces += steady + unsteady + grav + total_forces += steady + unsteady # Compute equivalent forces at hub position hub_elem = np.where(beam.body_number == self.settings['blade_num_body'][0])[0][0] From 3e4594412e43340d86b91196987f57e17c8aa758 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 14 Jun 2021 09:46:50 +0100 Subject: [PATCH 112/253] generator power and torque models --- sharpy/controllers/bladepitchpid.py | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index f5ecf127d..1f5733734 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -99,6 +99,15 @@ class BladePitchPid(controller_interface.BaseController): #settings_default['variable_speed'] = True #settings_description['variable_speed'] = 'Allow the change in the rotor velocity' + settings_types['gen_model_const_var'] = 'str' + settings_default['gen_model_const_var'] = '' + settings_description['gen_model_const_var'] = 'Generator metric to be kept constant at a value `target_gen_value`' + settings_options['gen_model_const_var'] = ['power', 'torque'] + + settings_types['gen_model_const_value'] = 'float' + settings_default['gen_model_const_value'] = 3945990.325 + settings_description['gen_model_const_value'] = 'Constant value of the generator metric to be kept constant ' + settings_types['GBR'] = 'float' settings_default['GBR'] = 97. settings_description['GBR'] = 'Gear box ratio' @@ -107,10 +116,6 @@ class BladePitchPid(controller_interface.BaseController): settings_default['inertia_dt'] = 43776046.25 settings_description['inertia_dt'] = 'Drive train inertia' - settings_types['target_gen_power'] = 'float' - settings_default['target_gen_power'] = 3945990.325 - settings_description['target_gen_power'] = 'Generator power' - settings_types['newmark_damp'] = 'float' settings_default['newmark_damp'] = 1e-4 settings_description['newmark_damp'] = 'Damping of the time integration newmark-beta scheme' @@ -409,7 +414,10 @@ def drive_train_model(self, aero_torque, ini_rot_vel, ini_rot_acc): # Assuming contant generator torque demand print(ini_rot_vel) - gen_torque = self.settings['target_gen_power']/self.settings['GBR']/ini_rot_vel + if self.settings['gen_model_const_var'] == 'power': + gen_torque = self.settings['gen_model_const_value']/self.settings['GBR']/ini_rot_vel + elif self.settings['gen_model_const_var'] == 'torque': + gen_torque = self.settings['gen_model_const_value'] print("aero_torque", aero_torque) print("gen_torque", gen_torque*self.settings['GBR']) From 52ae4aab69b71908a3b485130873279c44f3fe58 Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 16 Jun 2021 09:49:19 +0100 Subject: [PATCH 113/253] compute blade pitch and use gen vel --- sharpy/controllers/bladepitchpid.py | 48 +++++++++++++++++++++++------ 1 file changed, 39 insertions(+), 9 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 1f5733734..71ad80018 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -50,7 +50,7 @@ class BladePitchPid(controller_interface.BaseController): settings_description['sp_type'] = ( 'Quantity used to define the' + ' set point') - settings_options['sp_type'] = ['rbm', 'pitch', 'rotor_vel'] + settings_options['sp_type'] = ['rbm', 'pitch', 'gen_vel'] settings_types['sp_source'] = 'str' settings_default['sp_source'] = None @@ -178,8 +178,8 @@ def initialise(self, in_dict, controller_id=None): if self.settings['write_controller_log']: self.log = open(self.settings['controller_log_route'] + '/' + self.controller_id + '.dat', 'w+') - self.log.write(('#'+ 1*'{:>2},' + 9*'{:>12},' + '{:>12}\n'). - format('tstep', 'time', 'ref_state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control', 'gen_torque', 'rotor_vel', 'pitch_vel')) + self.log.write(('#'+ 1*'{:>2},' + 10*'{:>12},' + '{:>12}\n'). + format('tstep', 'time', 'ref_state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control', 'gen_torque', 'rotor_vel', 'pitch_vel', 'pitch')) self.log.flush() # save input time history @@ -241,7 +241,7 @@ def control(self, data, controlled_state): # System process value sys_pv = self.compute_system_pv(struct_tstep, data.structure, - rotor_vel=rotor_vel) + gen_vel=rotor_vel*self.settings['GBR']) if data.ts < self.settings['nocontrol_steps']: sys_pv = prescribed_sp @@ -293,7 +293,7 @@ def control(self, data, controlled_state): # pitch_rate = -self.settings['max_pitch_rate'] # else: # pitch_rate = 0. - # pitch_rate = 0. + pitch_rate = 0. next_pitch = self.pitch + pitch_rate*self.settings['dt'] if next_pitch < 0.: @@ -301,6 +301,12 @@ def control(self, data, controlled_state): next_pitch = 0. self.pitch = next_pitch + int_pitch = self.compute_blade_pitch(data.structure, + struct_tstep, + tower_ibody=self.settings['blade_num_body'][0] - 1, + blade_ibody=self.settings['blade_num_body'][0]) + print("int comp pitch:", self.pitch, int_pitch) + controlled_state['info']['pitch_vel'] = pitch_rate # Apply control order @@ -348,7 +354,7 @@ def control(self, data, controlled_state): "pitch_vel:", pitch_rate, "control_c:", control_command) self.log.write(('{:>6d},' - + 9*'{:>12.6f},' + + 10*'{:>12.6f},' + '{:>12.6f}\n').format(data.ts, data.ts*self.settings['dt'], self.prescribed_sp[-1], @@ -359,7 +365,8 @@ def control(self, data, controlled_state): control_command, aero_torque/self.settings['GBR'], rotor_vel, - pitch_rate)) + pitch_rate, + self.pitch)) return controlled_state @@ -392,8 +399,8 @@ def compute_system_pv(self, struct_tstep, beam, **kwargs): rbm = steady[4] + unsteady[4] + grav[4] self.system_pv.append(rbm) # print("rbm: ", rbm) - elif self.settings['sp_type'] == 'rotor_vel': - self.system_pv.append(kwargs['rotor_vel']) + elif self.settings['sp_type'] == 'gen_vel': + self.system_pv.append(kwargs['gen_vel']) return self.system_pv[-1] @@ -456,3 +463,26 @@ def compute_aero_torque(self, beam, struct_tstep): hub_forces[3:6] = total_forces[3:6] + np.cross(hub_pos, total_forces[0:3]) return hub_forces[5] + + @staticmethod + def compute_blade_pitch(beam, struct_tstep, tower_ibody=0, blade_ibody=1): + # Tower top + tt_elem = np.where(beam.body_number == tower_ibody)[0][-1] + tt_node = beam.connectivities[tt_elem, 1] + ielem, inode_in_elem = beam.node_master_elem[tt_node] + ca0b = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem, :]) + cga0 = algebra.quat2rotation(struct_tstep.mb_quat[tower_ibody, :]) + zg_tower_top = algebra.multiply_matrices(cga0, ca0b, np.array([0., 0., 1.])) + + # blade root + # hub_elem = np.where(beam.body_number == blade_ibody)[0][0] + # hub_node = beam.connectivities[hub_elem, 0] + # ielem, inode_in_elem = beam.node_master_elem[hub_node] + # cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem, :]) + cga = algebra.quat2rotation(struct_tstep.mb_quat[blade_ibody, :]) + # zg_hub = algebra.multiply_matrices(cga, cab, np.array([0., 0., 1.])) + zg_hub = algebra.multiply_matrices(cga, np.array([0., 0., 1.])) + + pitch = algebra.angle_between_vectors(zg_tower_top, zg_hub) + return pitch + From 5d774f4dbbc1a7b6a7dde35e37a2b1ed65de0b9a Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 16 Jun 2021 09:49:59 +0100 Subject: [PATCH 114/253] comment out pitch rate = 0 --- sharpy/controllers/bladepitchpid.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 71ad80018..79dcfc9e3 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -293,7 +293,7 @@ def control(self, data, controlled_state): # pitch_rate = -self.settings['max_pitch_rate'] # else: # pitch_rate = 0. - pitch_rate = 0. + # pitch_rate = 0. next_pitch = self.pitch + pitch_rate*self.settings['dt'] if next_pitch < 0.: From 0532d43eeaeb9307b1d638cbc72cee7a100ac09f Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 17 Jun 2021 07:56:06 +0100 Subject: [PATCH 115/253] save solvers in pickledata and restart --- sharpy/generators/floatingforces.py | 28 +++++---- sharpy/presharpy/presharpy.py | 1 + sharpy/sharpy_main.py | 14 ++++- sharpy/solvers/dynamiccoupled.py | 63 +++++++++++++++------ sharpy/solvers/nonlineardynamicmultibody.py | 42 +++++++++----- sharpy/solvers/staticcoupled.py | 19 +++++-- sharpy/utils/controller_interface.py | 5 +- sharpy/utils/generator_interface.py | 5 +- sharpy/utils/solver_interface.py | 3 + 9 files changed, 130 insertions(+), 50 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index f78727622..9d673fbf9 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -579,9 +579,15 @@ def initialise(self, in_dict=None, data=None): self.gravity_dir = self.settings['gravity_dir'] # Platform dofs - self.q = np.zeros((self.settings['n_time_steps'] + 1, 6)) - self.qdot = np.zeros_like(self.q) - self.qdotdot = np.zeros_like(self.q) + if self.q is None: + self.q = np.zeros((self.settings['n_time_steps'] + 1, 6)) + self.qdot = np.zeros_like(self.q) + self.qdotdot = np.zeros_like(self.q) + else: + increase_ts = self.settings['n_time_steps'] + 1 - self.q.shape[0] + self.q = np.concatenate((self.q, np.zeros((increase_ts, 6))), axis=0) + self.qdot = np.concatenate((self.qdot, np.zeros((increase_ts, 6))), axis=0) + self.qdotdot = np.concatenate((self.qdotdot, np.zeros((increase_ts, 6))), axis=0) # Read the file with the floating information fid = h5.File(self.settings['floating_file_name'], 'r') @@ -593,8 +599,9 @@ def initialise(self, in_dict=None, data=None): self.n_mooring_lines = self.floating_data['mooring']['n_lines'] self.anchor_pos = np.zeros((self.n_mooring_lines, 3)) self.fairlead_pos_A = np.zeros((self.n_mooring_lines, 3)) - self.hf_prev = [None]*self.n_mooring_lines - self.vf_prev = [None]*self.n_mooring_lines + if len(self.hf_prev) == 0: + self.hf_prev = [None]*self.n_mooring_lines + self.vf_prev = [None]*self.n_mooring_lines if self.n_mooring_lines > 0: theta = 2.*np.pi/self.n_mooring_lines @@ -668,8 +675,11 @@ def initialise(self, in_dict=None, data=None): self.hd_K = TransferFunction(hd_K_num, hd_K_den) self.ab_freq_rads = self.floating_data['hydrodynamics']['ab_freq_rads'] - self.x0_K = [None]*(self.settings['n_time_steps'] + 1) - self.x0_K[0] = 0. + try: + self.x0_K.extend([None]*increase_ts) + except AttributeError: + self.x0_K = [None]*(self.settings['n_time_steps'] + 1) + self.x0_K[0] = 0. # Wave forces @@ -871,9 +881,6 @@ def generate(self, params): elif self.settings['method_matrices_freq'] == 'rational_function': # Damping - if self.x0_K[data.ts - 1] is None: - # This loop is needed when computations are restarted - self.x0_K[data.ts - 1] = 0 (T, yout, xout) = forced_response(self.hd_K, T=[0, self.settings['dt']], U=self.qdot[data.ts-1:data.ts+1, :].T, @@ -977,3 +984,4 @@ def generate(self, params): if self.settings['write_output']: self.write_output(data.ts, k, mooring_forces, mooring_yaw, hs_f_g, hd_f_qdot_g, hd_f_qdotdot_g, hd_correct_grav, total_drag_force, self.wave_forces_g[data.ts, :]) + diff --git a/sharpy/presharpy/presharpy.py b/sharpy/presharpy/presharpy.py index d025c6616..5fbfdab71 100644 --- a/sharpy/presharpy/presharpy.py +++ b/sharpy/presharpy/presharpy.py @@ -82,6 +82,7 @@ def __init__(self, in_settings=None): self._settings = False self.ts = 0 + self.solvers = dict() if self._settings: self.settings = in_settings diff --git a/sharpy/sharpy_main.py b/sharpy/sharpy_main.py index 5d81d37a1..cdb4c8e5f 100644 --- a/sharpy/sharpy_main.py +++ b/sharpy/sharpy_main.py @@ -106,11 +106,19 @@ def main(args=None, sharpy_input_dict=None): # for it in range(self.num_steps): # data.structure.dynamic_input.append(dict()) + # Restart the solvers + old_solvers_list = list(data.solvers.keys()) + for old_solver_name in old_solvers_list: + if old_solver_name not in settings['SHARPy']['flow']: + del data.solvers[old_solver_name] + # Loop for the solvers specified in *.sharpy['SHARPy']['flow'] for solver_name in settings['SHARPy']['flow']: - solver = solver_interface.initialise_solver(solver_name) - solver.initialise(data) - data = solver.run() + if (args.restart is None) or (solver_name not in data.solvers.keys()): + data.solvers[solver_name] = solver_interface.initialise_solver(solver_name) + data.solvers[solver_name].initialise(data) + data = data.solvers[solver_name].run() + data.solvers[solver_name].teardown() cpu_time = time.process_time() - t wall_time = time.perf_counter() - t0_wall diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 1b168fcfd..6f313ef58 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -272,38 +272,50 @@ def initialise(self, data, custom_settings=None): # timestep_info[0] and remove the rest self.cleanup_timestep_info() - self.structural_solver = solver_interface.initialise_solver( - self.settings['structural_solver']) + if self.structural_solver is None: + self.structural_solver = solver_interface.initialise_solver( + self.settings['structural_solver']) self.structural_solver.initialise( self.data, self.settings['structural_solver_settings']) - self.aero_solver = solver_interface.initialise_solver( - self.settings['aero_solver']) + if self.aero_solver is None: + self.aero_solver = solver_interface.initialise_solver( + self.settings['aero_solver']) self.aero_solver.initialise(self.structural_solver.data, self.settings['aero_solver_settings']) self.data = self.aero_solver.data # initialise postprocessors - self.postprocessors = dict() if self.settings['postprocessors']: self.with_postprocessors = True + # Remove previous postprocessors not required on restart + old_list = list(self.postprocessors.keys()) + for old_list_name in old_list: + if old_list_name not in self.settings['postprocessors']: + del self.postprocessors[old_list_name] for postproc in self.settings['postprocessors']: - self.postprocessors[postproc] = solver_interface.initialise_solver( - postproc) + if not postproc in self.postprocessors.keys(): + self.postprocessors[postproc] = solver_interface.initialise_solver( + postproc) self.postprocessors[postproc].initialise( self.data, self.settings['postprocessors_settings'][postproc], caller=self) # initialise controllers - self.controllers = dict() self.with_controllers = False if self.settings['controller_id']: self.with_controllers = True + # Remove previous controllers not required on restart + old_list = list(self.controllers.keys()) + for old_list_name in old_list: + if old_list_name not in self.settings['controller_id']: + del self.controllers[old_list_name] for controller_id, controller_type in self.settings['controller_id'].items(): - self.controllers[controller_id] = ( - controller_interface.initialise_controller(controller_type)) + if not controller_id in self.controllers.keys(): + self.controllers[controller_id] = ( + controller_interface.initialise_controller(controller_type)) self.controllers[controller_id].initialise( self.settings['controller_settings'][controller_id], controller_id) - + # print information header if self.print_info: self.residual_table = cout.TablePrinter(8, 12, ['g', 'f', 'g', 'f', 'f', 'f', 'e', 'e']) @@ -329,13 +341,18 @@ def initialise(self, data, custom_settings=None): self.network_loader.initialise(in_settings=self.settings['network_settings']) # initialise runtime generators - self.runtime_generators = dict() if self.settings['runtime_generators']: self.with_runtime_generators = True - for id, param in self.settings['runtime_generators'].items(): - gen = gen_interface.generator_from_string(id) - self.runtime_generators[id] = gen() - self.runtime_generators[id].initialise(param, data=self.data) + # Remove previous runtime generators not required on restart + old_list = list(self.runtime_generators.keys()) + for old_list_name in old_list: + if old_list_name not in self.settings['runtime_generators']: + del self.runtime_generators[old_list_name] + for rg_id, param in self.settings['runtime_generators'].items(): + if not rg_id in self.runtime_generators.keys(): + gen = gen_interface.generator_from_string(rg_id) + self.runtime_generators[rg_id] = gen() + self.runtime_generators[rg_id].initialise(param, data=self.data) def cleanup_timestep_info(self): if max(len(self.data.aero.timestep_info), len(self.data.structure.timestep_info)) > 1: @@ -860,6 +877,20 @@ def interpolate_timesteps(step0, step1, out_step, coeff): return out_step + def teardown(self): + + self.structural_solver.teardown() + self.aero_solver.teardown() + if self.with_postprocessors: + for pp in self.postprocessors.values(): + pp.teardown() + if self.with_controllers: + for cont in self.controllers.values(): + cont.teardown() + if self.with_runtime_generators: + for rg in self.runtime_generators.values(): + rg.teardown() + def relax(beam, timestep, previous_timestep, coeff): timestep.steady_applied_forces = ((1.0 - coeff)*timestep.steady_applied_forces + diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 73a380d77..ec5d42cd1 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -119,10 +119,10 @@ def initialise(self, data, custom_settings=None): dire = './output/' + self.data.settings['SHARPy']['case'] + '/NonLinearDynamicMultibody/' if not os.path.isdir(dire): os.makedirs(dire) - self.fid_lambda = open(dire + 'lambda.dat', "w") - self.fid_lambda_dot = open(dire + 'lambda_dot.dat', "w") - self.fid_lambda_ddot = open(dire + 'lambda_ddot.dat', "w") - self.fid_cond_num = open(dire + 'cond_num.dat', "w") + self.fname_lambda = dire + 'lambda.dat' + self.fname_lambda_dot = dire + 'lambda_dot.dat' + self.fname_lambda_ddot = dire + 'lambda_ddot.dat' + self.fname_cond_num = dire + 'cond_num.dat' # Define the number of dofs self.define_sys_size() @@ -327,18 +327,29 @@ def compute_forces_constraints(self, MB_beam, MB_tstep, ts, dt, Lambda, Lambda_d def write_lm_cond_num(self, iteration, Lambda, Lambda_dot, Lambda_ddot, cond_num, cond_num_lm): - self.fid_lambda.write("%d %d " % (self.data.ts, iteration)) - self.fid_lambda_dot.write("%d %d " % (self.data.ts, iteration)) - self.fid_lambda_ddot.write("%d %d " % (self.data.ts, iteration)) - self.fid_cond_num.write("%d %d " % (self.data.ts, iteration)) + fid_lambda = open(self.fname_lambda, "a") + fid_lambda_dot = open(self.fname_lambda_dot, "a") + fid_lambda_ddot = open(self.fname_lambda_ddot, "a") + fid_cond_num = open(self.fname_cond_num, "a") + + fid_lambda.write("%d %d " % (self.data.ts, iteration)) + fid_lambda_dot.write("%d %d " % (self.data.ts, iteration)) + fid_lambda_ddot.write("%d %d " % (self.data.ts, iteration)) + fid_cond_num.write("%d %d " % (self.data.ts, iteration)) for ilm in range(self.num_LM_eq): - self.fid_lambda.write("%f " % Lambda[ilm]) - self.fid_lambda_dot.write("%f " % Lambda_dot[ilm]) - self.fid_lambda_ddot.write("%f " % Lambda_ddot[ilm]) - self.fid_lambda.write("\n") - self.fid_lambda_dot.write("\n") - self.fid_lambda_ddot.write("\n") - self.fid_cond_num.write("%e %e\n" % (cond_num, cond_num_lm)) + fid_lambda.write("%f " % Lambda[ilm]) + fid_lambda_dot.write("%f " % Lambda_dot[ilm]) + fid_lambda_ddot.write("%f " % Lambda_ddot[ilm]) + fid_lambda.write("\n") + fid_lambda_dot.write("\n") + fid_lambda_ddot.write("\n") + fid_cond_num.write("%e %e\n" % (cond_num, cond_num_lm)) + + fid_lambda.close() + fid_lambda_dot.close() + fid_lambda_ddot.close() + fid_cond_num.close() + def run(self, structural_step=None, dt=None): @@ -540,3 +551,4 @@ def run(self, structural_step=None, dt=None): self.Lambda_ddot = Lambda_ddot.astype(dtype=ct.c_double, copy=True, order='F') return self.data + diff --git a/sharpy/solvers/staticcoupled.py b/sharpy/solvers/staticcoupled.py index 75ccfb84f..7e0840c17 100644 --- a/sharpy/solvers/staticcoupled.py +++ b/sharpy/solvers/staticcoupled.py @@ -137,10 +137,10 @@ def initialise(self, data, input_dict=None): self.runtime_generators = dict() if self.settings['runtime_generators']: self.with_runtime_generators = True - for id, param in self.settings['runtime_generators'].items(): - gen = gen_interface.generator_from_string(id) - self.runtime_generators[id] = gen() - self.runtime_generators[id].initialise(param, data=self.data) + for rg_id, param in self.settings['runtime_generators'].items(): + gen = gen_interface.generator_from_string(rg_id) + self.runtime_generators[rg_id] = gen() + self.runtime_generators[rg_id].initialise(param, data=self.data) def increase_ts(self): self.data.ts += 1 @@ -351,3 +351,14 @@ def change_trim(self, alpha, thrust, thrust_nodes, tail_deflection, tail_cs_inde def extract_resultants(self, tstep=None): return self.structural_solver.extract_resultants(tstep) + + + def teardown(self): + + self.structural_solver.teardown() + self.aero_solver.teardown() + if self.with_runtime_generators: + for rg in self.runtime_generators.values(): + rg.teardown() + + diff --git a/sharpy/utils/controller_interface.py b/sharpy/utils/controller_interface.py index aeff6fbc9..401ec0c77 100644 --- a/sharpy/utils/controller_interface.py +++ b/sharpy/utils/controller_interface.py @@ -25,7 +25,10 @@ def print_available_controllers(): class BaseController(metaclass=ABCMeta): - pass + + def teardown(self): + pass + def controller_from_string(string): return dict_of_controllers[string] diff --git a/sharpy/utils/generator_interface.py b/sharpy/utils/generator_interface.py index 717dae296..9d2ab7555 100644 --- a/sharpy/utils/generator_interface.py +++ b/sharpy/utils/generator_interface.py @@ -28,7 +28,10 @@ def print_available_generators(): class BaseGenerator(metaclass=ABCMeta): - pass + + def teardown(self): + pass + def generator_from_string(string): return dict_of_generators[string] diff --git a/sharpy/utils/solver_interface.py b/sharpy/utils/solver_interface.py index 898e4b70b..04b36232e 100644 --- a/sharpy/utils/solver_interface.py +++ b/sharpy/utils/solver_interface.py @@ -62,6 +62,9 @@ def __doc__(self): _doc += settings_table.generate(settings_types, settings_default, settings_description) return _doc + def teardown(self): + pass + def solver_from_string(string): try: From ab6e0313b9f54d67890d6c939078e68e33c65e88 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 18 Jun 2021 10:43:13 +0100 Subject: [PATCH 116/253] avoid doubling added mass on restart --- sharpy/generators/floatingforces.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 9d673fbf9..902270d7d 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -647,7 +647,8 @@ def initialise(self, in_dict=None, data=None): self.hd_damping_const = self.floating_data['hydrodynamics']['damping_matrix'][-1, :, :] self.added_mass_in_mass_matrix = self.settings['added_mass_in_mass_matrix'] - if self.added_mass_in_mass_matrix: + if ((self.added_mass_in_mass_matrix) and (data.ts == 0)): + cout.cout_wrap(("Including added mass in mass matrix"), 2) if data.structure.lumped_mass_mat is None: data.structure.lumped_mass_mat_nodes = np.array([self.buoyancy_node]) data.structure.lumped_mass_mat = np.array([self.hd_added_mass_const]) From 73daefce144d7741b2be7eb5c27be8bd7f168bcb Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 24 Jun 2021 16:57:20 +0100 Subject: [PATCH 117/253] fix nonmatching nodes lagrange constraints --- sharpy/structure/utils/lagrangeconstraints.py | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index e98e7e850..0b66a9530 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -303,7 +303,7 @@ def equal_pos_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, inode_in_body, no return ieq -def equal_lin_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q): +def equal_lin_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, scalingFactor, penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_posB = np.zeros((3))): """ This function generates the stiffness and damping matrices and the independent vector associated to a constraint that imposes equal linear velocities between a node and a frame of reference @@ -317,6 +317,7 @@ def equal_lin_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_dof (int): position of the first degree of freedom associated to the "node" FoR_body (int): body number of the "FoR" FoR_dof (int): position of the first degree of freedom associated to the "FoR" + rel_posB (float np.array): relative position between the node and the FoR (in the node B FoR) """ num_LM_eq_specific = 3 @@ -327,9 +328,13 @@ def equal_lin_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_cga = MB_tstep[node_body].cga() node_FoR_va = MB_tstep[node_body].for_vel[0:3] node_FoR_wa = MB_tstep[node_body].for_vel[3:6] - node_Ra = MB_tstep[node_body].pos[node_number,:] + + ielem, inode_in_elem = MB_beam[node_body].node_master_elem[node_number] + psi = MB_tstep[node_body].psi[ielem, inode_in_elem, :] + node_cab = ag.crv2rotation(psi) + node_Ra = MB_tstep[node_body].pos[node_number,:] + np.dot(node_cab, rel_posB) + node_dot_Ra = MB_tstep[node_body].pos_dot[node_number,:] - FoR_cga = MB_tstep[FoR_body].cga() FoR_va = MB_tstep[FoR_body].for_vel[0:3] @@ -1084,7 +1089,7 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, # Define the equations # ieq = equal_pos_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) - ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_posB=self.rel_posB) # ieq = def_rot_vect_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_vect, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) ieq = def_rot_axis_FoR_wrt_node_xyz(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.rot_axisB, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, self.zero_comp) ieq = def_rot_vel_mod_FoR_wrt_node(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.nonzero_comp, self.rot_vel, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) @@ -1193,7 +1198,7 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, np.array([self.pitch_vel, 0., 0.])) # Define the equations - ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_posB=self.rel_posB) ieq = rel_rot_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_vel=rel_vel) return @@ -1616,7 +1621,7 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, ieq = self._ieq # Define the equations - ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q) + ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_posB=self.rel_posB) ieq = rel_rot_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_vel=np.zeros((3))) return From 7fe4e1d8968e4b16be04e24825587a4e9281912e Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 24 Jun 2021 17:16:28 +0100 Subject: [PATCH 118/253] kwargs for solvers and solvers variable in sharpy_main --- sharpy/postproc/aeroforcescalculator.py | 10 +++--- sharpy/postproc/aerogridplot.py | 11 +++--- sharpy/postproc/asymptoticstability.py | 11 +++--- sharpy/postproc/beamloads.py | 11 +++--- sharpy/postproc/beamplot.py | 11 +++--- sharpy/postproc/cleanup.py | 15 ++++---- sharpy/postproc/frequencyresponse.py | 18 ++++++---- sharpy/postproc/liftdistribution.py | 9 +++-- sharpy/postproc/pickledata.py | 17 ++++++--- sharpy/postproc/plotflowfield.py | 15 +++++--- sharpy/postproc/savedata.py | 14 +++++--- sharpy/postproc/saveparametriccase.py | 15 ++++---- sharpy/postproc/stabilityderivatives.py | 16 +++++---- sharpy/postproc/stallcheck.py | 11 +++--- sharpy/postproc/udpout.py | 8 +++-- sharpy/postproc/writevariablestime.py | 10 +++--- sharpy/presharpy/presharpy.py | 1 - sharpy/sharpy_main.py | 16 +++++---- sharpy/solvers/_basestructural.py | 3 +- sharpy/solvers/aerogridloader.py | 12 +++---- sharpy/solvers/beamloader.py | 8 ++--- sharpy/solvers/dynamiccoupled.py | 28 +++++++-------- sharpy/solvers/dynamicuvlm.py | 8 ++--- sharpy/solvers/initialaeroelasticloader.py | 22 ++++++------ sharpy/solvers/lindynamicsim.py | 8 ++--- sharpy/solvers/linearassembler.py | 13 ++++--- sharpy/solvers/modal.py | 14 ++++---- sharpy/solvers/noaero.py | 29 ++++++++------- sharpy/solvers/nonlineardynamic.py | 8 ++--- sharpy/solvers/nonlineardynamiccoupledstep.py | 15 ++++---- sharpy/solvers/nonlineardynamicmultibody.py | 27 ++++++-------- .../solvers/nonlineardynamicprescribedstep.py | 14 ++++---- sharpy/solvers/nonlinearstatic.py | 8 ++--- sharpy/solvers/nostructural.py | 8 ++--- sharpy/solvers/prescribeduvlm.py | 8 ++--- sharpy/solvers/rigiddynamiccoupledstep.py | 23 ++++++------ sharpy/solvers/rigiddynamicprescribedstep.py | 15 ++++---- sharpy/solvers/staticcoupled.py | 16 ++++----- sharpy/solvers/statictrim.py | 8 ++--- sharpy/solvers/staticuvlm.py | 29 ++++++--------- sharpy/solvers/steplinearuvlm.py | 30 ++++++---------- sharpy/solvers/stepuvlm.py | 35 ++++++++----------- sharpy/solvers/timeintegrators.py | 12 +++---- sharpy/solvers/trim.py | 6 ++-- sharpy/structure/utils/lagrangeconstraints.py | 8 +---- sharpy/utils/settings.py | 9 +++++ sharpy/utils/solver_interface.py | 2 +- 47 files changed, 336 insertions(+), 309 deletions(-) diff --git a/sharpy/postproc/aeroforcescalculator.py b/sharpy/postproc/aeroforcescalculator.py index a12293226..4c41cafc9 100644 --- a/sharpy/postproc/aeroforcescalculator.py +++ b/sharpy/postproc/aeroforcescalculator.py @@ -3,7 +3,7 @@ import sharpy.utils.cout_utils as cout from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra import sharpy.aero.utils.mapping as mapping @@ -54,7 +54,7 @@ class AeroForcesCalculator(BaseSolver): settings_default['c_ref'] = 1 settings_description['c_ref'] = 'Reference chord' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -72,7 +72,7 @@ def initialise(self, data, custom_settings=None, caller=None): self.data = data self.settings = data.settings[self.solver_id] self.ts_max = len(self.data.structure.timestep_info) - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.caller = caller self.folder = data.output_folder + '/forces/' @@ -87,7 +87,9 @@ def initialise(self, data, custom_settings=None, caller=None): self.table = cout.TablePrinter(7, field_length=12, field_types=['g'] + 6 * ['e']) self.table.print_header(['tstep', 'fx_g', 'fy_g', 'fz_g', 'mx_g', 'my_g', 'mz_g']) - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) if online: self.ts_max = len(self.data.structure.timestep_info) diff --git a/sharpy/postproc/aerogridplot.py b/sharpy/postproc/aerogridplot.py index d6ace9822..fd644fe99 100644 --- a/sharpy/postproc/aerogridplot.py +++ b/sharpy/postproc/aerogridplot.py @@ -7,7 +7,7 @@ import sharpy.utils.cout_utils as cout from sharpy.utils.settings import str2bool from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.aero.utils.uvlmlib as uvlmlib from sharpy.utils.constants import vortex_radius_def @@ -81,7 +81,7 @@ class AerogridPlot(BaseSolver): settings_default['save_wake'] = True settings_description['save_wake'] = 'Plot the wake' - table = settings.SettingsTable() + table = su.SettingsTable() __doc__ += table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -100,7 +100,7 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.ts_max = self.data.ts + 1 # create folder for containing files if necessary self.folder = data.output_folder + '/aero/' @@ -116,7 +116,10 @@ def initialise(self, data, custom_settings=None, caller=None): self.data.settings['SHARPy']['case']) self.caller = caller - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) + # TODO: Create a dictionary to plot any variable as in beamplot if not online: for self.ts in range(self.ts_max): diff --git a/sharpy/postproc/asymptoticstability.py b/sharpy/postproc/asymptoticstability.py index 6239fe9df..fef9c840b 100644 --- a/sharpy/postproc/asymptoticstability.py +++ b/sharpy/postproc/asymptoticstability.py @@ -2,7 +2,7 @@ import warnings as warn import numpy as np import scipy.linalg as sclalg -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.solver_interface import solver, BaseSolver, initialise_solver import sharpy.utils.cout_utils as cout import sharpy.utils.algebra as algebra @@ -77,7 +77,7 @@ class AsymptoticStability(BaseSolver): settings_default['postprocessors_settings'] = dict() settings_description['postprocessors_settings'] = 'To be used with ``modes_to_plot``. Under development.' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -103,7 +103,7 @@ def initialise(self, data, custom_settings=None, caller=None): else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) + su.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) self.num_evals = self.settings['num_evals'] @@ -121,7 +121,7 @@ def initialise(self, data, custom_settings=None, caller=None): self.caller = caller - def run(self, online=False): + def run(self, **kwargs): """ Computes the eigenvalues and eigenvectors @@ -130,6 +130,9 @@ def run(self, online=False): eigenvectors (np.ndarray): Corresponding mode shapes """ + + online = su.set_value_or_default(kwargs, 'online', False) + try: self.frequency_cutoff = self.settings['frequency_cutoff'] except AttributeError: diff --git a/sharpy/postproc/beamloads.py b/sharpy/postproc/beamloads.py index 9eedbe92c..4d20587db 100644 --- a/sharpy/postproc/beamloads.py +++ b/sharpy/postproc/beamloads.py @@ -2,7 +2,7 @@ import numpy as np import os from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.structure.utils.xbeamlib as xbeamlib @@ -27,7 +27,7 @@ class BeamLoads(BaseSolver): settings_default['output_file_name'] = 'beam_loads' settings_description['output_file_name'] = 'Output file name' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -44,14 +44,17 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.caller = caller self.folder = data.output_folder + '/beam/' if not os.path.isdir(self.folder): os.makedirs(self.folder) - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) + self.calculate_loads(online) if self.settings['csv_output']: self.print_loads(online) diff --git a/sharpy/postproc/beamplot.py b/sharpy/postproc/beamplot.py index b3ea5bf97..4ca1268ec 100644 --- a/sharpy/postproc/beamplot.py +++ b/sharpy/postproc/beamplot.py @@ -5,7 +5,7 @@ import sharpy.utils.cout_utils as cout from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra @@ -45,7 +45,7 @@ class BeamPlot(BaseSolver): settings_default['output_rbm'] = True settings_description['output_rbm'] = 'Write ``csv`` file with rigid body motion data' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -64,7 +64,7 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) # create folder for containing files if necessary self.folder = data.output_folder + '/beam/' if not os.path.exists(self.folder): @@ -79,7 +79,10 @@ def initialise(self, data, custom_settings=None, caller=None): self.data.settings['SHARPy']['case']) self.caller = caller - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) + self.plot(online) if not online: self.write() diff --git a/sharpy/postproc/cleanup.py b/sharpy/postproc/cleanup.py index 83ab85ea0..90294f579 100644 --- a/sharpy/postproc/cleanup.py +++ b/sharpy/postproc/cleanup.py @@ -5,7 +5,7 @@ import sharpy.utils.cout_utils as cout from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra import sharpy.structure.utils.xbeamlib as xbeamlib @@ -34,7 +34,7 @@ class Cleanup(BaseSolver): settings_default['remaining_steps'] = 10 settings_description['remaining_steps'] = 'The last `remaining_steps` are not cleaned up' - table = settings.SettingsTable() + table = su.SettingsTable() __doc__ += table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -48,12 +48,15 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default) self.caller = caller - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) + if self.settings['clean_structure']: self.clean(self.data.structure.timestep_info, self.settings['remaining_steps']) if self.settings['clean_aero']: diff --git a/sharpy/postproc/frequencyresponse.py b/sharpy/postproc/frequencyresponse.py index 395e02d10..54d9eab52 100644 --- a/sharpy/postproc/frequencyresponse.py +++ b/sharpy/postproc/frequencyresponse.py @@ -2,7 +2,7 @@ import time import os import sharpy.utils.solver_interface as solver_interface -import sharpy.utils.settings as settings_utils +import sharpy.utils.settings as su import sharpy.utils.cout_utils as cout import warnings import sharpy.linear.src.libss as libss @@ -74,7 +74,7 @@ class FrequencyResponse(solver_interface.BaseSolver): settings_default['quick_plot'] = False settings_description['quick_plot'] = 'Produce array of ``.png`` plots showing response. Requires matplotlib.' - settings_table = settings_utils.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options) def __init__(self): @@ -96,9 +96,11 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = self.data.settings[self.solver_id] else: self.settings = custom_settings - settings_utils.to_custom_types(self.settings, self.settings_types, self.settings_default, - self.settings_options, - no_ctype=True) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + self.settings_options, + no_ctype=True) self.print_info = self.settings['print_info'] @@ -127,7 +129,8 @@ def initialise(self, data, custom_settings=None, caller=None): os.makedirs(self.folder) self.caller = caller - def run(self, ss=None, online=False): + + def run(self, **kwargs): """ Computes the frequency response of the linear state-space. @@ -136,7 +139,8 @@ def run(self, ss=None, online=False): If not given, the response for the previously assembled systems and specified in ``target_system`` will be performed. """ - # TODO: This postproc does not have an standard call. Maybe a @staticmethod might help + online = su.set_value_or_default(kwargs, 'online', False) + ss = su.set_value_or_default(kwargs, 'ss', None) if ss is None: ss_list = [find_target_system(self.data, system_name) for system_name in self.settings['target_system']] diff --git a/sharpy/postproc/liftdistribution.py b/sharpy/postproc/liftdistribution.py index 69908c26c..c6d319a72 100644 --- a/sharpy/postproc/liftdistribution.py +++ b/sharpy/postproc/liftdistribution.py @@ -7,7 +7,7 @@ import sharpy.utils.cout_utils as cout from sharpy.utils.settings import str2bool from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.datastructures import init_matrix_structure, standalone_ctypes_pointer import sharpy.aero.utils.uvlmlib as uvlmlib @@ -39,11 +39,14 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.ts_max = len(self.data.structure.timestep_info) self.caller = caller - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) + if not online: for self.ts in range(self.ts_max): self.lift_distribution() diff --git a/sharpy/postproc/pickledata.py b/sharpy/postproc/pickledata.py index 33e0df30d..5cfabb313 100644 --- a/sharpy/postproc/pickledata.py +++ b/sharpy/postproc/pickledata.py @@ -6,7 +6,7 @@ import sharpy import sharpy.utils.cout_utils as cout from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.h5utils as h5utils @@ -35,7 +35,7 @@ class PickleData(BaseSolver): settings_default['stride'] = 1 settings_description['stride'] = 'Number of steps between the execution calls when run online' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -53,16 +53,23 @@ def initialise(self, data, custom_settings=None, caller=None): else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, self.settings_default) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default) self.folder = data.output_folder self.filename = self.folder + self.data.settings['SHARPy']['case']+'.pkl' self.caller = caller - def run(self, online=False): + + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) + solvers = su.set_value_or_default(kwargs, 'solvers', None) + if ((online and (self.data.ts % self.settings['stride'] == 0)) or (not online)): with open(self.filename, 'wb') as f: pickle.dump(self.data, f, protocol=pickle.HIGHEST_PROTOCOL) + pickle.dump(solvers, f, protocol=pickle.HIGHEST_PROTOCOL) return self.data diff --git a/sharpy/postproc/plotflowfield.py b/sharpy/postproc/plotflowfield.py index ee4f6c060..c5840e449 100644 --- a/sharpy/postproc/plotflowfield.py +++ b/sharpy/postproc/plotflowfield.py @@ -3,7 +3,7 @@ from tvtk.api import tvtk, write_data from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.utils.generator_interface as gen_interface -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.aero.utils.uvlmlib as uvlmlib import ctypes as ct from sharpy.utils.constants import vortex_radius_def @@ -63,7 +63,7 @@ class PlotFlowField(BaseSolver): settings_default['vortex_radius'] = vortex_radius_def settings_description['vortex_radius'] = 'Distance below which inductions are not computed.' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options) def __init__(self): @@ -78,8 +78,10 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, - self.settings_options) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + self.settings_options) self.folder = data.output_folder + '/' + 'GenerateFlowField/' if not os.path.isdir(self.folder): @@ -180,7 +182,10 @@ def output_velocity_field(self, ts): filename = self.folder + "VelocityField_" + '%06u' % ts + ".vtk" write_data(vtk_info, filename) - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) + if online: if divmod(self.data.ts, self.settings['stride'])[1] == 0: self.output_velocity_field(len(self.data.structure.timestep_info) - 1) diff --git a/sharpy/postproc/savedata.py b/sharpy/postproc/savedata.py index a236afba9..532383e39 100644 --- a/sharpy/postproc/savedata.py +++ b/sharpy/postproc/savedata.py @@ -4,7 +4,7 @@ import sharpy import sharpy.utils.cout_utils as cout from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.h5utils as h5utils from sharpy.presharpy.presharpy import PreSharpy @@ -94,7 +94,7 @@ class SaveData(BaseSolver): settings_default['stride'] = 1 settings_description['stride'] = 'Number of steps between the execution calls when run online' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options=settings_options) @@ -120,8 +120,10 @@ def initialise(self, data, custom_settings=None, caller=None): else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, self.settings_default, options=self.settings_options) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + options=self.settings_options) # Add these anyway - therefore if you add your own skip_attr you don't have to retype all of these self.settings['skip_attr'].extend(['fortran', @@ -193,7 +195,9 @@ def initialise(self, data, custom_settings=None, caller=None): self.ClassesToSave += (sharpy.solvers.linearassembler.Linear, sharpy.linear.src.libss.ss) self.caller = caller - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) # Use the following statement in case the ct types are not defined and # you need them on uvlm3d diff --git a/sharpy/postproc/saveparametriccase.py b/sharpy/postproc/saveparametriccase.py index b16d733ba..fea8ad6fb 100644 --- a/sharpy/postproc/saveparametriccase.py +++ b/sharpy/postproc/saveparametriccase.py @@ -1,5 +1,5 @@ from sharpy.utils.solver_interface import solver, BaseSolver, initialise_solver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import configobj import os import sharpy.utils.cout_utils as cout @@ -48,7 +48,7 @@ class SaveParametricCase(BaseSolver): settings_default['parameters'] = None settings_description['parameters'] = 'Dictionary containing the chosen simulation parameters and their values.' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -64,14 +64,15 @@ def initialise(self, data, custom_settings=None): else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default - ) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default) self.folder = data.output_folder - def run(self): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) config = configobj.ConfigObj() file_name = self.folder + '/' + self.data.settings['SHARPy']['case'] + '.pmor.sharpy' diff --git a/sharpy/postproc/stabilityderivatives.py b/sharpy/postproc/stabilityderivatives.py index abf096b63..f861d2b67 100644 --- a/sharpy/postproc/stabilityderivatives.py +++ b/sharpy/postproc/stabilityderivatives.py @@ -3,7 +3,7 @@ import numpy as np import sharpy.utils.cout_utils as cout import sharpy.utils.algebra as algebra -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.linear.utils.derivatives import Derivatives, DerivativeSet import sharpy.linear.utils.derivatives as derivatives_utils @@ -42,7 +42,7 @@ class StabilityDerivatives(solver_interface.BaseSolver): settings_default['c_ref'] = 1. settings_description['c_ref'] = 'Reference chord' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -65,9 +65,11 @@ def initialise(self, data, custom_settings=None, caller=None): else: self.settings = self.data.settings[self.solver_id] - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, - options=self.settings_options, - no_ctype=True) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + options=self.settings_options, + no_ctype=True) self.caller = caller self.folder = data.output_folder + '/derivatives/' if not os.path.isdir(self.folder): @@ -102,7 +104,9 @@ def initialise(self, data, custom_settings=None, caller=None): target_system='aeroelastic') - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) # TODO: consider running all required solvers inside this one to keep the correct settings # i.e: run Modal, Linear Ass diff --git a/sharpy/postproc/stallcheck.py b/sharpy/postproc/stallcheck.py index b283dd4af..b1b8a7c4b 100644 --- a/sharpy/postproc/stallcheck.py +++ b/sharpy/postproc/stallcheck.py @@ -1,7 +1,7 @@ import numpy as np import sharpy.utils.cout_utils as cout from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.datastructures import init_matrix_structure, standalone_ctypes_pointer import sharpy.aero.utils.uvlmlib as uvlmlib @@ -43,7 +43,7 @@ class StallCheck(BaseSolver): settings_default['output_degrees'] = False settings_description['output_degrees'] = 'Output incidence angles in degrees vs radians' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -61,11 +61,14 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.ts_max = len(self.data.structure.timestep_info) self.caller = caller - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) + if not online: for self.ts in range(self.ts_max): self.check_stall() diff --git a/sharpy/postproc/udpout.py b/sharpy/postproc/udpout.py index 86a91dbd2..ced44989a 100644 --- a/sharpy/postproc/udpout.py +++ b/sharpy/postproc/udpout.py @@ -1,5 +1,5 @@ from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.io.network_interface as network_interface import sharpy.utils.cout_utils as cout @@ -33,7 +33,7 @@ class UDPout(BaseSolver): del settings_default['send_output_to_all_clients'] del settings_description['send_output_to_all_clients'] - table = settings.SettingsTable() + table = su.SettingsTable() __doc__ += table.generate(settings_types, settings_default, settings_description, header_line='This post-processor takes in the following settings, for a more ' 'detailed description see ' @@ -69,7 +69,9 @@ def initialise(self, data, custom_settings=None, caller=None): self.caller = caller - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) if online: self.set_of_variables.get_value(self.data) diff --git a/sharpy/postproc/writevariablestime.py b/sharpy/postproc/writevariablestime.py index 17b6355d4..403af1301 100644 --- a/sharpy/postproc/writevariablestime.py +++ b/sharpy/postproc/writevariablestime.py @@ -1,7 +1,7 @@ import os import numpy as np from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su @solver @@ -92,7 +92,7 @@ class WriteVariablesTime(BaseSolver): settings_default['vel_field_points'] = np.array([0., 0., 0.]) settings_description['vel_field_points'] = 'List of coordinates of the control points as x1, y1, z1, x2, y2, z2 ...' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -111,7 +111,7 @@ def initialise(self, data, custom_settings=None, caller=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.folder = data.output_folder + '/WriteVariablesTime/' if not os.path.isdir(self.folder): @@ -193,7 +193,9 @@ def initialise(self, data, custom_settings=None, caller=None): # For coupled solvers self.velocity_generator = self.caller.aero_solver.velocity_generator - def run(self, online=False): + def run(self, **kwargs): + + online = su.set_value_or_default(kwargs, 'online', False) if online: self.data = self.write(-1) diff --git a/sharpy/presharpy/presharpy.py b/sharpy/presharpy/presharpy.py index 5fbfdab71..d025c6616 100644 --- a/sharpy/presharpy/presharpy.py +++ b/sharpy/presharpy/presharpy.py @@ -82,7 +82,6 @@ def __init__(self, in_settings=None): self._settings = False self.ts = 0 - self.solvers = dict() if self._settings: self.settings = in_settings diff --git a/sharpy/sharpy_main.py b/sharpy/sharpy_main.py index cdb4c8e5f..2ce0874e9 100644 --- a/sharpy/sharpy_main.py +++ b/sharpy/sharpy_main.py @@ -85,10 +85,12 @@ def main(args=None, sharpy_input_dict=None): if args.restart is None: # run preSHARPy data = PreSharpy(settings) + solvers = dict() else: try: with open(args.restart, 'rb') as restart_file: data = pickle.load(restart_file) + solvers = pickle.load(restart_file) except FileNotFoundError: raise FileNotFoundError('The file specified for the snapshot \ restart (-r) does not exist. Please check.') @@ -107,18 +109,18 @@ def main(args=None, sharpy_input_dict=None): # data.structure.dynamic_input.append(dict()) # Restart the solvers - old_solvers_list = list(data.solvers.keys()) + old_solvers_list = list(solvers.keys()) for old_solver_name in old_solvers_list: if old_solver_name not in settings['SHARPy']['flow']: - del data.solvers[old_solver_name] + del solvers[old_solver_name] # Loop for the solvers specified in *.sharpy['SHARPy']['flow'] for solver_name in settings['SHARPy']['flow']: - if (args.restart is None) or (solver_name not in data.solvers.keys()): - data.solvers[solver_name] = solver_interface.initialise_solver(solver_name) - data.solvers[solver_name].initialise(data) - data = data.solvers[solver_name].run() - data.solvers[solver_name].teardown() + if (args.restart is None) or (solver_name not in solvers.keys()): + solvers[solver_name] = solver_interface.initialise_solver(solver_name) + solvers[solver_name].initialise(data) + data = solvers[solver_name].run(solvers=solvers) + solvers[solver_name].teardown() cpu_time = time.process_time() - t wall_time = time.perf_counter() - t0_wall diff --git a/sharpy/solvers/_basestructural.py b/sharpy/solvers/_basestructural.py index e1bf1cbf1..8398eac86 100644 --- a/sharpy/solvers/_basestructural.py +++ b/sharpy/solvers/_basestructural.py @@ -1,5 +1,4 @@ from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings import sharpy.utils.cout_utils as cout @solver @@ -67,5 +66,5 @@ class _BaseStructural(BaseSolver): def initialise(self, data): pass - def run(self): + def run(self, **kwargs): pass diff --git a/sharpy/solvers/aerogridloader.py b/sharpy/solvers/aerogridloader.py index 486ee70d7..1c0eaaa54 100644 --- a/sharpy/solvers/aerogridloader.py +++ b/sharpy/solvers/aerogridloader.py @@ -3,7 +3,7 @@ from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.aero.models.aerogrid as aerogrid -import sharpy.utils.settings as settings_utils +import sharpy.utils.settings as su import sharpy.utils.h5utils as h5utils import sharpy.utils.generator_interface as gen_interface @@ -82,7 +82,7 @@ class AerogridLoader(BaseSolver): settings_default['wake_shape_generator_input'] = dict() settings_description['wake_shape_generator_input'] = 'Dictionary of inputs needed by the wake shape generator' - settings_table = settings_utils.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -102,9 +102,9 @@ def initialise(self, data): self.settings = data.settings[self.solver_id] # init settings - settings_utils.to_custom_types(self.settings, - self.settings_types, - self.settings_default) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default) # read input file (aero) self.read_files() @@ -131,7 +131,7 @@ def read_files(self): # store files in dictionary self.aero_data_dict = h5utils.load_h5_in_dict(aero_file_handle) - def run(self): + def run(self, **kwargs): self.data.aero = aerogrid.Aerogrid() self.data.aero.generate(self.aero_data_dict, self.data.structure, diff --git a/sharpy/solvers/beamloader.py b/sharpy/solvers/beamloader.py index 95b92e66f..7e1d09fae 100644 --- a/sharpy/solvers/beamloader.py +++ b/sharpy/solvers/beamloader.py @@ -3,7 +3,7 @@ from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.structure.models.beam as beam -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.h5utils as h5utils import os @@ -60,7 +60,7 @@ class BeamLoader(BaseSolver): settings_default['for_pos'] = [0., 0, 0] settings_description['for_pos'] = 'Initial position of the A FoR.' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -81,7 +81,7 @@ def initialise(self, data): self.settings = data.settings[self.solver_id] # init settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) # read input files (fem and dyn) self.read_files() @@ -131,7 +131,7 @@ def validate_fem_file(self): def validate_dyn_file(self): raise NotImplementedError('validation of the dyn file in beamloader is not yet implemented!') - def run(self): + def run(self, **kwargs): self.data.structure = beam.Beam() self.data.structure.ini_mb_dict = self.mb_data_dict self.data.structure.generate(self.fem_data_dict, self.settings) diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 6f313ef58..7a72a6a1b 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -13,7 +13,7 @@ import sharpy.utils.solver_interface as solver_interface import sharpy.utils.controller_interface as controller_interface from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra import sharpy.utils.exceptions as exc import sharpy.io.network_interface as network_interface @@ -178,7 +178,7 @@ class DynamicCoupled(BaseSolver): 'The dictionary values are dictionaries with the settings ' \ 'needed by each generator.' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options) def __init__(self): @@ -254,10 +254,10 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default, - options=self.settings_options) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + options=self.settings_options) self.original_settings = copy.deepcopy(self.settings) @@ -429,12 +429,12 @@ def process_controller_output(self, controlled_state): return controlled_state['structural'], controlled_state['aero'] - def run(self): + def run(self, **kwargs): """ Run the time stepping procedure with controllers and postprocessors included. """ - + solvers = su.set_value_or_default(kwargs, 'solvers', None) if self.network_loader is not None: self.set_of_variables = self.network_loader.get_inout_variables() @@ -444,7 +444,7 @@ def run(self): finish_event = threading.Event() with concurrent.futures.ThreadPoolExecutor(max_workers=2) as executor: netloop = executor.submit(self.network_loop, incoming_queue, outgoing_queue, finish_event) - timeloop = executor.submit(self.time_loop, incoming_queue, outgoing_queue, finish_event) + timeloop = executor.submit(self.time_loop, incoming_queue, outgoing_queue, finish_event, solvers) # TODO: improve exception handling to get exceptions when they happen from each thread for t1 in [netloop, timeloop]: @@ -455,7 +455,7 @@ def run(self): raise Exception else: - self.time_loop() + self.time_loop(solvers=solvers) if self.print_info: cout.cout_wrap('...Finished', 1) @@ -498,7 +498,7 @@ def network_loop(self, in_queue, out_queue, finish_event): in_network.close() out_network.close() - def time_loop(self, in_queue=None, out_queue=None, finish_event=None): + def time_loop(self, in_queue=None, out_queue=None, finish_event=None, solvers=None): self.logger.debug('Inside time loop') # dynamic simulations start at tstep == 1, 0 is reserved for the initial state for self.data.ts in range( @@ -592,8 +592,8 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): # run the solver ini_time_aero = time.perf_counter() - self.data = self.aero_solver.run(aero_kstep, - structural_kstep, + self.data = self.aero_solver.run(aero_step=aero_kstep, + structural_step=structural_kstep, convect_wake=True, unsteady_contribution=unsteady_contribution) self.time_aero += time.perf_counter() - ini_time_aero @@ -688,7 +688,7 @@ def time_loop(self, in_queue=None, out_queue=None, finish_event=None): # run postprocessors if self.with_postprocessors: for postproc in self.postprocessors: - self.data = self.postprocessors[postproc].run(online=True) + self.data = self.postprocessors[postproc].run(online=True, solvers=solvers) # network only # put result back in queue diff --git a/sharpy/solvers/dynamicuvlm.py b/sharpy/solvers/dynamicuvlm.py index 6fc505cf5..1ec32e032 100644 --- a/sharpy/solvers/dynamicuvlm.py +++ b/sharpy/solvers/dynamicuvlm.py @@ -9,7 +9,7 @@ import sharpy.utils.solver_interface as solver_interface from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.cout_utils as cout @solver @@ -74,7 +74,7 @@ class DynamicUVLM(BaseSolver): settings_default['postprocessors_settings'] = dict() settings_description['postprocessors_settings'] = 'Dictionary with the applicable settings for every ``psotprocessor``. Every ``postprocessor`` needs its entry, even if empty' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -98,7 +98,7 @@ def initialise(self, data, custom_settings=None): else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.dt = self.settings['dt'] self.print_info = self.settings['print_info'] @@ -119,7 +119,7 @@ def initialise(self, data, custom_settings=None): self.residual_table = cout.TablePrinter(2, 14, ['g', 'f']) self.residual_table.print_header(['ts', 't']) - def run(self): + def run(self, **kwargs): # struct info - only for orientation, no structural solution is performed struct_ini_step = self.data.structure.timestep_info[-1] diff --git a/sharpy/solvers/initialaeroelasticloader.py b/sharpy/solvers/initialaeroelasticloader.py index d9458e52f..08ef1d89d 100644 --- a/sharpy/solvers/initialaeroelasticloader.py +++ b/sharpy/solvers/initialaeroelasticloader.py @@ -2,7 +2,7 @@ import h5py as h5 from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra import sharpy.utils.h5utils as h5utils import sharpy.utils.exceptions as exceptions @@ -29,7 +29,7 @@ class InitialAeroelasticLoader(BaseSolver): settings_default['include_forces'] = True settings_description['include_forces'] = 'Map the forces' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -44,20 +44,18 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default, - no_ctype=True) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + no_ctype=True) # Load simulation data self.file_info = h5utils.readh5(self.settings['input_file']) - def run(self, structural_step=None, aero_step=None): - - if structural_step is None: - structural_step = self.data.structure.timestep_info[-1] - if aero_step is None: - aero_step = self.data.aero.timestep_info[-1] + def run(self, **kwargs): + aero_step = su.set_value_or_default(kwargs, 'aero_step', self.data.aero.timestep_info[-1]) + structural_step = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + # Copy structural information attributes = ['pos', 'pos_dot', 'pos_ddot', 'psi', 'psi_dot', 'psi_ddot', diff --git a/sharpy/solvers/lindynamicsim.py b/sharpy/solvers/lindynamicsim.py index b28771191..93e713e0d 100644 --- a/sharpy/solvers/lindynamicsim.py +++ b/sharpy/solvers/lindynamicsim.py @@ -2,7 +2,7 @@ import os import h5py as h5 from sharpy.utils.solver_interface import solver, BaseSolver, initialise_solver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.linear.src.libss as libss import scipy.linalg as sclalg import sharpy.utils.h5utils as h5utils @@ -73,7 +73,7 @@ class LinDynamicSim(BaseSolver): settings_types['postprocessors_settings'] = 'dict' settings_default['postprocessors_settings'] = dict() - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -95,7 +95,7 @@ def initialise(self, data, custom_settings=None): self.settings = custom_settings else: self.settings = data.settings[self.solver_id] - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) + su.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) # Read initial state and input data and store in dictionary self.read_files() @@ -149,7 +149,7 @@ def input_vector(self, ss): return u_vect - def run(self): + def run(self, **kwargs): ss = self.data.linear.ss diff --git a/sharpy/solvers/linearassembler.py b/sharpy/solvers/linearassembler.py index e65a97bed..2c5d4eaf8 100644 --- a/sharpy/solvers/linearassembler.py +++ b/sharpy/solvers/linearassembler.py @@ -5,7 +5,7 @@ from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.linear.utils.ss_interface as ss_interface -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.h5utils as h5 import sharpy.utils.cout_utils as cout @@ -105,7 +105,7 @@ class LinearAssembler(BaseSolver): settings_default['recover_accelerations'] = False settings_description['recover_accelerations'] = 'Recover structural system accelerations as additional outputs.' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options) def __init__(self): @@ -123,8 +123,11 @@ def initialise(self, data, custom_settings=None): else: self.settings = data.settings[self.solver_id] - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, - options=self.settings_options, no_ctype=True) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + options=self.settings_options, + no_ctype=True) # Get consistent linearisation timestep ii_step = self.settings['linearisation_tstep'] @@ -151,7 +154,7 @@ def initialise(self, data, custom_settings=None): lsys.initialise(data) self.data.linear.linear_system = lsys - def run(self): + def run(self, **kwargs): self.data.linear.ss = self.data.linear.linear_system.assemble() diff --git a/sharpy/solvers/modal.py b/sharpy/solvers/modal.py index a9c5ea69e..7ca8cafb2 100644 --- a/sharpy/solvers/modal.py +++ b/sharpy/solvers/modal.py @@ -6,7 +6,7 @@ import warnings import sharpy.structure.utils.xbeamlib as xbeamlib from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra import sharpy.utils.cout_utils as cout import sharpy.structure.utils.modalutils as modalutils @@ -95,7 +95,7 @@ class Modal(BaseSolver): settings_default['rigid_modes_cg'] = False settings_description['rigid_modes_cg'] = 'Not implemente yet' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -115,9 +115,9 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default) self.rigid_body_motion = self.settings['rigid_body_modes'] @@ -151,7 +151,7 @@ def initialise(self, data, custom_settings=None): self.eigenvalue_table = modalutils.EigenvalueTable(filename=eigenvalue_filename) self.eigenvalue_table.print_header(self.eigenvalue_table.headers) - def run(self): + def run(self, **kwargs): r""" Extracts the eigenvalues and eigenvectors of the clamped structure. @@ -236,7 +236,7 @@ def run(self): # full_matrix_settings = self.data.settings['DynamicCoupled']['structural_solver_settings'] import sharpy.solvers._basestructural as basestructuralsolver full_matrix_settings = basestructuralsolver._BaseStructural().settings_default - settings.to_custom_types(full_matrix_settings, basestructuralsolver._BaseStructural().settings_types, full_matrix_settings) + su.to_custom_types(full_matrix_settings, basestructuralsolver._BaseStructural().settings_types, full_matrix_settings) # Obtain the tangent mass, damping and stiffness matrices diff --git a/sharpy/solvers/noaero.py b/sharpy/solvers/noaero.py index e952bb253..77a778664 100644 --- a/sharpy/solvers/noaero.py +++ b/sharpy/solvers/noaero.py @@ -1,4 +1,4 @@ -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.solver_interface import solver, BaseSolver @@ -28,7 +28,7 @@ class NoAero(BaseSolver): settings_default['update_grid'] = True settings_description['update_grid'] = 'Update aerodynamic grid as the structure deforms.' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -41,25 +41,24 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default, - no_ctype=True) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + no_ctype=True) if len(self.data.aero.timestep_info) == 0: # initialise with zero timestep for static sims self.update_step() - def run(self, - aero_tstep=None, - structure_tstep=None, - convect_wake=True, - dt=None, - t=None, - unsteady_contribution=False): + def run(self, **kwargs): + + aero_tstep = su.set_value_or_default(kwargs, 'aero_step', self.data.aero.timestep_info[-1]) + structure_tstep = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + convect_wake = su.set_value_or_default(kwargs, 'convect_wake', True) + dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) + t = su.set_value_or_default(kwargs, 't', self.data.ts*dt) + unsteady_contribution = su.set_value_or_default(kwargs, 'unsteady_contribution', False) # generate the wake because the solid shape might change - if aero_tstep is None: - aero_tstep = self.data.aero.timestep_info[self.data.ts] self.data.aero.wake_shape_generator.generate({'zeta': aero_tstep.zeta, 'zeta_star': aero_tstep.zeta_star, 'gamma': aero_tstep.gamma, diff --git a/sharpy/solvers/nonlineardynamic.py b/sharpy/solvers/nonlineardynamic.py index 03faf9001..a02776366 100644 --- a/sharpy/solvers/nonlineardynamic.py +++ b/sharpy/solvers/nonlineardynamic.py @@ -8,7 +8,7 @@ import sharpy.structure.utils.xbeamlib as xbeamlib from sharpy.utils.settings import str2bool from sharpy.utils.solver_interface import solver, BaseSolver, solver_from_string -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.cout_utils as cout _BaseStructural = solver_from_string('_BaseStructural') @@ -38,7 +38,7 @@ class NonLinearDynamic(_BaseStructural): settings_types['gravity_dir'] = 'list(float)' settings_default['gravity_dir'] = [0, 0, 1] - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -48,7 +48,7 @@ def __init__(self): def initialise(self, data): self.data = data self.settings = data.settings[self.solver_id] - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) # load info from dyn dictionary self.data.structure.add_unsteady_information(self.data.structure.dyn_dict, self.settings['num_steps']) @@ -61,7 +61,7 @@ def initialise(self, data): self.data.structure.timestep_info[i].steady_applied_forces[:] = self.data.structure.ini_info.steady_applied_forces - def run(self): + def run(self, **kwargs): prescribed_motion = False try: prescribed_motion = self.settings['prescribed_motion'] diff --git a/sharpy/solvers/nonlineardynamiccoupledstep.py b/sharpy/solvers/nonlineardynamiccoupledstep.py index c4ba08282..32ff12e8b 100644 --- a/sharpy/solvers/nonlineardynamiccoupledstep.py +++ b/sharpy/solvers/nonlineardynamiccoupledstep.py @@ -8,7 +8,7 @@ import sharpy.structure.utils.xbeamlib as xbeamlib from sharpy.utils.settings import str2bool from sharpy.utils.solver_interface import solver, BaseSolver, solver_from_string -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra import sharpy.utils.cout_utils as cout @@ -50,7 +50,7 @@ class NonLinearDynamicCoupledStep(_BaseStructural): settings_default['relaxation_factor'] = 0.3 settings_description['relaxation factor'] = 'Relaxation factor' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -63,7 +63,7 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) # load info from dyn dictionary self.data.structure.add_unsteady_information(self.data.structure.dyn_dict, self.settings['num_steps']) @@ -77,9 +77,12 @@ def initialise(self, data, custom_settings=None): # generate q, dqdt and dqddt xbeamlib.xbeam_solv_disp2state(self.data.structure, self.data.structure.timestep_info[-1]) - def run(self, structural_step, previous_structural_step=None, dt=None): - if dt is None: - dt = self.settings['dt'] + def run(self, **kwargs): + + structural_step = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + # TODO: previous_structural_step never used + previous_structural_step = su.set_value_or_default(kwargs, 'previous_structural_step', self.data.structure.timestep_info[-1]) + dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) xbeamlib.xbeam_step_couplednlndyn(self.data.structure, self.settings, diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index ec5d42cd1..769e2a5ec 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -3,7 +3,7 @@ import os from sharpy.utils.solver_interface import solver, BaseSolver, solver_from_string -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.solver_interface as solver_interface import sharpy.utils.cout_utils as cout @@ -62,7 +62,7 @@ class NonLinearDynamicMultibody(_BaseStructural): settings_default['zero_ini_dot_ddot'] = False settings_description['zero_ini_dot_ddot'] = 'Set to zero the position and crv derivatives at the first time step' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -91,11 +91,11 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default, - self.settings_options, - no_ctype=True) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + self.settings_options, + no_ctype=True) # load info from dyn dictionary self.data.structure.add_unsteady_information( @@ -352,20 +352,15 @@ def write_lm_cond_num(self, iteration, Lambda, Lambda_dot, Lambda_ddot, cond_num - def run(self, structural_step=None, dt=None): - if structural_step is None: - structural_step = self.data.structure.timestep_info[-1] + def run(self, **kwargs): + structural_step = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) if structural_step.mb_dict is not None: MBdict = structural_step.mb_dict else: MBdict = self.data.structure.ini_mb_dict - - if dt is None: - dt = self.settings['dt'] - else: - self.settings['dt'] = dt - + #if self.data.ts == 1: # compute_psi_local = True # print("Computing psi local") diff --git a/sharpy/solvers/nonlineardynamicprescribedstep.py b/sharpy/solvers/nonlineardynamicprescribedstep.py index 4c0610f8a..0d62cef56 100644 --- a/sharpy/solvers/nonlineardynamicprescribedstep.py +++ b/sharpy/solvers/nonlineardynamicprescribedstep.py @@ -8,7 +8,7 @@ import sharpy.structure.utils.xbeamlib as xbeamlib from sharpy.utils.settings import str2bool from sharpy.utils.solver_interface import solver, BaseSolver, solver_from_string -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.cout_utils as cout import sharpy.utils.algebra as algebra @@ -34,7 +34,7 @@ class NonLinearDynamicPrescribedStep(_BaseStructural): settings_default = _BaseStructural.settings_default.copy() settings_description = _BaseStructural.settings_description.copy() - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -47,17 +47,15 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) # load info from dyn dictionary self.data.structure.add_unsteady_information(self.data.structure.dyn_dict, self.settings['num_steps']) - def run(self, structural_step=None, dt=None): - if dt is None: - dt = self.settings['dt'] - if structural_step is None: - structural_step = self.data.structure.timestep_info[-1] + def run(self, **kwargs): + structural_step = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + dt = su.set_value_or_default(kwargs, 'dt', self.settings['dt']) if self.data.ts > 0: try: diff --git a/sharpy/solvers/nonlinearstatic.py b/sharpy/solvers/nonlinearstatic.py index ec5354b41..a48d1314f 100644 --- a/sharpy/solvers/nonlinearstatic.py +++ b/sharpy/solvers/nonlinearstatic.py @@ -2,7 +2,7 @@ import sharpy.structure.utils.xbeamlib as xbeamlib import sharpy.utils.cout_utils as cout -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.solver_interface import solver, BaseSolver, solver_from_string import sharpy.utils.algebra as algebra @@ -34,7 +34,7 @@ class NonLinearStatic(_BaseStructural): settings_types['initial_velocity'] = 'list(float)' settings_default['initial_velocity'] = np.array([0., 0., 0., 0., 0., 0.]) - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -47,9 +47,9 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) + su.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) - def run(self): + def run(self, **kwargs): self.data.structure.timestep_info[self.data.ts].for_pos[0:3] = self.settings['initial_position'] self.data.structure.timestep_info[self.data.ts].for_vel = self.settings['initial_velocity'].copy() xbeamlib.cbeam3_solv_nlnstatic(self.data.structure, self.settings, self.data.ts) diff --git a/sharpy/solvers/nostructural.py b/sharpy/solvers/nostructural.py index 44628c2b2..d9baf6703 100644 --- a/sharpy/solvers/nostructural.py +++ b/sharpy/solvers/nostructural.py @@ -1,7 +1,7 @@ import numpy as np import sharpy.utils.cout_utils as cout -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.solver_interface import solver, BaseSolver, solver_from_string _BaseStructural = solver_from_string('_BaseStructural') @@ -29,7 +29,7 @@ class NoStructural(_BaseStructural): settings_types['initial_position'] = 'list(float)' settings_default['initial_position'] = np.array([0.0, 0.0, 0.0]) - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -42,9 +42,9 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) - def run(self): + def run(self, **kwargs): self.data.structure.timestep_info[self.data.ts].for_pos[0:3] = self.settings['initial_position'] self.extract_resultants() return self.data diff --git a/sharpy/solvers/prescribeduvlm.py b/sharpy/solvers/prescribeduvlm.py index a3a46e228..a7507643a 100644 --- a/sharpy/solvers/prescribeduvlm.py +++ b/sharpy/solvers/prescribeduvlm.py @@ -2,7 +2,7 @@ import numpy as np import sharpy.utils.algebra as algebra -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.utils.solver_interface as solver_interface import sharpy.utils.cout_utils as cout @@ -70,7 +70,7 @@ class PrescribedUvlm(BaseSolver): settings_default['vortex_radius_wake_ind'] = vortex_radius_def settings_description['vortex_radius_wake_ind'] = 'Distance between points below which induction is not computed in the wake convection' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -88,7 +88,7 @@ def __init__(self): def initialise(self, data): self.data = data self.settings = data.settings[self.solver_id] - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.dt = self.settings['dt'] self.aero_solver = solver_interface.initialise_solver(self.settings['aero_solver']) @@ -127,7 +127,7 @@ def increase_ts(self): self.data.structure.next_step() self.aero_solver.add_step() - def run(self): + def run(self, **kwargs): structural_kstep = self.data.structure.ini_info.copy() # dynamic simulations start at tstep == 1, 0 is reserved for the initial state diff --git a/sharpy/solvers/rigiddynamiccoupledstep.py b/sharpy/solvers/rigiddynamiccoupledstep.py index 54ff72d2a..c7ebc82a2 100644 --- a/sharpy/solvers/rigiddynamiccoupledstep.py +++ b/sharpy/solvers/rigiddynamiccoupledstep.py @@ -4,7 +4,7 @@ import sharpy.structure.utils.xbeamlib as xbeamlib from sharpy.utils.settings import str2bool from sharpy.utils.solver_interface import solver, BaseSolver, solver_from_string -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra import sharpy.utils.cout_utils as cout @@ -37,7 +37,7 @@ class RigidDynamicCoupledStep(_BaseStructural): settings_default['relaxation_factor'] = 0.3 settings_description['relaxation factor'] = 'Relaxation factor' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -50,7 +50,7 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) # load info from dyn dictionary self.data.structure.add_unsteady_information(self.data.structure.dyn_dict, self.settings['num_steps']) @@ -58,15 +58,18 @@ def initialise(self, data, custom_settings=None): # generate q, dqdt and dqddt xbeamlib.xbeam_solv_disp2state(self.data.structure, self.data.structure.timestep_info[-1]) - def run(self, structural_step, previous_structural_step=None, dt=None): - if dt is None: - dt = self.settings['dt'] + def run(self, **kwargs): + + structural_step = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + # TODO: previous_structural_step never used + previous_structural_step = su.set_value_or_default(kwargs, 'previous_structural_step', self.data.structure.timestep_info[-1]) + dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) xbeamlib.xbeam_step_coupledrigid(self.data.structure, - self.settings, - self.data.ts, - structural_step, - dt=dt) + self.settings, + self.data.ts, + structural_step, + dt=dt) self.extract_resultants(structural_step) self.data.structure.integrate_position(structural_step, dt) diff --git a/sharpy/solvers/rigiddynamicprescribedstep.py b/sharpy/solvers/rigiddynamicprescribedstep.py index db709c3a1..4223c66ae 100644 --- a/sharpy/solvers/rigiddynamicprescribedstep.py +++ b/sharpy/solvers/rigiddynamicprescribedstep.py @@ -8,7 +8,7 @@ import sharpy.structure.utils.xbeamlib as xbeamlib # from sharpy.utils.settings import str2bool from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.cout_utils as cout import sharpy.utils.algebra as algebra from sharpy.utils.solver_interface import solver_from_string @@ -33,7 +33,7 @@ class RigidDynamicPrescribedStep(BaseSolver): settings_default['num_steps'] = 500 settings_description['num_steps'] = 'Number of timesteps to be run' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -47,17 +47,14 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) # load info from dyn dictionary self.data.structure.add_unsteady_information(self.data.structure.dyn_dict, self.settings['num_steps']) - def run(self, structural_step=None, dt=None): - - if structural_step is None: - structural_step = self.data.structure.timestep_info[-1] - if dt is None: - dt = self.settings['dt'] + def run(self, **kwargs): + structural_step = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) if self.data.ts > 0: try: diff --git a/sharpy/solvers/staticcoupled.py b/sharpy/solvers/staticcoupled.py index 7e0840c17..45a6a5b2d 100644 --- a/sharpy/solvers/staticcoupled.py +++ b/sharpy/solvers/staticcoupled.py @@ -6,7 +6,7 @@ import sharpy.utils.cout_utils as cout import sharpy.utils.solver_interface as solver_interface from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra import sharpy.utils.generator_interface as gen_interface @@ -76,7 +76,7 @@ class StaticCoupled(BaseSolver): 'The dictionary values are dictionaries with the settings ' \ 'needed by each generator.' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options) def __init__(self): @@ -102,11 +102,11 @@ def initialise(self, data, input_dict=None): self.settings = data.settings[self.solver_id] else: self.settings = input_dict - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default, - options=self.settings_options, - no_ctype=True) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + options=self.settings_options, + no_ctype=True) self.print_info = self.settings['print_info'] @@ -160,7 +160,7 @@ def cleanup_timestep_info(self): self.data.ts = 0 - def run(self): + def run(self, **kwargs): for i_step in range(self.settings['n_load_steps'] + 1): if (i_step == self.settings['n_load_steps'] and self.settings['n_load_steps'] > 0): diff --git a/sharpy/solvers/statictrim.py b/sharpy/solvers/statictrim.py index 15406987c..9d05a4b71 100644 --- a/sharpy/solvers/statictrim.py +++ b/sharpy/solvers/statictrim.py @@ -3,7 +3,7 @@ import sharpy.utils.cout_utils as cout import sharpy.utils.solver_interface as solver_interface from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import os @@ -90,7 +90,7 @@ class StaticTrim(BaseSolver): settings_default['save_info'] = False settings_description['save_info'] = 'Save trim results to text file' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -117,7 +117,7 @@ def __init__(self): def initialise(self, data): self.data = data self.settings = data.settings[self.solver_id] - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.solver = solver_interface.initialise_solver(self.settings['solver']) self.solver.initialise(self.data, self.settings['solver_settings']) @@ -135,7 +135,7 @@ def increase_ts(self): self.structural_solver.next_step() self.aero_solver.next_step() - def run(self): + def run(self, **kwargs): # In the event the modal solver has been run prior to StaticCoupled (i.e. to get undeformed modes), copy # results and then attach to the resulting timestep diff --git a/sharpy/solvers/staticuvlm.py b/sharpy/solvers/staticuvlm.py index 65f518cd9..e43a6cb72 100644 --- a/sharpy/solvers/staticuvlm.py +++ b/sharpy/solvers/staticuvlm.py @@ -4,7 +4,7 @@ import sharpy.utils.algebra as algebra import sharpy.aero.utils.uvlmlib as uvlmlib import sharpy.utils.cout_utils as cout -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.utils.generator_interface as gen_interface from sharpy.utils.constants import vortex_radius_def @@ -110,7 +110,7 @@ class StaticUvlm(BaseSolver): settings_default['centre_rot_g'] = [0., 0., 0.] settings_description['centre_rot_g'] = 'Centre of rotation in G FoR around which ``rbm_vel_g`` is applied' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -125,7 +125,7 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) + su.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) self.update_step() @@ -151,22 +151,13 @@ def update_custom_grid(self, structure_tstep, aero_tstep): self.data.aero.aero_settings, dt=self.settings['rollup_dt']) - def run(self, - aero_tstep=None, - structure_tstep=None, - convect_wake=False, - dt=None, - t=None, - unsteady_contribution=False): - - if aero_tstep is None: - aero_tstep = self.data.aero.timestep_info[self.data.ts] - if structure_tstep is None: - structure_tstep = self.data.structure.timestep_info[self.data.ts] - if dt is None: - dt = self.settings['rollup_dt'] - if t is None: - t = self.data.ts*dt + def run(self, **kwargs): + + aero_tstep = su.set_value_or_default(kwargs, 'aero_step', self.data.aero.timestep_info[-1]) + structure_tstep = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + dt = su.set_value_or_default(kwargs, 'dt', self.settings['rollup_dt']) + t = su.set_value_or_default(kwargs, 't', self.data.ts*dt) + unsteady_contribution = False convect_wake = False diff --git a/sharpy/solvers/steplinearuvlm.py b/sharpy/solvers/steplinearuvlm.py index fff9bbd0c..7b2f7dcb9 100644 --- a/sharpy/solvers/steplinearuvlm.py +++ b/sharpy/solvers/steplinearuvlm.py @@ -5,7 +5,7 @@ """ from sharpy.utils.solver_interface import BaseSolver, solver import numpy as np -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.generator_interface as gen_interface import sharpy.utils.algebra as algebra import sharpy.linear.src.linuvlm as linuvlm @@ -113,7 +113,7 @@ class StepLinearUVLM(BaseSolver): settings_default['cfl1'] = True settings_description['cfl1'] = 'If it is ``True``, it assumes that the discretisation complies with CFL=1' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) scaling_settings_types = dict() @@ -171,8 +171,8 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) - settings.to_custom_types(self.settings['ScalingDict'], self.scaling_settings_types, + su.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) + su.to_custom_types(self.settings['ScalingDict'], self.scaling_settings_types, self.scaling_settings_default, no_ctype=True) # Initialise velocity generator @@ -268,13 +268,7 @@ def initialise(self, data, custom_settings=None): # aero_tstep.linear.u = u_0 # aero_tstep.linear.y = f_0 - def run(self, - aero_tstep, - structure_tstep, - convect_wake=False, - dt=None, - t=None, - unsteady_contribution=False): + def run(self, **kwargs): r""" Solve the linear aerodynamic UVLM model at the current time step ``n``. The step increment is solved as: @@ -328,14 +322,12 @@ def run(self, """ - if aero_tstep is None: - aero_tstep = self.data.aero.timestep_info[-1] - if structure_tstep is None: - structure_tstep = self.data.structure.timestep_info[-1] - if dt is None: - dt = self.settings['dt'] - if t is None: - t = self.data.ts*dt + aero_tstep = su.set_value_or_default(kwargs, 'aero_step', self.data.aero.timestep_info[-1]) + structure_tstep = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + convect_wake = su.set_value_or_default(kwargs, 'convect_wake', False) + dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) + t = su.set_value_or_default(kwargs, 't', self.data.ts*dt) + unsteady_contribution = su.set_value_or_default(kwargs, 'unsteady_contribution', False) integr_order = self.settings['integr_order'] diff --git a/sharpy/solvers/stepuvlm.py b/sharpy/solvers/stepuvlm.py index 566cc8325..accdd8771 100644 --- a/sharpy/solvers/stepuvlm.py +++ b/sharpy/solvers/stepuvlm.py @@ -5,7 +5,7 @@ import sharpy.utils.algebra as algebra import sharpy.aero.utils.uvlmlib as uvlmlib -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.utils.generator_interface as gen_interface import sharpy.utils.cout_utils as cout @@ -133,7 +133,7 @@ class StepUvlm(BaseSolver): settings_default['quasi_steady'] = False settings_description['quasi_steady'] = 'Use quasi-steady approximation in UVLM' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options) def __init__(self): @@ -150,10 +150,10 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default, - self.settings_options) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + self.settings_options) self.data.structure.add_unsteady_information( self.data.structure.dyn_dict, @@ -183,25 +183,18 @@ def initialise(self, data, custom_settings=None): self.velocity_generator.initialise( self.settings['velocity_field_input']) - def run(self, - aero_tstep=None, - structure_tstep=None, - convect_wake=True, - dt=None, - t=None, - unsteady_contribution=False): + def run(self, **kwargs): """ Runs a step of the aerodynamics as implemented in UVLM. """ - if aero_tstep is None: - aero_tstep = self.data.aero.timestep_info[-1] - if structure_tstep is None: - structure_tstep = self.data.structure.timestep_info[-1] - if dt is None: - dt = self.settings['dt'] - if t is None: - t = self.data.ts*dt + # Default values + aero_tstep = su.set_value_or_default(kwargs, 'aero_step', self.data.aero.timestep_info[-1]) + structure_tstep = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) + convect_wake = su.set_value_or_default(kwargs, 'convect_wake', True) + dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) + t = su.set_value_or_default(kwargs, 't', self.data.ts*dt) + unsteady_contribution = su.set_value_or_default(kwargs, 'unsteady_contribution', False) if not aero_tstep.zeta: return self.data diff --git a/sharpy/solvers/timeintegrators.py b/sharpy/solvers/timeintegrators.py index 66f4be694..5d40ccaa1 100644 --- a/sharpy/solvers/timeintegrators.py +++ b/sharpy/solvers/timeintegrators.py @@ -1,7 +1,7 @@ import numpy as np import ctypes as ct -import sharpy.utils.settings as settings +import sharpy.utils.settings as su from sharpy.utils.solver_interface import solver @@ -81,10 +81,10 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, - self.settings_types, - self.settings_default, - no_ctype=True) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + no_ctype=True) self.dt = self.settings['dt'] self.gamma = 0.5 + self.settings['newmark_damp'] @@ -180,7 +180,7 @@ def initialise(self, data, custom_settings=None): self.settings = data.settings[self.solver_id] else: self.settings = custom_settings - settings.to_custom_types(self.settings, + su.to_custom_types(self.settings, self.settings_types, self.settings_default, no_ctype=True) diff --git a/sharpy/solvers/trim.py b/sharpy/solvers/trim.py index 199ed138b..8bec85716 100644 --- a/sharpy/solvers/trim.py +++ b/sharpy/solvers/trim.py @@ -7,7 +7,7 @@ import sharpy.utils.cout_utils as cout import sharpy.utils.solver_interface as solver_interface from sharpy.utils.solver_interface import solver, BaseSolver -import sharpy.utils.settings as settings +import sharpy.utils.settings as su import sharpy.utils.algebra as algebra @@ -86,7 +86,7 @@ class Trim(BaseSolver): settings_default['refine_solution'] = False settings_description['refine_solution'] = 'If ``True`` and the optimiser routine allows for it, the optimiser will try to improve the solution with hybrid methods' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -102,7 +102,7 @@ def __init__(self): def initialise(self, data): self.data = data self.settings = data.settings[self.solver_id] - settings.to_custom_types(self.settings, self.settings_types, self.settings_default) + su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.solver = solver_interface.initialise_solver(self.settings['solver']) self.solver.initialise(self.data, self.settings['solver_settings']) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 0b66a9530..bd8804f52 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -40,6 +40,7 @@ import ctypes as ct import numpy as np import sharpy.utils.algebra as ag +from sharpy.utils.settings import set_value_or_default ############################################################################### # Basic structures @@ -224,13 +225,6 @@ def define_FoR_dof(MB_beam, FoR_body): return FoR_dof -def set_value_or_default(dictionary, key, default_val): - try: - value = dictionary[key] - except KeyError: - value = default_val - return value - ################################################################################ # Equations ################################################################################ diff --git a/sharpy/utils/settings.py b/sharpy/utils/settings.py index 50955d2d7..636291794 100644 --- a/sharpy/utils/settings.py +++ b/sharpy/utils/settings.py @@ -439,3 +439,12 @@ def setting_line_format(self): for i_field in range(self.n_fields): string += '{0[' + str(i_field) + ']:<' + str(self.field_length[i_field]) + '}' return string + + +def set_value_or_default(dictionary, key, default_val): + try: + value = dictionary[key] + except KeyError: + value = default_val + return value + diff --git a/sharpy/utils/solver_interface.py b/sharpy/utils/solver_interface.py index 04b36232e..5ea5f8592 100644 --- a/sharpy/utils/solver_interface.py +++ b/sharpy/utils/solver_interface.py @@ -51,7 +51,7 @@ def initialise(self, data): # This executes the solver @abstractmethod - def run(self): + def run(self, **kwargs): pass # @property From 06caa551cb6f9fdd191f02c8187b640830723728 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 25 Jun 2021 11:48:44 +0100 Subject: [PATCH 119/253] add restart variable --- sharpy/controllers/bladepitchpid.py | 2 +- .../controlsurfacepidcontroller.py | 2 +- .../takeofftrajectorycontroller.py | 2 +- sharpy/generators/bumpvelocityfield.py | 2 +- sharpy/generators/dynamiccontrolsurface.py | 2 +- sharpy/generators/floatingforces.py | 12 +++++------ sharpy/generators/gridbox.py | 2 +- sharpy/generators/gustvelocityfield.py | 18 ++++++++--------- sharpy/generators/helicoidalwake.py | 2 +- sharpy/generators/shearvelocityfield.py | 2 +- sharpy/generators/steadyvelocityfield.py | 2 +- sharpy/generators/straightwake.py | 2 +- sharpy/generators/trajectorygenerator.py | 2 +- sharpy/generators/turbvelocityfield.py | 2 +- sharpy/generators/turbvelocityfieldbts.py | 2 +- sharpy/postproc/aeroforcescalculator.py | 2 +- sharpy/postproc/aerogridplot.py | 2 +- sharpy/postproc/asymptoticstability.py | 5 +++-- sharpy/postproc/beamloads.py | 2 +- sharpy/postproc/beamplot.py | 2 +- sharpy/postproc/cleanup.py | 2 +- sharpy/postproc/frequencyresponse.py | 2 +- sharpy/postproc/liftdistribution.py | 2 +- sharpy/postproc/pickledata.py | 2 +- sharpy/postproc/plotflowfield.py | 6 +++--- sharpy/postproc/savedata.py | 2 +- sharpy/postproc/saveparametriccase.py | 5 +++-- sharpy/postproc/stabilityderivatives.py | 2 +- sharpy/postproc/stallcheck.py | 2 +- sharpy/postproc/udpout.py | 2 +- sharpy/postproc/writevariablestime.py | 2 +- sharpy/sharpy_main.py | 5 +++-- sharpy/solvers/_basestructural.py | 2 +- sharpy/solvers/aerogridloader.py | 5 +++-- sharpy/solvers/beamloader.py | 2 +- sharpy/solvers/dynamiccoupled.py | 20 ++++++++++--------- sharpy/solvers/dynamicuvlm.py | 6 +++--- sharpy/solvers/initialaeroelasticloader.py | 2 +- sharpy/solvers/lindynamicsim.py | 4 ++-- sharpy/solvers/linearassembler.py | 2 +- sharpy/solvers/modal.py | 2 +- sharpy/solvers/noaero.py | 2 +- sharpy/solvers/nonlineardynamic.py | 2 +- sharpy/solvers/nonlineardynamiccoupledstep.py | 2 +- sharpy/solvers/nonlineardynamicmultibody.py | 15 +++++--------- .../solvers/nonlineardynamicprescribedstep.py | 2 +- sharpy/solvers/nonlinearstatic.py | 2 +- sharpy/solvers/nostructural.py | 2 +- sharpy/solvers/prescribeduvlm.py | 5 +++-- sharpy/solvers/rigiddynamiccoupledstep.py | 2 +- sharpy/solvers/rigiddynamicprescribedstep.py | 2 +- sharpy/solvers/staticcoupled.py | 8 ++++---- sharpy/solvers/statictrim.py | 4 ++-- sharpy/solvers/staticuvlm.py | 4 ++-- sharpy/solvers/steplinearuvlm.py | 4 ++-- sharpy/solvers/stepuvlm.py | 5 +++-- sharpy/solvers/timeintegrators.py | 6 +++--- sharpy/solvers/trim.py | 4 ++-- sharpy/utils/solver_interface.py | 2 +- 59 files changed, 112 insertions(+), 109 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 79dcfc9e3..a392a4bfc 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -163,7 +163,7 @@ def __init__(self): self.log = None - def initialise(self, in_dict, controller_id=None): + def initialise(self, in_dict, controller_id=None, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, diff --git a/sharpy/controllers/controlsurfacepidcontroller.py b/sharpy/controllers/controlsurfacepidcontroller.py index fe0ee53d5..64848c8d7 100644 --- a/sharpy/controllers/controlsurfacepidcontroller.py +++ b/sharpy/controllers/controlsurfacepidcontroller.py @@ -96,7 +96,7 @@ def __init__(self): self.log = None - def initialise(self, in_dict, controller_id=None): + def initialise(self, in_dict, controller_id=None, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, diff --git a/sharpy/controllers/takeofftrajectorycontroller.py b/sharpy/controllers/takeofftrajectorycontroller.py index ba9a95c47..e68795fae 100644 --- a/sharpy/controllers/takeofftrajectorycontroller.py +++ b/sharpy/controllers/takeofftrajectorycontroller.py @@ -87,7 +87,7 @@ def __init__(self): self.log = None - def initialise(self, in_dict, controller_id=None): + def initialise(self, in_dict, controller_id=None, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, diff --git a/sharpy/generators/bumpvelocityfield.py b/sharpy/generators/bumpvelocityfield.py index b34d0dba5..347103dd7 100644 --- a/sharpy/generators/bumpvelocityfield.py +++ b/sharpy/generators/bumpvelocityfield.py @@ -78,7 +78,7 @@ def __init__(self): self.u_inf = 0. self.u_inf_direction = None - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, BumpVelocityField.settings_types, BumpVelocityField.settings_default) self.settings = self.in_dict diff --git a/sharpy/generators/dynamiccontrolsurface.py b/sharpy/generators/dynamiccontrolsurface.py index 470c31cdf..f2017ad8f 100644 --- a/sharpy/generators/dynamiccontrolsurface.py +++ b/sharpy/generators/dynamiccontrolsurface.py @@ -68,7 +68,7 @@ def __init__(self): self.deflection = None self.deflection_dot = None - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, self.settings_default, no_ctype=True) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 902270d7d..efdb00ff4 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -565,7 +565,7 @@ def __init__(self): self.added_mass_in_mass_matrix = None - def initialise(self, in_dict=None, data=None): + def initialise(self, in_dict=None, data=None, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, @@ -579,7 +579,7 @@ def initialise(self, in_dict=None, data=None): self.gravity_dir = self.settings['gravity_dir'] # Platform dofs - if self.q is None: + if not restart: self.q = np.zeros((self.settings['n_time_steps'] + 1, 6)) self.qdot = np.zeros_like(self.q) self.qdotdot = np.zeros_like(self.q) @@ -599,7 +599,7 @@ def initialise(self, in_dict=None, data=None): self.n_mooring_lines = self.floating_data['mooring']['n_lines'] self.anchor_pos = np.zeros((self.n_mooring_lines, 3)) self.fairlead_pos_A = np.zeros((self.n_mooring_lines, 3)) - if len(self.hf_prev) == 0: + if not restart: self.hf_prev = [None]*self.n_mooring_lines self.vf_prev = [None]*self.n_mooring_lines @@ -647,7 +647,7 @@ def initialise(self, in_dict=None, data=None): self.hd_damping_const = self.floating_data['hydrodynamics']['damping_matrix'][-1, :, :] self.added_mass_in_mass_matrix = self.settings['added_mass_in_mass_matrix'] - if ((self.added_mass_in_mass_matrix) and (data.ts == 0)): + if ((self.added_mass_in_mass_matrix) and (not restart)): cout.cout_wrap(("Including added mass in mass matrix"), 2) if data.structure.lumped_mass_mat is None: data.structure.lumped_mass_mat_nodes = np.array([self.buoyancy_node]) @@ -676,9 +676,9 @@ def initialise(self, in_dict=None, data=None): self.hd_K = TransferFunction(hd_K_num, hd_K_den) self.ab_freq_rads = self.floating_data['hydrodynamics']['ab_freq_rads'] - try: + if restart: self.x0_K.extend([None]*increase_ts) - except AttributeError: + else: self.x0_K = [None]*(self.settings['n_time_steps'] + 1) self.x0_K[0] = 0. diff --git a/sharpy/generators/gridbox.py b/sharpy/generators/gridbox.py index 4a9d0fecb..3f60de320 100644 --- a/sharpy/generators/gridbox.py +++ b/sharpy/generators/gridbox.py @@ -46,7 +46,7 @@ def __init__(self): self.in_dict = dict() self.settings = None - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, self.settings_default) self.settings = copy.deepcopy(self.in_dict) diff --git a/sharpy/generators/gustvelocityfield.py b/sharpy/generators/gustvelocityfield.py index 8a5fb0d8b..2e8b579e7 100644 --- a/sharpy/generators/gustvelocityfield.py +++ b/sharpy/generators/gustvelocityfield.py @@ -92,7 +92,7 @@ class one_minus_cos(BaseGust): __doc__ += setting_table.generate(settings_types, settings_default, settings_description, header_line=doc_settings_description) - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.settings = in_dict settings.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -139,7 +139,7 @@ class DARPA(BaseGust): __doc__ += setting_table.generate(settings_types, settings_default, settings_description, header_line=doc_settings_description) - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.settings = in_dict settings.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -184,7 +184,7 @@ class continuous_sin(BaseGust): __doc__ += setting_table.generate(settings_types, settings_default, settings_description, header_line=doc_settings_description) - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.settings = in_dict settings.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -223,7 +223,7 @@ class lateral_one_minus_cos(BaseGust): __doc__ += setting_table.generate(settings_types, settings_default, settings_description, header_line=doc_settings_description) - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.settings = in_dict settings.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -267,7 +267,7 @@ def __init__(self): self.file_info = None - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.settings = in_dict settings.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -312,7 +312,7 @@ def __init__(self): self.file_info = None - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.settings = in_dict settings.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -366,7 +366,7 @@ class span_sine(BaseGust): __doc__ += setting_table.generate(settings_types, settings_default, settings_description, header_line=doc_settings_description) - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.settings = in_dict settings.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -448,7 +448,7 @@ def __init__(self): self.implemented_gusts = dict_of_gusts - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.settings = in_dict settings.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -465,7 +465,7 @@ def initialise(self, in_dict): self.gust.u_inf = self.u_inf self.gust.u_inf_direction = self.u_inf_direction - self.gust.initialise(self.settings['gust_parameters']) + self.gust.initialise(self.settings['gust_parameters'], restart=restart) def generate(self, params, uext): zeta = params['zeta'] diff --git a/sharpy/generators/helicoidalwake.py b/sharpy/generators/helicoidalwake.py index fc7744fe2..fd3328217 100644 --- a/sharpy/generators/helicoidalwake.py +++ b/sharpy/generators/helicoidalwake.py @@ -95,7 +95,7 @@ def __init__(self): self.h_ref = None self.h_corr = None - def initialise(self, data, in_dict): + def initialise(self, data, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, self.settings_default, no_ctype=True) diff --git a/sharpy/generators/shearvelocityfield.py b/sharpy/generators/shearvelocityfield.py index 470c2a363..564959e17 100644 --- a/sharpy/generators/shearvelocityfield.py +++ b/sharpy/generators/shearvelocityfield.py @@ -61,7 +61,7 @@ def __init__(self): self.h_ref = None self.h_corr = None - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, self.settings_default) diff --git a/sharpy/generators/steadyvelocityfield.py b/sharpy/generators/steadyvelocityfield.py index 3e49f2d9d..419c33f71 100644 --- a/sharpy/generators/steadyvelocityfield.py +++ b/sharpy/generators/steadyvelocityfield.py @@ -53,7 +53,7 @@ def __init__(self): self.u_inf = 0. self.u_inf_direction = None - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, diff --git a/sharpy/generators/straightwake.py b/sharpy/generators/straightwake.py index bcb8d4a78..301bb3cb8 100644 --- a/sharpy/generators/straightwake.py +++ b/sharpy/generators/straightwake.py @@ -62,7 +62,7 @@ def __init__(self): self.u_inf_direction = None self.dt = None - def initialise(self, data, in_dict=None): + def initialise(self, data, in_dict=None, restart=False): self.in_dict = in_dict # For backwards compatibility diff --git a/sharpy/generators/trajectorygenerator.py b/sharpy/generators/trajectorygenerator.py index 4e694980b..a8c7550f5 100644 --- a/sharpy/generators/trajectorygenerator.py +++ b/sharpy/generators/trajectorygenerator.py @@ -87,7 +87,7 @@ def __init__(self): self.implemented_accelerations = ["constant", "linear"] - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, self.settings_default) diff --git a/sharpy/generators/turbvelocityfield.py b/sharpy/generators/turbvelocityfield.py index 9ab86099a..c2969cc2f 100644 --- a/sharpy/generators/turbvelocityfield.py +++ b/sharpy/generators/turbvelocityfield.py @@ -106,7 +106,7 @@ def __init__(self): self.vel_holder0 = 3*[None] self.vel_holder1 = 3*[None] - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, self.settings_default) self.settings = self.in_dict diff --git a/sharpy/generators/turbvelocityfieldbts.py b/sharpy/generators/turbvelocityfieldbts.py index f66a64bfb..61a6d1cb0 100644 --- a/sharpy/generators/turbvelocityfieldbts.py +++ b/sharpy/generators/turbvelocityfieldbts.py @@ -162,7 +162,7 @@ def __init__(self): self.gird_size_vec = None self.grid_size_ufed_dir = None - def initialise(self, in_dict): + def initialise(self, in_dict, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, self.settings_default, no_ctype=True) self.settings = self.in_dict diff --git a/sharpy/postproc/aeroforcescalculator.py b/sharpy/postproc/aeroforcescalculator.py index 4c41cafc9..c3526f9d5 100644 --- a/sharpy/postproc/aeroforcescalculator.py +++ b/sharpy/postproc/aeroforcescalculator.py @@ -68,7 +68,7 @@ def __init__(self): self.table = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data self.settings = data.settings[self.solver_id] self.ts_max = len(self.data.structure.timestep_info) diff --git a/sharpy/postproc/aerogridplot.py b/sharpy/postproc/aerogridplot.py index fd644fe99..ea925dfe7 100644 --- a/sharpy/postproc/aerogridplot.py +++ b/sharpy/postproc/aerogridplot.py @@ -94,7 +94,7 @@ def __init__(self): self.ts_max = 0 self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/asymptoticstability.py b/sharpy/postproc/asymptoticstability.py index fef9c840b..b36f5e378 100644 --- a/sharpy/postproc/asymptoticstability.py +++ b/sharpy/postproc/asymptoticstability.py @@ -95,7 +95,7 @@ def __init__(self): self.with_postprocessors = False self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: @@ -358,7 +358,8 @@ def plot_modes(self): for postproc in postprocessor_list: postprocessors[postproc] = initialise_solver(postproc) postprocessors[postproc].initialise( - self.data, postprocessors_settings[postproc]) + self.data, postprocessors_settings[postproc], + restart=restart) # Plot reference for postproc in postprocessor_list: diff --git a/sharpy/postproc/beamloads.py b/sharpy/postproc/beamloads.py index 4d20587db..b2291307a 100644 --- a/sharpy/postproc/beamloads.py +++ b/sharpy/postproc/beamloads.py @@ -38,7 +38,7 @@ def __init__(self): self.folder = None self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/beamplot.py b/sharpy/postproc/beamplot.py index 4ca1268ec..5e892170e 100644 --- a/sharpy/postproc/beamplot.py +++ b/sharpy/postproc/beamplot.py @@ -58,7 +58,7 @@ def __init__(self): self.filename_for = '' self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/cleanup.py b/sharpy/postproc/cleanup.py index 90294f579..34312f454 100644 --- a/sharpy/postproc/cleanup.py +++ b/sharpy/postproc/cleanup.py @@ -42,7 +42,7 @@ def __init__(self): self.data = None self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/frequencyresponse.py b/sharpy/postproc/frequencyresponse.py index 54d9eab52..a96d89add 100644 --- a/sharpy/postproc/frequencyresponse.py +++ b/sharpy/postproc/frequencyresponse.py @@ -88,7 +88,7 @@ def __init__(self): self.wv = None self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data diff --git a/sharpy/postproc/liftdistribution.py b/sharpy/postproc/liftdistribution.py index c6d319a72..3e84784d1 100644 --- a/sharpy/postproc/liftdistribution.py +++ b/sharpy/postproc/liftdistribution.py @@ -33,7 +33,7 @@ def __init__(self): self.ts = None self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/pickledata.py b/sharpy/postproc/pickledata.py index 5cfabb313..386c0b43f 100644 --- a/sharpy/postproc/pickledata.py +++ b/sharpy/postproc/pickledata.py @@ -46,7 +46,7 @@ def __init__(self): self.folder = None self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/plotflowfield.py b/sharpy/postproc/plotflowfield.py index c5840e449..b688e16af 100644 --- a/sharpy/postproc/plotflowfield.py +++ b/sharpy/postproc/plotflowfield.py @@ -72,7 +72,7 @@ def __init__(self): self.folder = None self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] @@ -91,13 +91,13 @@ def initialise(self, data, custom_settings=None, caller=None): velocity_generator_type = gen_interface.generator_from_string( self.settings['velocity_field_generator']) self.velocity_generator = velocity_generator_type() - self.velocity_generator.initialise(self.settings['velocity_field_input']) + self.velocity_generator.initialise(self.settings['velocity_field_input'], restart=restart) # init postproc grid generator postproc_grid_generator_type = gen_interface.generator_from_string( self.settings['postproc_grid_generator']) self.postproc_grid_generator = postproc_grid_generator_type() - self.postproc_grid_generator.initialise(self.settings['postproc_grid_input']) + self.postproc_grid_generator.initialise(self.settings['postproc_grid_input'], restart=restart) self.caller = caller def output_velocity_field(self, ts): diff --git a/sharpy/postproc/savedata.py b/sharpy/postproc/savedata.py index 532383e39..65cf61202 100644 --- a/sharpy/postproc/savedata.py +++ b/sharpy/postproc/savedata.py @@ -113,7 +113,7 @@ def __init__(self): # see initialise and add_as_grp self.ClassesToSave = (PreSharpy,) - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/saveparametriccase.py b/sharpy/postproc/saveparametriccase.py index fea8ad6fb..144992001 100644 --- a/sharpy/postproc/saveparametriccase.py +++ b/sharpy/postproc/saveparametriccase.py @@ -56,7 +56,7 @@ def __init__(self): self.settings = None self.folder = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: @@ -73,6 +73,7 @@ def initialise(self, data, custom_settings=None): def run(self, **kwargs): online = su.set_value_or_default(kwargs, 'online', False) + restart = su.set_value_or_default(kwargs, 'restart', False) config = configobj.ConfigObj() file_name = self.folder + '/' + self.data.settings['SHARPy']['case'] + '.pmor.sharpy' @@ -87,7 +88,7 @@ def run(self, **kwargs): if 'PickleData' not in self.data.settings['SHARPy']['flow'] and self.settings['save_case']: pickle_solver = initialise_solver('PickleData') - pickle_solver.initialise(self.data) + pickle_solver.initialise(self.data, restart=restart) self.data = pickle_solver.run() sim_info['path_to_data'] = os.path.abspath(self.folder) else: diff --git a/sharpy/postproc/stabilityderivatives.py b/sharpy/postproc/stabilityderivatives.py index f861d2b67..a0420faa4 100644 --- a/sharpy/postproc/stabilityderivatives.py +++ b/sharpy/postproc/stabilityderivatives.py @@ -57,7 +57,7 @@ def __init__(self): self.ppal_axes = None self.n_control_surfaces = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings: diff --git a/sharpy/postproc/stallcheck.py b/sharpy/postproc/stallcheck.py index b1b8a7c4b..f88fc29fa 100644 --- a/sharpy/postproc/stallcheck.py +++ b/sharpy/postproc/stallcheck.py @@ -55,7 +55,7 @@ def __init__(self): self.ts = None self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/udpout.py b/sharpy/postproc/udpout.py index ced44989a..fb5d52639 100644 --- a/sharpy/postproc/udpout.py +++ b/sharpy/postproc/udpout.py @@ -51,7 +51,7 @@ def __init__(self): self.caller = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/postproc/writevariablestime.py b/sharpy/postproc/writevariablestime.py index 403af1301..5be78a963 100644 --- a/sharpy/postproc/writevariablestime.py +++ b/sharpy/postproc/writevariablestime.py @@ -105,7 +105,7 @@ def __init__(self): self.caller = None self.velocity_generator = None - def initialise(self, data, custom_settings=None, caller=None): + def initialise(self, data, custom_settings=None, caller=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/sharpy_main.py b/sharpy/sharpy_main.py index 2ce0874e9..75f262291 100644 --- a/sharpy/sharpy_main.py +++ b/sharpy/sharpy_main.py @@ -86,6 +86,7 @@ def main(args=None, sharpy_input_dict=None): # run preSHARPy data = PreSharpy(settings) solvers = dict() + restart = False else: try: with open(args.restart, 'rb') as restart_file: @@ -95,7 +96,7 @@ def main(args=None, sharpy_input_dict=None): raise FileNotFoundError('The file specified for the snapshot \ restart (-r) does not exist. Please check.') - + restart = True # update the settings data.update_settings(settings) @@ -118,7 +119,7 @@ def main(args=None, sharpy_input_dict=None): for solver_name in settings['SHARPy']['flow']: if (args.restart is None) or (solver_name not in solvers.keys()): solvers[solver_name] = solver_interface.initialise_solver(solver_name) - solvers[solver_name].initialise(data) + solvers[solver_name].initialise(data, restart=restart) data = solvers[solver_name].run(solvers=solvers) solvers[solver_name].teardown() diff --git a/sharpy/solvers/_basestructural.py b/sharpy/solvers/_basestructural.py index 8398eac86..60f442e29 100644 --- a/sharpy/solvers/_basestructural.py +++ b/sharpy/solvers/_basestructural.py @@ -63,7 +63,7 @@ class _BaseStructural(BaseSolver): settings_types['num_steps'] = 'int' settings_default['num_steps'] = 500 - def initialise(self, data): + def initialise(self, data, restart=False): pass def run(self, **kwargs): diff --git a/sharpy/solvers/aerogridloader.py b/sharpy/solvers/aerogridloader.py index 1c0eaaa54..af0d4b18f 100644 --- a/sharpy/solvers/aerogridloader.py +++ b/sharpy/solvers/aerogridloader.py @@ -97,7 +97,7 @@ def __init__(self): self.wake_shape_generator = None - def initialise(self, data): + def initialise(self, data, restart=False): self.data = data self.settings = data.settings[self.solver_id] @@ -113,7 +113,8 @@ def initialise(self, data): self.settings['wake_shape_generator']) self.wake_shape_generator = wake_shape_generator_type() self.wake_shape_generator.initialise(data, - self.settings['wake_shape_generator_input']) + self.settings['wake_shape_generator_input'], + restart=restart) def read_files(self): # open aero file diff --git a/sharpy/solvers/beamloader.py b/sharpy/solvers/beamloader.py index 7e1d09fae..07673b627 100644 --- a/sharpy/solvers/beamloader.py +++ b/sharpy/solvers/beamloader.py @@ -76,7 +76,7 @@ def __init__(self): # structure storage self.structure = None - def initialise(self, data): + def initialise(self, data, restart=False): self.data = data self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 7a72a6a1b..8cbdcabfb 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -243,7 +243,7 @@ def set_rho(self, new_rho): """ self.aero_solver.settings['rho'] = ct.c_double(new_rho) - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): """ Controls the initialisation process of the solver, including processing the settings and initialising the aero and structural solvers, postprocessors @@ -272,16 +272,17 @@ def initialise(self, data, custom_settings=None): # timestep_info[0] and remove the rest self.cleanup_timestep_info() - if self.structural_solver is None: + if not restart: self.structural_solver = solver_interface.initialise_solver( self.settings['structural_solver']) - self.structural_solver.initialise( - self.data, self.settings['structural_solver_settings']) - if self.aero_solver is None: self.aero_solver = solver_interface.initialise_solver( self.settings['aero_solver']) + self.structural_solver.initialise( + self.data, self.settings['structural_solver_settings'], + restart=restart) self.aero_solver.initialise(self.structural_solver.data, - self.settings['aero_solver_settings']) + self.settings['aero_solver_settings'], + restart=restart) self.data = self.aero_solver.data # initialise postprocessors @@ -297,7 +298,8 @@ def initialise(self, data, custom_settings=None): self.postprocessors[postproc] = solver_interface.initialise_solver( postproc) self.postprocessors[postproc].initialise( - self.data, self.settings['postprocessors_settings'][postproc], caller=self) + self.data, self.settings['postprocessors_settings'][postproc], caller=self, + restart=restart) # initialise controllers self.with_controllers = False @@ -314,7 +316,7 @@ def initialise(self, data, custom_settings=None): controller_interface.initialise_controller(controller_type)) self.controllers[controller_id].initialise( self.settings['controller_settings'][controller_id], - controller_id) + controller_id, restart=restart) # print information header if self.print_info: @@ -352,7 +354,7 @@ def initialise(self, data, custom_settings=None): if not rg_id in self.runtime_generators.keys(): gen = gen_interface.generator_from_string(rg_id) self.runtime_generators[rg_id] = gen() - self.runtime_generators[rg_id].initialise(param, data=self.data) + self.runtime_generators[rg_id].initialise(param, data=self.data, restart=restart) def cleanup_timestep_info(self): if max(len(self.data.aero.timestep_info), len(self.data.structure.timestep_info)) > 1: diff --git a/sharpy/solvers/dynamicuvlm.py b/sharpy/solvers/dynamicuvlm.py index 1ec32e032..c0a2be909 100644 --- a/sharpy/solvers/dynamicuvlm.py +++ b/sharpy/solvers/dynamicuvlm.py @@ -90,7 +90,7 @@ def __init__(self): self.postprocessors = dict() self.with_postprocessors = False - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: @@ -103,7 +103,7 @@ def initialise(self, data, custom_settings=None): self.print_info = self.settings['print_info'] self.aero_solver = solver_interface.initialise_solver(self.settings['aero_solver']) - self.aero_solver.initialise(self.data, self.settings['aero_solver_settings']) + self.aero_solver.initialise(self.data, self.settings['aero_solver_settings'], restart=False) self.data = self.aero_solver.data # initialise postprocessors @@ -113,7 +113,7 @@ def initialise(self, data, custom_settings=None): for postproc in self.settings['postprocessors']: self.postprocessors[postproc] = solver_interface.initialise_solver(postproc) self.postprocessors[postproc].initialise( - self.data, self.settings['postprocessors_settings'][postproc], caller=self) + self.data, self.settings['postprocessors_settings'][postproc], caller=self, restart=False) if self.print_info: self.residual_table = cout.TablePrinter(2, 14, ['g', 'f']) diff --git a/sharpy/solvers/initialaeroelasticloader.py b/sharpy/solvers/initialaeroelasticloader.py index 08ef1d89d..32a55d945 100644 --- a/sharpy/solvers/initialaeroelasticloader.py +++ b/sharpy/solvers/initialaeroelasticloader.py @@ -37,7 +37,7 @@ def __init__(self): self.settings = None self.file_info = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: diff --git a/sharpy/solvers/lindynamicsim.py b/sharpy/solvers/lindynamicsim.py index 93e713e0d..27e5a5a8f 100644 --- a/sharpy/solvers/lindynamicsim.py +++ b/sharpy/solvers/lindynamicsim.py @@ -88,7 +88,7 @@ def __init__(self): self.folder = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings: @@ -112,7 +112,7 @@ def initialise(self, data, custom_settings=None): for postproc in self.settings['postprocessors']: self.postprocessors[postproc] = initialise_solver(postproc) self.postprocessors[postproc].initialise( - self.data, self.settings['postprocessors_settings'][postproc], caller=self) + self.data, self.settings['postprocessors_settings'][postproc], caller=self, restart=False) def input_vector(self, ss): """ diff --git a/sharpy/solvers/linearassembler.py b/sharpy/solvers/linearassembler.py index 2c5d4eaf8..b9dce02bd 100644 --- a/sharpy/solvers/linearassembler.py +++ b/sharpy/solvers/linearassembler.py @@ -113,7 +113,7 @@ def __init__(self): self.settings = dict() self.data = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings: diff --git a/sharpy/solvers/modal.py b/sharpy/solvers/modal.py index 7ca8cafb2..76a462038 100644 --- a/sharpy/solvers/modal.py +++ b/sharpy/solvers/modal.py @@ -109,7 +109,7 @@ def __init__(self): self.filename_shapes = None self.rigid_body_motion = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/noaero.py b/sharpy/solvers/noaero.py index 77a778664..ae1760b17 100644 --- a/sharpy/solvers/noaero.py +++ b/sharpy/solvers/noaero.py @@ -35,7 +35,7 @@ def __init__(self): self.data = None self.settings = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/nonlineardynamic.py b/sharpy/solvers/nonlineardynamic.py index a02776366..97200336e 100644 --- a/sharpy/solvers/nonlineardynamic.py +++ b/sharpy/solvers/nonlineardynamic.py @@ -45,7 +45,7 @@ def __init__(self): self.data = None self.settings = None - def initialise(self, data): + def initialise(self, data, restart=False): self.data = data self.settings = data.settings[self.solver_id] su.to_custom_types(self.settings, self.settings_types, self.settings_default) diff --git a/sharpy/solvers/nonlineardynamiccoupledstep.py b/sharpy/solvers/nonlineardynamiccoupledstep.py index 32ff12e8b..80da34353 100644 --- a/sharpy/solvers/nonlineardynamiccoupledstep.py +++ b/sharpy/solvers/nonlineardynamiccoupledstep.py @@ -57,7 +57,7 @@ def __init__(self): self.data = None self.settings = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index 769e2a5ec..b09ec9113 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -84,7 +84,7 @@ def __init__(self): self.prev_Dq = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: @@ -101,12 +101,6 @@ def initialise(self, data, custom_settings=None): self.data.structure.add_unsteady_information( self.data.structure.dyn_dict, self.settings['num_steps']) - # Initialise time integrator - self.time_integrator = solver_interface.initialise_solver( - self.settings['time_integrator']) - self.time_integrator.initialise( - self.data, self.settings['time_integrator_settings']) - # Define the number of equations self.lc_list = lagrangeconstraints.initialize_constraints(self.data.structure.ini_mb_dict) self.num_LM_eq = lagrangeconstraints.define_num_LM_eq(self.lc_list) @@ -133,10 +127,11 @@ def initialise(self, data, custom_settings=None): self.settings['time_integrator_settings']['num_LM_eq'] = self.num_LM_eq # Initialise time integrator - self.time_integrator = solver_interface.initialise_solver( - self.settings['time_integrator']) + if not restart: + self.time_integrator = solver_interface.initialise_solver( + self.settings['time_integrator']) self.time_integrator.initialise( - self.data, self.settings['time_integrator_settings']) + self.data, self.settings['time_integrator_settings'], restart=restart) def add_step(self): self.data.structure.next_step() diff --git a/sharpy/solvers/nonlineardynamicprescribedstep.py b/sharpy/solvers/nonlineardynamicprescribedstep.py index 0d62cef56..f68c3762d 100644 --- a/sharpy/solvers/nonlineardynamicprescribedstep.py +++ b/sharpy/solvers/nonlineardynamicprescribedstep.py @@ -41,7 +41,7 @@ def __init__(self): self.data = None self.settings = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/nonlinearstatic.py b/sharpy/solvers/nonlinearstatic.py index a48d1314f..0575391b2 100644 --- a/sharpy/solvers/nonlinearstatic.py +++ b/sharpy/solvers/nonlinearstatic.py @@ -41,7 +41,7 @@ def __init__(self): self.data = None self.settings = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/nostructural.py b/sharpy/solvers/nostructural.py index d9baf6703..661b9fdbf 100644 --- a/sharpy/solvers/nostructural.py +++ b/sharpy/solvers/nostructural.py @@ -36,7 +36,7 @@ def __init__(self): self.data = None self.settings = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/prescribeduvlm.py b/sharpy/solvers/prescribeduvlm.py index a7507643a..c02340ef8 100644 --- a/sharpy/solvers/prescribeduvlm.py +++ b/sharpy/solvers/prescribeduvlm.py @@ -85,7 +85,7 @@ def __init__(self): self.postprocessors = dict() self.with_postprocessors = False - def initialise(self, data): + def initialise(self, data, restart=False): self.data = data self.settings = data.settings[self.solver_id] su.to_custom_types(self.settings, self.settings_types, self.settings_default) @@ -106,7 +106,8 @@ def initialise(self, data): for postproc in self.settings['postprocessors']: self.postprocessors[postproc] = solver_interface.initialise_solver(postproc) self.postprocessors[postproc].initialise( - self.data, self.settings['postprocessors_settings'][postproc], caller=self) + self.data, self.settings['postprocessors_settings'][postproc], caller=self, + restart=restart) self.residual_table = cout.TablePrinter(2, 14, ['g', 'f']) self.residual_table.field_length[0] = 6 diff --git a/sharpy/solvers/rigiddynamiccoupledstep.py b/sharpy/solvers/rigiddynamiccoupledstep.py index c7ebc82a2..f39c90eb9 100644 --- a/sharpy/solvers/rigiddynamiccoupledstep.py +++ b/sharpy/solvers/rigiddynamiccoupledstep.py @@ -44,7 +44,7 @@ def __init__(self): self.data = None self.settings = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/rigiddynamicprescribedstep.py b/sharpy/solvers/rigiddynamicprescribedstep.py index 4223c66ae..f13764b57 100644 --- a/sharpy/solvers/rigiddynamicprescribedstep.py +++ b/sharpy/solvers/rigiddynamicprescribedstep.py @@ -40,7 +40,7 @@ def __init__(self): self.data = None self.settings = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: diff --git a/sharpy/solvers/staticcoupled.py b/sharpy/solvers/staticcoupled.py index 45a6a5b2d..0a46a1f81 100644 --- a/sharpy/solvers/staticcoupled.py +++ b/sharpy/solvers/staticcoupled.py @@ -96,7 +96,7 @@ def __init__(self): self.runtime_generators = dict() self.with_runtime_generators = False - def initialise(self, data, input_dict=None): + def initialise(self, data, input_dict=None, restart=False): self.data = data if input_dict is None: self.settings = data.settings[self.solver_id] @@ -111,9 +111,9 @@ def initialise(self, data, input_dict=None): self.print_info = self.settings['print_info'] self.structural_solver = solver_interface.initialise_solver(self.settings['structural_solver']) - self.structural_solver.initialise(self.data, self.settings['structural_solver_settings']) + self.structural_solver.initialise(self.data, self.settings['structural_solver_settings'], restart=restart) self.aero_solver = solver_interface.initialise_solver(self.settings['aero_solver']) - self.aero_solver.initialise(self.structural_solver.data, self.settings['aero_solver_settings']) + self.aero_solver.initialise(self.structural_solver.data, self.settings['aero_solver_settings'], restart=restart) self.data = self.aero_solver.data if self.print_info: @@ -140,7 +140,7 @@ def initialise(self, data, input_dict=None): for rg_id, param in self.settings['runtime_generators'].items(): gen = gen_interface.generator_from_string(rg_id) self.runtime_generators[rg_id] = gen() - self.runtime_generators[rg_id].initialise(param, data=self.data) + self.runtime_generators[rg_id].initialise(param, data=self.data, restart=restart) def increase_ts(self): self.data.ts += 1 diff --git a/sharpy/solvers/statictrim.py b/sharpy/solvers/statictrim.py index 9d05a4b71..d98881d0a 100644 --- a/sharpy/solvers/statictrim.py +++ b/sharpy/solvers/statictrim.py @@ -114,13 +114,13 @@ def __init__(self): self.table = None self.folder = None - def initialise(self, data): + def initialise(self, data, restart=False): self.data = data self.settings = data.settings[self.solver_id] su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.solver = solver_interface.initialise_solver(self.settings['solver']) - self.solver.initialise(self.data, self.settings['solver_settings']) + self.solver.initialise(self.data, self.settings['solver_settings'], restart=restart) self.folder = data.output_folder + '/statictrim/' if not os.path.exists(self.folder): diff --git a/sharpy/solvers/staticuvlm.py b/sharpy/solvers/staticuvlm.py index e43a6cb72..da103b31e 100644 --- a/sharpy/solvers/staticuvlm.py +++ b/sharpy/solvers/staticuvlm.py @@ -119,7 +119,7 @@ def __init__(self): self.settings = None self.velocity_generator = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): self.data = data if custom_settings is None: self.settings = data.settings[self.solver_id] @@ -133,7 +133,7 @@ def initialise(self, data, custom_settings=None): velocity_generator_type = gen_interface.generator_from_string( self.settings['velocity_field_generator']) self.velocity_generator = velocity_generator_type() - self.velocity_generator.initialise(self.settings['velocity_field_input']) + self.velocity_generator.initialise(self.settings['velocity_field_input'], restart=restart) def add_step(self): self.data.aero.add_timestep() diff --git a/sharpy/solvers/steplinearuvlm.py b/sharpy/solvers/steplinearuvlm.py index 7b2f7dcb9..af2edaa3c 100644 --- a/sharpy/solvers/steplinearuvlm.py +++ b/sharpy/solvers/steplinearuvlm.py @@ -143,7 +143,7 @@ def __init__(self): self.lin_uvlm_system = None self.velocity_generator = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): r""" Initialises the Linear UVLM aerodynamic solver and the chosen velocity generator. @@ -178,7 +178,7 @@ def initialise(self, data, custom_settings=None): # Initialise velocity generator velocity_generator_type = gen_interface.generator_from_string(self.settings['velocity_field_generator']) self.velocity_generator = velocity_generator_type() - self.velocity_generator.initialise(self.settings['velocity_field_input']) + self.velocity_generator.initialise(self.settings['velocity_field_input'], restart=restart) # Check whether linear UVLM has been initialised try: diff --git a/sharpy/solvers/stepuvlm.py b/sharpy/solvers/stepuvlm.py index accdd8771..c17e3cf2b 100644 --- a/sharpy/solvers/stepuvlm.py +++ b/sharpy/solvers/stepuvlm.py @@ -141,7 +141,7 @@ def __init__(self): self.settings = None self.velocity_generator = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): """ To be called just once per simulation. """ @@ -181,7 +181,8 @@ def initialise(self, data, custom_settings=None): self.settings['velocity_field_generator']) self.velocity_generator = velocity_generator_type() self.velocity_generator.initialise( - self.settings['velocity_field_input']) + self.settings['velocity_field_input'], + restart=restart) def run(self, **kwargs): """ diff --git a/sharpy/solvers/timeintegrators.py b/sharpy/solvers/timeintegrators.py index 5d40ccaa1..c60d08cc3 100644 --- a/sharpy/solvers/timeintegrators.py +++ b/sharpy/solvers/timeintegrators.py @@ -23,7 +23,7 @@ def __init__(self): pass - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): pass @@ -75,7 +75,7 @@ def __init__(self): self.beta = None self.gamma = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): if custom_settings is None: self.settings = data.settings[self.solver_id] @@ -174,7 +174,7 @@ def __init__(self): self.gamma = None self.beta = None - def initialise(self, data, custom_settings=None): + def initialise(self, data, custom_settings=None, restart=False): if custom_settings is None: self.settings = data.settings[self.solver_id] diff --git a/sharpy/solvers/trim.py b/sharpy/solvers/trim.py index 8bec85716..af8dcaaeb 100644 --- a/sharpy/solvers/trim.py +++ b/sharpy/solvers/trim.py @@ -99,13 +99,13 @@ def __init__(self): self.with_special_case = False - def initialise(self, data): + def initialise(self, data, restart=False): self.data = data self.settings = data.settings[self.solver_id] su.to_custom_types(self.settings, self.settings_types, self.settings_default) self.solver = solver_interface.initialise_solver(self.settings['solver']) - self.solver.initialise(self.data, self.settings['solver_settings']) + self.solver.initialise(self.data, self.settings['solver_settings'], restart=restart) # generate x_info (which elements of the x array are what) counter = 0 diff --git a/sharpy/utils/solver_interface.py b/sharpy/utils/solver_interface.py index 5ea5f8592..db6ecc762 100644 --- a/sharpy/utils/solver_interface.py +++ b/sharpy/utils/solver_interface.py @@ -46,7 +46,7 @@ def solver_id(self): # The input is a ProblemData class structure @abstractmethod - def initialise(self, data): + def initialise(self, data, restart=False): pass # This executes the solver From f4f37339b2e1d4ac89cf0bdac201d1332219aa2a Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 8 Jul 2021 18:45:59 +0100 Subject: [PATCH 120/253] save more data to plot in test --- .../multibody/floating_forces/test_floatingforces.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/tests/coupled/multibody/floating_forces/test_floatingforces.py b/tests/coupled/multibody/floating_forces/test_floatingforces.py index fb8470c05..1944b9823 100644 --- a/tests/coupled/multibody/floating_forces/test_floatingforces.py +++ b/tests/coupled/multibody/floating_forces/test_floatingforces.py @@ -143,7 +143,11 @@ def test_time_wave_forces(self): self.assertLess(error, 0.3) save_fig = False - if save_fig: + if save_fig: + np.savetxt("zero_noise_jonswap.txt", np.column_stack((w_js, zero_noise_spectrum))) + np.savetxt("realisations_jonswap.txt", np.column_stack((w_ns, np.abs(ns)))) + np.savetxt("average_jonswap.txt", np.column_stack((w_ns, avg_noise_spectrum))) + import matplotlib.pyplot as plt fig, ax = plt.subplots(1, 1, figsize=(4, 3)) ax.grid() From d48bc5f1d540cc7f68f10f39d002ee242448ec33 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 9 Jul 2021 17:59:50 +0100 Subject: [PATCH 121/253] initial pitch and fix restart bugs --- sharpy/controllers/bladepitchpid.py | 47 +++++++++++++++++++---------- sharpy/solvers/dynamiccoupled.py | 18 +++++++---- 2 files changed, 43 insertions(+), 22 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index a392a4bfc..00bbedef2 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -6,6 +6,7 @@ import sharpy.utils.control_utils as control_utils import sharpy.utils.cout_utils as cout import sharpy.utils.algebra as algebra +from sharpy.utils.constants import deg2rad @controller_interface.controller @@ -86,6 +87,10 @@ class BladePitchPid(controller_interface.BaseController): settings_default['max_pitch_rate'] = 0.1396 settings_description['max_pitch_rate'] = 'Maximum pitch rate [rad/s]' + settings_types['initial_pitch'] = 'float' + settings_default['initial_pitch'] = 0. + settings_description['initial_pitch'] = 'Initial pitch [rad]' + settings_types['min_pitch'] = 'float' settings_default['min_pitch'] = 0. settings_description['min_pitch'] = 'Minimum pitch [rad]' @@ -161,7 +166,7 @@ def __init__(self): # self.n_control_surface = 0 - self.log = None + self.log_fname = None def initialise(self, in_dict, controller_id=None, restart=False): self.in_dict = in_dict @@ -177,10 +182,11 @@ def initialise(self, in_dict, controller_id=None, restart=False): # self.nblades = len(self.settings['blade_num_body']) if self.settings['write_controller_log']: - self.log = open(self.settings['controller_log_route'] + '/' + self.controller_id + '.dat', 'w+') - self.log.write(('#'+ 1*'{:>2},' + 10*'{:>12},' + '{:>12}\n'). + self.log_fname = self.settings['controller_log_route'] + '/' + self.controller_id + '.dat' + fid = open(self.log_fname, 'w+') + fid.write(('#'+ 1*'{:>2},' + 10*'{:>12},' + '{:>12}\n'). format('tstep', 'time', 'ref_state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control', 'gen_torque', 'rotor_vel', 'pitch_vel', 'pitch')) - self.log.flush() + fid.close() # save input time history if self.settings['sp_source'] == 'file': @@ -201,7 +207,8 @@ def initialise(self, in_dict, controller_id=None, restart=False): alpha = np.exp(-self.settings['lp_cut_freq']*self.settings['dt']) self.filter = ss(alpha, 1.-alpha, alpha, 1.-alpha, self.settings['dt']) - self.pitch = 0. + self.pitch = self.settings['initial_pitch']*deg2rad + def control(self, data, controlled_state): r""" @@ -218,6 +225,12 @@ def control(self, data, controlled_state): :returns: A `dict` with `structural` and `aero` time steps and control input included. """ + # TODO: move this to the initialisation with restart + if len(self.system_pv) == 0: + for it in range(data.ts - 1): + self.system_pv.append(0.) + self.prescribed_sp.append(0.) + struct_tstep = controlled_state['structural'] aero_tstep = controlled_state['aero'] if not "info" in controlled_state: @@ -305,7 +318,7 @@ def control(self, data, controlled_state): struct_tstep, tower_ibody=self.settings['blade_num_body'][0] - 1, blade_ibody=self.settings['blade_num_body'][0]) - print("int comp pitch:", self.pitch, int_pitch) + # print("int comp pitch:", self.pitch, int_pitch) controlled_state['info']['pitch_vel'] = pitch_rate @@ -349,11 +362,12 @@ def control(self, data, controlled_state): # controlled_state['aero'].control_surface_deflection = ( # np.array(self.settings['controlled_surfaces_coeff'])*control_command) - print("gen torque [MNm]:", aero_torque/self.settings['GBR']*1e-6, - "rotor_vel:", rotor_vel, - "pitch_vel:", pitch_rate, - "control_c:", control_command) - self.log.write(('{:>6d},' + #print("gen torque [MNm]:", aero_torque/self.settings['GBR']*1e-6, + # "rotor_vel:", rotor_vel, + # "pitch_vel:", pitch_rate, + # "control_c:", control_command) + fid = open(self.log_fname, 'w+') + fid.write(('{:>6d},' + 10*'{:>12.6f},' + '{:>12.6f}\n').format(data.ts, data.ts*self.settings['dt'], @@ -367,6 +381,7 @@ def control(self, data, controlled_state): rotor_vel, pitch_rate, self.pitch)) + fid.close() return controlled_state @@ -420,15 +435,15 @@ def __exit__(self, *args): def drive_train_model(self, aero_torque, ini_rot_vel, ini_rot_acc): # Assuming contant generator torque demand - print(ini_rot_vel) + # print(ini_rot_vel) if self.settings['gen_model_const_var'] == 'power': gen_torque = self.settings['gen_model_const_value']/self.settings['GBR']/ini_rot_vel elif self.settings['gen_model_const_var'] == 'torque': gen_torque = self.settings['gen_model_const_value'] - print("aero_torque", aero_torque) - print("gen_torque", gen_torque*self.settings['GBR']) - print("error_torque", (aero_torque - gen_torque*self.settings['GBR'])/aero_torque*100) + # print("aero_torque", aero_torque) + # print("gen_torque", gen_torque*self.settings['GBR']) + # print("error_torque", (aero_torque - gen_torque*self.settings['GBR'])/aero_torque*100) rot_acc = (aero_torque - self.settings['GBR']*gen_torque)/self.settings['inertia_dt'] # rot_acc = ini_rot_acc + delta_rot_acc @@ -438,7 +453,7 @@ def drive_train_model(self, aero_torque, ini_rot_vel, ini_rot_acc): # (1. - self.newmark_beta)*self.settings['dt']*ini_rot_acc + # self.newmark_beta*self.settings['dt']*rot_acc) rot_vel = ini_rot_vel + rot_acc*self.settings['dt'] - print("rot vel acc", rot_vel, rot_acc) + # print("rot vel acc", rot_vel, rot_acc) return rot_vel, rot_acc # return ini_rot_vel, ini_rot_acc diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 8cbdcabfb..8df67792b 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -306,14 +306,20 @@ def initialise(self, data, custom_settings=None, restart=False): if self.settings['controller_id']: self.with_controllers = True # Remove previous controllers not required on restart - old_list = list(self.controllers.keys()) - for old_list_name in old_list: - if old_list_name not in self.settings['controller_id']: - del self.controllers[old_list_name] + if self.controllers is not None: + old_list = list(self.controllers.keys()) + for old_list_name in old_list: + if old_list_name not in self.settings['controller_id']: + del self.controllers[old_list_name] for controller_id, controller_type in self.settings['controller_id'].items(): - if not controller_id in self.controllers.keys(): + if self.controllers is not None: + if not controller_id in self.controllers.keys(): + self.controllers[controller_id] = ( + controller_interface.initialise_controller(controller_type)) + else: + self.controllers = dict() self.controllers[controller_id] = ( - controller_interface.initialise_controller(controller_type)) + controller_interface.initialise_controller(controller_type)) self.controllers[controller_id].initialise( self.settings['controller_settings'][controller_id], controller_id, restart=restart) From 8aa88713c89332a5eb64f42ba260f0346b5e8867 Mon Sep 17 00:00:00 2001 From: Arturo Date: Sat, 10 Jul 2021 11:09:52 +0100 Subject: [PATCH 122/253] include space delay to waves --- sharpy/generators/floatingforces.py | 140 +++++++++++++++++----------- 1 file changed, 83 insertions(+), 57 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index efdb00ff4..5ff93f279 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -361,49 +361,6 @@ def noise_freq_1s(w): return wn*sigma -def time_wave_forces(Tp, Hs, dt, time, xi, w_xi): - """ - Compute the time evolution of wave forces - """ - # Compute time and frequency discretisations - ntime_steps = time.shape[0] - - nomega = ntime_steps//2 + 1 - w = np.zeros((nomega)) - w_temp = np.fft.fftfreq(ntime_steps, d=dt)*2.*np.pi - w[:ntime_steps//2] = w_temp[:ntime_steps//2] - if ntime_steps%2 == 0: - w[-1] = -1*w_temp[ntime_steps//2] - else: - w[-1] = w_temp[ntime_steps//2] - nomega_2s = ntime_steps - - # Compute the one-sided spectrums - noise_freq = noise_freq_1s(w) - jonswap_1s = jonswap_spectrum(Tp, Hs, w)*2.*np.pi - jonswap_freq = np.sqrt(2*ntime_steps/dt*jonswap_1s/2) + 0j - jonswap_freq[0] = np.sqrt(ntime_steps/dt*jonswap_1s[0]/2) + 0j # The DC values does not have the 2 - - # Compute the two-sided spectrum - force_freq_2s = np.zeros((nomega_2s, 6), dtype=np.complex) - for idim in range(6): - for iomega in range(nomega): - xi_interp = np.interp(w[iomega], w_xi, xi[:, idim]) - force_freq_2s[iomega, idim] = (noise_freq[iomega]* - 0.5*jonswap_freq[iomega]* - xi_interp) - if not iomega == 0: - if not ((iomega == nomega - 1) and (nomega_2s%2 == 0)): - force_freq_2s[-iomega, idim] = (np.conj(noise_freq[iomega])* - 0.5*jonswap_freq[iomega]* - np.conj(xi_interp)) - - # Compute the inverse Fourier transform - force_waves = ifft(force_freq_2s, axis=0) - - return force_waves - - @generator_interface.generator class FloatingForces(generator_interface.BaseGenerator): r""" @@ -704,16 +661,12 @@ def initialise(self, in_dict=None, data=None, restart=False): interp_x2 = interp1d(self.floating_data['wave_forces']['xi_beta_deg']*deg2rad, xi_matrix2, axis=0) - xi = interp_x2(self.settings['wave_incidence']) + self.xi_interp = interp_x2(self.settings['wave_incidence']) # xi = interp_x2(self.floating_data['wave_forces']['xi_beta_deg'][5]*deg2rad) # print(xi[0, :]) # print(self.floating_data['wave_forces']['xi'][2, 5, :]) # print(xi[0, :] - self.floating_data['wave_forces']['xi'][2, 5, :]) - phase = self.settings['wave_freq']*np.arange(self.settings['n_time_steps'] + 1)*self.settings['dt'] - self.wave_forces_g = np.zeros((self.settings['n_time_steps'] + 1, 6)) - for idim in range(6): - self.wave_forces_g[:, idim] = np.real(self.settings['wave_amplitude']*xi[idim]*(np.cos(phase) + 1j*np.sin(phase))) elif self.settings['method_wave'] == 'jonswap': @@ -722,12 +675,12 @@ def initialise(self, in_dict=None, data=None, restart=False): axis=1) xi_matrix = interp_x1(self.settings['wave_incidence']) - self.wave_forces_g = np.real(time_wave_forces(self.settings['wave_Tp'], - self.settings['wave_Hs'], - self.settings['dt'], - np.arange(self.settings['n_time_steps'] + 1)*self.settings['dt'], - xi_matrix, - self.floating_data['wave_forces']['xi_freq_rads'])) + self.freq_wave_forces_variables(self.settings['wave_Tp'], + self.settings['wave_Hs'], + self.settings['dt'], + np.arange(self.settings['n_time_steps'] + 1)*self.settings['dt'], + xi_matrix, + self.floating_data['wave_forces']['xi_freq_rads']) # Log file if not os.path.exists(self.settings['folder']): @@ -805,6 +758,67 @@ def update_dof_vector(self, beam, struct_tstep, it, k): return + def freq_wave_forces_variables(self, Tp, Hs, dt, time, xi, w_xi): + """ + Compute the frequency arrays needed for wave forces + """ + # Compute time and frequency discretisations + ntime_steps = time.shape[0] + + nomega = ntime_steps//2 + 1 + w = np.zeros((nomega)) + w_temp = np.fft.fftfreq(ntime_steps, d=dt)*2.*np.pi + w[:ntime_steps//2] = w_temp[:ntime_steps//2] + if ntime_steps%2 == 0: + w[-1] = -1*w_temp[ntime_steps//2] + else: + w[-1] = w_temp[ntime_steps//2] + nomega_2s = ntime_steps + + # Compute the one-sided spectrums + noise_freq = noise_freq_1s(w) + jonswap_1s = jonswap_spectrum(Tp, Hs, w)*2.*np.pi + jonswap_freq = np.sqrt(2*ntime_steps/dt*jonswap_1s/2) + 0j + jonswap_freq[0] = np.sqrt(ntime_steps/dt*jonswap_1s[0]/2) + 0j # The DC values does not have the 2 + + self.noise_freq = noise_freq + self.jonswap_freq = jonswap_freq + self.omega = w + self.nomega_2s = nomega_2s + + self.xi_interp = np.zeros((nomega, 6), dtype=np.complex) + for iomega in range(nomega): + for idim in range(6): + self.xi_interp[iomega, idim] = np.interp(self.omega[iomega], w_xi, xi[:, idim]) + + + def time_wave_forces(self, dx, grav): + """ + Compute the time evolution of wave forces + """ + + # Compute the two-sided spectrum + force_freq_2s = np.zeros((self.nomega_2s, 6), dtype=np.complex) + for idim in range(6): + for iomega in range(self.omega.shape[0]): + k = self.omega[iomega]**2/grav + force_freq_2s[iomega, idim] = (self.noise_freq[iomega]* + 0.5*self.jonswap_freq[iomega]* + self.xi_interp[iomega, idim]* + np.exp(-1j*k*dx)) + if not iomega == 0: + if not ((iomega == self.omega.shape[0] - 1) and (self.nomega_2s%2 == 0)): + force_freq_2s[-iomega, idim] = (np.conj(self.noise_freq[iomega])* + 0.5*self.jonswap_freq[iomega]* + np.conj(self.xi_interp[iomega, idim])* + np.exp(1j*k*dx)) + + # Compute the inverse Fourier transform + force_waves = ifft(force_freq_2s, axis=0) + + return np.real(force_waves) + + def generate(self, params): # Renaming for convenience data = params['data'] @@ -978,11 +992,23 @@ def generate(self, params): cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) cbg = np.dot(cab.T, cga.T) - struct_tstep.runtime_unsteady_forces[self.wave_forces_node, 0:3] += np.dot(cbg, self.wave_forces_g[data.ts, 0:3]) - struct_tstep.runtime_unsteady_forces[self.wave_forces_node, 3:6] += np.dot(cbg, self.wave_forces_g[data.ts, 3:6]) + wave_node_pos = struct_tstep.for_pos[0:3] + np.dot(cga, struct_tstep.pos[self.wave_forces_node, :]) + dx = (wave_node_pos[1]*np.sin(self.settings['wave_incidence']) + + wave_node_pos[2]*np.cos(self.settings['wave_incidence'])) + wave_forces_g = np.zeros((6)) + if self.settings['method_wave'] == 'sin': + phase = (self.settings['wave_freq']*data.ts*self.settings['dt'] + + dx*self.settings['wave_freq']**2/self.settings['gravity']) + for idim in range(6): + wave_forces_g[idim] = np.real(self.settings['wave_amplitude']*self.xi_interp[idim]*(np.cos(phase) + 1j*np.sin(phase))) + elif self.settings['method_wave'] == 'jonswap': + wave_forces_g = self.time_wave_forces(dx, self.settings['gravity'])[data.ts, :] + + struct_tstep.runtime_unsteady_forces[self.wave_forces_node, 0:3] += np.dot(cbg, wave_forces_g[0:3]) + struct_tstep.runtime_unsteady_forces[self.wave_forces_node, 3:6] += np.dot(cbg, wave_forces_g[3:6]) # Write output if self.settings['write_output']: self.write_output(data.ts, k, mooring_forces, mooring_yaw, hs_f_g, - hd_f_qdot_g, hd_f_qdotdot_g, hd_correct_grav, total_drag_force, self.wave_forces_g[data.ts, :]) + hd_f_qdot_g, hd_f_qdotdot_g, hd_correct_grav, total_drag_force, wave_forces_g) From 233eb24498a45bc4a4535be211598e12e414de92 Mon Sep 17 00:00:00 2001 From: Arturo Date: Mon, 12 Jul 2021 18:29:45 +0100 Subject: [PATCH 123/253] append controller output --- sharpy/controllers/bladepitchpid.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 00bbedef2..0a8d60900 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -183,7 +183,7 @@ def initialise(self, in_dict, controller_id=None, restart=False): if self.settings['write_controller_log']: self.log_fname = self.settings['controller_log_route'] + '/' + self.controller_id + '.dat' - fid = open(self.log_fname, 'w+') + fid = open(self.log_fname, 'a') fid.write(('#'+ 1*'{:>2},' + 10*'{:>12},' + '{:>12}\n'). format('tstep', 'time', 'ref_state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control', 'gen_torque', 'rotor_vel', 'pitch_vel', 'pitch')) fid.close() @@ -366,7 +366,7 @@ def control(self, data, controlled_state): # "rotor_vel:", rotor_vel, # "pitch_vel:", pitch_rate, # "control_c:", control_command) - fid = open(self.log_fname, 'w+') + fid = open(self.log_fname, 'a') fid.write(('{:>6d},' + 10*'{:>12.6f},' + '{:>12.6f}\n').format(data.ts, From 9b47688cd6cc3d2dd7481f5ddd48b0dc78e4b9a3 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 13 Jul 2021 16:51:22 +0100 Subject: [PATCH 124/253] fix radians initial pitch --- sharpy/controllers/bladepitchpid.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 0a8d60900..4a8d29bf7 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -207,7 +207,7 @@ def initialise(self, in_dict, controller_id=None, restart=False): alpha = np.exp(-self.settings['lp_cut_freq']*self.settings['dt']) self.filter = ss(alpha, 1.-alpha, alpha, 1.-alpha, self.settings['dt']) - self.pitch = self.settings['initial_pitch']*deg2rad + self.pitch = self.settings['initial_pitch'] def control(self, data, controlled_state): From d80d961ca4c34c063e5750740d8ca60e82e29738 Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 14 Jul 2021 20:11:28 +0100 Subject: [PATCH 125/253] fix drag force --- sharpy/generators/floatingforces.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 5ff93f279..1021441ea 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -882,6 +882,10 @@ def generate(self, params): mooring_yaw) # Hydrostatic model + ielem, inode_in_elem = data.structure.node_master_elem[self.buoyancy_node] + cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) + cbg = np.dot(cab.T, cga.T) + hs_f_g = - np.dot(self.buoy_rest_mat, self.q[data.ts, :]) add_damp = self.floating_data['hydrodynamics']['additional_damping'].copy() @@ -926,10 +930,6 @@ def generate(self, params): else: hd_correct_grav = np.zeros((6)) - ielem, inode_in_elem = data.structure.node_master_elem[self.buoyancy_node] - cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) - cbg = np.dot(cab.T, cga.T) - struct_tstep.runtime_steady_forces[self.buoyancy_node, 0:3] += np.dot(cbg, self.buoy_F0[0:3] + hs_f_g[0:3]) struct_tstep.runtime_steady_forces[self.buoyancy_node, 3:6] += np.dot(cbg, self.buoy_F0[3:6] + hs_f_g[3:6]) struct_tstep.runtime_unsteady_forces[self.buoyancy_node, 0:3] += np.dot(cbg, hd_f_qdot_g[0:3] + hd_f_qdotdot_g[0:3]) @@ -948,7 +948,7 @@ def generate(self, params): for inode in range(len(spar_node_pos)): if self.settings['concentrate_spar']: - ielem, inode_in_elem = data.structure.node_master_elem[inode + self.floating_data['hydrodynamics']['CD_node']] + ielem, inode_in_elem = data.structure.node_master_elem[self.floating_data['hydrodynamics']['CD_node']] else: ielem, inode_in_elem = data.structure.node_master_elem[inode + self.floating_data['hydrodynamics']['CD_first_node']] cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem]) From 0c42f21db1f60a861609aaf248787305a3abe050 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 15 Jul 2021 11:47:08 +0100 Subject: [PATCH 126/253] new controllers folder --- sharpy/controllers/bladepitchpid.py | 20 +++++++++---------- .../controlsurfacepidcontroller.py | 12 +++++------ .../takeofftrajectorycontroller.py | 8 +++++--- sharpy/solvers/dynamiccoupled.py | 2 +- 4 files changed, 20 insertions(+), 22 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 4a8d29bf7..31a7c82dc 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -132,11 +132,6 @@ class BladePitchPid(controller_interface.BaseController): 'Write a time history of input, required input, ' + 'and control') - settings_types['controller_log_route'] = 'str' - settings_default['controller_log_route'] = './output/' - settings_description['controller_log_route'] = ( - 'Directory where the log will be stored') - settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, @@ -168,7 +163,7 @@ def __init__(self): self.log_fname = None - def initialise(self, in_dict, controller_id=None, restart=False): + def initialise(self, data, in_dict, controller_id=None, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, @@ -180,11 +175,14 @@ def initialise(self, in_dict, controller_id=None, restart=False): # self.controller_id = controller_id # self.nblades = len(self.settings['blade_num_body']) - + if self.settings['write_controller_log']: - self.log_fname = self.settings['controller_log_route'] + '/' + self.controller_id + '.dat' + folder = data.output_folder + '/controllers/' + if not os.path.exists(folder): + os.makedirs(folder) + self.log_fname = (folder + self.controller_id + ".dat") fid = open(self.log_fname, 'a') - fid.write(('#'+ 1*'{:>2},' + 10*'{:>12},' + '{:>12}\n'). + fid.write(('#'+ 1*'{:>2} ' + 10*'{:>12} ' + '{:>12}\n'). format('tstep', 'time', 'ref_state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control', 'gen_torque', 'rotor_vel', 'pitch_vel', 'pitch')) fid.close() @@ -367,8 +365,8 @@ def control(self, data, controlled_state): # "pitch_vel:", pitch_rate, # "control_c:", control_command) fid = open(self.log_fname, 'a') - fid.write(('{:>6d},' - + 10*'{:>12.6f},' + fid.write(('{:>6d} ' + + 10*'{:>12.6f} ' + '{:>12.6f}\n').format(data.ts, data.ts*self.settings['dt'], self.prescribed_sp[-1], diff --git a/sharpy/controllers/controlsurfacepidcontroller.py b/sharpy/controllers/controlsurfacepidcontroller.py index 64848c8d7..365c858ca 100644 --- a/sharpy/controllers/controlsurfacepidcontroller.py +++ b/sharpy/controllers/controlsurfacepidcontroller.py @@ -61,11 +61,6 @@ class ControlSurfacePidController(controller_interface.BaseController): 'Write a time history of input, required input, ' + 'and control') - settings_types['controller_log_route'] = 'str' - settings_default['controller_log_route'] = './output/' - settings_description['controller_log_route'] = ( - 'Directory where the log will be stored') - supported_input_types = ['pitch', 'roll', 'pos_'] settings_table = settings.SettingsTable() @@ -96,7 +91,7 @@ def __init__(self): self.log = None - def initialise(self, in_dict, controller_id=None, restart=False): + def initialise(self, data, in_dict, controller_id=None, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, @@ -120,7 +115,10 @@ def initialise(self, in_dict, controller_id=None, restart=False): raise NotImplementedError() if self.settings['write_controller_log']: - self.log = open(self.settings['controller_log_route'] + '/' + self.controller_id + '.log.csv', 'w+') + folder = data.output_folder + '/controllers/' + if not os.path.exists(folder): + os.makedirs(folder) + self.log = open(folder + self.controller_id + ".log.csv", "w+") self.log.write(('#'+ 1*'{:>2},' + 6*'{:>12},' + '{:>12}\n'). format('tstep', 'time', 'Ref. state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control')) self.log.flush() diff --git a/sharpy/controllers/takeofftrajectorycontroller.py b/sharpy/controllers/takeofftrajectorycontroller.py index e68795fae..4ee21b155 100644 --- a/sharpy/controllers/takeofftrajectorycontroller.py +++ b/sharpy/controllers/takeofftrajectorycontroller.py @@ -87,7 +87,7 @@ def __init__(self): self.log = None - def initialise(self, in_dict, controller_id=None, restart=False): + def initialise(self, data, in_dict, controller_id=None, restart=False): self.in_dict = in_dict settings.to_custom_types(self.in_dict, self.settings_types, @@ -98,8 +98,10 @@ def initialise(self, in_dict, controller_id=None, restart=False): if self.settings['write_controller_log']: # TODO substitute for table writer in cout_utils. - self.log = open(self.settings['controller_log_route'] + - '/' + self.controller_id + '.log.csv', 'w+') + folder = data.output_folder + '/controllers/' + if not os.path.exists(folder): + os.makedirs(folder) + self.log = open(folder + self.controller_id + ".log.csv", "w+") self.log.write(('#'+ 1*'{:>2},' + 6*'{:>12},' + '{:>12}\n'). format('tstep', 'time', 'Ref. state', 'state', 'Pcontrol', 'Icontrol', 'Dcontrol', 'control')) self.log.flush() diff --git a/sharpy/solvers/dynamiccoupled.py b/sharpy/solvers/dynamiccoupled.py index 8df67792b..44ed0a308 100644 --- a/sharpy/solvers/dynamiccoupled.py +++ b/sharpy/solvers/dynamiccoupled.py @@ -320,7 +320,7 @@ def initialise(self, data, custom_settings=None, restart=False): self.controllers = dict() self.controllers[controller_id] = ( controller_interface.initialise_controller(controller_type)) - self.controllers[controller_id].initialise( + self.controllers[controller_id].initialise(self.data, self.settings['controller_settings'][controller_id], controller_id, restart=restart) From e6154e21255dc94e18791cf2e266f88a614000ab Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 20 Jul 2021 11:03:50 +0100 Subject: [PATCH 127/253] import os controllers --- sharpy/controllers/bladepitchpid.py | 1 + sharpy/controllers/controlsurfacepidcontroller.py | 1 + sharpy/controllers/takeofftrajectorycontroller.py | 1 + 3 files changed, 3 insertions(+) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 31a7c82dc..0add0dc6a 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -1,4 +1,5 @@ import numpy as np +import os from control import ss, forced_response import sharpy.utils.controller_interface as controller_interface diff --git a/sharpy/controllers/controlsurfacepidcontroller.py b/sharpy/controllers/controlsurfacepidcontroller.py index 365c858ca..e30098660 100644 --- a/sharpy/controllers/controlsurfacepidcontroller.py +++ b/sharpy/controllers/controlsurfacepidcontroller.py @@ -1,4 +1,5 @@ import numpy as np +import os import sharpy.utils.controller_interface as controller_interface import sharpy.utils.settings as settings diff --git a/sharpy/controllers/takeofftrajectorycontroller.py b/sharpy/controllers/takeofftrajectorycontroller.py index 4ee21b155..80b1112e0 100644 --- a/sharpy/controllers/takeofftrajectorycontroller.py +++ b/sharpy/controllers/takeofftrajectorycontroller.py @@ -1,5 +1,6 @@ import ctypes as ct import numpy as np +import os import scipy.interpolate as interpolate import sharpy.utils.controller_interface as controller_interface From 8bc147a1531c36b829cc27f9dbd6ea962388e91b Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 21 Jul 2021 17:30:33 +0100 Subject: [PATCH 128/253] fix bugs controller --- sharpy/controllers/bladepitchpid.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 0add0dc6a..ee164f338 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -285,7 +285,7 @@ def control(self, data, controlled_state): 'I': self.settings['I'], 'D': self.settings['D']}, i_current=data.ts) - control_command *= -1. + # control_command *= -1. # Limit pitch and pitch rate # current_pitch = algebra.quat2euler(struct_tstep.mb_quat[self.settings['blade_num_body'][0]])[0] # print(control_command, current_pitch) @@ -474,7 +474,7 @@ def compute_aero_torque(self, beam, struct_tstep): hub_forces = np.zeros((6)) hub_forces[0:3] = total_forces[0:3].copy() - hub_forces[3:6] = total_forces[3:6] + np.cross(hub_pos, total_forces[0:3]) + hub_forces[3:6] = total_forces[3:6] - np.cross(hub_pos, total_forces[0:3]) return hub_forces[5] From f664a1ad66ae16cb50338ae85e1791806b536730 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 22 Jul 2021 12:16:16 +0100 Subject: [PATCH 129/253] option map forces in staticuvlm --- sharpy/solvers/staticuvlm.py | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/sharpy/solvers/staticuvlm.py b/sharpy/solvers/staticuvlm.py index da103b31e..61eb21e0b 100644 --- a/sharpy/solvers/staticuvlm.py +++ b/sharpy/solvers/staticuvlm.py @@ -8,6 +8,7 @@ from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.utils.generator_interface as gen_interface from sharpy.utils.constants import vortex_radius_def +import sharpy.aero.utils.mapping as mapping @solver @@ -110,6 +111,10 @@ class StaticUvlm(BaseSolver): settings_default['centre_rot_g'] = [0., 0., 0.] settings_description['centre_rot_g'] = 'Centre of rotation in G FoR around which ``rbm_vel_g`` is applied' + settings_types['map_forces_on_struct'] = 'bool' + settings_default['map_forces_on_struct'] = False + settings_description['map_forces_on_struct'] = 'Maps the forces on the structure at the end of the timestep. Only usefull if the solver is used outside StaticCoupled' + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -180,6 +185,18 @@ def run(self, **kwargs): uvlmlib.vlm_solver(aero_tstep, self.settings) + if self.settings['map_forces_on_struct']: + structure_tstep.steady_applied_forces[:] = mapping.aero2struct_force_mapping( + aero_tstep.forces, + self.data.aero.struct2aero_mapping, + self.data.aero.timestep_info[self.data.ts].zeta, + structure_tstep.pos, + structure_tstep.psi, + self.data.structure.node_master_elem, + self.data.structure.connectivities, + structure_tstep.cag(), + self.data.aero.aero_dict) + return self.data def next_step(self): From 81e4e7f040881a51fe2716660696deab89d8643a Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 22 Jul 2021 22:04:34 +0100 Subject: [PATCH 130/253] option to apply sweep before twist --- cases/templates/template_wt.py | 17 ++++++++++------- sharpy/aero/models/aerogrid.py | 23 +++++++++++++++-------- sharpy/utils/generate_cases.py | 23 ++++++++++++++++++++--- 3 files changed, 45 insertions(+), 18 deletions(-) diff --git a/cases/templates/template_wt.py b/cases/templates/template_wt.py index d5ad1d440..887e3efc6 100644 --- a/cases/templates/template_wt.py +++ b/cases/templates/template_wt.py @@ -418,6 +418,7 @@ def rotor_from_excel_type03(in_op_params, options['user_defined_m_distribution_type'] = None # type of distribution of the chordwise panels when 'm_distribution' == 'user_defined' options['include_polars'] = False # options['separate_blades'] = False # Keep blades as different bodies + options['twist_in_aero'] = False # Twist the aerodynamic surface instead of the structure excel_description = {} excel_description['excel_file_name'] = 'database_excel_type02.xlsx' @@ -602,7 +603,7 @@ def rotor_from_excel_type03(in_op_params, stiffness_db=blade.StructuralInformation.stiffness_db, mass_db=blade.StructuralInformation.mass_db, frame_of_reference_delta='y_AFoR', - vec_node_structural_twist=node_twist, + vec_node_structural_twist=np.zeros_like(node_twist) if options['twist_in_aero'] else node_twist, num_lumped_mass=0) # Boundary conditions @@ -691,11 +692,11 @@ def rotor_from_excel_type03(in_op_params, else: udmd_by_nodes = None - node_twist = np.zeros_like(node_chord) + node_twist_aero = np.zeros_like(node_chord) if camber_effect_on_twist: cout.cout_wrap("WARNING: The steady applied Mx should be manually multiplied by the density", 3) for inode in range(blade.StructuralInformation.num_node): - node_twist[inode] = gc.get_aoacl0_from_camber(airfoils[inode, :, 0], airfoils[inode, :, 1]) + node_twist_aero[inode] = gc.get_aoacl0_from_camber(airfoils[inode, :, 0], airfoils[inode, :, 1]) mu0 = gc.get_mu0_from_camber(airfoils[inode, :, 0], airfoils[inode, :, 1]) r = np.linalg.norm(blade.StructuralInformation.coordinates[inode, :]) vrel = np.sqrt(rotation_velocity**2*r**2 + wsp**2) @@ -706,15 +707,15 @@ def rotor_from_excel_type03(in_op_params, else: dr = 0.5*np.linalg.norm(blade.StructuralInformation.coordinates[inode + 1, :] - blade.StructuralInformation.coordinates[inode - 1, :]) moment_factor = 0.5*vrel**2*node_chord[inode]**2*dr - # print("node", inode, "mu0", mu0, "CMc/4", 2.*mu0 + np.pi/2*node_twist[inode]) - blade.StructuralInformation.app_forces[inode, 3] = (2.*mu0 + np.pi/2*node_twist[inode])*moment_factor + # print("node", inode, "mu0", mu0, "CMc/4", 2.*mu0 + np.pi/2*node_twist_struct[inode]) + blade.StructuralInformation.app_forces[inode, 3] = (2.*mu0 + np.pi/2*node_twist_aero[inode])*moment_factor airfoils[inode, :, 1] *= 0. # Write SHARPy format blade.AerodynamicInformation.create_aerodynamics_from_vec(blade.StructuralInformation, aero_node, node_chord, - node_twist, + (node_twist + node_twist_aero) if options['twist_in_aero'] else node_twist_aero, np.pi*np.ones_like(node_chord), chord_panels, surface_distribution, @@ -722,7 +723,8 @@ def rotor_from_excel_type03(in_op_params, node_ElAxisAftLEc, airfoil_distribution, airfoils, - udmd_by_nodes) + udmd_by_nodes, + first_twist=False) # Read the polars of the pure airfoils if include_polars: @@ -1099,6 +1101,7 @@ def rotor_from_excel_type02(chord_panels, options['camber_effect_on_twist'] = camber_effect_on_twist options['user_defined_m_distribution_type'] = user_defined_m_distribution_type options['include_polars'] = False + options['twist_in_aero'] = False excel_description = {} excel_description['excel_file_name'] = excel_file_name diff --git a/sharpy/aero/models/aerogrid.py b/sharpy/aero/models/aerogrid.py index ad4acc2f2..0030b56b9 100644 --- a/sharpy/aero/models/aerogrid.py +++ b/sharpy/aero/models/aerogrid.py @@ -222,6 +222,10 @@ def generate_zeta_timestep_info(self, structure_tstep, aero_tstep, beam, aero_se except KeyError: self.aero_dict['sweep'] = np.zeros_like(self.aero_dict['twist']) + # Define first_twist for backwards compatibility + if 'first_twist' not in self.aero_dict: + self.aero_dict['first_twist'] = [True]*self.aero_dict['surface_m'].shape[0] + # one surface per element for i_elem in range(self.n_elem): i_surf = self.aero_dict['surface_distribution'][i_elem] @@ -348,7 +352,8 @@ def generate_zeta_timestep_info(self, structure_tstep, aero_tstep, beam, aero_se self.airfoil_db, aero_settings['aligned_grid'], orientation_in=aero_settings['freestream_dir'], - calculate_zeta_dot=True)) + calculate_zeta_dot=True, + first_twist=self.aero_dict['first_twist'][i_surf])) def generate_zeta(self, beam, aero_settings, ts=-1, beam_ts=-1): self.generate_zeta_timestep_info(beam.timestep_info[beam_ts], @@ -479,7 +484,10 @@ def compute_gamma_dot(dt, tstep, previous_tsteps): -def generate_strip(node_info, airfoil_db, aligned_grid, orientation_in=np.array([1, 0, 0]), calculate_zeta_dot = False): +def generate_strip(node_info, airfoil_db, aligned_grid, + orientation_in=np.array([1, 0, 0]), + calculate_zeta_dot = False, + first_twist=True): """ Returns a strip of panels in ``A`` frame of reference, it has to be then rotated to simulate angles of attack, etc @@ -495,11 +503,6 @@ def generate_strip(node_info, airfoil_db, aligned_grid, orientation_in=np.array( strip_coordinates_b_frame[1, :] = np.linspace(0.0, 1.0, node_info['M'] + 1) elif node_info['M_distribution'] == '1-cos': domain = np.linspace(0, 1.0, node_info['M'] + 1) - strip_coordinates_b_frame[1, :] = 0.5*(1.0 - np.cos(domain*np.pi)) - elif node_info['M_distribution'].lower() == 'user_defined': - # strip_coordinates_b_frame[1, :-1] = np.linspace(0.0, 1.0 - node_info['last_panel_length'], node_info['M']) - # strip_coordinates_b_frame[1,-1] = 1. - strip_coordinates_b_frame[1,:] = node_info['user_defined_m_distribution'] else: raise NotImplemented('M_distribution is ' + node_info['M_distribution'] + ' and it is not yet supported') @@ -567,8 +570,12 @@ def generate_strip(node_info, airfoil_db, aligned_grid, orientation_in=np.array( # transformation from beam to beam prime (with sweep and twist) for i_M in range(node_info['M'] + 1): - strip_coordinates_b_frame[:, i_M] = np.dot(c_sweep, np.dot(Crot, + if first_twist: + strip_coordinates_b_frame[:, i_M] = np.dot(c_sweep, np.dot(Crot, np.dot(Ctwist, strip_coordinates_b_frame[:, i_M]))) + else: + strip_coordinates_b_frame[:, i_M] = np.dot(Ctwist, np.dot(Crot, + np.dot(c_sweep, strip_coordinates_b_frame[:, i_M]))) strip_coordinates_a_frame[:, i_M] = np.dot(Cab, strip_coordinates_b_frame[:, i_M]) cs_velocity[:, i_M] = np.dot(Cab, cs_velocity[:, i_M]) diff --git a/sharpy/utils/generate_cases.py b/sharpy/utils/generate_cases.py index 1c59ba34a..b2b5c74c1 100644 --- a/sharpy/utils/generate_cases.py +++ b/sharpy/utils/generate_cases.py @@ -1062,6 +1062,7 @@ def __init__(self): # self.control_surface_chord = None # self.control_surface_hinge_coords = None self.polars = None + self.first_twist = [None] def copy(self): """ @@ -1087,6 +1088,7 @@ def copy(self): copied.user_defined_m_distribution = self.user_defined_m_distribution.copy() if self.polars is not None: copied.polars = self.polars.copy() + copied.first_twist = self.first_twist.copy() return copied @@ -1119,6 +1121,7 @@ def set_to_zero(self, num_node_elem, num_node, num_elem, self.airfoils = np.zeros((num_airfoils, num_points_camber, 2), dtype=float) for iairfoil in range(num_airfoils): self.airfoils[iairfoil, :, 0] = np.linspace(0.0, 1.0, num_points_camber) + self.first_twist = [True] def generate_full_aerodynamics(self, aero_node, @@ -1130,7 +1133,8 @@ def generate_full_aerodynamics(self, m_distribution, elastic_axis, airfoil_distribution, - airfoils): + airfoils, + first_twist): """ generate_full_aerodynamics @@ -1147,6 +1151,7 @@ def generate_full_aerodynamics(self, elastic_axis (np.array): position of the elastic axis in the chord airfoil_distribution (np.array): airfoil at each element node airfoils (np.array): coordinates of the camber lines of the airfoils + first_twist (list(bool)): Apply the twist rotation before the sweep """ self.aero_node = aero_node @@ -1159,6 +1164,7 @@ def generate_full_aerodynamics(self, self.elastic_axis = elastic_axis self.airfoil_distribution = airfoil_distribution self.airfoils = airfoils + self.first_twist = first_twist def create_aerodynamics_from_vec(self, StructuralInformation, @@ -1172,7 +1178,8 @@ def create_aerodynamics_from_vec(self, vec_elastic_axis, vec_airfoil_distribution, airfoils, - user_defined_m_distribution=None): + user_defined_m_distribution=None, + first_twist=True): """ create_aerodynamics_from_vec @@ -1190,6 +1197,7 @@ def create_aerodynamics_from_vec(self, vec_elastic_axis (np.array): position of the elastic axis in the chord vec_airfoil_distribution (np.array): airfoil at each element node airfoils (np.array): coordinates of the camber lines of the airfoils + first_twist (bool): Apply the twist rotation before the sweep """ self.aero_node = vec_aero_node @@ -1210,6 +1218,8 @@ def create_aerodynamics_from_vec(self, udmd_by_elements = from_node_array_to_elem_matrix(user_defined_m_distribution, StructuralInformation.connectivities) self.user_defined_m_distribution = [udmd_by_elements] + self.first_twist = [first_twist] + def create_one_uniform_aerodynamics(self, StructuralInformation, chord, @@ -1219,7 +1229,8 @@ def create_one_uniform_aerodynamics(self, m_distribution, elastic_axis, num_points_camber, - airfoil): + airfoil, + first_twist=True): """ create_one_uniform_aerodynamics @@ -1235,6 +1246,7 @@ def create_one_uniform_aerodynamics(self, elastic_axis (float): position of the elastic axis in the chord num_points_camber (int): Number of points to define the camber line airfoils (np.array): coordinates of the camber lines of the airfoils + first_twist (bool): Apply the twist rotation before the sweep """ num_node = StructuralInformation.num_node num_node_elem = StructuralInformation.num_node_elem @@ -1258,6 +1270,8 @@ def create_one_uniform_aerodynamics(self, self.user_defined_m_distribution = [] self.user_defined_m_distribution.append(np.zeros((num_chord_panels + 1, num_elem, num_node_elem))) + self.first_twist = [first_twist] + def change_airfoils_discretezation(self, airfoils, new_num_nodes): """ change_airfoils_discretezation @@ -1333,6 +1347,7 @@ def assembly_aerodynamics(self, *args): # total_num_surfaces += len(aerodynamics_to_add.surface_m) total_num_surfaces += np.sum(aerodynamics_to_add.surface_m != -1) + self.first_twist.extend(aerodynamics_to_add.first_twist) # self.num_airfoils = total_num_airfoils # self.num_surfaces = total_num_surfaces @@ -1471,6 +1486,8 @@ def generate_aero_file(self, route, case_name, StructuralInformation): h5file.create_dataset('elastic_axis', data=self.elastic_axis) h5file.create_dataset('airfoil_distribution', data=self.airfoil_distribution) h5file.create_dataset('sweep', data=self.sweep) + + h5file.create_dataset('first_twist', data=np.array(self.first_twist)) airfoils_group = h5file.create_group('airfoils') for iairfoil in range(len(self.airfoils)): From 8b54e620dad5d6212898a826f6a3605976898572 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 19 Aug 2021 20:30:13 +0100 Subject: [PATCH 131/253] option to generate aero in initialaeroelasticloader --- sharpy/solvers/initialaeroelasticloader.py | 50 +++++++++++++++------- 1 file changed, 34 insertions(+), 16 deletions(-) diff --git a/sharpy/solvers/initialaeroelasticloader.py b/sharpy/solvers/initialaeroelasticloader.py index 32a55d945..41064711b 100644 --- a/sharpy/solvers/initialaeroelasticloader.py +++ b/sharpy/solvers/initialaeroelasticloader.py @@ -29,6 +29,10 @@ class InitialAeroelasticLoader(BaseSolver): settings_default['include_forces'] = True settings_description['include_forces'] = 'Map the forces' + settings_types['generate_aero'] = 'bool' + settings_default['generate_aero'] = False + settings_description['generate_aero'] = 'Generate the aerodynamics grids from scratch' + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -78,22 +82,36 @@ def run(self, **kwargs): exceptions.NotValidInputFile(error_msg) # Copy aero information - attributes = ['zeta', 'zeta_star', 'normals', - 'gamma', 'gamma_star', - 'u_ext', 'u_ext_star',] - # 'dist_to_orig', 'gamma_dot', 'zeta_dot', - - if self.settings['include_forces']: - attributes.extend(['dynamic_forces', 'forces',]) + if self.settings['generate_aero']: + # Generate aerodynamic surface + self.data.aero.generate_zeta_timestep_info(structural_step, + aero_step, + self.data.structure, + self.data.aero.aero_settings) + # generate the wake because the solid shape might change + self.data.aero.wake_shape_generator.generate({'zeta': aero_step.zeta, + 'zeta_star': aero_step.zeta_star, + 'gamma': aero_step.gamma, + 'gamma_star': aero_step.gamma_star, + 'dist_to_orig': aero_step.dist_to_orig}) - for att in attributes: - for isurf in range(aero_step.n_surf): - new_attr = getattr(aero_step, att)[isurf] - db_attr = getattr(self.file_info.aero, att)[isurf] - if new_attr.shape == db_attr.shape: - new_attr[...] = db_attr - else: - error_msg = "Non matching shapes in attribute %s" % att - exceptions.NotValidInputFile(error_msg) + else: + attributes = ['zeta', 'zeta_star', 'normals', + 'gamma', 'gamma_star', + 'u_ext', 'u_ext_star',] + # 'dist_to_orig', 'gamma_dot', 'zeta_dot', + + if self.settings['include_forces']: + attributes.extend(['dynamic_forces', 'forces',]) + + for att in attributes: + for isurf in range(aero_step.n_surf): + new_attr = getattr(aero_step, att)[isurf] + db_attr = getattr(self.file_info.aero, att)[isurf] + if new_attr.shape == db_attr.shape: + new_attr[...] = db_attr + else: + error_msg = "Non matching shapes in attribute %s" % att + exceptions.NotValidInputFile(error_msg) return self.data From 7163110b9352c977d5dff6112376c3e1e43fe034 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 20 Aug 2021 10:49:55 +0100 Subject: [PATCH 132/253] rotor velocity wrt zb --- sharpy/structure/utils/lagrangeconstraints.py | 12 +++--------- 1 file changed, 3 insertions(+), 9 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index bd8804f52..83d3783e0 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -1052,8 +1052,6 @@ def initialise(self, MBdict_entry, ieq, print_info=True): raise NotImplementedError("Hinges should be parallel to the xB, yB or zB of the reference node") self.set_rot_vel(MBdict_entry['rot_vect'][self.nonzero_comp]) - self.pitch_vel = set_value_or_default(MBdict_entry, "pitch_vel", 0.) - # self.static_constraint = fully_constrained_node_FoR() # self.static_constraint.initialise(MBdict_entry, ieq) @@ -1064,10 +1062,6 @@ def set_rot_vel(self, rot_vel): self.rot_vel = rot_vel - def set_pitch_vel(self, pitch_vel): - self.pitch_vel = pitch_vel - - def staticmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, sys_size, dt, Lambda, Lambda_dot): return @@ -1187,9 +1181,9 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem, inode_in_elem, :]) FoR_cga = MB_tstep[self.FoR_body].cga() - rel_vel = np.array([0., 0., self.rotor_vel]) - rel_vel += ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, - np.array([self.pitch_vel, 0., 0.])) + rel_vel = np.array([self.pitch_vel, 0., 0.]) + rel_vel += ag.multiply_matrices(FoR_cga.T, node_cga, cab, + np.array([0., 0., self.rotor_vel])) # Define the equations ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_posB=self.rel_posB) From a86bd67f2307ac75531d2cb5f7ae913b2f151fe0 Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 20 Aug 2021 10:50:34 +0100 Subject: [PATCH 133/253] fix bugs and min/max pitch --- sharpy/controllers/bladepitchpid.py | 108 +++++++++++++++++++++------- 1 file changed, 83 insertions(+), 25 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index ee164f338..1663a507d 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -80,6 +80,14 @@ class BladePitchPid(controller_interface.BaseController): settings_default['ntime_steps'] = None settings_description['ntime_steps'] = 'Number of time steps' + #settings_types['tower_body'] = 'int' + #settings_default['tower_body'] = 0 + #settings_description['tower_body'] = 'Body number of the tower' + + #settings_types['tower_top_node'] = 'int' + #settings_default['tower_top_node'] = 0 + #settings_description['tower_top_node'] = 'Global node number of the tower top' + settings_types['blade_num_body'] = 'list(int)' settings_default['blade_num_body'] = [0,] settings_description['blade_num_body'] = 'Body number of the blade(s) to pitch' @@ -88,14 +96,26 @@ class BladePitchPid(controller_interface.BaseController): settings_default['max_pitch_rate'] = 0.1396 settings_description['max_pitch_rate'] = 'Maximum pitch rate [rad/s]' + settings_types['pitch_sp'] = 'float' + settings_default['pitch_sp'] = 0. + settings_description['pitch_sp'] = 'Pitch set point [rad]' + settings_types['initial_pitch'] = 'float' settings_default['initial_pitch'] = 0. settings_description['initial_pitch'] = 'Initial pitch [rad]' + + settings_types['initial_rotor_vel'] = 'float' + settings_default['initial_rotor_vel'] = 0. + settings_description['initial_rotor_vel'] = 'Initial rotor velocity [rad/s]' settings_types['min_pitch'] = 'float' settings_default['min_pitch'] = 0. settings_description['min_pitch'] = 'Minimum pitch [rad]' + settings_types['max_pitch'] = 'float' + settings_default['max_pitch'] = 0. + settings_description['max_pitch'] = 'Maximum pitch [rad]' + settings_types['nocontrol_steps'] = 'int' settings_default['nocontrol_steps'] = -1 settings_description['nocontrol_steps'] = 'Time steps without control action' @@ -207,7 +227,8 @@ def initialise(self, data, in_dict, controller_id=None, restart=False): self.filter = ss(alpha, 1.-alpha, alpha, 1.-alpha, self.settings['dt']) self.pitch = self.settings['initial_pitch'] - + self.rotor_vel = self.settings['initial_rotor_vel'] + self.rotor_acc = 0. def control(self, data, controlled_state): r""" @@ -241,26 +262,35 @@ def control(self, data, controlled_state): aero_torque = self.compute_aero_torque(data.structure, struct_tstep) # if self.settings['variable_speed']: if True: - rotor_vel, rotor_acc = self.drive_train_model(aero_torque, - struct_tstep.mb_FoR_vel[self.settings['blade_num_body'][0], 5], - struct_tstep.mb_FoR_acc[self.settings['blade_num_body'][0], 5]) + #ielem, inode_in_elem = data.structure.node_master_elem[self.settings['tower_top_node'] + #node_cga = ag.quat2rotation(struct_tstep.mb_quat[self.settings['tower_body'], :]) + #cab = ag.crv2rotation(struct_tstep.psi[ielem, inode_in_elem, :]) + #FoR_cga = ag.quat2rotation(struct_tstep.mb_quat[self.settings['blade_num_body'][0], :]) + + #ini_rotor_vel = ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, + # struct_tstep.mb_FoR_vel[self.settings['blade_num_body'][0], 3:6])[2] + #ini_rotor_acc = ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, + # struct_tstep.mb_FoR_acc[self.settings['blade_num_body'][0], 3:6])[2] + self.rotor_vel, self.rotor_acc = self.drive_train_model(aero_torque, + self.rotor_vel, + self.rotor_acc) else: - rotor_vel = self.settings['sp_const'] - rotor_acc = 0. + self.rotor_vel = self.settings['sp_const'] + self.rotor_acc = 0. # System set point prescribed_sp = self.compute_prescribed_sp(time) # System process value sys_pv = self.compute_system_pv(struct_tstep, data.structure, - gen_vel=rotor_vel*self.settings['GBR']) + gen_vel=self.rotor_vel*self.settings['GBR']) if data.ts < self.settings['nocontrol_steps']: sys_pv = prescribed_sp self.system_pv[-1] = sys_pv return controlled_state else: - controlled_state['info']['rotor_vel'] = rotor_vel + controlled_state['info']['rotor_vel'] = self.rotor_vel # Apply filter if self.filter_pv and (len(self.system_pv) > 1): @@ -278,26 +308,29 @@ def control(self, data, controlled_state): # i_current = len(self.real_state_input_history) # # apply it where needed. - control_command, detail = self.controller_wrapper( + # print("self.prescribed_sp", self.prescribed_sp) + # print("filtered_pv", filtered_pv) + delta_pitch_ref, detail = self.controller_wrapper( required_input=self.prescribed_sp, current_input=filtered_pv, control_param={'P': self.settings['P'], 'I': self.settings['I'], 'D': self.settings['D']}, i_current=data.ts) - # control_command *= -1. + # NREL controller does error = state - reference. Here is done the other way + delta_pitch_ref *= -1. # Limit pitch and pitch rate # current_pitch = algebra.quat2euler(struct_tstep.mb_quat[self.settings['blade_num_body'][0]])[0] # print(control_command, current_pitch) # target_pitch = current_pitch + control_command # target_pitch = max(target_pitch, self.settings['min_pitch']) # pitch_rate = (target_pitch - current_pitch)/self.settings['dt'] - pitch_rate = control_command/self.settings['dt'] - - if pitch_rate < -self.settings['max_pitch_rate']: - pitch_rate = -self.settings['max_pitch_rate'] - elif pitch_rate > self.settings['max_pitch_rate']: - pitch_rate = self.settings['max_pitch_rate'] + # pitch_rate = control_command/self.settings['dt'] + # + # if pitch_rate < -self.settings['max_pitch_rate']: + # pitch_rate = -self.settings['max_pitch_rate'] + # elif pitch_rate > self.settings['max_pitch_rate']: + # pitch_rate = self.settings['max_pitch_rate'] # delta_pitch = pitch_rate*self.settings['dt'] # if control_command > 0.: # pitch_rate = self.settings['max_pitch_rate'] @@ -306,20 +339,43 @@ def control(self, data, controlled_state): # else: # pitch_rate = 0. # pitch_rate = 0. + + target_pitch = delta_pitch_ref + self.settings['pitch_sp'] + pitch_rate = (target_pitch - self.pitch)/self.settings['dt'] + #if target_pitch > self.pitch: + # pitch_rate = self.settings['max_pitch_rate'] + #elif target_pitch < self.pitch: + # pitch_rate = -self.settings['max_pitch_rate'] + #else: + # pitch_rate = 0. + if pitch_rate < -self.settings['max_pitch_rate']: + pitch_rate = -self.settings['max_pitch_rate'] + elif pitch_rate > self.settings['max_pitch_rate']: + pitch_rate = self.settings['max_pitch_rate'] next_pitch = self.pitch + pitch_rate*self.settings['dt'] - if next_pitch < 0.: + if next_pitch < self.settings['min_pitch']: + pitch_rate = 0. + next_pitch = self.settings['min_pitch'] + if next_pitch > self.settings['max_pitch']: pitch_rate = 0. - next_pitch = 0. + next_pitch = self.settings['max_pitch'] + + # elif pitch_rate > 0. and next_pitch > target_pitch: + # pitch_rate = (target_pitch - self.pitch)/self.settings['dt'] + # elif pitch_rate < 0. and next_pitch < target_pitch: + # pitch_rate = (target_pitch - self.pitch)/self.settings['dt'] + + # next_pitch = self.pitch + pitch_rate*self.settings['dt'] self.pitch = next_pitch - int_pitch = self.compute_blade_pitch(data.structure, - struct_tstep, - tower_ibody=self.settings['blade_num_body'][0] - 1, - blade_ibody=self.settings['blade_num_body'][0]) + # int_pitch = self.compute_blade_pitch(data.structure, + # struct_tstep, + # tower_ibody=self.settings['blade_num_body'][0] - 1, + # blade_ibody=self.settings['blade_num_body'][0]) # print("int comp pitch:", self.pitch, int_pitch) - controlled_state['info']['pitch_vel'] = pitch_rate + controlled_state['info']['pitch_vel'] = -pitch_rate # Apply control order # rot_mat = algebra.rotation3d_x(control_command) @@ -375,9 +431,9 @@ def control(self, data, controlled_state): detail[0], detail[1], detail[2], - control_command, + delta_pitch_ref, aero_torque/self.settings['GBR'], - rotor_vel, + self.rotor_vel, pitch_rate, self.pitch)) fid.close() @@ -423,6 +479,8 @@ def controller_wrapper(self, current_input, control_param, i_current): + # print("ri[i-1]", required_input[i_current - 1]) + # print("ci[-1]", current_input[-1]) self.controller_implementation.set_point(required_input[i_current - 1]) control_param, detailed_control_param = self.controller_implementation(current_input[-1]) return (control_param, detailed_control_param) From 6ad563e1da0054894f9cf92642b8c9e39d87e6c8 Mon Sep 17 00:00:00 2001 From: Arturo Date: Tue, 24 Aug 2021 13:40:46 +0100 Subject: [PATCH 134/253] change default max pitch --- sharpy/controllers/bladepitchpid.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 1663a507d..8ecaae182 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -113,7 +113,7 @@ class BladePitchPid(controller_interface.BaseController): settings_description['min_pitch'] = 'Minimum pitch [rad]' settings_types['max_pitch'] = 'float' - settings_default['max_pitch'] = 0. + settings_default['max_pitch'] = 1.5707963267948966 settings_description['max_pitch'] = 'Maximum pitch [rad]' settings_types['nocontrol_steps'] = 'int' From 25de1671baad4f18eda0a3bb8ef052561e13d277 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 26 Aug 2021 19:14:27 +0100 Subject: [PATCH 135/253] rel vel in B FoR --- sharpy/structure/utils/lagrangeconstraints.py | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 83d3783e0..960278264 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -1181,9 +1181,14 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem, inode_in_elem, :]) FoR_cga = MB_tstep[self.FoR_body].cga() - rel_vel = np.array([self.pitch_vel, 0., 0.]) - rel_vel += ag.multiply_matrices(FoR_cga.T, node_cga, cab, - np.array([0., 0., self.rotor_vel])) + # rel_vel in A FoR + # rel_vel = np.array([self.pitch_vel, 0., 0.]) + # rel_vel += ag.multiply_matrices(FoR_cga.T, node_cga, cab, + # np.array([0., 0., self.rotor_vel])) + # rel_vel in B FoR + rel_vel = np.array([0., 0., self.rotor_vel]) + rel_vel += ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, + np.array([self.pitch_vel, 0., 0.])) # Define the equations ieq = equal_lin_vel_node_FoR(MB_tstep, MB_beam, self.FoR_body, self.node_body, self.node_number, node_FoR_dof, node_dof, FoR_dof, sys_size, Lambda_dot, self.scalingFactor, self.penaltyFactor, ieq, LM_K, LM_C, LM_Q, rel_posB=self.rel_posB) From b32660351044078c9e3c1f0c537a77f93fec6ede Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 26 Aug 2021 19:15:14 +0100 Subject: [PATCH 136/253] change gen speed filter --- sharpy/controllers/bladepitchpid.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 8ecaae182..95a9ed5a7 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -1,6 +1,6 @@ import numpy as np import os -from control import ss, forced_response +from control import ss, forced_response, TransferFunction import sharpy.utils.controller_interface as controller_interface import sharpy.utils.settings as settings @@ -39,7 +39,7 @@ class BladePitchPid(controller_interface.BaseController): # Filter settings_types['lp_cut_freq'] = 'float' settings_default['lp_cut_freq'] = 0. - settings_description['lp_cut_freq'] = 'Cutting frequency of the low pass filter of the process value. Choose 0 for no filter' + settings_description['lp_cut_freq'] = 'Cutting frequency of the low pass filter of the process value in Hz. Choose 0 for no filter' settings_types['anti_windup_lim'] = 'list(float)' settings_default['anti_windup_lim'] = [-1., -1.] @@ -223,8 +223,9 @@ def initialise(self, data, in_dict, controller_id=None, restart=False): self.filter_pv = False else: self.filter_pv = True - alpha = np.exp(-self.settings['lp_cut_freq']*self.settings['dt']) - self.filter = ss(alpha, 1.-alpha, alpha, 1.-alpha, self.settings['dt']) + w0 = self.settings['lp_cut_freq']*2*np.pi + self.filter = TransferFunction(np.array([w0]), np.array([1., w0])) + self.min_it_filter = int(1./(self.settings['lp_cut_freq']*self.settings['dt'])) self.pitch = self.settings['initial_pitch'] self.rotor_vel = self.settings['initial_rotor_vel'] @@ -293,7 +294,8 @@ def control(self, data, controlled_state): controlled_state['info']['rotor_vel'] = self.rotor_vel # Apply filter - if self.filter_pv and (len(self.system_pv) > 1): + # Filter only after five periods of the cutoff frequency + if self.filter_pv and (len(self.system_pv) > self.min_it_filter): nit = len(self.system_pv) time = np.linspace(0, (nit - 1)*self.settings['dt'], nit) # print(time.shape, len(self.system_pv)) From 8cd2f77c0e3a262f69e9cfde38d5acbe46e82bef Mon Sep 17 00:00:00 2001 From: Arturo Date: Fri, 3 Sep 2021 15:14:39 +0100 Subject: [PATCH 137/253] add uns forces staticcoupled --- sharpy/solvers/staticcoupled.py | 1 + 1 file changed, 1 insertion(+) diff --git a/sharpy/solvers/staticcoupled.py b/sharpy/solvers/staticcoupled.py index 0a46a1f81..a36a2e2fd 100644 --- a/sharpy/solvers/staticcoupled.py +++ b/sharpy/solvers/staticcoupled.py @@ -212,6 +212,7 @@ def run(self, **kwargs): runtime_generator.generate(params) struct_forces += self.data.structure.timestep_info[self.data.ts].runtime_steady_forces + struct_forces += self.data.structure.timestep_info[self.data.ts].runtime_unsteady_forces if not self.settings['relaxation_factor'] == 0.: if i_iter == 0: From f2cc5ca8c69f6f381948fef0030c5a4b89e6a6bb Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 13 Oct 2021 13:07:02 +0100 Subject: [PATCH 138/253] include rotation velocity in polaraeroforces --- sharpy/aero/utils/utils.py | 9 ++++- sharpy/generators/polaraeroforces.py | 58 ++++++++++++++++++---------- 2 files changed, 45 insertions(+), 22 deletions(-) diff --git a/sharpy/aero/utils/utils.py b/sharpy/aero/utils/utils.py index c1f842884..7a2547495 100644 --- a/sharpy/aero/utils/utils.py +++ b/sharpy/aero/utils/utils.py @@ -22,7 +22,8 @@ def alpha_beta_to_direction(alpha, beta): return direction -def magnitude_and_direction_of_relative_velocity(displacement, displacement_vel, for_vel, cga, uext): +def magnitude_and_direction_of_relative_velocity(displacement, displacement_vel, for_vel, cga, uext, + add_rotation=False, rot_vel_g=np.zeros((3)), centre_rot_g=np.zeros((3))): r""" Calculates the magnitude and direction of the relative velocity ``u_rel`` at a local section of the wing. @@ -39,6 +40,9 @@ def magnitude_and_direction_of_relative_velocity(displacement, displacement_vel, for_vel (np.array): ``A`` frame of reference (FoR) velocity. Expressed in A FoR cga (np.array): Rotation vector from FoR ``G`` to FoR ``A`` uext (np.array): Background flow velocity on solid grid nodes + add_rotation (bool): Adds rotation velocity. Probalby needed in steady computations + rot_vel_g (np.array): Rotation velocity. Only used if add_rotation = True + centre_rot_g (np.array): Centre of rotation. Only used if add_rotation = True Returns: tuple: ``u_rel``, ``dir_u_rel`` expressed in the inertial, ``G`` frame. @@ -49,6 +53,9 @@ def magnitude_and_direction_of_relative_velocity(displacement, displacement_vel, urel = -np.dot(cga, urel) urel += np.average(uext, axis=1) + if add_rotation: + urel -= algebra.cross3(rot_vel_g, + np.dot(cga, displacement) - centre_rot_g) dir_urel = algebra.unit_vector(urel) return urel, dir_urel diff --git a/sharpy/generators/polaraeroforces.py b/sharpy/generators/polaraeroforces.py index 5bf451642..c68d78880 100644 --- a/sharpy/generators/polaraeroforces.py +++ b/sharpy/generators/polaraeroforces.py @@ -71,6 +71,18 @@ class PolarCorrection(generator_interface.BaseGenerator): 'Else, it will add the polar Cm to the moment already computed by ' \ 'SHARPy.' + settings_types['add_rotation'] = 'bool' + settings_default['add_rotation'] = False + settings_description['add_rotation'] = 'Add rotation velocity. Probably needed in steady computations' + + settings_types['rot_vel_g'] = 'list(float)' + settings_default['rot_vel_g'] = [0., 0., 0.] + settings_description['rot_vel_g'] = 'Rotation velocity in G FoR. Only used if add_rotation = True' + + settings_types['centre_rot_g'] = 'list(float)' + settings_default['centre_rot_g'] = [0., 0., 0.] + settings_description['centre_rot_g'] = 'Centre of rotation in G FoR. Only used if add_rotation = True' + settings_table = settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options, header_line='This generator takes in the following settings.') @@ -147,7 +159,10 @@ def generate(self, **params): structural_kstep.pos_dot[inode, :], structural_kstep.for_vel[:], cga, - aero_kstep.u_ext[isurf][:, :, i_n]) + aero_kstep.u_ext[isurf][:, :, i_n], + self.settings['add_rotation'], + self.settings['rot_vel_g'], + self.settings['centre_rot_g'],) # Coefficient to change from aerodynamic coefficients to forces (and viceversa) coef = 0.5 * rho * np.linalg.norm(urel) ** 2 * chord * span @@ -188,28 +203,29 @@ def generate(self, **params): new_struct_forces[inode, 0:3] = c_bs.dot(forces_s) # Pitching moment - # The panels are shifted by 0.25 of a panel aft from the leading edge - panel_shift = 0.25 * (aero_kstep.zeta[isurf][:, 1, i_n] - aero_kstep.zeta[isurf][:, 0, i_n]) - ref_point = aero_kstep.zeta[isurf][:, 0, i_n] + 0.25 * chord * dir_chord - panel_shift - - # viscous contribution (pure moment) - moment_s[1] += cm * coef * chord - - # moment due to drag - arm = cgb.T.dot(ref_point - pos_g[inode]) # in B frame - moment_polar_drag = algebra.cross3(c_bs.T.dot(arm), cd * dir_urel * coef) # in S frame - moment_s += moment_polar_drag - - # moment due to lift (if corrected) - if correct_lift and moment_from_polar: - # add moment from scratch: cm_polar + cm_drag_polar + cl_lift_polar - moment_s = np.zeros(3) - moment_s[1] = cm * coef * chord + if moment_from_polar: + # The panels are shifted by 0.25 of a panel aft from the leading edge + panel_shift = 0.25 * (aero_kstep.zeta[isurf][:, 1, i_n] - aero_kstep.zeta[isurf][:, 0, i_n]) + ref_point = aero_kstep.zeta[isurf][:, 0, i_n] + 0.25 * chord * dir_chord - panel_shift + + # viscous contribution (pure moment) + moment_s[1] += cm * coef * chord + + # moment due to drag + arm = cgb.T.dot(ref_point - pos_g[inode]) # in B frame + moment_polar_drag = algebra.cross3(c_bs.T.dot(arm), cd * dir_urel * coef) # in S frame moment_s += moment_polar_drag - moment_polar_lift = algebra.cross3(c_bs.T.dot(arm), forces_s[2] * np.array([0, 0, 1])) - moment_s += moment_polar_lift - new_struct_forces[inode, 3:6] = c_bs.dot(moment_s) + # moment due to lift (if corrected) + if correct_lift and moment_from_polar: + # add moment from scratch: cm_polar + cm_drag_polar + cl_lift_polar + moment_s = np.zeros(3) + moment_s[1] = cm * coef * chord + moment_s += moment_polar_drag + moment_polar_lift = algebra.cross3(c_bs.T.dot(arm), forces_s[2] * np.array([0, 0, 1])) + moment_s += moment_polar_lift + + new_struct_forces[inode, 3:6] = c_bs.dot(moment_s) return new_struct_forces From c498c6768d4f611f8b5b22fd93d8bbc9edfd1588 Mon Sep 17 00:00:00 2001 From: Unknown Date: Sat, 16 Oct 2021 14:04:32 +0100 Subject: [PATCH 139/253] update master xbeam --- lib/UVLM | 2 +- lib/xbeam | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/lib/UVLM b/lib/UVLM index 75d2ee917..edbd9da15 160000 --- a/lib/UVLM +++ b/lib/UVLM @@ -1 +1 @@ -Subproject commit 75d2ee917c04987c68583fa86c181360a674fb71 +Subproject commit edbd9da1546762e81711c586a688885db2f15749 diff --git a/lib/xbeam b/lib/xbeam index fb28eaada..56d933b8f 160000 --- a/lib/xbeam +++ b/lib/xbeam @@ -1 +1 @@ -Subproject commit fb28eaadac70b35bccb04677123b77b1ee086b09 +Subproject commit 56d933b8f0de6e03615bfc73003c524dfdafc00b From d9cf5e29dcf2f083246ff99173ec825827d389d4 Mon Sep 17 00:00:00 2001 From: Unknown Date: Sat, 16 Oct 2021 14:17:37 +0100 Subject: [PATCH 140/253] include missing packages after merge --- sharpy/postproc/liftdistribution.py | 14 ++++++++------ sharpy/solvers/aerogridloader.py | 8 ++++---- 2 files changed, 12 insertions(+), 10 deletions(-) diff --git a/sharpy/postproc/liftdistribution.py b/sharpy/postproc/liftdistribution.py index 87a96fcb8..2eb03611c 100644 --- a/sharpy/postproc/liftdistribution.py +++ b/sharpy/postproc/liftdistribution.py @@ -2,6 +2,8 @@ import numpy as np +import sharpy.utils.cout_utils as cout +import sharpy.utils.algebra as algebra from sharpy.utils.solver_interface import solver, BaseSolver import sharpy.utils.settings as su from sharpy.utils.datastructures import init_matrix_structure, standalone_ctypes_pointer @@ -13,9 +15,9 @@ @solver class LiftDistribution(BaseSolver): """LiftDistribution - + Calculates and exports the lift distribution on lifting surfaces - + """ solver_id = 'LiftDistribution' solver_classification = 'post-processor' @@ -36,7 +38,7 @@ class LiftDistribution(BaseSolver): settings_default['rho'] = 1.225 settings_description['rho'] = 'Reference freestream density [kg/m³]' - settings_table = settings.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) def __init__(self): @@ -59,7 +61,7 @@ def initialise(self, data, custom_settings=None, caller=None, restart=False): os.makedirs(self.folder) def run(self, **kwargs): - + online = su.set_value_or_default(kwargs, 'online', False) if not online: @@ -83,7 +85,7 @@ def lift_distribution(self, struct_tstep, aero_tstep): self.data.structure.connectivities, struct_tstep.cag(), self.data.aero.aero_dict) - # Prepare output matrix and file + # Prepare output matrix and file N_nodes = self.data.structure.num_node numb_col = 4 header = "x,y,z,fz" @@ -102,7 +104,7 @@ def lift_distribution(self, struct_tstep, aero_tstep): local_node = self.data.aero.struct2aero_mapping[inode][0]["i_n"] ielem, inode_in_elem = self.data.structure.node_master_elem[inode] i_surf = int(self.data.aero.surface_distribution[ielem]) - # get c_gb + # get c_gb cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem, :]) cgb = np.dot(cga, cab) # Get c_bs diff --git a/sharpy/solvers/aerogridloader.py b/sharpy/solvers/aerogridloader.py index 976d66b4b..99fe104d3 100644 --- a/sharpy/solvers/aerogridloader.py +++ b/sharpy/solvers/aerogridloader.py @@ -84,7 +84,7 @@ class AerogridLoader(BaseSolver): settings_default['wake_shape_generator_input'] = dict() settings_description['wake_shape_generator_input'] = 'Dictionary of inputs needed by the wake shape generator' - settings_table = settings_utils.SettingsTable() + settings_table = su.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description, settings_options=settings_options) @@ -105,9 +105,9 @@ def initialise(self, data, restart=False): self.settings = data.settings[self.solver_id] # init settings - settings_utils.to_custom_types(self.settings, - self.settings_types, - self.settings_default, options=self.settings_options) + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, options=self.settings_options) # read input file (aero) self.read_files() From 3bfffe79ce3e09183887e83b5a695ba09a9a54a6 Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 21 Oct 2021 11:42:01 +0100 Subject: [PATCH 141/253] new floating test case and example --- cases/coupled/WindTurbine/generate_rotor.py | 2 +- .../source/type02_db_NREL5MW_v02.xlsx | Bin 71929 -> 0 bytes .../source/type04_db_nrel5mw_oc3_v06.xlsx | Bin 0 -> 117877 bytes .../example_notebooks/wind_turbine.ipynb | 2 +- .../test_floating_wind_turbine.py | 391 ++++++++++++++++++ .../prescribed/WindTurbine/test_rotor.py | 2 +- tests/utils/test_generate_cases.py | 2 +- 7 files changed, 395 insertions(+), 4 deletions(-) delete mode 100644 docs/source/content/example_notebooks/source/type02_db_NREL5MW_v02.xlsx create mode 100755 docs/source/content/example_notebooks/source/type04_db_nrel5mw_oc3_v06.xlsx create mode 100755 tests/coupled/multibody/floating_wind_turbine/test_floating_wind_turbine.py diff --git a/cases/coupled/WindTurbine/generate_rotor.py b/cases/coupled/WindTurbine/generate_rotor.py index 30ae736ce..27982a618 100644 --- a/cases/coupled/WindTurbine/generate_rotor.py +++ b/cases/coupled/WindTurbine/generate_rotor.py @@ -58,7 +58,7 @@ options['separate_blades'] = False excel_description = {} -excel_description['excel_file_name'] = '../../../docs/source/content/example_notebooks/source/type02_db_NREL5MW_v02.xlsx' +excel_description['excel_file_name'] = '../../../docs/source/content/example_notebooks/source/type04_db_nrel5mw_oc3_v06.xlsx' excel_description['excel_sheet_parameters'] = 'parameters' excel_description['excel_sheet_structural_blade'] = 'structural_blade' excel_description['excel_sheet_discretization_blade'] = 'discretization_blade' diff --git a/docs/source/content/example_notebooks/source/type02_db_NREL5MW_v02.xlsx b/docs/source/content/example_notebooks/source/type02_db_NREL5MW_v02.xlsx deleted file mode 100644 index d8c22077c5f7e3c306c154af80942407643a3aa1..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 71929 zcmbTdQD#ZX+vk&Os16YkF<#oBhGXtY&T!;Kq&39Uy!lVes`0cq8Xbg<_{5Bk`WRP<=V7S zF>hGjg}De%XSkg<-zG_?G-SvSO~%R>25j$%66}HNahXw`#e&+dLJh@*d^l3--*KvtXXrh|Sug8tAWcX_kR)f4@@AN-?WFc$`^FNy;UYy}cQ2*61bG zq>P@@^g*fvYGevtc*1^l@5GtZ{1bN;KwC&`qWEWJba(S+XeD$bE%Zm%GJ^@aF)N}d zB~587FB81wT++}I-ihUv=(6UY;0mBx4I>nBD@~U&Ey=X?PouQ@B#@~n&E>qhKusk) z>hIr1hw28MsL?lEp}{+>1nx5W^qt8yTRfp(E8v|O2$m)zDp@t04}PFjO&rR8;Df11 z=u%^#;Smc&PBUnV2ieIc@+vNM|4|N zuSK>Uwywke{;h&(p2$oytLo5wv#z6MC=M<++%T%|4t(3y7d5$C7z93YH~v__!V!Jk zprReR6<*>vwvRkwFf_+8UYikp^Dj3G=z82lqUK&FS0-8Ecp#d*r{Y8Led8BN9Z z;p>leN`5Th#0q7{yzk?97gH8_ajG8pV#*uFMv;X0FK(RoV>2IXw!pVAx6RAJ_@HO4>^Th1_mzE$G1V6O_DTxjK|Cg5V|4B<1S1(&Lm#?I}(9(0r zWJ2@ZuBm?yB{cUr485X1%jNpVulmRt(K*v$B( zOGx;NqtkL!krW_F=iHYLDLKpmmIls8M)&w<)7Z}yMwkH^7Wn|qyS9g$?@6$wm5!=Q zo+(90+^`iAmAXMOB^eT0LD_GDbz&hiED}w65v?xS0;G^>IWI{&#!j&c4H?2Wm44of z#s%q`Jdps8lfp2fCV!U$U(~Qq??y@aIRG0YOvI+*uIS8`aQ*Q?a(!!ufAfB8hkO0r z7DQ)}%ZGEO^KcOL z`^PRmtXfo-G^`Rv`L;KMNOFbSG^u8$kd)E{c7aDaB&nDS9PYfu$AER=l?t9Tx@H{L z?63XwUx8Ais_JFTZ8oT_Wu=#(awk;^Z-leo?=uEy*5uSQI2Qa0TED5ImRaY~6%J;d z5vkBQnYGaA@f5?#7^m!7#Bc`4;*B_O(@b_nT1&<`3j0;ed#dpD45{f{lv|4LcsQ*v^L>#83A(i>)SEPD>P2iGc4OtN^ zdjhxb6$#c7F8riR$tD^r<$KT-Rn=Z&De!wn6@dO)eOe36BUrYfH==&_xqcv_Av2X^LI7)~I|S z6#qp0()eyAR&*3lAfOby|35Ne{U42Yu{1Mtbz%JX#r(yqPEC22LN27vtC~En2`iJH z?I}Y=a(6t3WJ+oB^z8D^QKBfCA6U{W(thvFWIaAD#?wn0KDGG|$IF|FBG&EO`gfm?raoK*$9mECWgoaSsoFuM%G7)MFAD)4@5$U6*0Q z#OrHgJc;0uZsk)e7?S1DNr2d|F6~nHk97m{UunkeT#`2tE>Pzdt;dux-{i%EN|^K zw8i~%Fs#$`1e{BOxD`G;%u|&)gY_G?zoCQ>$dVP=NWTWB# z%O#{mW(wCMsb#b+Jfg}P{}9zfDNjC(CmBC6&&C)24ht3HJMUS-=69~=8&N4*Zi}CZJdL9d>}%}LwkwNW6K0XN*81>`%90v$=ZwJ?2r zr+JC{voJGU=2BAo^)Ms+I%`r1@;(r78SJ)PI?>Dmw`}{5Y^D#yMHG^si3i8u zNMvI=d8^mMhDdxASg5RYL&t17@t5P0 z0<$;Cm8Qe%i(1XpF|d*D$o#7whC}U^mAZeD!`+~rmjnm=$zu++eePxA5fbH-5^!2a zln}7mG&j5I7?>!S!eb_s7vs0^Pgb%5+g7+^CfbW=$l*8cXtTR9v%rKO^n0GGQPtFg zB;?l=N#STXcyt8v&>DAO*7+4pYV0gNC}4T2BuSs5Qo+w#PY&*(zj$2AuFi_>9>E7s zmRnywZfOg5&sZBHH(CNUuH%QOp6`$y@-a=nEA3=ezqC461>&A4L*8xkjb&h+z6iHY z`nGDYE4I*o#-zQ&eraKb(oW+L7!c4L(*HsWS^jBZ=6b@K6iUd|6EzgWp|xbGj0NIk zP-X}OBt%NT!oXIU@+=h{Su|POrr!%SzOYs}I4*=i%g%DiSY@Sw_{qZi-RqW3XC0M0 z=x4q>S?i|p2Zf{V=RTQ)KNwxgW&i3#Ct`&+o ziWSVV@XkgajjG(&N%HWEi{o|Tw`@+l+o{f$oJ=26?q=`J${VkRwKn~}f|{TG!)7+# z%zNu1ugUaU^#~0YqcmwQ`5PN2ZoGq2oz;7{D8>C-5i5`R?*QVWvWv6qb~AX#DhmAG z)w>qhhbG|TWmq2{I2v)IsGe@g5DOL21-p9h!M%}jw8^&rOSnf)8$9B>d4oo2o2e#G z@i?B~Wt+%Uf?@71#YbTFT;~tnQ4StzcM+Ic#C`24taj?acM#f~i?Oh02VsO$IL*g+ zVcFg!y~>Q3S8=fvOSHns**rXMYDsBOvbrTCH_lxr7$B;F?l&;<7AB1tl1lV9MaHVa znMX>Ca_%<7{rev@?nWJsZ`+zV<5J9u!9Lp>Zyp>ZCqvc)bH$2+sV1xweEpE^rC>FE z2Gxn@p37vbDsvl=^gdD&bo5+`88UpAhyrN8RM2=vBKeFQCiZ+%Cd-C&roETTz^~lA zg!j%r8yj=*hbRkwa}P+@GS-iUS{(5p+|AZ%O?19zTa13T`8{$f2+Zy5L+nm(Cav z&eD-&q-m8EZ4niz2Q}8l)r;99C5#*}Q*YPg7G*%yrVFJ~wF*x-QxL7F35AK-Bdbvd z8aDvfR99{hS#pE^B2*&WG(;ddAQQXRl45m0YRC$K;y}EKIZag%3wB>+lu_5WW!UYW z{Ibeq8 z7F;+9=H&XO5+ZraOQ|dlyL7KmN{Q**7Yw-nV<8GIBc3<_=#GyRifOtO8#@vTcGb3X;37^^1HXs`2=&gpymBpbw(*H+7SIqM zG-&w-(^0Uk%g8JRHF5R*b3&|Ln?J$`w3M~hN}`F(o>YBe%;5oj)5bVz>~4B0KVTX5 zhoTqX=A`6g3RIyC@|lAB;9&0Rp?+NxQqlckkfo~3s}(@DPFcLP)sm;n2lL}26qhK3 z5j+C}U6SMyXQvjH_lD=25t~OTIBBsGPg9D-X|Wn)qncG01?jdfgl%P3Q8ZkWFfI_D z7cqhf#zs5DVWUUGa7-mf(@@g1v5>3SUTx$t)~?O+M#ElYV;=>wi5KWQfmwuKXk6|A z)w|9wI5`l5m8b0s8iVMSr!5wi6D94F^Csq$IE9v5my&a})TWZlXA11o4J{7t1G%gZ z>Vtu?d5^M+=FMCZl7ofVRW?Y_OYL$^3v+GcW>-*yPk~4+Bx9^UZEMFQ)=^0) zf1BddG-qm*(nO3Pf?L7gVS>Ro%%FqO(Uz95yNiFXUV1NTNZ`R@l*d999dFcA@WG1; zm7lT{2X00| zbytp-90+bkeBOkXl$=+onA{e9<#+d!h=U_9T3kxGlzcQGT0Cy7tvtK#hW$P-&xT`3 z4z*i?Nz5{Fj+GXI3^_6Pskh(Dm6&rV0>*9wF!a8qN$G!wmc$kPe-G{39;`GlbiK<5 zLS0`h#iA=jM8q6cwnH0MaV#vnTr;im-5mbsOo;oXExfeY@4s4Dx)Qo0(RBqPxSS-3 zFx+ccG^)bs&|@7mgR?_QT2S8f;AZ4hXR5#K_q?}_NMMXjVAnK*N{uphM{z+=k{Pkw zHinjG0RG5L&^l;h>>VPh%EUkrBn`KO5M)F(-y3gX)=;zDlQ2~w{xX$@id8uM+b=G_ zG_XcBzw#=<%zVoi?0l}gt;ISg4V4ASkRNw^CrR_ZRC|O`t)UmwV=l`pq`d_ zC=ri>;?F1>n7n=Sn@rqaw#0S4?jHVH@~frLmE{n@kUUBLp=@5Z@aro`Jc{1ZOlrY( z5~cK4{!@Y9*~V9!%Ku~f+lcu~hi4KY;lVN)R0F0co3+~K-?|4BvNyxN=JWcJk63uy zKqBtvtulQTuAr(J1g%C_|Jpa^r8nxg^YoW0+(GG=#`pVL|50~`BStnfMaB4Cn+G}X z_GAv;$odt9>&qJViQF5QYZE?aFW~xAF@iNCB=YzRiVoPE&gaKfkB_xh>4zAx@$mD+ zWn_+tyO&-8-*qwt1FGv*_pntY^KVo9i<*4F3?7PWiOxtdV-!%Eu1XCSQg_bq4J1u? z9_OhwR2iZRjL6C3(!^Nup2O%kQ=w_gZ9aS7DDuEh)tc(+lEsaFylhQPbc%vH9eZyl(Ga>@{WOv( z=skh-ZX#vd@yYEfEsTb_#0uaYvJH{^)rA#5D)cd58Brrae>Vbp^ zzS*Sz8af$<-C;UWN-{faC%$~XsxmmPv`f98-D z(NKigcpC7gFE9>rq~j36vapp8+r`?YWg?{WY9*pm5FNbBc^u+5w%S(pbvC=E1*LTFC}+k>JsN zbkM#&;uEF4r`mn6NDs+BeDm6P8E%YG z*X~Mp8^0jrd|a2qlv(WxPp8PaBls}4Yg@kalDEQ45!;q1!!wvmhyWlb-JYI4Lqo6- zUd^7tU6@Nl2v{8~SX{~>@P1vU>OV1)KcF!oP#^uUn3BOo@#r?;T8yFf=yu>zERE=9 zvBo3Bn5Ct#D0)z6dU`QhS4c2**aGSGv2^%;Myt>m2Vto8VL2@uo*PH%+1|i4n;O}U zqBV1cOTqo<=?fY}XdW0$X<13Yw)HWx^#Q>J68j+*9!_P>=3487iR)2!gKcYUWNQqg zv)_ZvfVb0!%<4#`)wY`eEz|-;j7(Nc65*)ahMv}P%^*|Fo;Crjo24>C{R7WmwUg#JMR7)HV>VwirjC4pM(_T#aI4p67TSX+*oZK}cMGQI?6^5iZ{LcWr zgX@6oF&<*REGjb3pqQ~Cu_RHFB%jelFlzycYs~kVU#*bYB!o_Q4NNf!Vuslih41Xf zgsw4mGrvwCvUhQzdtb$}9A&)lf(tj|(jbsP@cdffRFr z7YC5u>>&+hwX}mvB!L`4fzinm8Ab>>;_QfG#I}ZkwfttmLWW9vmp8s4BriS&LEHlq zp#cMeyu9?qa)L}VfvIIv{Xt#alL$pvAd(mGX9sF3jHU;V`NywtU^!$^;jl37B?V!* zgs#wr;MM{}SxnzFnimkP;eH(BMkgqUs^t1X)!i=acq!F8OzQpOa$xdU z3~x*Y)n_gbI4RZ3OzJh_C@?;UMM8B7E%$z~E{oVH)l*FB*}?fg7MO(ZH{W;6VO@gL z>Gjf9)r>Geaw~ws{saggs~ys3R`lDR@Jtk+)*|r@NP6KQM}YNrcGkAmkEbxS+pfSJ zXLZ}pOf?zK_?2aL%sn+-G^n_ z$bwAGd8vCmZA_UI{g7WH{JU0dWvkQk+F{jXh2YPX68q@feb)W-&b*eZuU*?^v9QIt zcobN9$qbU#MKKJt;(=rTrp?|a?GlX?;reu7m;CNG^6=}|m6<%xan6;gvaPz6 zevGC3XS>L1UGnd0k0Ud;(ZO~ePTXAGM91WFwQSjT873^f7JIw64!Z3tX658&h-!iC z!6&W9>7z62%}VtYH%4$Sh7`^6{O+}Fc1QVDJC$6}rXL}IfLKZY7qye^ zU+v7+b6Mxg2)=sy*5bqbjhF349EDZ7xPYquxJK$UC!1!w%#K{S$8l}ezIsmcv+vnfu_s!Ym)my7BPfy>ca0uj{{CK_zY*MeTdr`3Jg8C3wP;vWUg_;hTrmsed@f!j+#LXCHKI`ox|=&Qt6ZMQ$x!(9!}0L!5iKqFaJA!NOwWKkC%g+8l&OZoqfOb?a6Q5Rk1gJCo3MN zB*zP5@7fn_y;@t~FK(T_Ke54fduRD&ytC=N-#NX%E>1@(Lv_5p>`zuCP7XQfZ%&D# zyHENxX8HQ~zG=KyJx!e`G^D&u`#fGyKR?aR9}WH%=IUegm@i4iuMR93f4&%eGr}mS zI7pRutpEFH@5BkGj{KtW5_zUo+K}4g{Bh#KH59oztiEwz{W7lD(7rlp?cT0B5z1K6 zt~93Dz4=++66xKN?VIJ-s^d0{G^Rsmuxrpy+%4dDY<+W zCkmX*FYw}9*YbH{{vGqQ%zf0qW=Y4Qw_1R)xSPJK(uQ2K7%t^x<9giq#s>5BQQN($ zQ6Rk9kFX@$g=5&!hYfzVrs2rMt7eSty5nMYzI$1I?wy50>-X9HHlrP@rbouiT4n}R z({;`B#iP@8hI{NFtntUT|pOlKAz*RX(*oNoIsT-?!Vr^Rsh?<7LUjp}wu$ z=}Xg+Yt9;xV1X)scXe-0UmqFmtHbemYo~7R@}t9NzV6O!{u$$Cvn|C>)EJgGet*r+ z_r{kho1E(!hw1j4VC%NAXBXMVOcZu%<>cTSf4_Kp)uKX5tNUC7<0k4l5^{}TCx5^2 zhvI>Z9Fu2I8Cwo=j>dsQ$fRRV^6x6fs>g&gF?y$-kCI-s-_>UmCz8}>-+)wU-c=|X z%+xI(K*!h^%`yVX2_F)C+x!h*lm&~O4eEayLzhx-#2&XWJ`3FhU2i^a40Kf}y(d_r zk3;WhKZDYI>sG5aZ{^Spl6?i8QcHdrWX@2(j^$ofvOe$rwbfP}b+9Df#PGE5Re8-f zmQ!8qpihsv9g}h<>cjBvrCG;+#$`Mjv#<3IDVpYX;~2BE(7xN|^k=?pq4q{K%+I&* zy&|z@6WN}OKPk=m+ii^0LUoZM+4pa^IZ_kVrb1-y-<)O0?7y*)C0Ku(Ly_*Jm|LtVN@yx=KzGDXQ{TlZ6g;*0110leFQ3lJY&4yYn=&-hEef_i zwNjhGY&4nfndtY7R7wUzfMHa+oU}EV zn=U*;kuE4Eo{OHT=doQVk=~coDygKgD8F+jJa^JCRorfqM3ehz8ndIVifs2<$^NSN z2!}qUzLb!iEhwu;^3e3yEPMi0pnW{3?656T^rUjde2YNxo~j)c|Ad6yf#(*LC1MH{k3nJ~Z905+*^}e3aF^`R zSl{O4_BVZ-HC~=&Ix?b5*7-zWdQZRfNO_3=>H{(7Nc+-@@;d>#H~&@F_MKWpj>qpyDfO#4hXPO&dMB_DgMaoHr@ z4LqTzX(hXrlB-;U&wp2Mu~pfx2Wcp)FOTqn^9XL+cquR@qZukN4uF4Ie)!uk!63AZ z?ny|}3DbcX?+3mWI+6!+CHkKwFA`iWLq7UVc3fp>FHd8>UbCJ_^4CkJfPV$W#-^tH zFQx1?z@!XtC5?5aq!GpscAWO+saZ0i#;un&Bk4ShL?D{Vr=djJ7ccoJJqJi{}RT$C;my&O=nK`FH;@xdVX>A8K?re*dbps;&uDPW|NQ{#*>)v%jsng*<2--VOf>4sH-7mM{nU9c zG9tbdD>4H5B57$K(XbkqNkHs7JQg9zJ46&>yfElc=m-)Cz1UO+|Iia8N0)`$dH+LC z%kkU9U(>{izXb);5ltt51^p+U34Z5M1DQ>o^}U?$x}VN2897#2!4PS$w}ikC=r9%o zsbT4?YsaJg>0Ne1kEti22Ktq3XE@<<((9^MOw|D96$;N@}ixgp-d4B^v;{&Y*6$2ME zRMWZoRq<{@sk$s{ziKD)2{qz-sLqxBi2fVP0vvBy7~MdIZrfPaoBbfupexk4q%NMV z2x{;8ozki_j;_I0$kmG{j+|7BC50Sy&0=iq<;|XmV~K;(uoN@XFcY0=Ar`%D5*7<* zpm5t90uG*e!T6XC{=z&o5L7k746>@}Hgi8tk@0DT!pj|r+*iAn-O)kFm5)4c${Lq} z5=f1@*2_$0+LoJ4yG8`25L17l-6&OB|s$gRU4awf27e&i!0Fr3>?CB3$1CC z737qNG%O*W4tqQS`hwC-uYzJ43WgOV=zAS>LKINGU*!xLsgNa7tiUJ~5{_}{;EWc| z+9Xsc#ZZztc77o6eOD_;vvdx!m~<|Nt()GZzr7I0&M2^3ws5(R@tZ5D9Q;+5JzOgS zVt6xjKaF_fg~V&c(f* z7qtR6sn2W5LSTQH*9uH7(;Bi#kmbpHeB|v{LKwV%M>MM zPg(UY=5@$uFZ(zn5v?!N3=LaS|0)#69Y;NhgHL0jCj{)U=(6AIgESd!T%o7mI3&xV zqlDAQR*g&ywTfsm6$NQ09-&~0*~qB&?1R+%FpS)04$>9`MiCVT|Hq!dl%_x(=mA*f zg-H51Q!p|(6JH8!VC;U+dua)wF(gs?kg2&DdkHQ!t5U4BUu~vJm)F_8+f_6=2 z{1YBDK{@t634T?oeN_A0BqD(<${(CW67mAWEe;2dmJosUFSXOxBx%b<_aY*IjoM6} z9tCTXyu`nPln99erV6(h*PXyk)aIy&GAA)bLsf(rZABxQt6b2`fICPiHBv+p&!wX? zL`yw@D9YoQQxpSRusDWJP>dIkP${F{^XexC`79KIZuZYHjL@9O>N$u=ngdFT#PwnM zT_TpqqM*SmBq1SK*37QOkNJ_OGv@`yS!tIN*OQ0f;#gE8=LK{p^Ul&dMArojNy}b5 zLV8@cAb-Sz#R?vW7F=b3o06NCkiWO6vvf+4aj3BzpvOtGsV`y`bP{PVE(8bI{us$S zgFt5bMFbl4uYIUD?c|-F6B6Z=>MeSHZ}_48O}pGKIf?}( zoOx;5$)M`2YpspAkItTpB8TM)0P+#0H;g9J)o&X zW1Z6O<1n)+NpTqehuzkMo27{IoYoLg!7z+27LRExvY-HI9`9!pG9`vjdXCfpEnr>3 z?B&+NnSr7ViC1iqC9?WqS@jzpcj>qGAy)VR)!-rU6njB<@p+C~0-I1{xk<(yB|J`9 zFH;}z#!bZWEgO;S{}B2cPcEaY8-AvBCIl0JL$>SO89M76Ze<@6I~R1N|pPDIxCj zJ^9QMlT^(3mx$+E7O}R8e1s!dr1WX~pd!pE;_x2OVis-8Oh06BM#ZXZ4#I~+#cVR` zsYio57FhP)Nw73T+ zLgrXz(z%#XCqEn`H;W*OKo_w0V1bAg+3UmF;P9gm5S487%2wKyt5RCUNoE(#8*QmXi?@HDl=zjY5Xe55dUa z0vksHtnv8)NaFuUo{yuYtuiad#L9JvH)g%c4kcYAwMk@s(KPIk&kq&@HP7EdO5*dK z^oZl8Bz~nho0b^}P)ns%^x@Px^o0>(1?@HhvXD}Q)_c}%_sFy5bN%-xza*Gu)Y?Xv zV*rZhN|YG!Pw^TPkLUIgV`@xP$xnc!2UkF(d4yD$H7pYl;?$xfbBjR9(Eq2776*zZ zMr8anEFK5VG*vpfc8Il0C;?4Z+fZdH0!{KtV1MqY3|1!@(ovK8MBq0n|P3Qm-bmdazUrn-X`D+tsjV*N7cDGvIAc&C}+ zXtCNvmb?`RdvFCvnn6f{dC4LHHcmN;GHoBk6peYIIA3p%5JzeO?hYok&G8N=I~Ugg z0tFB*47sS-dWwy=^^IpL)-fW>qS1m7iYy8*0WPvNM<4RcUWcYAB9!p*DkB>rs{t5M zl4kP4#PDY7c%cQUxAb~of|H2jo@bT-D%l}t%=8%slr@>73gUqjnXFhSW7{7C&tXJ> z?D+zGy`wN|4Q=^rRqYC=@noZ3A>43wWK(qiX_pE+G7FbS)%!7#cX~#POtJ zrvW*m(x!BYmKXI5m0)&FyDl}kaRLh^ygoCv*ySuS7@oEed&*U~(a12jKO+?%u(5<-o!XefF|*B#V1032;|dh!A^)ey^FxmvJ`Y_);d< zU&}uA*ZJ(OzQwQwP3KdDtNeDS1wltaEOJ!;=>0D^W2+rEHSB#sSf^G&(98?VP^iY1 zdB_w4Gf1LUTapN;qKSbSy;{|5<<)!Qf}CAZ2xAEX^l4axX6nj&z5-)yv>BtqC93j{ zJt5UtEMzM95Xc$&w`R_9QW=K6<~|^x<>mQ#NV5>4N21xX@)!d5>cE7_Bs@%A6Yu~& zZ-`PfhEf&Yp=Z~ah>{OU+A}Tr8~f}-0IKvC$T9o^|IH4Rg{VH5-?RExI?_eM9HY^U zq5+M73zFOzH~S3<&DPRIj$)$~*>^soenn;>m$^^XlZR>3lLm;Xc)1_>RYN~us??g% z;-gkQihooe|B@h3WG5#Jqb&g48~>39==u0fMZCjUj8>9y34w(H;Q$E$gaZr=5DqA) z|AeCucrxEgsK14FIr{oZ;K(G?bSU*p{Bd$eba!sApb^64bku|9N1_~{PQG!thP#l! zug;{L>j9IB{uJA_9;bMOclOh_X;VXvx7I85(cdQeQ9`4)zn4#2Fz(CvFD4!U!VuA@ z`G1TEHqS3TVVw@1Zod$SzH8>{Y@1jjDLS5ce|5qDzHAfXe6qsTI(OAsUxD&BOJ90p ze-?tHZWm5q2vDvP=nR=YgHRwBldCsuE@KUy~bR?_Srj0HUZJ z&YIhMemZ}DPw80Z<>uIAr*F)CgS_+d_yhrcT1(E1rx8@<^a*l$xvuhI>~}@@{6|-H z7Ry*^b(7;$BZ-j5FtJqE8>T?K99EfG9q*(i&oarNDUWTpNqNS*@BazSRocwfY-ena z;{LFNj9hGoe&y@H{m9winA{ftXcz$ei%qd0Ta5)4s`}aGT>TX^!8#dd=fv4;K=_F= zhIQ{z4y7z?n&LPrw|=i~UNOA@1`2 zmTJ>XIOX~^=XF;n_+K_eoqpK>9k^@+-g>rL{_~vn0OE$%;C6>!3vOl^{zl)%R3TPM zZBXjdCGc3U6eHxu0I7`jmdw`*DYN35;!ng#&mBu4B|y!O(q^Xe+bv33kK$+hm8OXb zL-V_YB@jhH1EUDOx{^r&iD|rySys59@=OXWqiyFrfO-OcD+x=HLwT*2e@m$fN}{@k ziGYE?X^P)HHq*Ae4LBL9Z3AFEWt!+>Jrbw&a3 zv#)B#r>OB5=wJq)R$kd}iDZ8aon3Ma`yzIt*6-N1G-68-uhjRnL1e$&2|1B+PpTq{ z7h9U;CjMb`MN0xYJg%Dq&?!9=k@k=&?A@~!k?`&Ku}JpZzxZVxnyLRlNh$#F!8KV~ zE?>D1M>O;Wj<))9^3fVm zOlW?NFdm|)Zy*;z2n2)^-I@TONo;Vu(S9e7lGmKcN(}c}oo%((K!WEG{OtJFFx27c7NZYJB@${M_ zMbp+jvr)ja!h>q&d^>`n`{&!j<+|wRm|-QxrT3*9Kx?|T!9yS#=oz3hYyyY_2mA%k z#|%-9S&QmkyWlI3E7hX1du=OTy)Ihp8iM>%l}yY> zQby(K0Im5g*%mtw-~vg9RE&Hs)jr;^Z(s=&D}%(oJ)W!ZVV30xFj$h08N15u}*LS>F+- zUkOGXkE%9@!*DWMdlQSlB$?~S`vyvJ^?k;Uhn%+Bvs$M(iGl}{4#58I|IwtOpyt;4 z=qZOi6I}8b$v1{2-(AmvD`Pu~FOXyS1(?1n#V{dGcLSWut;C}HRU?3f9vxBJ02c10 z!@}a6)R`#)&vJhOFbU2`JFAB<36%WPK&y^THnU(JVuI6Pi;M6@rupc zZ-PJ*DhRqv5VQj6U#pQPb+zeX^Box~QkO z3D|Rmq+)YJz|z-Zq~Km7u3E{#vYB0D2$IQXhEp+aI1TorhB7bQ16_eT)~Sxz1ru9s*xEn+xfH!P&sXLh&ntH9U1tbJjNMtKXx%njh{2G1 zQ&<)o_qqnGTW{r!d8$m@PvIm)e=A&toxR__Qf>`7T>1VZd&UKAw4G=SMIh9}3fb4@ zM^7gS&2@X!>VGF6hY-l{v_ozHC@+aQKzYR{5JW*E)9}BP_d;M|iU6mf0nX}nQ>tr? zSCrAj{p;BwgpIu zzg~Qi8#>^$KMj!4SMjA>If=}J9nf?z@rUAfz^6fIT z_?(V3!{FENyS=!zsy&gdM_IdCbLwPuohHA@O;y-2L?$z#a<>Y-sv&r^V6D!E! z8c}6Uw&c9cx>JDpTSltHPbZ0uB-Q@7r`IL|nspsHOYhW8TDaEr_}Z^k8-1<1?`zdT z|Fi18Dg2CDmn1`*)0xpn{wP3uX#cN0Y|9=SdrN~5Yu3MF_)Ll>J=LZ(`$eq{QLoj$JIdUGG0!!$95IngX#!#kD+hhkG!d zbl8jmJdT{GT4!bpqik{G{c`)ibdz7^4qLTUWn`3qV zwu~;Xhn6hCN&&v=!^qH*!fC)e;BJQ ztF1`_jfR7zX-NZ%@x?a?f8>}0rxz=CZau$@(10s*!v3u`&aJbVl9Xw!y@T$GK@-b_ z8Mw9>f03bQvpN{+koRKV=vC+Tz}Uz^n&;2rb4L&Zf>?r**oFheyKRe_*!Ii}$I=~x zUUQ?0=UXdwn7#_er|wG5E8~h>%+HMNYJnQw(U)#UX@WedrJTwP8Ub+fdzx2ndK}(p7R|;klR;x_}=lJD$HF78BX4`VEpQhl`>;i?x;NZT!TpS1Nb zbDuGO+#ReM3!G6h9%><=jMeMFuWzq7jAqjRniJD{ zO|+=!F#Zv7xDuHA*J?DgpV;kkX5Hg!*Ksayl7P~+Lc$_z;hwtcABQlR75&i;1Vjy_$_<>-34F%W|(?ewt~))*@VkBk~R;O{S16MKwJI@C)``nXad z^5QGCjf8TUekH_mObQ{9(CZO~^@uDgDz?ib{TJVroWbq2cGh%GWX6Sm=lZ3nCAB49 z6tyYJHP-TJJSD=F+2QY~wOWMU{iRh`LKhtxRpQi(e3{vI4qTsT|E9yqkl5gE#qWb1$d zDfP_&qS2H#X`#4sw2FwI=n$7owL?7+pgKGS<(zfpIerbsTAypC&&w2q{B*Sc*D#&P zTJPaz50C+BGDw&y!BPNCjQ_3nbL=d_%6{m_!C=s~UGJK`KchmatX~4RNE6u@ovz zEa#XJKsjYP?8RU@=Pmv!AQ|GrYiJH3jfeeYhv2|k2_a>XKpn@zHZ1~%-W_pik0-%? z!0tkY7_lzX@#-Di2jBBF9;*9UC)w8vxy|(gw|xWp##^Kl&8$FSo|T3*Y+Aef2j`5{ zC)C=m!2Y1sd}tuM4bdGw%U3YU>JRy5ScPrcE^l?@GGrh&ei>_e$15eo5-@T2nWPct zt_*Imr^5bT=DH!r*!R=JEG5)4Dmmla8T$q6D#e>DAVxRYKx}f-$`bpWa0^5Hmj!r! z!4t^|?cCj7V?yJlwpFULGH)GYYkN{o5`pMIzky2m$tqbUD^VBR*tncFGqU0w=7{6# zKTqSA00$Rav>abmR2RKxaA zFTitpZG+ge+t>@gg9cw&CWim~HEJ7muuz3Hc*U}9HR2rBG2wpul=&BbhZkN;<)UfF z_PVRx{#M4;x=Gmdlhrf$a{wp)>K?Yi zUiOi}j=%*?ak{~YVE0jU3nvOv4LihbGTSvZ(Y1E53Vpf`de7DZRMV~dPQ+NtZl>!Uxb-x;q~3ML zMMGfzT3ZA5iqyu|k0yRNXW)bdPVG(a{TEG8VXFz6oxa+u0IFCv^YDA0&2eCYaHbyP z#hta}0?SGsXBE-rumfGBI&+IWSw@vkpBtUUunI;ACzK6L(|jx$8nfm1A)23f*WD_} z7T8%Sg_pTh_LM~ST=1M$IlGrvw4UGQb+h^FbTjOA2I&X(x6od1spC#7no4ResPR8l zI_CBE>W7Q_heVDs2~{`6mA;iwfH-_&4h)%aKprkx^bqSGju2;zoTZDo#Uf{_!jU9G zx9D)n>jHwrgKe;t`bd2?chy_MCjMX)b_g>D5se+ZD}Dtu_adXC*=y*K%}BED%-)2( zbLYMYS9-G5xiapb==Sh7d*m4`o_g)f^=kQ;M-avg&MJ#&_zHE-Oz8!)n02<$fNsm{ zHcRu8w;AKll=N{ZU3fiKRWSJ|-{5xjzz$*iu`*GU;4Z4laFGinxj{2+{K0pJAD-go z@oQ#xF@!wgd|C9GdGn&g1=gLfPKV)n49^XpeMF$mR645^%rjbihC4$|&C$|OfL+G$ zjP|`zsyWQFIrTF(ul4!j!;KzH?sC!3HvHrx;!0wr(XY*0c;`<9?PYSfZ=e#RIO@v$ zY2?k(<~N5;!?=d4B3o`=YFLfCQD|nXShw#{LyBmSha_8G1XbVgebfM5y|3VE!31&u zu3t7CoR27wLD1i~Hl=w!8-bIwe!ZZ5nE%ka^I_-u9oD6|*Q0M$cfG9(4s-i-!qmm4 zW0h$}h7NJ;8A>};R(r;D{ZCS1+n6Ibzia%W`1wAz6Taawt?QM`G6PA*J_OA~1 zf)e92NZHlFt#+E~M}q^P^KBZd$-2QkqM8;gneJ`rX-OL|j0QB?3pB`cGHVN5ZRyM7 z5UI5V4YH`EqbGD8CA8X;(hZ!($y4b1IyoeAlvjKYtAtr%PkBC~tpSc0R6W zCvw53oPh? znK`yhA!F&?WtT2)q}{ZcJdTj6Ti1+vEfKvM?D+Y7#nJo}aW#dwNZy zk?L~bmY`o>A+&q@dWr4pmHv2<(AHH;<)6yks=y$IS#_f@w|sOO?xf_fl-*B_!U>VIsKK6e-Q1-2dcJ`x@V&_il#%MMMY z=#sCAE)PYsaSaz)rY~@AD6Ictei3@M#h1uaHi$U+e4Iz!ktcSO4~|8}4oUU3I$Tg8NxtKx=3!6 z1`SVw&K`L#R%7#A_G2z|Unh@UCa<>AF8%QP9^;6@@h9ju zo0y>dxOKcDU`rs%lIN*;%oNios{Q?`T6L> z$KX+*uCBYLItidRB8#dmyP-b_t7Ie9w&;KUW39qu%A@LWLEBo2~;tI`eAzp^9S|}UPnb8DNWR`d>}Y@WJC<_wD=_7<;^^Hq1h*02jf=n zU#d8i$A0M4vh&j}nJaNjcYAq0ca(8XwI?T;MZJseO@1$F=zBNp<_1x2^pftCsRf+t zTChMXJu|I3qx99o%D&BJw4gmv#voG`<7y8ik7lxX+`%l7@;!aCTvn!MR%vxj_3X^s zGhRwg`&>h?dgkw)mfwSae(cQB9)UBy9i`?-y%w3d|XaHhpx& zRk1k4J*+ZQx}p!!G+t_JaGCUc5&kghnZvCUAQAR``B(R%xXWMgZXBAw?I7#uaA>bC z!(pcc>-|>7HZFdxMKrE-yPEk=9xFZ7Qe&YjqYy~TBNt|JLNCw7T4wUB^~LHHzJpYH zm;53QzLauI80z?F_E=QKVl=SuoTW9KUb*(nQM%UM`ZVE27R;|@`GmbcB){S$J{-*O z2J0>LBaOR`7<|N~eOdz2b$+f?pq=lPH4j7l{@UXboo}VSJdk@BR2t?VH8X9-9Iv~# zbg9ZEUH|-0{Be`rMgv^ylR++BwM9)9#CVJnLsiik;5r5I5GrX%vQ)9#5dVqIOZ_L0 zKT~(8yKVjYaX#Ibg@^@AD662U-qb*>2>vFQ=KU8ZbcXNT{R(?h`7r0jCGj3?Vyx0c zeY93@Nq2A{O$qso9UgiR#;C4#EhN~U$V%~5<~{K;S86J%KEPkU_7!l0#eaQu$-{%< zs$!uFV87iFy@{U~1&G&pRDZr|XHZ43N83Xn1b%W)WLcubJ!Ky3!KC%d2q5 zE;w3DwUWEYSMUPg{<^m(^9xnIzm$j6S>DyLqWr&-#AOMC40?hSmQ*i;G zusr7O=I!9-ZF|n&!{Mqm#afN$8;#x_=EjoDq{{CXh2E-xdCU$!+lTM|w1hV8h$*BS z!j=f0+Szo#vnB2RQu%-x`^+K!d>#HnmF9W&x7IK>MeZa+tws+7r1sbFIjO0f%5-5> zm@jY5eCAQfe5XRzSgQh6;$1>1Y9Q@W%!>e6Ws&-Zg?2-r zQ7Gz;)aOo7n&)Ieb)0^xfM|U5xiG3lfZ{VnNT2joz+X3a{+-W$aUYc; z#c^-aEaN_RBs&a@nMo{aob87Q7K;-r$a2MTN4B41WOvkR)_AUzt2P{vfW359<)`%%3*p1og+Vo&@ zjAjVJrD`(>c*ZU~u)a2&l0HCQBQ_6gOcHLoZ#LU*bf#~tPLo4|S9*I(gt7j+W+!iI zhLB2Pgn>V1u$!}01N|HGqgB2$!3ff1mFDVX*)sOc>dLIK#+Y>B#fIhq z_wzYbl&_6CapJX7SBvD%q|IsY$j?3ZLSOgZ`P&@Ra{Rm3|ZJ9 z*lw=pc5G&f^yMm~pG`m3XXL)QI@BGqISQDCEEnh(9kRLFcr#yAv+66^NOM#Zux(gy z;O4Sk*BesS^7PosP|BQ#kNPIVaPQ5T9<$kvtj(3)s)7##8%x7&?_=CIfEUI}Gy?-k z!wa>hA)6};ReYs@PeVeM7urIFfsZu~glw#gA5aS{^_{`ahp4Fy1MZp3avyJI7abrI z$4~pYhit622`}}!2d~5%2#pHE2Z9#{X8OrqV6S(_Uk5ZbsnklWO2)Vw~I zuC{^%yzHi_Hqz+JuGz6k9vnL8zutr;%^zwS*cc`>v#&NAjVdFOHb$C>%$|0ojTEHq3>#x$WqY(Fv$)O7x>tjaP z;EiT>;mxI!O;sVJu|yg6knp~-gG=IT~ujDq3=_En5l@ z@-aruvog>_2pLRoKJ_W89gkntfr4*%~No4^(fGGjOeG2V4YUj zUGtcz%KmME-edP$XR0jf)ZZ6& zX6;SA;j#Oj^KT2sJ$6?*@5tgv{e6KYOD46(V|SJFZwq1`_uo3xWHF}xzQB}qAT`tD z{yXR27A||-uXLu*;!pj3fh|ipb=2d2mGf^4ydD;BovE|vQh#4y%-Wxt;9>F3`L~7h z9u}3(bXh#9zb~+6$)|RBSX4RxLRf!#;1^#Xr!$0j1cbFQr`ilI(q!=|mB0P#qglnF zUwnq%P(aCburRFcZ-g6@tR6jYooTaJQx*Oz1YB=Bm})b$$dqNKRQ_(9$1vaH7ms|; z5B}v-#U4HHoSCx@rT#CWL3f{$>rmnKHeN%^Z9yQle{hjLOHrx3a-7xB-6J5P?Qb5r zCI0DCg%NFRhN?=0!G9zS*Mn2x9zB)L3|WGyM30^-XZ9@he=1yM=Qczr5rztHwow~0 zC@M5%w%DeHMS)#uw zSXKE>4PE6JKu6A)SNl%kRTJg}dsm`;0&6uY?Dh_zV`t3ke5bysCd><3u0|IH)&ghw zWCqa5Gvlu`TNRkc5b1H0(iy4MUuc9nB@b|I6 zCO~=(m9l|Swuq)DjW4g6~?W(Fd?juP0!*JCjY5NR^XaueT!#VkXlH&7{?_z5hA z1d-lE^={(Vu$WB9&osn85yUTU0Js5u>|j0(!H1*1j!P@&nu zyfnDuq2`PrRchz~Ef^iLhziXI=B3454mD>5l~F^LwO|a$B`UNqn0E*6MyNRlNRFg34&2{#r10-p|N1zT{!v(^GhIA7HFh4Oa>`WkFEvt z@*i=Q4cy%5(@b|WDDoe%G;!6?j9Dr`?7pzU;;VI5p&32qiPo+WDAwHqR<0j=1}{f6(U-H*3w(Ax+@nP!0~SKEbB106 zbDUtg8~Oyye}e67XgnBnAc^}NlQdm&xPf-opb1EF7f(FXzr$&}m6irSMVPP~s{ac? z*f2a(@9|zeH`*FW&wI$o(07{Rf5pRY*Xc_yN@Y zLx}bb$bFXn6Oh}&T>k-I|4XR7r~L;|N5Nb|-@(`a7RH1mzJodn=2Ce(PPGNT{*mBO z%D08?ejB2F19GKkRsh=x4tZZ|<1p0wO`-J0Ojp&INQE8O0Q%NUSGBLyuxjy~;N(hl zP+;xR3OmsO^xc`RI$x;~)#75)(_qg;TdPsNlGSRTV9#`0tFL^DYt{FHJ+o}BCiqI$s*8d>^KGrB_!LRi z?ZKWUwpP=8C8X-5U{9>A)hwUldNogoXRWQ(JYUIrwS0(Yv#r%4pCY;1G{m#h){4ki zLaz1+@f@(VTH#aNsJ<8CIc96M##gdYT@>OuV{5g}r?^?&9^$!dYqh~wvRS!JMU^oMAKD0{+ zG)W5$(UJloS!vKm!SJ0p&af^KkjoBejFuE9(trki3Jhn&$%b`_fhKoA)3v0ykx?}0 zvtT$A?rd0>B*=vhny)3ri)^GpTY%xrIIplSY0xAc6ssk*3&~20hJxWNxVvFpvLF|F zXtS2oZlnP%`U)7%ihC8-r2v|whYn~-?LkJ-qP@UyHe731mkP**0Xm~4C4_9GMF)W4 z?6~=`E)CEm19VeM3XEjkfer`5K{(FvuA?BAoltgdDG{W>4)iTBoC7Bt-gO)_xf3d^ zEwv9BwF7+@4Cln14evSya$$r*w57z5jXTiy!Ei2|S9q5pXp#}CsVyaeWTiuAfZ^P@ zyWw4DK`u;CBW)>3qyZiJIT+4^dllYw9yG}WwbhoALPpV{UxDGgxYqD43y=#l)LmOj z8revPehr56;pW4;Y(SID&=75@!$?+o^gA$o7mhQc3kq^!fyQV{$vU;#Cw;zsg;cNj zxF2#$)#|+C*Q2=w&2|&Nak-89A}$wGW|u7rW{g&?|H5d zM~4EY>mjJvLT!*F266HIr*zJTdYFw(?^ zpVWRjc=pbLE^coo4Z26+#@gAx$D#d!cKdhuZ0oImh0iFc?qA}wEmZff@Yxos`*-+k z>#cu<&$dwAzr$x+Z~ZHLwuS2c9X{K7>tErsEmZgK@Y&W|{|cXNp}K#E&$izB8+=Cj z(tRudkAIHee#V~tg;3iN+w*hM?N_kukGxrrM>+LRNVi|IXFqamBTY;{KKcVW_E%W; z=O@73o_{9Y{+>Pikz=bN$o}ck|AJ){-t51hvEsk>U-s>P!?HhPxaqKW-`KZ*1k3)6 z;Sv!;TkP9EWY2!&*wO@gDUW_1pHWatX@W8UmLHKxkDSo#Q( z_Z6kOhQC{Zc?!uJMZU; z&7;cJ@v>MGNV$s?l5$apU-rVo<0 zj3SZo;aJQNByRn|M4HvkJ-EK$UIc=dl!0yRz{)SLlCqJr+#g6%-wqe63m6KHVfL(Q2%2x_Q|7K|R*PK6c# zC(z>Hq2}x$5;as?3$_!z-Z~{H9Bh*{~grJ3bYQfl$?bK*hZ~_C47-}vIBGE#_v|u144-NVlIAJG_ zH_TiVgxCR%)q-&%O=-}l!3m5wg)nn*5NQYWkrs>_d5;Ed0#0DUoewiV2tv?7(ONKG zWIGMo5}d${gNKDhR;XH2_i8-skLEXB+m|X z1ULbN;|(`I214wFa%jUukfuA(C~yJ?P9fY}4@BAt-K!1ThrG7~9S2U}#GMZ}KMg`K zLS?jJV#xL#=oD}Q7Y-h7ZUiDRLbbJF5=b68^kZ-WH!dOE+ysPRf*NbXB$1|c=p1kY z53V@e+zdowf?m>wNg?mip$otXyts~Vb4w6{8S1GGlSa1Fq07Jtd^lpbxh;sq3=PwU z9Y*rdqpQFPyKuY_=5`MsD)m6R@8Hw}e z5e|LH<*O>w!&n#n9z48vSdYD3c_s)O( zgIX$s8~vjwIe(hB4|ubN3f^SQYb5x1g8o7X^+mOfn2!X?7yu8V$YS z86{j1X_(%~7Q+*89eRFte&J-QWKiw65+ZPJr^f5(J8i2MvE_sH>g%6+^UWfzFC1Nd zqi(Y)oyynzp|{6fUMe-Q>4T-^zz}TcO`zL@rFEvn_Jx+U=OZot^uoTxGWGVB*MXCd zgXnu7DqCpMnjwz6h`Yfv3b@MCc1_{>3~$4az7myv@ArP?{f_t7-s`-_z2Eo#$$R_v zU*2=SkAJWA)z?=CSM3{tRy#%RFq<Xoxl^(^2@OZ!T|T@;^&Lkqd?3dU;J9IMe2 z(-PAWJ1TZuOj}G>?3kEdrdFm7y@;vkRc-oT(8v!|)Aqa_Gt&rdCdw6r`ND9uqX`ASJiF^Pl^mMiT75KHQq@DKP0_tt4%$kf&7Ebe`mzI-gTj z_j0M~f@@R`tb3_j10cCm303V6T6!W=(!NgVxQo-PdX{iKP6J6h{C2+0`h^1r5-9mL z^xCF;etd15*)UxIxqRYBHlx3yP6F?U#PSn z$9cQqYc!k_4L>-FTU6p@oYIRsE|KiLpF5QI^+FtmDuVYlH(A~pja5_il*!T^y`g_o zKjuT|2f<_x{yEviOZ9g3j*=H8?Iod-mnAPrI!M|{IzGSn-2T=rQ#qeYw-R(4GaQWz zoh;5Bdd=&ADvlaH^Vs!R?`0?=Ksw)+WMwmKRUEl|Vrs$O_f<&gD2v7(Dg-IF?)t{h}NYK4Ie{y`W45JKdCRV~4 z@`dXbBD%#IMg4;h_g=NIcYE*se(^oa`_Hlbu^jnV`7_lr12btdk7kNwLNhrt&t}SI zdSx2%?fQ~<9oDpR*T!^ODRsaMHRzDJ?ZRjfFRVPUk0{W6Kmixsf# z6s?29W=5Ycy)YXUNwDYQIL_lTzGvgmxk7KKnw)2mZ7;*ZyU6j+I*2yk@wb6+unojL zb?jA;R0xlXV2QeW2N4a+q3CM2t*g{ub@lpvU7L=4)3tVCJ5DfqX$hBzxkM) z(e6ucHrdysagUFU#gX1^HgfQ^c#RxaC((91?kQJWX(Ta4vAZ>LbqZGyB;{^hJI^*Y zZ}zy&A3;*LOQL9M(k;d+&xpK7g%IUSO}V&%MCkF&+95s8+*L>MsXvKxOgs@VDou* zBPYn6@Z2Shy|=wZ<6c^M-crAYArP)W5cKxdXe96%-gXpoVgvg5OFXQyU|XWu;_dA{+}_3Rr5uAFb+*3GfI^<4h2Zujn3*=V`O z!@64mD}{yUxJ5NFB1_;3SmIbapjcX8eo?s?kCfo9CYH~HIo_Igk#iq#1P=F0QmIKz z28F=kGay*U#HI;MeLdZe3T&Sy8XeDCh}PR^WtV>~AK(rC!KBAQbFzH-SN(M~jI|b* zRMJu#q&j5o9lj@fPv)MS>0wh@-RkGbuMf8$)@{6!oZ;l7Z(Ky5DPbvkw#M@rf2LFK zO0!AZ)z#UaG1=!5;C@jwdwgHFMuK%|`ylys`X~gzX}`w ztVP<{$jkO&jJ}6ipxW-EMjSzOHRr=PW}!as<++bGns>+aUK#9Gn_y}U|E#5QN64P4 z6u1Et&m(PvpGO8}gi7qYg@k5Y`#RZvMEP!PeX?YdWO4?yUEezCN>awGOK6>EpB+5G>_t1S z6>x|83!7{>va{6hQG@7wBu&O036WcooEh;FqV#sD@%o|C56q zO-%hY8i{FwZyE#KH8s-gFe^2Gbz^{#KuzJ%p!m+ADZG3{8 zqgsd2_*6W{hz_0cNuBDo2|q9Cf`_%-@;MH-GTLQy+jl2rz@kp@*FL(Ol;Jw8X=Knm z(wR4zYYeBJ>u74~cC&+IuQm-{DY)RiRXsnddqzDSbQ-7V$T)KdvL~sDMXl#_7$w&~ z>y+u5yhtOclcINx#2KG%sM|PZ<^h;;@F%8BEcHwKnJMogZ!NXYeX+V+67$#OIYvpI znve(gQyWq`rPo|P0$M6Gh4&DhHYEpuijycg=;m`H~nWMueV!b`5{AiyKYjnO#P3R7q_(Z zp=b$vroOJ;wb7U^hk>>znybj9CS%Y8I#CIfs+niJXt|X;n>5mZke=e?4&xJWY-u?zB$Ag~g z@EaSR1Kra(_u~H7qdE;4mxGqnloKv2{#Y(49v5oJw_fahI75SXO=T@=Y|`)zbo3}v ze!xaVzwv-7$$6I4OpaXV8cvQ(i6A4eTRjMlm7ypZ6iv*Yl3YtO#H`N6wT{18=-%)( zrdwU2x7PegVNXNxy;c)RmjE+Giew~7>^&7Jo00kqEEx&3^p@+$|3Z-5{5&A*%YuRA z$^M=^?4zC2Kv?=w!t!p<{pF19mTnNf-O~H}FCn+==tcT%Ryz-65#jipuvu3m9K~fNbUClss zpQ#gLX2_JIH8!c+uIcF!W-u!QY#a4tgON(sS+*5LW4gH|defiTG7804`j2e+9nR@c z;M{1AYwe>zKf*Eor+lE9*e-_p`i&Fz1N>I5io~*v%GSt72>hu1fPsjGip+y#zn24| z+oiIncK)6J>XaN#wx-fYdidPN#8t_Wz?T9^JRdq^zN}`$;{MvkV^LP=_@(+%ArH55jnX*h({O4-+EjgWD-^=_l8bAz$kaqjcwugjB?wwLupCP0Nh}d zR>;d6h@62cH3XMc-5Qgv4;G03S@Cg@wi)~T;)8mi+mhjIT=dl<{!ouX^s%U7R@anB z!g%TW(e9aL&BPW;%H+*=kH0AyNS#fqY$rN}Oc=lPrewBV2;LR|!W1QYXZpmp(#H6m z&6Xh%q>Jz(vSC-#!Sqx^qtS()iX{^|(h|MT&%*H$%Iu$|_V;i!|K@BjS$ErKB=WTQ z0&f~nBPXwkl;{u7wJ-rQ< zW_`^)%Lmi18D03;SXQmg!);UtxkF4 zHEzgZdLFTJ06qJ)c(BFXEB4W?8g7Y**}DzW20S#j8V!;#lAA;D{ZctKMIsoHBFZHg zR+o5#e&*(XT*1G)`P}!MK8*diOd_*i_6Bk~HzyeWZg<4Yhg`TN$$hc%UDzYUAkk?# z;qi6a;p8v`DZ#DoUD)`Cw|$K6P$_|=W{qQ{6L3>9ZbnO#03edIhmeAIw>H(RI1g7Kvz0}Vr_a(YFYy}u%!tXT&fhDH|DD9K@HTf; z4KuRDr>NPGpJ_$HH@;}EAv8rgV)oM3-FW#YM&x_#_w=`n82!C4iZ2Wm8C@;}+zbq~5{Q2N zCP2qo{)a$w8Tz1uSdg|*ISgkH^kZ}zIPJEL9V-T`ivc4p?;)`BNeD%BRDST4t=OIR zK{am{eU9fdrNfl|ti$|&8FI)S)j=_&{6|AXe^57|WGAtFV0&8V>)4REv+d_A?gIuC zH37`%cABE4VoSvZFSL*8Mzqz%U@sN*ZlCewu~z+MG}^Uu6rDJy9)FuaP_v?triJ{ zSjJQGxgdLV#ZMCejRR?fnt?48G3`+-5VBPgjbDAk5W=h}Tip*wPAti*8K^`9cx+v; z+0WRvGPqoKnEgrR<2>-8_pDE7$F=G2sJ`DRV)GS$PdetkI1}<{22w)o6!L7wZ3%Hn zCDpKAHpaR!xpWar7HqRk@WV8RZ^UQ&v%$pXrJM&#EN*S_sbx$$jZm z_1^ebgTW8I+2nga0mjudtY83u5}UeBd-JBsv{ryZ6Y^^FxzN^(r6V8;ATYSm=SwAr zD8)J%Q_H(RnFFs{b(Js3nE&|NNln_R>$DKhOK(SY8ONggx-i57x)+$r9p0WzU z(ni}m_RV-(bqfgb6n3h9`dLH%k(c=EWc7mq7jAz8Hvl8y^UZ)4OfA#R{LoWV&jl5p z0fQdU?xqPTDtf0GYNo@=3dj?xTNdr`VN|A8EPx3V81=Cw zAz54Ou6`kd*lCIZ3Hv9vLy#OsRo&FSa`nyip%?2xYv$Ud8(to^Gr*k(f2B?SX4d~j zv-@7B$L4|h0(S!Hi>jlkt50FGEHDNLP8r>2OW1NT1F6Im81n(t6-BOarC@A1%( zW`@zLv_^g|-KHz59zm;hUl*207$11v6= zgHLg1A^^FD?DPBRx0*32E=X>5t4NDXZ)^|vg_B3N*%FdTHLCWZk8E%4yxAk5QoSs3 z7dO=oBA<95+@SDRE1H%1CI42p`vZULvP_0Q15lT$8F|XDzgzJh0I_fKT_e8o+^RHw z9#c@M)Lmub)60S7z&H(9(Q)(8-t7sW0hN|BQ!=(TAJ;Zs7pT&+eDwK6Z2zMfhSou2 zvpc+B=v%`U!L;uM?RRiMyys3O>V4s&)7fjR!_Bo{=Ya9?crG5D{Tw_wVy{6huby34 zl)A-hfO@XmnE`7l_T1xA=<3v~4>K|X24@oCV*pSI^VYiOh8$k@;o$UUwYg+tukDHN zl54v0HlwpKH1aq|7DAy!zc2%MaRFePXH+R#-n3k~XLKsPwj+l}<76fWxPo4SulJ`^+(AVup? zvIgJR0ZjQH)#qLoxjS(HI}yN~M#K*Dt*D%H3JJE^>ddi_Wa}tw`LJ&Y&|cQs7;yOg za=SxRkNmNAZ^W)Q?^Oa{)w`^7{OE}{ts^ocay*B5WO-zGp}hqmYS)3AM>y6Alv@6GoE*Cj2JKCUhqIP5#626a{iBW~yWcWYT9&>raH!zC2hjt-P%%Iu7mI zP9|Di3O=i%p2UurI(#g+T(57dS;u?{31<28<|Y=z35+nm*fN;vZ!yityugbMpQ5s( zvma!KWviM{IPvF{9SVhN20Eh;R{a*x8T(DORfURONQog$gA;|twzs#_{$^ZIbJTX) zuR-csDXSZj(1Y!?M{qsuDpLtTyosHA;vH}}T_LdgcI$x9c5BqQJH{Y)D&!AqrvIg^ z4qwI%SR?}QCZHTczNlV1L@hJ*>`^2hddLZL@FzXe9nGg&7cEp zZji6!Y502-ZXk=JHuo4bf9aH7C$s?RPt2paPsX?UW}X-Sd_~;+h_rW%svBG>Ch<0^ zZmzNs8* z0HFAc@hqiPP6De%*~f!7|F8&U+zV9E+W6*kZ_m9yhdcM-+`Dt%8T@k`0GazAe~Uct z(9-GN9me7+a7+i_#iKK~=bBGe+jC8CM35#O&@j`?h*{C!^rUq|qA6U8pHi=CJ0&td z;NqmRzraC5YSJ$mx6k?1{}vfZa{(11eQzNdGrIN z%VP{c-z&&x7Y=dg=7?roVbuY)HSa$b%ji&+HBJH2Sa_9t%w0-UDzwddbzeBG>OMtk zU_en0aMV5yQqo1$RLc#YCr%vOcDS3+WmL^b!SEFMOLzZtTC zJo$2a`l@j&p>Vmt_EW+V0x)NWYCYlwfR0tAQ?SKce|DB<`O6ZEl(ELg-M9a*rHEp} zzbp~~1DIs5+m^;P4a%}FS-~1b~GB`2Qy%{Z;&JFy&yYl@ul|DgQL0cKkP$tzba`jl| zu}rBbrdike0W`V8~ISdE7jTXm6k z0`dOyo$)*4vD=Gc9edoVFn+towEv7oO&-Yo*XokI4d!6le|?X>u?_G*^_IS>5Ly zASJBmvZp};_|NulB?$G1I^__<_g&#Wkz-$ewkiBm@crkw1?#p6f#d*Mb>cFc#7vkU zgW030iy_yZ%N5xOo`*jTXu*6;wn#H1o^{=Juv+?*Z!BNb>9Lw_5-%!qT335l z@1;Kc$wxk*nPTG161Ys`A$r?-ySJ?Oec^gS=f?Y=tXuE?sh#|nY5b3W+3}rjQ-UA6 zXy@4SG`fer_zl0~S@#y8L-YZ=wvUv87$~rH6lAWjc#|!ivUk%jOu5zFN*N6+(xxP5 zyO-Zeq+heBm9}8lUyKcgh)m~rG46>)NV%l4*n9!8uxj*jG|EFvJJXBK>cZ)L-!sYjMsy?jr(y|4t z7bnOT?R&_oaw)(u-=D%S0!3&usEU-{r={pT+3reDM?*)C@(cM>maM=~^;$gdypu5` zZ5Ob{TBr}MOaqelwfKW31cCuzKq-4vI$!U5%Tp!Z_2Q3!V^JZ+FyIUi2LaGA@#7CV z=2-onj(=nodl7m^%%h!V1g#xjMGP0GHVv)~nI;E~t!*ERtJ%>1^pw`l(Zk24_jJ=X z&f-ys+m6EggqXbP{*GYOvp~)(!VSdo34r;G`8pkT1as|2a&hGEYRpf##kTKx(vaWR zr8k=vNw@n{$syh-=Dy+c=1xf7C{$W@yMIKRUtOWM+ine4_ZCc` zTWUEG?(MTwEKb@5_gyl?C|c9CFL78??DyeE`~9Ym9l!aw&2FWrEI@D3Ec)w&VA^%L zT0!Ns%B4{!hKOzB^=lw9fDHj)ynf(fUL}B8M5fd^Y@O91^bYdrnfb;D8<3xT>JKkq zIDf}hxTTNQ*@NT9;|5I*f75v>rwx7}#kRKO6jCh7wyexoCt?IS-QRLSLj_N_2Q4u8|+vf$r-HB z$an*Ex7|M;Axmxm{dAAEHH!SVZ}~X8j4LDNtO7ol2fh(a@2g?BOgx9_4FXl z$1i<#E&&+J^y(i^B$0~I^)m8}`Yj&fWv5;NPo=gmXs)aVHj-5QD5-2ldlAn&dS zC#}V*X(qbodCK?-lP9?lg--RQdh<2a+WKR8!{kA zXa8+B%|Aul&g? zz#mQU@)SaljYa^;hPupL%l}{(Ty}N3<4oddCacnygDTNi=lfnMw$K}*Qs3};92p7^ zM}0Y|5yz7+!_Qi)wDp4V*oSK0 zRVB#ekp)h%o;q|&@Ra%~+Eb#ZsGl-E<$p@|l)=H$W(jw?UZaFq6XonVvPQtODgH=7@z>`n zx|h!5-$ois7b@|a!H+F?x4>Z$kBl#6(!@REF zS!Jzfjn{nmS$mbao;E(@p_=yGt}!9nKJ24U4?ksmdi3e>k%vbzxX;`_bKltFjLIYL zUOdP?p*yV1!N3lyPAwaRW3}+=&9+rR2RqElJ zdoaxl$D2l;98Y{_jLW^(<%vHyR(GBGpywd&MBcmT^B2#AqOC3`QFMJb@@aqHTXA-b z#43G-+RcSQjkI*<(rc`N53TlI436-k9buR7J+l!$Pcsv$ z*zH)>-$>LrB>Z1pk0npJxjvg*y2aN}ZO@fAtYj8{=guKa*l@-<8!h?!9@YhLp z9K`H6f9LdTNA~m5rz#vFG0g9AFCFu*sUrYYkN-qf`r_L6#DA&k6Pf?0$|YP5e3!H> zv!1?i+;9{y>t#b}5lbKjR4|nVC7cX~x4rx)Mx6H3Ur(y^dUa39MaTc_`?IYEf%EUm z@4Dj~Bug45BC3Pd+V?&(=BXVP(UdqrIk)W_NF$VNK2=5N^JxsB?Li0y1O<=h!`}elpx(9 zC@rvQK|+v{`kr^|%$Yf7e&@_Nzwi5JF1W7o+3Q*BUiW>k^}fLR*5-%wJ;jlB>`udu zodl~nGu1n;w!G0WyTaxuve}zELpvD2GS=_PbMte^h{(H?k=jIZyv^fd{oIUqaU;>2 zY-;66P%|NP3KXlkwxit5ZTfGs}a}CE96i z>i>om5SX4jfTZBdB-}&)SM6=WS+gAP-H(ArOYwAT8nCm60{5J6t#5jB{_pz$^ccbTV%QMy0zDn(CEnu-9}ZAS;gwD2vna!ByShjl7bMFS@fyUNkux553HLv z4nHUo;`1jpcPOGLa^ltACAgA3QSS0SZyMKr(Af8+x444PYwt!?qwhAY)Y3mEHo_UG z?0-nCZh~Xlwchf!&>fLMhWxQvBQKPFbh&XnDyZBTV4-GoGJigIcO$VRI`6U4u446W z1gaOr8US}O;4YnQu8doM{Vq|&amH)CLb*%swt7hD*Jwx!7+cHwEICIR>Zo|p2Pn-3 zZVOLZF6HCA$Jc-upzD7Sncx3sHE69W)_CymA#1GB_?L+-qxmhd$tkZuxVK8;^Wtc$ zCb_Ejl^OaJjCo&KTIkp{-lt2J+1z+D`IuH@?V-8soCO&#he*|dC+vfDATHh@AH{eD zyV{Jz!`>`!zvNd7HYqDgIO#h-)0^`z=_Rx?&HeuGS++Xo@n4D;%Rdz1{H1rc#r_X@ z5+_=>bv{Je%sB#@^W?ZJx+;0N-f(&=B zvuhXmw_g`Y*;m4${e^|w%m0i8Lg)WE*r)$cT5d>b{f&7jjH-1@k1RP6Y4J413|(E^ zm|)LDMK2XL`;i&Pc32UBSewO@9y$W@x?pbFrddkly*YL5VJ`Gnj?K1>x+p~pVJ*rw;_=G^eUBE)A*j5Z4f1>`jGKZjF((&D)f4y#W5zV zS=H|y)KRBhVtzh>`%t%@G2-6z{^`s=a>DG`Fvq)p@41RN&;kdvivMD{T7I)!2QuE@ zgWlo0m1;Y#n6&J~=grxx-to>O+sBzQ0Oo*=8s%utN{m|K>TZYHEN`NiUq7^5>hb4E zr52%$j^W9{#fY%u1zC^a`kQ?woZy&q zM9=yM{`!~X@`B`k2FWc;pz8swz_&p^dh@FYzhBD~L}2_;mW6jKNKdm@b17Px2$9+Z z>UEMWB!%6b4o8#L^>I>!j&|%=rX2hOw>itWnG(}g0gHSd3|WV#=g)-!gD9x@?|oMu zx1vbTaS*9$MSbq$zjiXtKCUJ~#ylsSQ(MleTcOIG-SeBU#G03oHpEFyvW!7MXi+V? zAI)YoEuz~Y_qF43ItAV2+V>|KY`0T`-*QeYqG5@`1{vmMeBczaQthG*)1#oP)qacT zJ=Ui82{Q3Kj{O!vyp=ouWxSU-&=^B&`43JYx%AGW*k9$(ZD!Iz`DjQHWS4V3_BzD5 zx9Pev9_1!dk>6(F!$lP|r;-`7^1Ub;IetgQ`}qL%;h_mHz6cia!m(zMvfvVrMh-qsL?0eBL*SPbYF!)iSvevb9Td z*xQz@z4-k80SN9lUgvw~4^e8diGJ=usrA|=4}W#pv!7k&aqPc{mFYX}>EC7%^Ix#S zlt$x=o%0EfWk+OB)Ben04~zY;@KD%Ky&Aa(^XxN}HZBS&ZMA6t;vlz490Q31ud3CR zdyrRbaw8zPtAivdGU#7@;5a|INWMnq#L#t(-zMd&63+PcPibge`Uh&K_wh2>J;YmI zx4qwSSo*i)EhN21M64*Jul%|EF$wj?jvcj_J8>;{5*#u9o3u1MYO?t4arl9RLww!* zj0!1rAYE@q#`?vBQ@<#%m35%1&0fEZ8)4t0Mex2EZO7w`^*+bt4b&!3x0 zEnuzLUOwC1t#8r!kTqRx?p|ftx}EcGhgc6io5RS~TZNiAqMG9kiNkl`t1HI7{rBaE zOA+o!S zW1&c!9OICkaHMWd?5PdmoY)H+?m4lSH_qq8Ufodpc!w14K9uGA<%2TS*F6T!pe!2? zM&6s_P+xPEWjtUvfR}5f*y3M2N=*%DjQI9a0uDziFFB+`8E&MO?OGrorCkm)9jsBC z+L(84y-{gD!0XjSEOmI^f#YcOsqxFCqWYx=Su2;SGnXEyeX4Yd*_#Y0W~@uv6P;NJ zb+}v?yNCTvrCFG4O3Ir(CnMC2af~m=82ltG^4|vg^16qiITY-z!BvMj4=7kpQ$j;1 z*!5M?n3s{=lIE>eEa^{sy0iG<$djvZo5<95KS#+gVFN^Y z66qCPT_rXbjL*9sNe`15uX|Dp6O&E>8w+;q-&=tumW(qt$d!?zt=y_<~Y;3Kpsj}bm}loEjE<7 zD&=A8i~1~A*)Kr@^m+B^6-qS&Kk=GxJaO^n?|A*T-7I`z>ZZ5f9@|WMr~_ji*|&_) zXyqBNv6hGa&EW4{-jg|yuK1To4M6e3dd{nrI^zwEvxR=YL3})?sw@cEptAKs0YBNkJ8!xcn^F7Q@wv6FyW}1Bf52NCaDZ|OC#-Q? zQ~v=q8<+8V2gOcEY}WQ~UG>*dc8_>D<6KH@-JQd~4top!jkkNw5$jk0l7;Y)>~&hR zq%m0`NM{v8?Mg9}PNUIh<&RNQfVl9s%|7(DLxFY@`(Xmb)+Z(171PM+oD2i{7;C>}H!w(k56g)n}RaEbhBvxx+t&nROmJQL_ zLNd@vp`-&W7RO#3*rPiI)h&MoaGE1m=Et6^V_XQXe+IT_hyob#n^?5y4J;feXg->v7eE|amV z{h$G@adlRT;T(TzYI&=&0s+Oi*1|OS+i#gc! zCEA?(GQWTJ=3b_FJ^ShDjMk?#kvXsyYBmTKet!Liyd)Fe~rgwd+=viT3)U z7MG3Gt8-kXzeEk3&SO{1e4OhLGDLFsvccssWx&PlvtFBrnS_tnnWsB0c))N4sRJHJ z;4)d!)fKm*>uB2C+}l^q(BAW!C#d{B4rQNG!OY<_G5!UI!#Cgj8^e_6D>u+eSb28nBw__Ob$;{-#SJE`3gUvUhog#56DHYcWimV zPGv?sVwaxop!#S@xO_wvLg%!%LlitNOgF9-6T>`JxkXX6ss0@!Qwwv9tr(eN38KyD zh7zw?^aayJTKaW{(9L6DBln`7D>@qy1l{-(F2&EuPhBWv2I6_6A{EJ=6Wg{sw||ZL zl$zZ8c*YG&!aFeBZ689JP7!Yczosi^q6Ev>=LBGDu2#S~-|gvEHMi!UFmkXa#)rrH zE+FM_aj28a_{?DtA$Iaq*sI3!Ph;mmMUN0^Sr$Lj_>TsDkTa(s@*@aI{{c4#C#MHU zcBFV6d*6D;DGwNSCZQj@g?c>y^IeO}nyu)}B$#9zC<1p5!&UTgm z;x|CXs@B*iEVB|Kbm7VcpueHWxo_7zebjK@$CGSWo)xDKNQ;nscjw~I(k;!k}i`XCC-5AYG8ZcH?u-fEds@mL#{XT+(o z)mpRIEY#QAZm@(liCv?2dmuWN*G{aE-K(4VzR9u>0^Ez*pjS}hLx(G(AtL6VoVBy= zrGdw;kOBcloYur$J>+rOpSFnz`19u?|IX)HMl{ii(hIqYj`_9sE@!Fg>NuY$VKN>- zoQDwrCeuf9a2Q8>Wy~d__*8^lx89H_=y6h9Bhn4QnuCZ~%FUQjIPU)d^%6DeZ)lB;FCG3KPr~Nx{G21PcWPqy(-vg9fuy3+V2{G z9w&jxdiMgXvy|3eT!|q2CyMd;I}}6iHI{5opP|k7uhS zY}}u~n2^e1|0}Ie_ETF(+jRfHw~7#)*vaI}y4H0DuzFGlU+^Skr{iW2m!YgXGrEfOp1{CyO=FYg&|A793VHeiHW*1V zLgW~x;um)3@uX|85Ef+nsIFbNFgw0x zLHB2BllfcJW-%9RLpUn7^F{&I%xK&{*`&$PGce|n(bxr>(6GiP#=pvV@JZ!;)~RpW zLmjv%iY)GV_O3F7Rn#N$Qi#%7`cr&bLx1csA(ff5} zXG}zpR=~h0DH(kh04PswADhEy8T+Q8831|UmoRb(X(XJT!T1NF<{*JY{%J^959;!t z)Z{-B>Jb8WuHfC?hIKDhI>KT|ld61m`Qw*qRL@YvS8|q>?lS0;o6EkL3&6oJWRZFW zlW*cRZs1*RQpa3Ha@&xwde~Dw{(}pKMD*%^6j6z`N30P|UI>e?^AY+=*@qwRR<1q_ zKkE~$2XVQk=OZJ?x?FYIbesBsONf6pDY2`gHJxH|WsrdTS%D|~<%Udn-~I&k7FQyl zgw20X=e|)`3ZxzA&*|sf9M}r-uc~HCRHJ)$3-kNatT1_>v+lr9>kN|!PFp7-KD>2M zq_ACIvd&bQ(?zZ^4Z$qluSoxXpDzRp6{)%cqXgA!?}lIGR;>AVHd5UP3vHJV@K#V1=eYBaKJ zZ@V)2$^R^+*aQDbN?%~5B*#&h~7W{v!h%-Y9qMm@W6ulGz1f^00D zD!=TB^qXmh)OQI7XO9r94h$(_=0OxI~}Mju0>N^OYl$^>g*XYP#ZpVwQVzuO@B?FS&=8L7NCU7)i@WA0csO@Y}opPNYx(UMuJ1D|BB2W~ID{$=I zZUw#iMef(rVz_trx~J^aW8fudvZud|-w^SL|0VJ4^^uHxUW^(edtJ>24gb9&wP<)l zP~YPndY#aML*cOUhz&L@&~+%=sB1Hz>qKVHM30og0%pA5k-ay$#qFYlik)zMYcH1y zziQQ=)F-YuZ|VtlKYtvj|8i_OT0GTUlYj-rdbN*WSJtCS#yPu@)OW`4I$2(_mXN$a zSo!m(<-k$2q*|BNeMnCYn2E@!-7o`uI}^b*`cx1zs#>mp0y5Kk*^asbN8pv&yDt&h z|I~Cb|6F;AClZsaMEz?rUKhZqj@cy~JdI_T#7?_Sfb66dvlu-!$_B@3 zRI&^wIzis)%(Fjr5{AK10NakGQi>yx7a1ZOB}mr8sfz``2 z*oT><{&F&3bxE2v?mUGV)h>b^o*VO62J(E)HH}wxIf7y;Pa~SdZfJcyrDA*Oc4h}d zp_~(?;}a(g$|Fl`p={@Ol_GCj;kHn-mYE5pro!FjZgEO<0^{z2TV(CsyMEpFsTJuSEVYrKire4AzPKKV83%;r2@?6Pn|pnkYQJ{IPc1In}4g* zKn2FXefbtFB}B-Op=*HPoT{~luE+t3>E&q6VAEOX&d^A-5YtsOyn*KZ)CY~ny4C@1 zyk{T(nplK6k27IU!LS5YE`MB0{LHz)zYNIqS)6WPE-}#|C(!;H97TZw>=b?P#q!$$#rj(;*dXGVQZOk3Bs(`K!1b0 z{&7COm=pUK_7%Y_A#T&&TJcsTj-R1JuwBk+A#Xx|6llwgGR#v&6NpRLAfgIxApk!O zGS2$s;m_TGR5xg{f%m9VmG#NR+jxOGA>iu6Dr576oWI7zf4MpHU+e~)ThS_6oI-xj zYKh>5S$9!lE_($Sz|F|6KpTo8g)={4`IN)*Am)`@+Z2AEjpXJEE~BppTfxJ;W8+!~ z$FR~UOS^S2(=kZ6)qj=nl0K?YG<_De+av44_U^M6Z&bmf=X%UAv{sprE((bms+i{t zL6(j+xVHQmAy@s>@g_j)7m=;nRU-}_bh3CuHWtr>?UA=r88vSy;UmyxC>g9 z68P)=+ay++IUZ6@jKrccr9cCv&q8sNnUC(>2YVD2jy@ zZfs(#9^`psm>o5+al+3w1sdRTU_M`ATXp^~;Xb=T*-vPA1MXvK{rJdeB6Ys3uL>wi zPbykL4AL@Y_C7wqZ|^gT`_76BH+7-}t+~{yFnEjMM-m{@+G#)aQsDuP0Z#>}G=FVB zi$jP0xP&tfk^75{2-r-B-GF~R)sx_(U{ABy%aeHGj^P-KvztK1E8#D>jJir-0U+Dr z>7dUAt(i<20KdWH{9i%$?xQX)mPao7s{rfLh=6X+m1q|Zxo2x?3yEYfp?Bvr zE2$j2bUwx6v`GK_?h0S&06z3Ms9K>Wfidr=gWOL;{&5X97Kr@o#cM5&KoezugfLT* zhda&vYJtSn5$MyqcWLo2TT!J3EJRqLZ$lP_hq-Fq4&=Q>e{R#zVHCw=)odvl@a7R) z@wz;6>G!g~r&N!@>?i&%#StKbu4GZK%P1=u;milSHCmZMpRbH}?IvJYWbe&2Q))=i z!xf9jF*|3t=ke4}at9GU=<5rI?{dFhL(I%(<{8yv`5thlfxRCEz% zH9J*W$yv=wI`?B|A0?WRv-nspzdz?V^Yl;8Ie2CMN><}q(UDnI_F`V+EPL9?s~JS@ z)hw;E0nqwY&N=d_Ff(3@erpOWqCE>?jMGI8p0S9yi1-7{!K`8;B*BL>CD+{UH63!` zJS`^4X!MWOuj8Lqu>aqfClg3ku>mc|_j&VGHClD|2UeiLD`+vrk;J~Siz)q01{ZNq zdKbCP%*z2`F;+*MWWKbMgWeu~V+) zi*U(Q~4e*9)gMn}ik4%s0FXa#*Qv52EGm%#yp9U&j9CHIrD29$LQw zv0A|V*3!|!?;`l)tgTtpF8hk2`myEK%9gwUfMP)?7>DWyhdN)+W(B9~Av<4DcLGiFv6X4&8A-aT4%Clf0^knUh9ld+hFW zRFD<+@N7nX!Bitmw`p_QzME3!+^iX%4uwI-Gr3+UYqo$})%#?LIF7pZRl8WpK7BRbfkh z_pFd&l(Us9PWFwDOD9=-`*{&T%1tr1isM*G{)H%S=dqabJI&$>Pg*4f1~St{I!nEe zZI37;^JpURgdfy`%u}Z--+Pa&+!Exh444G_P@8k?)Vt|qs*{O8<$=kB38kI%W+Bj) zz0eCJHoUral=GoXRmE!+)Qmi6{QRxtZ9_dB13gN-x1^Z!=qgom0F)+Y`I-ix^HR~D zO>hb`n88I$o?lBl>CQqB?CZn85V-JorIB*pZ|%`HMDBGCIsqvHpqTn>&b!9-hs}UMjQr@ z{x-q0GDS^plQiuf1tE?7q82E_oZk}=Uv3$Td!)BPy{uJ%+P1V#gP~owvTw4(qf>)sQP3*bIvAn5f~V{$a3;gi~H(> z!*b;2(cljfBvELN;0|&0zD)Skje$pO2W|wYXvrBszvY^|o6!sPV6-449!vo*ZMYXJMvS}6wPRrf~qB)KBW+c&p)1obn|r)pIv599o-Pk}7)Z}o-3 z%EPoO*`bxW4GDT4hEsU=GAOA&7vDC0kFSk7it{UWCiFsyweyR+AU3`_9;AMol_UQo zbQssCGH{rFepX8$3u8yz`hL(lgu-UBd;w=;{FBi$5gY2 z+&Y`=#8|KJH#=8$T#pOsYzh}+E#zu2(+Zl^li`SZY+e(_3d)*Zt&!azO#0^o+P^q1n>t$+4p99+BWKHe! zIQi!}GqCFIV!*9_?#r0>!+gGOw1L+_l}yH*O6j^FP~Ci)m$A7qpsK)4=)@A8X;04n zJ?OQyWxhzcOcK+N9!_RV+PVSt@`b+KEY&yDLm0;<8%>ZMZvb&C_DZVB)cI;oY?{t_gg<4p%P zRka(xtw8sy)LsGi+s=s7p++@%;a0(w=7WYXtU!}k5@)ix$_=$K_GI5Y>!xEU0#9JV;0>))aY-TpzL&-Ln3`oFJ$(%l-`{T}r1E9I)B3S^(E+oVoKGZ{rclQU?!mU(xD z=6N)0W*8-nN$RERtyS=z4UvnOJ&J#R^R3!$EKs@DvIpXjQiyzu2m-jg&sK1OGrHI9 zv2H~x*}P-nH;7VrKhdb&_lV5Tc^$-&yci$^_N?^mm^OJVV4zd`5pxdz8jwOLq<-q_ zKyf;o%_l@;JB$ zigdRG6H=aL7-Ec@0u!peCzCTpSVjCGH|Ssi(RO zwEhE^p?EWe>aVyAZ67UT+xKj6SNkG5hAU$M5X5^lJzecj7kT8dC(;h}n)W(KzMy>Y zvWegt#T8*0#}n&Z5%kp~@PJOhk}dt*K~Lywb3M&PRlEZWIY28F^;$y$?9c}FsiCx| z>%bYKZ>S9mAh~h7<@wl2VghAu2wxLdOWLdA~C@*P}_zXiaGKfzPDDP#;<|RC)73 zqF~5gMP4dsdVagu6_d02{1j9Qx2-$d2t9$mxYqk!vIV@sU2$x0N=Nsd9NCOv`G$MN+-z~ z=n(FME~a-UFGEDMx}y9z+@1>Eegpi^s>uMB0ybRkFyPSgamn(^reuZk(jiMlw!efy z<%nMw1Bcy7@RP}O4Y|DVxvozb`F%a0N=I)zrhg)f5V;U7@xUM;AMWv^XV$gPY$GDb zmzzpFz5z}v9*%anemC>xE~;L9s!@Tvz4^ljoYZYo0XBr|@j7!Cx+aTc>_xveZ`}9v zPjL(V`}NVEY!3GYr2>dsbfsno`<4gWHXmA>pVY>EDPh~HkJe^aa~1XVtZ#XylK^rX z4qK^5dh^LF{^+L=I7-RRz`tS{Y*?><#UW_PC>!A|k)ACXDE06GOyaoUx(`=+CgnC? zOR{u9m-iWO7Utu_`6Eh{fjL`L6mNIINzN)6P2|aeUO+>wt%Vy+{6iV;mUGH!NTb-i zuiA8l-B~b#(H^+|rH49~=!Gs{S)K|t9neeJ=R4mNsA@XtVE*Ek^~};zXZH`jv?SV8 zmq;b#o4Y;zs)3D8{zukFo-MJ6likuej#qGNWPg?hPO@m~CEp>2lcUT_XI1mAGwad| zGoP`EYckkN-ZgZ*Ly-n*B?Z;$a<)_xY9&FpY;z(F+^}c5Gp^@{OKcEAg2{xz50(a9 zad_3z=TP74@T}KhMLjuzU^-cDd4la6bioXRyoGH!M-SJ{Ff7W~sar?c7JAu8;gx8L zr6|NOg3ppq*CB|QOMsO-Rt~A2tq}CVmTpj=c5s+GvX(>YKq;T;Rtf4Z@0?*Zv_37OfqIMR`W_+zVM|n>X&gD`()~Y^98TGYP;laZeC`}T-Nv8!P z3;sm*L?|M;b#OJk$LVLi;I8V~v9)rR0@C2TTRb)1KTjgnzh?pxMcXdS9(0?Sea+XC zpZq*uqsYoJ&4Q71X$-CISkI4H>lARzb569k33QA{N)#o8rkMEx(q!&O&2#ckFytHo0 zyTPPwh?bp2^fdz-{VV+=HrLJh{MR-_BW49pPk8m9?E3S{B&t3aI6rpW5_BojNS+QZ zr4U7`i=ZsQ>Yy`$;0SWF%E9>uNcFN4gIu}&-EBbO4z~BBN>sL1GDR4)7 zE|10|_@X>&8wFc1I(?om0Nh~iTNZ5L(8DxgUGg2ZD6*d=>6&ydNF$QPokzubsX)>+ zJHXFIyinOf&gy$19Y^EZ#>?PYF`11Kxdo%9qDN%PLa*rD#R2J`cv(Dt4u|1Iras-g zZwBg#A31+}-7=_`MnH8=^#lY_PAhmvn{7&{cx{&VdTlGoRtBp_*cF#L3Dvb}uGAhb zd4}jxtKMi`xhlCKa1~q?e3AAcLLx4K*h>WQ)S`C%B8h=jvVL*p_JT<5h14B5?In{B zAzzlo5TDW!!<9)a^u&Jj27h)Sc!UWTcUsY)0SC;!u zaQWb2Y$&Bia5CTR>W`|t2(w=BdsFx4R;?46quAIn8zTAAKOLP}O>rTrCR}TUN#hay z`0=IDRG(P@*?*=lTo{0hriqm}9J|HPRN$G{iQEv#DonQf{8(dpG5A+C+Q$+T_jC|z z9@`WyMdrGl=&w-YK0^$(74&CGWf-NVcK7QCv^t(l=iDegcS}-q5&v$3$n{!Pk}Zph z4VoJZM!Cd79&gic5sOWpZbx03;@lK|CX9(AArSXEx4`rMGsH$$K^$Q%4IrUwnt@-8 z5?}DS1rKxHHpsv1o&#Gvm`x}-$O8zO_@=21O3lleEp8nMQW4-qAO{CGA%Byu1_2~q zZ%2v;pL|@7;%Rue!;}_4X|Y!Gq1lz%%W0rHmF6|&0n$rmi9U2!$z>Rgtb(Tr7S;+8 zk~WWViP9+dPTN_6*An~)$SHBc+-2;Plf4aNN%-A8LYah2Rwu76(zxJE7?kRNR_h1N zp7LtW?;WPDJn>U40H^{;MbV7{kPWs?6*G;Lk;H-v#xyVLi-L#QZ~NRjH(}O)b@5o{8-ZC^lOFG%1XgTT&F>x;oUS>=eOMpmpqroc0$atFJtgAyfT zJ~ft36_zsNdeCHFHT9cp!7=X8F+s*`;~ki;tvZwjZ#f{ld148yF*tqt{#qR!*OR5E zjK&KU>%(&!12R%dWD21#qC|#M0;FG!0j$$!(YqA!>vj$oW5_47J>xUxI!T?^f-#4j zQ6tpOiWN`$@|53r=jfXLzPFGm;Zr>vL(e?mh zkm4s-JYJPc1>p8Ld%DbH03Qf{a}kGYcu|dJV16oHU*;pdN$O3c6_d&w9uO|OkCIrm zpv)s!WBiN0ms}1Z3d9fx1 z>1w8z6;|bW5rQ+`(TJ}JP?g+3diTE>1B6%-)097QIl`PGoE_<&HR?-ogOv&3q7V>iObtpuN$x9+Bd zGw(-Efj<5kH_AUt<4m#d^O_$oQa^6M&xW?gKve@JX0gN z8?4JhY7pC=;XQQ^P{CUn%JXBt?&6c&%rY6#FX>mePW32LlpAE$Xi`-SOgXK}+*MBQ z8d>&Y1=#m*W!@oR`+}wjP0(T4)IK&6!U&8mApjj70|YwrWb|?gg(ye=^KSHxGE|_( z4wp4dYV{wpo+D;8&%ZkR`G|n&D>0wq(+ZB*SqEBx zy_>f^FF4oyYUuN1?54Yr3&_%#pIh8O2H_GJJgpS$#s`=S%Aay#TMM`q;&k}X!S8H! z(+UY^p*(r2(S|)pjcDcPe1O}J5N>H)InRkQLx&``%Z7X)B%-Nk|Hj0`4Saxpn9ZOw z$2i`r8?$>}+q%u4(Kw+Alq_M2MWMpoRjtOX!$QAj#)*BL8S~oEhZPEXH$}Z{$pFec z@hB_E4y0LaK6(VW(zpa4t_sVyu4z&t<-DSh;OK7Dgj&bK&UbkY?XSP4Y}H#)9VT6s z!o#7tm1p#k1`=bXy~K0~bk>1JTgK!Z=YP++=N%Mv>fCzIM$et{OSHgCL_ z42Y%;A_pIyw&~7LU@Q7}2hTEojp)z1kvq_FjUGb|gh{0raqtbzC~l*Y?wodd;33PD zM-j>e{=8oZ$c)H`=bsDK*a3Jih4XI?KZmHFCU4}HO&~4~&AUv7fZnqpy*eH4?`8cO z%N7(YTJ;m}$ew)PNRv^tBQ37KP|xn6!Q{g7b%{$&BW684I&h&I zxv+RLiPY?J+#Y6e8-HnqkDTl>6jSc&q0hx?g<=QBnpf!0`kH&*Wm1|SFo5VEVyWnD zstIg6h+X`5_d${Hzi-zlfL~t+60;D+L#l;To?J;_&gpzUaGkxZ$&QTrl}aT?!_jdw zuuE>Atn8^Xu8KiPD!e?b59~n;-z;>90GCn~-fc{Y;-#B8$lVXPn}?(2pXOD6-Ds3) z#V6zCvTP{>z>!Zmft{tw3z)z+H&sE1;S%OcrS|l{P?MauiAjwV%~wd-oN~K? zIs)`ecX^=I#oH7Z+4NsdG9}TQq_ykWHs*1LB23aa=rhlyms+`EW6Yc)!>!L4UuyY- z4m_FV&!tjRsF1S3p`qXpMHr+$x-+3*!B(YI@x1GNvGQC6EVe;s6GZVmUYM!k7dKcC zsWXgyz#IbGKSqE#EI@8UQw$UcI}*Rv(jV3_YL3s}LGb!)`X!Upc3Uf^fE5M63>Lg? zE8{NJLeY>3%2MJVgc?8ve?R>ibVS_~eLP5Dq1&j=21@4=nl6)DYd%#y@b5X#r!rR| z5G!BlCa=l$j~vcu8jdz?m;7eE!JqS4Q^H_d`)bteu)Z z$v|asjXBf#fI?!dolk+N#cnmk-aL&2CCh$#}6 zB~^c&^YRQ|AZzdNY;(!kPxn-J$;yGTE2k3rStU4o{3fK1%cP#A6F-s5EN&1i)e&2Q z54*4M;*;6d&kSoj-ctbN(%(Yuquih8`51CR^oGnrQg}pZtj;H0&>=s5$TU2MLm5sa z?n}?=KYLI1nr-*)VC3t>_?eAPnFcO0r!#mmkaeK17_0a>&TQpQFshyT0*xZpj!nau zV6wir1Lg&ya$Fp+D~jKe8$xlLhCOfRoFN_P9z9zoH)09%P)L$+OMbC}UBA_4N;IYw zle&luFm>wsX3>bBL9xWWw2?rDA32RZ7~iT~&*uoq2~4A;Q|2qacr`H3&zUc#liO2d z+<5wK!djcHEc5|D&Eac*WwO`28gwSf9D2q~QRv<# z(2g-pI5Yl**<{v09dU%JBu2SvgmtXOxrHqL zt;c6FNI(O`gFo$^3f`O9wKCFsmaFdEUhl6APk!kD)U;$9kmxn1& zE~!u|AKkK}Sd_o=R?bJo!g=(3a9q-*%WWj%^6h9p6;@;KU_yC&yV?fg_(?fB0j5k( z{;?2A=2qgqN+A-Pz&(7pxU@g%yzrO;^Rt%ShnJZ;iHn63DkjxqE@{meoxT#kLJ0N% z(yBfxpQokag|@)JP^Hd9uvr^ zJn!2Fe3NFM-#+bHRc~W|bD~LSU&Bv=7rEEz&|hlFgd0iKw(0I%2Hl3iqGUrZbWVs3 zCsju_XZ0J``Qoby6^-hpQ(7kG9!Hro;k3rL;eqO6P1j}c9%7U4 zN8NgQp1JDDH@Z1@)nr~g(3SD@@XNNu31Ycj|4h*j>y62qUstJrNA7qz9-=n!_~KdU zDxhz(d>lYN66myR9XY(|o(NbjFl{rTH#hL5JGcld>%&K`OA%j0E54zLO0Nl7WuCM| zeixd_BH2>DmrZrIIg7+p;(5v>5BOzKbthSknY@Y#d=c!Cdk+RVU(eWjdT3-@$_6%r z+vF9+m`NCQ3^kpD{3Q6R${#;MV%nos+w}=FjX)6Z{Lh|Qa(s0?P*i+dNz%GlS49wP z&iE4wnq!*3UcAN4KdnS(c!3=nRsD(GT_Gv$iO25D*8zK9{wmxyh=~qz&NkB(@|(3g znNcR+Nxtdn5es6#C3R2?WK4S9`&+xn7n&3ycQ7~6b1RA#y4@dA9L=hHj}rWtmClz<;rJBXTrB7I5v;w@CM=j$6M&d%=vFTExwivQU3xljd7;T} z_yp+~@{9t&L$@Ct*+9-UoTW;`uf(-|wP|^SM!Mw=p@Jg7CRj0@-F3KSe+>muqSr(2 ziJKOX!4BU1fx)S~2TMJ4$n)-vCO;{92Hfn+zu`jb5jDI6rI& z2C@^SuPLj!Z|QdXQ$hmdSXSP#ne{(%V%hz!A_T5us=+q?=%Q+ZVXYbngnN6dLbUd! zdg)84#s{$>TNW1sjBY!C;oW)1>!rQLqt$tgdn`z(Kg1wpMVKaOvH&s${!xdS15Bsg z-gCC|D1DNC@v14Dkb)b=QotAr2tFX*`yaD=P`XV4q&9&@{It**ML*Gg4YEoP*E!p? z*wjbdD--ekfIP~mO0BBbha}CIExd$Qj0f&6Pk#acab8~ruIH`wKdLkdtMK^F#=M}PVQGg@xDGIqtd|06NZ`s1$W#hV$8t$!INws#q9n^?gKH!?&tFFo9F}&Q*jws zJOYh(Fx7@o?03`u!0Lv)$@J!=(8j%E2nF%k?S(la-P}kjft-LXb#_`Oose~Tv1vov z&*!lupJ`KsiR-|}(YFG_bSN;vD3vFont)Lvv60C4{#@5Se^QPqPeq*U7Bnq?Y-kXH zxJX^E$54cHZSK15`-10O^AxxLmV6}rxtp3;2TO` zUWlgbs;PKD3&h5jZDk5`ohC8eyATUJk>SvyWp7n~Ivk^~k5rjcaCKENKf0)pg6`vV z@%io;bJJo44NV6$_Iuf8(2BOD^#W8J=jE3WsqSj&&ZnIX?mQnBFW3F@=D6+?8Tnx< z@Pbi5lmIjTqP(ZEPx3Erb}4j~LS$iFK(!Qa19X?V995my7#r)a>a)d5ho7v860p=^ zO{D?9cm_HpmsmQ=bV^-kbN)53H7BfY-EUfHCk{T3gT_(j(l5qvnlTGsXsSK9jhyVc z8Wcj~O&&_%_RbG=jWB$09S!I@38j~`eJrF?yHqDYc^GXZo_F#FXs)Tb=5>UO9+u4R`(N3V0K&(TL+32wq+?B4ls zjipNs(>*MHJ^B!}k+{mKVyGaNU=iWSWF+W35aXFZc_)S5SV!+fmed-sYZZbfiW}PE zx$K0$G^W4ej{XjLX|gI)7w~MPb)sjU(n$_DEYl~8EK7UYN*7#EDe|%fMSBd!R^W^X z#6Wa2%C5UXq3^e=JTLAVPWd_2PCdjZXTtmJc}zaAqv{Ps1cKfX(rmt~(GM4O_sD4Y zAbR>K;`RZ@*><x~IUa4hyJsUf{#W`FVkBb}MSmgTJMofjl*n(@qD>Oe7u`A*2>0sJj?Kip0lz$4E!h zG>Jo$T3?q?ku35n65E@%d$$eC;);uZ-Nq<@H+h#1lM;*C*Tc~M;-%tfu`o2EUopGy zfL7nwtOW$JQ5iN0voa&VW zzZLSO^GK={b1w})pSd9=duxfir0m*{Etv#*6J5uOq8p-dU@)&Zv%_nzgIM^wt6kMR z+Ho-xO6hZM%Y$724=~?T3mB$B3mt+b|5N54QX;OEO)P_=+bgMxeVEMb0 zy|fcQS4%5DaCjy$a}xa<7JcwDc5=6{-LIxVN4ONg)RBaS)Y_JGvdc;n=v%mLF9|o_ zJvD!`ZAV&Ua1Sg`e)fM-*LE31XF1_kr+|2>hiKriw<-gOk!(fOzWz|=KT(rK>W01buXd@$JGAhjtsIUZql z-V9wQ(HDsWRY~Zd7w<5bSU486p4xrGKi>9$`kcrcD&l1Db@e@s_P!VlB_}lCdeMSk zb+}t&Hn)aD>ogSN$@1jE|7q*XqoMx4|L0v%#=d7umTZME*&_zovyLT8#Ms7QWUsgE zlr6$w$WWFj*|S!b#-40hvSnAuQj+cWoOyq~zw_>W%pc}(&V4+e_uj`{p7(iPFEg#D zq{R!{&9CZQiJ=u2X)P&CEQ{p-vTx3x9F#zu_2Kq$V5o!wQ%%w>kH#z8_ub%0T@l97 zXG%m?^oZ;#zi-BGhUl|zFnf1Cd#rWWKY|Cz92x7wN56QzSlX)Tf5TMeVMj0ZRw$TM zGj))W25c}9E-P&p;uT!7tu&>R!0Tico&~S`tcAqZD6_Nn2)o3i%q!j18dm(7ufUl3 z(AJ)S;&!Vz>&^mRa0H$^Ai!gZaj$+MSO656;b@EaF7#ue8;n<7TFnxfR}#ROIRb0S zBsu(04aa@80@INTCbI3L2}MTa_mgY?8S6&qG$N3FSoIK&N>Km9km;QL5pYJ7hEZZ^ zj&ZOaZK-%`NmF8(4bdibiMDtDFHmlawN=Sn1T)?BuJT{x#JRiWTbp*0Z@;?J2J0_} z=zRBjPPg@IuTh?Ni3Y$_Hr=;~XJt(~vvaxiP5_rN&ghgU=6n!`7m-&FFB0pE{iF81 z29hdlIG-j@`_MfWrn!q%DP!!Kcm36Q@|np1gURMX@63pZ- zX`!XS-HIr0?ZqH)!lTaUNQsY-nkU~+CcoQ;8#`j*wy}+NxffE!3p{hv0(vkfVQuI1 zLbG+Z3?X1PLNZ9Htbkna8PKbW&mUn(W30;XE=O6|J8P=3DK;nl1C^@{&2$6MliR%X z<3~#R%kN>=KYhZp#*7U6KP;Q+SL0;*vbT$%b7KJwjoc+gVn(JPP(6&J6ij+z{Nib% z$Z5|D8$`z-n9K!1C*omo0T)+kF&|xFYy1pK*O3_r29{t{E^Hf1>_xh*su%T$4@Mie zzom>4cW$#+eFd5E#gK+cWG_X3#g>gQ_Tz^Z#{V9V-4C+etKg(bDBy2syny1dI-!8P8Ae^r zMoP&KFA+2==)yF*r?-zfG;mk!p{(1NaM7>%|D6tz!yia^*v;(RfJ1lN)R-9Ah=5^3CCk)Ya&3*r^+Pp$3 z_Z80DoA5ys^;K`gUY2;q{Ak3Y!kt7s%$%5-E&)Tm3KI$KR1_C4x69kKpxj#JcIPM2h@B$_ph}BqTGa^Yn2B;_bAOxjSJ{LIC@$dqQV`Xm zDr9(=j~k5gjqsJdlf-FbplPncK{_$(uz0q-Bwk7?w%mS1oEKGS zigl7^rODrp0u^e`5#souM=259`%Enjwzmk^ZpFA7^^`q2+rHJBH^JrL2m9!H`|TU0 zr$PazeR?;THm@m$BT!SWd>N259Cm4{YfO|1!rMn^s?}nr zeV>f~6wtE`^VJRLv7SEYp`eCZhSX2gOi za@QxA$LTQC`lLJd8-o|yT2hAv?`H-Dft&p-bIUz&st4v5u86TJwyMxmUQ)ySm3Lwx zU2h={hn~d=-SI&E~c!CB5IhRuEMXh!LpxuJ|~#=ol+=P z=i{6eaOi;?q}Na`o;FI&E$*1GR6Rbvt1D`ByANF6UO6 zug}R2o94R`9u9Fugvvp$khUyLsqmBK5(l_WF&5L&Qot$5z=WKYCalkY#`USFRCH%7 z1j)ceguZ>`ma70xaJ}|5jW$DI3E_7Zx^Q{0gegWSO`+<=-sI%dWw*X~;j|Qf-10X- zr5-%0&<}o^tcL*=vL2y97LlLL=ahtHT+lY1-_)q7YcaSS^)66^L*QolPybxqcS$p; zBNC(Ksg;i53fvMx_Stqi7*;QX*2=Pk7eU+-+VvBvWj(u= z8Zhvjt;%WwDU{x0P~i$3aZ1yTIu+2liF_4{vCwTc#-*__Nu50XoT!8zWxdyJ5D*l4 zsFaWGcy)NL{s>iYxk~Xr2)9ZdTO7KmqI(e?n9=zppGA!cvTN>#xlHl1_d1u6Kp zG2tw;gv)9!>o-I8T4$}i=-%JvSA$X>;i) zC#8h)_{x@AZ+KWJl8r)M5M+d>WjoyS0iP&=2Sg3sLd`Y|wUgNwepRN_7ZMy~W}v znn{ydoJn=z3foF&{%;xG+U^LtJFuzv_IP2|uzs;&Ut&~OmT3g7N76v$MNdd9;rfK| zuUOdRnCj)v*c&#WlI>K{J_P*Jc=$;{J~VdI5*N00QLmP-@^z_eL33pqP zoO!2!uscK%$Ns>bOQ@1RKVCPt(% zXV+(9W)^5&+EmSpv}aU>igxUaSmBn#jM}v4S6;%ktfQ)5oxbaV#c27>Ob#aHPt$|U zN(P;eBZUN1R3wO)SOcgj4Hv^TsH;+cwBs-6bW?0S6P{Cg=jy|lYcHUd%ps#;4cf~wbPBAT>LV9nI?(07Jb z$kp1Yq6LapQ}0t7+vxb6H#93lfsw9m?O^nbud_Ia%l__ya9((=5@WZTvcCo|kCG>stk7H&}UKu{S3Y3$Z*O9sEaR>BWk~ z_eQF~KFqLOjAA;vLCRx9YA5#(7jD}uyp7N@8jE4267zzh&BsYknEI2e z4_~gmhMH6l#6N0QL(Ot@fAD|hwsvH}!N^B7EVOs8_WU#s=;G7``T5B|-B1F*;4s(u zK(E+UM`QFk&a;ElL}2};f{RRO+z zDT)v6prmHV7%kWY8T&Qnf!tp0`UHs7SEg=YCv)?yRZi(*s-*}S9ucG}Ox=Cw3<`^> z6|C~lyG`K@Zb&!lUWW$?h{H66aL)(p@h8pn-573qHuy>9*|V6l>!$Q=n_2m%w)gZ8 ztsKJJ_M`Ioecpk5muSZq{b0Tm40Jmk-CcTqWpS|cKQ_q=A_8~}{yp&%jWp@*7c05` zvc$qh-+i!9YUoU^&BVRJqCErYY6kC?$DfiA?Oj8#zrf|Fa2k{+2-49@O>LFlovG#1)uoo(f72vzPXTey#^D(Lv?kNV%fb6|;8!K2!MoCiuzaZE9mNsV6<>+&zpGRv^TZVKR1Z5@ZU``E3o+3P14P z1C#{UB8ZKW?@VIPOSI(m+bqZb79 zkD(u{2j;8($^Wx4la0Bec`X7*@s}WZh4zmOJD&l3em?xBWu8mRV^DCqOfq~x!AS8= zKWmcU52DI$e*7Qdr&yA3IqluNTS-=&^kO%Z#w=c#`Ej}~$W~I+w|NnGw7$La@aW&Z z;!H>}W*WceqaY(CgmkG7{E1%3!M?aRN%G!BH;#C#(Zpy*gidxlLv5f>7ao}kf9ONc zk>Ai8eAerd3g{fndM}M0X&@H!OgP%4I zkJmp&&b6mdYqd}~7_quG_LZzjz`Acc8-I~7aBN=r!k)?it}`xbWjii{C#S>nJsLCR zgaj;iY#dD5`;lmkm;4m;D!R7ktQ?!&eWLJoH1JG%jua8bZyk+|!ULbMTxRyBgx)wR zsD&M+oVd4vu44ZChp|vC{UUs4WJKn7#B&6jWzUKLyhS%sn$L&VM9w1Ry!Z-kD_f9|4sKv8jH9lV%ibh?+E$ah4HC;zETPeiAcQss*^aagylv$qk&^^`5N z+!A60^on-AR&rz<(mytVxe&fjyhy?${Y4~?w;uH2VhEH_dokKd6rzTO9VuEVSG4`C zbCiq_#Gw-oj!h{Q6!&+e1%bCC_ST8*#YQEaxMZhJ%>_u_t!9ZZ=r4@&o0#gMdl8Yl zP|@-3Ybjg5>5b6TU13CF?{l2pf#N{eu_l5H;-Ycx==?FwU@ zPp>W>rx2}T)b3t4no&#-&Ft%cEPq}>4EHACmaW_)6&`$z%ep!ZgG)+~xTJ_fyqi&c zcrw|LCPJif{3V*da!^x9ONRcr?m`RQ`F>|@u5`d_Zwj>xMmGNbzvTfpoCU(cFU*oP zw72taeTfNO(Q8u7{Rno8RMqJTe^9BD+j)u>J~H`u*^Rj2qEoID4c$4|SKpVwnM$(k zMHnEoRE5j9;pG`;l^+6M)h0h9WEd@71x%juahmql4{t1J7_YQ{dyUD~&-vaCn4zVQ z{w{fXS84U5Mv#n@2r`m+4i_WXP;@akfG#qoW@sWjwT|M-a)4G!MF5!si)F^42Jn!B z_GoRoie$%XPX{MI<9JCRu`tfLGU-yu*!7r{#|6~aJ?S%2#tUTKE5e9vMxOG}*_t9P zi}#ZDkqmSA!Zv5Ka6WxRXABg8^s(__A?%2ZE!{&^7Otvd4yfoACfEKqI1xsaX+7u- zu*pB?P2_ea!zO}lkcqmAOk-V~Oj1=>$4ND)^<11JQ~+zuM)(23d8v;PFkyQXT!zj1C$z}N@9 zx)Q0XLmd(M*py-3=cW*>(8YzE6O=BSovWnNyOo@jSJ|`!&F{Fe-?gAqzB0%Hi#ze4 z4gFCC|r6|tmK8~KV86FNCRlJBZq&|_fm7g27OOY*5fyB zh)t1a-5)#1w~`irYP#$HsAN^#%H~lkCueqN_|*5GJvls+>{mdDl5L~d?NO#-Ji7Z^F=}#S``6ya^4+5uLd(Fe=WhlzkHa9@ zEbiboZYq&oU7MBATr24-qAEr0&+Y+{z zK7G5f&?Sp&f=r%ESY%bUwGFDf|KWp2_WBdrf?&nNzkhu-+iH2gjVL(MS=5?don0Q- zUDWd5*`0kO7JTn;VmED8nVY+JU7YXk?#9oajK8zXl(WQ24?Oo*m(zBl3ZCTCW1G+g z1Q*EKqT%6Jvk!!U-8)DA*PKxqGvV*3jM@kfdKd0^b^ zJv`jR{M}Li6@FtN#msOL0!ihBK&bx^eg*ytguU+spd7uA6U{J~seFG50_mrNK+gUl zdO-gF*Y$RGbiCs&PWqBK4u#R&*#9;K1QHJWFA4?Ku_%(qp%{2GefSAhmE!v^N;&hf zC{o9vXk^_obvqA%NPhk=${H}w|19}$jbO*2berfozX5w$_kMIrgMwGnOB4EFW-$ z=?@&7HVMbu*$(6AV0;JTf_6HVE%_;e_3nU=699$&4}=qX5Qu}vZ3B#lr?>cR4~*k+ zis-j~w_F8c_W%Uo+rK_9_5USq=jnNzw2b(Km^YA&Is<_){!11D8NC64+=P3e?>M6G r*qQ`*I(l0l2k`H}{nHz9hR1qC<{uO?zyo4b(n4lII6;`f9w7e@2mDCL diff --git a/docs/source/content/example_notebooks/source/type04_db_nrel5mw_oc3_v06.xlsx b/docs/source/content/example_notebooks/source/type04_db_nrel5mw_oc3_v06.xlsx new file mode 100755 index 0000000000000000000000000000000000000000..b0b81909c78918dab59b4011b47102a2de323d68 GIT binary patch literal 117877 zcmaI6Wk8%uvo4AUcPD5VU~qRCG`PFFySoK<3-0bRI0U!g?j8sd+=E}%+WXvle%$Yy zA3bmPQ`J@7Q`PlORV&Is!(c2loDg-{XiR>YQkSMgGa0K~7__}5OR|Rq6EUyoD)npX^Zqg{`P?3E zx@qbYVy9;S{cd`6A5n3?Wx4ens~-Lkl2%`FA`$MfuMZ``Gy6-UFoEHLMuLg$2ZqA5 zn2K6Hp?s$;lgFcvJUq>kPQy-wQ%;*|V@!IF8-IJabB++!VMy(p3r`!oMEu*2B)Q{p z%f;SVYD*yqMVU|V=9R&%J0HvDgM#?z|EG;X`=Idrkm2BLW9;By!{}*e8~a_yVT~Dk zWcvX~(KD|L56lmX3N2J$>!`TB*5rws_jLR9lM|Nrtn*?ph%sSu4f?OQ|KaE7i{$8W zyU`pjS{y93m=`uQo+b(klSP>rlJm50EY2yzYGLi=mND+C1>>t_(Xk1273g)SD;l&C zp-XoQZa6^8$i<9uD_FYr1i%t=3R7(*U?_u@W)a{4JsrJ)*@)O2Qt?6>_R~e;NF>2c zif&Vc^0%hwZKYweNMm%i)6)vo{!T~t5FjMSP(Fe08UDG`RasVl`3}>4gl0rnNwNt& z%i$PJn%y*n=c{}e#~ro4=ZbR(I-z?oQMxS^3BhK$(8=TsdR?gLMd4g}T?BUah~)U) z778L_enkM<7y6*xn_xhuo@6feHIPHKa4U z{6*%ssM(*;joDHqu~?#g38O@?0h92U&U^$Je0)vvW~fcWnA#|Z8zD$HTm+t6+Ozd9 z!`L!BVhm--xchRr>XAd>uMYYXx75)m9hJO3&REj-iGee?|A5StpWis{m zolBhLPXd6gsbnu~_cJ@F+gPa00iW;=v3x~V&)tkuw7#MwyW*@40Z zt;FY^=pSP@4QI)z|1fmCPyfx>QU1r+U0l6v&0PL5^)szm`z&T`zikao{~T?2fD|93 z+B(O)eyO!wiPSuaF0^)qvh#gP`*?LaI#qS3sVczgDxrQGa;Yn;do5&S9-+$ z479H!oG|I3{1o(8yPLl5u86|q7}4mzk)P`aVfoPnJwxe%-Eu6cAaTP`G!@{DLaJH_ za7xi>!ewG1IXxO#Y7sk9Z6B(rd?r6eJI+p_8W{r)I-UWnMTLZZ4Vx_Js)NNmv@GeA z)rOw#sKKwS+HDvHTR5|J#DC7WKGNd%I@{9fsj$@5>M6f0u->aK5Z4>cql01r6-#~@ zWpNo%j%ZR?gq(FBN@h;RG6v5OJ3AZ3EMBNcL8Q4DiO?(xdd}Y^FVlrc+<126Y^>VO z73cMF`B6DDFGFKjwj4B!?#YvciNvXbqPTo$R;!Mn(r(hP>K||^4@3KPstvjvaq&U` zFL7+K^bo^VmW+aC7kRdGBb=oWHmv5DEx5uaD#+-2Renurb{$_LJ zhPvtldFib>^;^6rhqs(DK^--16`{4z?8ZrDq$-zU?!5D`8#)lTjZ;^hQD7bxfG~cE zG(yw|Ks9T2P&?=qjr}6oPBu;3l-papMSaUjEmbaO{sUd|N6L1)7**7-TS`SijbU}M z{=!O=yJ|^TBQzJmFJ~qIm9065lyEd|Ysped<(as$<`@GSvpQG8vr3i8n-WDm7mW&Y zf*+);Qy_Dsj2ssmGPVSQpU9?gtepu?3aH0&$8o4pu|A5n*`mfS?vkcqqEB?;u2nv> zEX%o5u@)UCp%w&n(Q7&FT=Lg^=et?ER;lP#H^`;l z)tir{o3HZMP7agrEtQE?y~~o95N~@n1z$>qG-u)*ACN=;@b*9cL&K2m4hszdVNCSj{0IO43l=VxW@fG~ zO#goI{NqYp8geebxUqj+)Hyyfm!ZHx?VH4uVK$!1s!_QXzvVDd}=q*r8%8Af6MOkR>+`la`%Pf=1-`Qa6z^^|1yx|ej_0;wBszbcXp$jXp_;L&U>cxBuRO~Ap z(gan@-INy?6&*Ise17On8442iV&TOOq<%Ml?;ZEac6u`Pd% zZg8pZ(3*2P3EGZ+k0{%iv=PU&oqsQ%ETjVrhfTdmw@?`%f2I+H=vBMpgT!0lH&y&g z3bit|d^uhU-&kF4|L99_4B-*6ctv%5_#vD(&!&czdT2O6)nm(&+c}5W5(RPMm3*Qt z_R3|VKD6D|1UH;H8F4QV`a8-V+dA{PozsR=Kmf!X$1c066ZRZ<=XwHH_dZ3g12;SD zZy9-XQ9>$gGMf&w)n`TX6up?*aAK^deAIrSKzvy~s?R1?Ud#fGpXOE8JB1=I(a5~v zK86UG`5GY`bL-y-j!ZgmKZ9=RxrdW7lw1`schMdeCE~g@J(Z`UuJY`Q?=0 z|Np#U;rQpk8OqUdS(m^J-G0!h|C><8!2ykIA6cv_R?VgJd$4w8RrQQWRs?g5vM(?J z`+50d0)z*CZc1JY-}3vZy}t{=jX&Xg)PDQ;5MayI`0UQ@`g(3`k7q7u<5A_md1lXe z(Btp8sC&X@?D$9s{Qx>oI4SDn0iPzdKex zYrk)Hw_9zu?$tg2ef?Vya46*Y^mKata(XqAc6c(SgKz(AYgxy1AhhCOla-ktnH1o0 zHn4lN-8f+Pez}&nyIIP^kApAtayV17?b^8%z>De;Px>||ME^V)zlCVf8rSnz;Y7ga z$?(YD{*|ZOs&3?vV&q`&*?qot*xk=Lz13rHnDqDS;n|4)jc$KOm;E`X3HPUfAO4Z`o1*7^1q)A>EL((NhK zo)I0)Zr^URf}_0vq0Ox2hPl6;uSX#syRG&DTTg6_(S;MXsnn~D3U4hhD{%9#%cK25 z>jp1po=^L;r~a%@az5MkKLm4UuPol+=W%j#vU~R)7baJ9bJ1Q0Cbpw@Za0liTa%9- z(V0ei&X!KxA6|xv-^LJz8m~MY=1aQ3f#aZvHjPsvFZ-~a9ib@en2=jLrbyXXm6 z*CtT$EYefQ^2`>OWfEF#G#*UwUD}Ek+KTowvXEN@z)~)R2&F9;e9zWQpw&qLv$-q; z3#HM&>naDRIU5J5wDc0I&FJwrYP7Hq!Z1=q0Tk(DYNUS+EFsM!DZi!UNeRkjZe)8Is^W5R zGeoKo6d%1s_~rnq?I9V#u2#Uyv_*5pEC>ZhVIcA0U z?14r!#1c3vIG?Qq0!ei%iN7dz6ER+Ws4}3f1?d5B zoTt)?R$Qu&3cj2_s4jKP;0o=6ADEkC#o?D~GU9|})|vH&5_{v|GMQy%yh$~MMamFP zWhl;9Dx3r(7_LUCV^Ln0DmofK=`oiS*U-p_dn#wYcv)-xzuCZr9WR`f`BSya1 z#1~u$fDSQ)WHNy87Rl0tt#hTTFf;Vg!xV`R#ij~q{aPx;)lz*Jt0JCwvQ18$klf=U zU`bP4SR`fW94%D<>FPJvY_)zLg~HfIgkCM&ba9GC8itcZjIz{Qwfr#fe%q=b@%6&+ zD)tUN(jQ(K_vH#MMnJg6icQ}t3*@uy zQ>=?@5ox|pa*I$nAo#eG6_}r%;s22}E3qz&1q1U{rL{hIoF?WBIc7rjTMC`9%h|+% ziaM45fD0k=Golm@($Wc9a3D5oKErj*+*)6FthSYA$;LO~mQBaqRZ zw&|wO^Hhd?QqAzi@20Xi-Av2R*Q3Qof5x?W+f_GEKO=eZ%}Cd zh$^+|{y`j68xQ_e{-f713Amw17={63q+?l7^fqkg)%tT%q^E7Ibg%Ah)>dk7&H5=5$UH>l&g|HnBZuV ze+kZoNO4w|g22CBuARKz?t~+%OxH}aAb%FO#j~3y?%O6}!RXxAs(y&dkdBXk>SyXr zx820sSCk-=$ww;1u9oZ5)!~IyW3{WDgfLWI`IQnW4s^;1$hfhxz-&ba=>1^Q^G!!Xi?= zp$>mgRp)|o&E} zK!nmN*)rx>0s!5t1{gw3y)3bsZ33{94IHFji7_r`rQcD8)^i-BO8T<)Im@NASPwNJ zB(wy3B_CM}3b?c;3wqYgGIo(q!Ilf8j3J+2!Wjd_L%YsmS|wT5PS*1rN=4O!Fpcd} z41?&kMZP3}@aUzAht>Svp-_`=(}8;4Yl3g{2;iTErwn z9Pdb{PS9sq7eP3pV#d%;7Rk~_syB{4!+_RsYaoCFng9K%iDLS(rX}Tq*g9CvIx|mk z;i?Xr9w;SzHuKIvh|T>-^iYPT$7YD}=A&rRIr`5;1h8OcoXFTB=nrh6-x}H$@@V1O zI~adywqjU@3@I6IMc)*})lOl@TY}O6OQ!lH7{iVpmMqO6?XNyoAt6vz0lR{H!pj5>9cya4k?3J7+X|xty?=4c!{aG6+uqL*Gx@ zE}sFi@_L0{*(<*UgNh7k{FkL+CtSzzRbQ#<8ov&tdP$#FG2|W0&whTK;YJYGA{IHX zj@6AVtmOA_i$uhxMi4IUckrp?ke2v29w^HTW2vfrELKg?pb zIoJ;WivREwj8!oKHK;?WwJv=~6m2|sQzs_9R658nwp58y6N@F*()<)W;@#VP=o#We z2l$3Ld|TZP*RTlRSiBg2Txk~Nvi3Pv7I)(4lPj%gM=ar0yST3ZB0LUe8d=}RFj$zU z!k16ww}C?UGDxR$bf`^{(-Y}$bE(0WYLF0c3f^@c#j=G^(v%s)qz36t>6h40BHNS> zY7H)xQ!6kV&e7K~MQ9*#*2v75!H)ZV3h7H%{Zmk*G@WnQyP&0Sg5HYD!v%Ldmd$V? z+^^yEP8)Pktu$R|$n6L|6HBC_2bF#y*3`fWgR@Cw##fPiHvG_6y3g^CY1TA_k|f;l zvvu3Et$bcPA;KQ&YQ+k*)x14F1xMI2J`9*(x(vc~S1riiO81MA=8#PZ%FKt{3PbKd zuwP9g4JG9+I`rWdxJ@rMr0y3X8xR=jpURxj5PcRLC&m&F&jEMTzjf&v>k}K&hfjSk z{T?oBlnq+VeU!x3hDq)JK(kdiOQSv(Bpbz|`RZy!=7u+3A1DU7t+j{bN)9!Z+>%dk zW>f}Yr5?YiKma%A(ct@8(zKUTOcHN6VMP)i6V621sw005}WJM@B)U} zC4F3Z$zTt2z7jnT;C3sH(BoN2nqoqaoCh`)Vh%``Iku5tNI8-vcbENh89nEJwV+5d zuX$wTg@jzje%aQlSlHN};v_GWj4%B@#1>f)V)7=Ud9R_VD`_yG4-Un|YDZE3WS9aI zL!B$?HPUZ>^aCeMW?DM89V3m#;@jdhZ5V6N6@Mtrqh>@Kvk4j0O-)t^lph)stoedV zv{njwj775;@TUk^LEXa8pXCDD$F3ic+l$s9K^&~4%}jzbA~k%Z_=1^=>t1E_9S+Yk zTPqE}D31-#k?vV~86 zA(%Pbk3*FfpBrgp@X;XmK7v=yS)*8g!hXnM-Y}r_JA2uBt1FA8WU>tYJx2t|M{^OtY zdYl^@XWHR&!FsI2gURv*YU6r~mPcpSz)i^(^5#=)kNV~4^HQ1+sz+b9|55jCXTvJ} z`sNBMlf=aNy3winOEg=+{z2($1%W+pz>b{HnN0NOUwjEh;OFD%hVAEdtQIJy-1kF= z#S#D82RJ`0#v)>U#J2P2tD}n%lV_y1_38V`ZsIKugSBX{a``va^^sN9V;$dDq;d)X74!^E*3N(7#jveedlzLOcJ(@(HO4 zWZE|S`m4wI-)#r~o|BOaLD%(r=I3_5^w&9utj+BJD~EH=NoGF+H_piShk?gc8J2>< zW7D@*%x}QPzZV`2DA1T2_s1EuykFlO9}WIVLal0)&_3wFB53vA4gwPtSubyorlm>erci zs|wYP0qFs3e3$nsttPUXJNf6er#a}8bjxR)eClR714QZrISdX}vb|={JMMDhU|qRN z=`?TseRVCR^{#M@Ga28@vzC?mR^P@tO$Kjj20Av#V~@_lX)Ik{g1O zzb!p3*I%I~4b*J4x2|d&Ie!o;&uf+1KYe(*mz1&ElK&dl_P0H_pPP7Q1r9Vk}Z3Hv``t8;H2p&BqC1s%Z-^NX#*?4#T?ss>9DJ zj=SPW@ZT=OaQoZUKkhG%C7Z{D@7n1jh2Wmr)gRI-BYt>Qrn?Hf`BqOhYqKey z3L_})##7+&Nv>Zh3!y3y3QKLV0J$mUh&`)&K)|@4Wb7B>-A3`%Fh1WW@u4pS_#U(_ zACY0s7HCQs8cT`P92zfR>cXm@u1}-*Et*-XqqNNO$Yng4tnaoWskKP{x*ly(#*xZ6 zb=!;aiWP@NREQ?kkeDEKI{_`gQXqO-7y zQRXH~ynm}5EZRcn%$3!K_pYY)Q6;}YyMVggllBG~+p-^e6f2<&(8hbqI|Dw7Lu6`Q?KV^~y z#hbo*BoFmuz5FrJVsZQyq=QV)Qs3XZ)352ZJD{Mi@GsbE z9pUi%jRUG)k^dFh2TMK>8H$V|f|)nR9l@Vhj&WQ*4gVQ)Nb>8Z^fJpJ@Bh;6!V(un zy2Z%yQYjq`Rcyyg7LeW%1Yw0~e*K1%%F@sJzhtwp1bdNYF(|Ba2_aIaKCclyDYqYF zp+Bt)bRG}uo-JaMBMGSCh6N)fn0`3^1BDfTS7@>$W2o653JKdeA`?Y zup8@>rxVcxBRIDsk!oR(H*SuStckQ)`$WZ;dQfMx-%w%{c1h)-eUPg@4(gA%e*)?k z^BRRKqsDk-lZtgk<3FM%OjM9^{YHb;a(?AsnXN=gGj+)X+{Ptk1x!BAUm+zg zl_^rkHIe=ftG&WJsUYGv{&R`>zL544qwxb-d2gDO!;&z@nFdVcgiU&>(JV7)L~)NGQ$&n7?`E07&O#OypWc&wnm zg=^r+0Cw)P?pyl^H1X9qLlQl^_u;;+TF;809cAL&KDgYUjkzrvSDrx6B2+g~!aRM& zARk7M^L$PYZv!9SiZi3c^7(O~)3&DEQvH4H-~I)KgjykCl|!TT!m|*5pw4-f569*? z+Lv&lwoykf-gq#>vHN1>3XjkNse8445L7+p8WfD;rym;b13I(jp%92>EswXQQ|~J{ zzg)Yme%o>KN^jJIbuXoJu|2Mt>)~v-8*H*SokDZ1uUde$wg#*`xVtg7o+`}EvY;6K zS{p#pcf555>`GkPUY@cqKgMqINT!hj1oynQ@)D+cCMyr_L}It!nh$^7g%=v->7r4(xZxzTPX_MO~dQE1~Qew%)W`zN$b z5G>Yyhl79sk^Q&O_Mhr2?EltR^yFOjhB3MhHR?Stfk<*Dm&cOMT4J2?i^C_^_P;7O z>M1B2QYkIbwas2n*r5M>JN0MibUxbOp&u=SyJW`yaeSQN@wOSjd9s>jzf$*fHk6IY zmFKp8;@`fur9bihcy*R#Ew~9XXAFDlz3od_ujULsKcG-b=KT3l~*I%Zf()sKjQN2@~iPJ z7gyCu?Qz`&*QPr^3_*t*U)cQic8&XUndQ6ITY=|zfggO@ldIs@vX#&NUU6SDB3iZd z&|bTH2$E0yZ#=E9X-^uT_IbIM1NH|w&n_SRAE;oqLZhFXwCjfJ=6R-=rptDOP#Uuq zy-&jeZpR%B?APwPk$TS7*3U(`-dwm|1^rJ05DoZWeciqM@Be-jSjN@znYZp&XEt>w zddeJ##;zkW$lkTx(4LC|rtdvo2i6_K9!}ifu^peT9R{o)?VHc~TlXB_|NfqS9Vj$- zM=yuBJNX+P;1SeV#uT=ArpGdl+KZg`RJ-;T$Hy1Xy+ zomuz(0>duwBPZcy7d;^=-RTZricZiQw}(vVJMMV(tx~5fmN8x*93v>Qru|QzC&N$N ziPLGXi{gdk1E#xUV!CZUDo0pMy9G|W1(DMOW!>+ed!m%|ekjbFiG_LC`MQ%#8w=VD zv>J2_to|5}6C!$AsA}<;kjY^GiW;8ljm*Iy8X0eTIlmkUG|JC=k8X``sQ0nkZ!KQ$bcVdTx(t& z;hQIE_p7s1+|+b;h)b9Mpf0(rca+v==5v@m1s0Tk)9Lia-d;A83Ko=#w!xH~SDZjc zOn=h3ABa2!y+kTILm6h-!Q0{V|2ss+R!YWaoxgrOv8DJM9|3a^9Vt-qvl`FdZZn9Q zeSesJKQJsQ=k+^G``|J`5mZ6;!%GE-xpExwMhX8$iA>P5F@X$Ep9*IWxJvmu2^$iQ5q7c--I0*b&(mI9BimYo=XyO z!;vTw)yxctm&9NYFN6Z-KGdVD>g#}~)ZAV}$1hcem-v9@* z?tvshZ$h&@fKpdwRxx2^!shB$5+9KA9hMq46sed7S_h0<7qUPXnHr33aV{p4$Sgg# zfS_C-xY(g(11Tffmt;vJ>2A(n)d0a9MWN0wK%#a3=E6N+xbkOjq{b0ZN9ioigKj!7Y~fRSGPp{}Z9ovQ?^oO*Ia2P2|@ z+6${3RsE|N1kCzQ2wYO;gjH6j#K)kyZ+J07b_~L1!bbd{_>t<>nhFLcfGO4^Kv!lH zSa1+{`onJIPgs;@0#=BC=KleIM}Sy_C`thdDROLytPpLWsBw1X>JnSTVtNg14R~xg zfw)5@2*#slWn^y%#seA-`G3LcpFD5m>6;@{P9adRAwLO9 z!12<8LBz|t(Ln1RO5x0V5i3t=svve?FcVO$prDHe1z{#?LbU@EZbwv^u3{J?u)WLB!~=JFc=@QP>HDK)H_gVDFHRC^{O&uDg>jos^FIe(C5S?mdhpOCFt+8 zv~lP({QMMjNRCQzk-}($i7Eyo|4uiCR9=ftLyLWN`!Qd%D#u{^8XXY&e-wN%u0y9u zpr~rhmylxsi_TfE|UOq)81H%NL3V#P@xNGgAPq&)y*pRNCMK@W^ zVHZY=GABk)4QjhY|6SPCYrNV-DUTd;_#?G-s@lyCZXAW1PH{OZ4z^N_DOG#Natd#a z&6L50EnoAb7`M)x-c}{o7rL!t932fK<{`?kLA`|ly+*CS%(WJM0?>ZgI0}Kc-QoLp zbI0@CQ`4=3vQK;C0Mwd_K>ACcJY9xW$rIHvnQ-@l;`8)k#hkvgO;8r}nKo6Shj4vG zQ}zv1iA|gS6jIFBxRlkn4eh-HP&Y2ZvJ3o2wj~&sMn4Ci;+N;XG@vU_r)uLf&6EfY zUPz`ozN2>jgqz6huBYq7HjrV7m+MoKN)rx^jEbN^6GU4i_7!}er4xNKF`jse_U&k#7cUqludi4~lUNpB4RXfBj~Us9|Vw+m8k z1sCkFYQ9N_F%KdxHCffjvfwRcwt%d(rV!{^&}|CHkez}7HJqaAnsjSWcoWXbJ5h{V z0gPnGiNUZn%gXSfkN0q(5NGL~Yi5>1RHFz?dW)`>{G$5QMp(@J!W8hpgoiSF=+?RB!|YH=)Bc_X)_k`GikD!6A+RlYVSt)HqsY;E<%$5+dxrK45W+=v5vG9Fxd`5%&9avxp3c1oVx0# zrdd)~lX^qRLP{`3)Bbp*+jj`g$si{YY>cW!lazyXS1DoO`~!p-Sp|&Yyl=&kF%E`~ z<>a9DP^z-ZbtDM{Ldqp@1~yP!S`5J3OYGWpztr$Cn`(-)GTl5Od-z`%v6-6zc)wK6qoLE$U?B%J@*0oU_a8)SP&axk?QB_T2(93v}4jOSZ!XA z+hoR&hKblLv~X=27G1P9I66{tqcS&;A-(>h5S(^QbWd0%-T4boSpOj6TI24)sQ3I5Xw^MA6LUqJ4LbzU02pj#$)d^=)8W@CU$39IY6M z2f%~iRGW!P4gP+51@V-Eb7N-_B>NjdD@006?G&oF6w3PQ&xdhX%^!VlPN@l${!XA3 zBCV_+*#uFqSxupXxCEBhSyR@rStW#5%S{qbZ!7t<2h&@6ZS^Jy*H&S#z8+c8g4@V3 zQ^86dt>|=UHHE0!*uJtvw6m36i^K~U(w%GNtsR4fO}?6!Iw%prW)1F!am5&Y5 zivWP6zZoEGwH?Xy1=?;~#!_Yt|B*wc=4Fm+1Vyde2Dx&)MH-*7(`>j_?PPae1Yue! zJ3*nkah2c##l^G35rh&*%stDw@3v&@&P&l_n41}zKNwwz6p~d+*On{ZJFxzBeSR&2 zh?bj7-7FZlABtnn0_wuOmkYuY{Zg$#WNJgb4{~;Fz6l*BGKi04-?)<)hTl?WQmZdR zhmJd6#|(_yPsZWsQw!BZK<{W{ha}~EfQp3rQzI7~N+yZCQB<|R$<$9Q5n;_`Vh`R4 z4E*k;1CKOuxq#IVYfjtkUoG4lNq9GDdfv2Ce4TQR1tDf=1?ZRS#2lsiHs30r#fAK9 zCL13psFKkuUeE18BTECpcwPXEP-1Oc^S9Wq=D2VblaF!Sh9P4wiE?yuVG?9?K)+15 z)JS3Caao6@b}L^&Kn?oUtK`n&NVFzvs}UVo$Jj{eL&sux0=P#J%eS1Tc%jMvs!5w& z{BfDKI&Yq&X>^cvZ4QQ7M&P;6_zN<>u0F>=PBR@Jz{mDk3qE%Dwuu~EqBCQvlv$IS zF!}~v;9b6n1*@mnm}mmk8#v+dJsipHT0&0Gh6C@?*rP(<44XB9Ax>(2cg7#$@ZIDH zGIZiFm?5wZaNx0*ks=c@2Nz3d3PeBDtS#l7tQmp-8;DSa1ta2P{^j$K6vY*d5nCg( z>x_i-!J7%pkKPa#R4DO1!#<>xk&;v6`U0)WrLKf_SOQ2sW~0IokQ1P;2|vsYEi~Om zwAV_8g`>ghTvVbLOIFjKTv3r4+}HcVk=9*YqW5R?^2EmIMpR57L;9tKXny(4&^V!Y zqE|zK#kW8QDkdR2enb1O61{}7>5t?yrj=9?!d|=dIGif*_>nvaN9A?KzzM%mc+U`oJVltO#Sn@^h}cn9qxWSpLrRI8`Y$dvtWXk0 z{ff9jzhDw*azuJpj0a;dQPX+KM)h63u|l~U_4?!Mq+o2zc|i_@%1hYF)`?Br0-;=r zSfNUddTR-FzIzEKcLwfa8X(oN0*ocrlGs^W>An~e!<|kx7-=00RUw2TIT&Ybs8W=! z(XDSZ#smi7M+S?9L_Ld{8UG0B2UrbRXcGdA-F1Pz?LqGB8I3%}X@HUzYFO0* zR$b>uYiUQr>PinbsUK!epiINJ#V5*o8pnf`ZTrIl8~9aD&FaK%n_Iw{6L!<^nhA*$ zUdBbNO#C(&%(Zm~Uuq;GC7XFm?9Tlpdc$H&m#{K25!81uxqfBzAKV#!5}dmC(BtAf zThY(G2wQab?IF^5brw~SV`{dBfci?`{1 z8iq$o?zT7<3{e_Z>z_b9>*%d zJCio9qcl%~%}dOk(uG%;;Jjb4_vo$>~U(MGgy@@>?fo$uCHpN48j? zUKQOQuW{{)rQh9t?os8b0!(tsKRFYdvu*EaN8qyNlmFz&Q&v{D&6F1KdVL+DoBJ^S z8%-r}++l67kSd>|exZtnQKTS&+U z0qYBi{6Ro8zEp0jP~k#PUN`~vW4@38-5|Camp)?2Y4AWDn>TlVii z6t@1oT-}wU=d#Y78G7-c(dNsd!H0Y$j>#rfT3Bv2Ymm4gkVU&)VFFNUw(~LtWaJw3 z{kQNkjj}wAs*#>9 z&#T+rn^XTMReBN&v|TPzyz%E_+82+<;bG^OdGEi-IeZPj;HiH;zHViT4?yAbN2Y!_d9m+)^7D%+ zt23ze5Y*1~&EBptAFmp+vrLPh?<~{$ySaBee|ot3ColeFyUt%LM#S*>1h3AZd&TzU z>Gv7Gs?qZ4he{(FWeyA5-VQnE>^7tC6BgUKNdbBMe)_&dAzxmcx%}479f|pMrW}|K z(Hhb97Uorw zQIqo85h0eJ9*+j#MnC5X$zF&Es4+fX+yGIfA2uTV<<11o&1aqWn_DZw zSyx50BHG1aYt{5_Z}eQ&+K@J4ENix#8VRZnUct_L$nc5;r&^b1?ZNo!@~YlU9U66P zXqQmlc63+2K@YOpQ`6h3+WF?~70{{&%^+7j`gu}GfNSRP@$Bq02)C2*#{cQUF=hAS zap38qZ1F-5IyAt~XDgOzp~LxY1M{p@Oio(W%;+W0pm-ho_(+QI^)OA-PP$q$Qq5>1 z&%n3~*id??`4)(oB^Qap(C`Qec#@0EOZen@ahl*SUh40C=;nI-*(Tg~wQcs4f14ONY+tYo4Gj36 zuZNb;;klAX65ISnbto$C0e%z}4*($ysYWIO^vLbB?1Ez22Y@Jr(sNR(#PUgv3_(Rsx02~cVJGr8=1uTl06rIeJ*(j{E?GhK` zs6IHkI|;B1-p|>P_@c$SWEi2#n)q;ip!<#d7E(0*3sJvevKhx}GQh!1${_WHQU(sZ zFPn<|zmtU0x2FI!!28;%Kav3-?419HeIt;30#bD4gPrQ@d%fTj7`~{h^p^2$0$GG} z^o5-Esd~k>_!7%H1t^;lU#O_QD7P!u(%EQ{Bj>S9qbB%1`gx$alw$2(%LX;?l!rFE zsv5x8>6zLg_Q&ST?%SLUEkmX)v)dj0ybmkZxeDvo0(!cOoO1lgsD|?NnK#W;S|W%o zTOG@jaxMq5x%DNVm>;2%0Xoqv*H~h3>qT*iY!S%hb0Yivk*8i;#H%-P-rd)+>grsz zs6vfK8u7MCUizxHdPy>9UL+490`aWpUJn76{L9YMe6u&@+(%vyueoK)w?Cc*r;F$x ze*C|3BXR?J&Oka}H@PLD(2sfkY4|=Gf`7UMBE_LU+xZe;D!)(%MX7mPyibS?j1qH^d}Ju`qNia%X*FNw~YjWZ}uAARB8vA+%5Z)4p2~wn-(hO0yP2 zYim`sZ=)7!PDq)!it6jkD?h_OaqxDvOwCq z%l90Au4Tz+B?^t{X{nl2v`rfK{I>Tq@`Gd{67``oAShnpSRuvWP)woz$4q|kBp|#b zvISXuKOevuXiG-~%YryZS%b=t8jbC|#|^>C0sRb?@}P{Hj(Wk)mmIHKFZ_6$Ost3{ z&RQdrhoxv9NSxuN7IjK$PiAku(4uNdd61PE5k8Kdm!nY{?-;#_ei6L_LZLAw?Qo&7 zh)=ohyD()R^tZdyZQ4{Tw z0I*tfWw7gAop2x)N32Y|h^Y?n%;Vyv?HAcieVa2IIZWtTcYXz_GAzztLeeN=g|VDd zNgMUErEwlhbdyQYv)URsZi20Cv&UWZg(CM8bI`NDAB9t6Oh+|SWi9i7bSF1N5wXlt zm<^BaT2P{0D>R+_K?VNRzw}CbXUKA=88r+oBMNXu53MYP3_cT2D$^TS)_mVCj`qdv z9N`?j38gun53UJ%Mkw5qf^t(|cN}W)N>Vg@8B56}aFcA(4=t8(2}yE+kxoJTxIq6K zKD7IxnbmeK(P|v*_=xoq%h+6e^Z#)6R#9~Y-I{11xCD2CySuyF#@*fBo!}bW-QC>@ z?oM!bcY=rBwW?~?^jcMO?cy)h!N&yRVexS^SmW`~7vv^76=c&$ zoR=;rTJ)nxh^K>Ml8#_OFLeglZ8SU=l~{7w7`y3X6!SDX(+P$2OQSvx4ZIt{7BmlX)=hWm z_D!)+6r*-|MaZUqF55b-yJ$9Tqm&q4xJXiws&UA^5aB3hyhzn3O00A~YZ0Y>JgA^B zhVe7)A?vJQbZncr22(OA%BJ8rm!Hk?yIATWR3RbbLZnUnJ`@;{5j;63XxxZ9pJcQE z1+p-0$khCdZ!`xRW*KI9ar?bIp65(2+o)4el-OLrBpyDvaKx1eY53G>IfLfG3Mhz# zmPGd;EV_MsvP<-1O-|k zwhI=v!J|5h96FOUC6G(om&JPs*+1kn6%ROm{W$K^jfAk}kBx(K>)xEx_FvUpVyS7A zI;0FQEN?1S%7Btwt)C55 zrA!q>#kimpreauHgIGB*BS5Gbo<|s>371tN>|VshrdNj9Tg<(DeLb&;RhtOZb_S0p z!PYT(cytJqQdl=8!npn8AR+C!)MCebXiCeodWE;0&?r^p@P;N6o+Ke%CK9M4Nv1Xu z%_{93111!Qp>pNmkWm?|>cr20|0yi#KHzP-N_H53DYyqzq9n{yY9K`{@<59IV|S;B znq|?Gs#HUDC$@=O)|+iXd4UtEV?fnTDf|kmb}HnNRq}Nqn3(=cwX%earJW3boJd~F z!s>f(mKN!Jl8B)&sgfpWnxvA-Pr_B{d=-EW#RxBhENq$#~aN4}0c;pJTCj8s2f0WwTKj~a*a30)w{}3S!@q|eO@&!#X2@{)Q zAIO(aV{&o{t6CT~rDpB_Efk#6#_T1NRs;g1;=ll#pgtC2>}|3ZWESfzayyd--du#Z ze}sIUG?qo6ad9mK{!EKjDN)2Q(UAEo26nH6lB*n#BsPKOZ^FgrJLsPihL}5FtUUnE z9@w$}Eg$Nv=_Q`_a6psvSIpBv^yMNDxCf))%egNh5I4te7GH#g;hHeHwwFf= zO-0hbJwpE3Mv-oo%tkOajz^cd1tBCG&kyMU%V*xe#6+a{iCVbWbUUyooZkdkN!%CO zv`kASLB2>bYk|fll-OWtH!Hty)x2f z<@j&0(NXZRg-%D}{aQ(M!b8)bJFT-*$O}td!xG)5GaK)ZTXv`gf z8*vec7_*mwoP2Q^dICipXa1R3Kqm}Y(EoKoQ;q6RxoU+8QM`n6lLkAP93&JcL|L9w zm`FvVD1joepSgFS0LiQ%U#!2xKlNReZdBk*azx3X8ifqwA3~S71=)?M6H4&@@nppF zLV{25_rD_=J}!>mLKG!4+uMomWTo;`TFv?pFsS)Q@!tk8;^$6apl#A3?$0{cJRV&s znGay96yN~nL3)Xsnn)Q+(&v-gCvhkgRwDK61v9pKiP;O-|ROo;OjCWO0#ulY=xXn4sWWYjF}#Rhf~2;qxQ z42Fia@yWAdM9|^6#Y&J8)RrdHFOF=pp0LvO+7@8YKOIEVr^M3~AZCdHixw<9ETeb5gtH-g)GKhl6(%xq63RC4T8)y# zo|wpWv{>^pjezjPd@-t-M0i9gp#DsyFp2^t)-e*~8aJc*Ja)xiSA={-oQR1-;J_yo zUdM;>3FH_)0jA~rO!r+3fWWf7GXG`=w1DmL3#ZsGw$Utll(0tqUGI7>qa6pKFD6{t zFQ+`BnHKd-1)B7#fJ!+iQ7fxKUC%it7YULvTiuzdD!F9S$|zHgdD7Vsf1hYOU5lVM zXEaA*b-m(mCZiI`Q3rfXc|IZIeme>E)RK+m>u(spOMco5Ga&SAjj|t{t4wK1|Hf{ z%piEpyau64Va_OHe<+1eP!ssTSbNH&L2V4vg-qVv@DMQL@f(^WT?|v^Hd}ENuS!M| zBr4}Sjm zf)Gz^5J9*HR?q-UY;!QMPybtiF#F?hnI+d?J?TvB2{Pxd4#2cG4h%<_Kjn<8?b&eh zzlF(YsVF}$;ZMU6zK?}ekIEJj;;hDZQR^F1#7bz}tPFGuPEA_@Fa(Jdt6-C+&v3x5 zm5X5CZqsDI#{MOy-;IU1!(e{r@ZZKFN{b6LD zQstoDisIij&!P^~HmC}y!)~kFQco=ycT$T9*JiVX5pcEkdTFuWk zVTMVk;*#2!1nvQ!pkF>CD?0*T|IyYIPoAXt{5z2F29P&JI4aONCBk!$e9TUnY02&Ms{4pZi;Xk$_%Jdw{xU%yOEx15GQRzXsp^NCdzXEa@))AD68B;%y}nBzx(Cs zRecRTMIH=o$cn|4>9c`zh&(VX6zBQOdGpyxrxJA@5y;JD0H2=82J280S9v2s|;$gALwNL{1}kB=xWc4yih!TgjNN zJ135Tsq8u@S)f-$oaHj3oXE4m=ow*BGv0a<-pVeY-<@=!`l>3eP_a*1;^i zjIzasI6$HFz!{Dm{EMo{B?6J1a>D~u2yUQ4e5=Nfe5atbZ#|wD@>JS_}+^z>E zwqYr2=rxa%HP18yMEUH78xjIvV*;=nFkM8MPDpy+?$G{POm)V99fad4bVT_Qz^B0V zn<2BBl_^7XjmVtRCVeclwXiAfP$- zZi={xzV?iB02Ogu2WXigsw%z*ZH!@i2Bl_*!~ODG1ks^+{(`s&pAPB}G1@HV=bi=x zFY8a0m+b_uX30bMPX-k1l}#MEIe#U(+aR%%Jx~`pk1D|@EtDGWewx=z8zhczH-5ZH zrfFNEXr6f@jXNdsqdgcS!ZEW}IHZ0<(YSQi_}qZDS;?4ZgfjYcza0at3$pfrTRoQ^ zC!Ua(IySfHVc`CAd+O#>4nXG+&CeEQhIP5{bU977}SXZiKi29;5FnLd3_ zKv&^Yv5O0v|2~n-tvhsO{4al~X3Vpxwl26^ds-F?-$Uw&bjjhsyXjER_y@>Sfq?s8 zsJIy(x}xdN>{Mvt<*)%-;dlByH()a3PWH9jR={{;_x3s6%M3k^YqDpuKk;Y%JvM!V zo5(I)Mrn(+NoV}e5Bjvm+HLnj;GqkQ!lgS_*S}Y`$sI#M&25fkehsH&%?i8jB3FhR zBMU2)=zPqT5^DEcZAj`Bqg{!8ZX8>&W$MCJ*s((vXt+w^RrbRTbmx zO(H-E{QEZsCDn+kiX}~~4q{|!jNi@158RWR>pdh=!B^8-U^}S3*+)P#xMFhoG=u5X z88QUlP&8&E6rj$Z(y96Y4d4>!gg!yG{wMh7gnIBZ+8f~PPLqdN9`fwYYd`tF@conj zyK2wimIB68!jJq7L4|ksS=hzS@Pl@hQR_(1I(~b7$Wc?*NW2=7H9t7HMYh}NQG0*r z9$x&1`M!*K@S8qsgl^osuE5<`t4`(kz(v^F;GHxOeE$rQSAUH5T$B9)o5B2l zwiC0W)<%KpLTYPPfZC5u#I!R$PH0zh*ganUJJ1f4qB5-1CC#*EV&wkrGcN;ZK{L3l z0&x@Q`4w!*0FKf#&pPXf=Ph6?i^1j>dT5ZS^eu&)V+d80G>-;>w-$B=ER51cbB zG=!}HJugxN(DM?R{`0(EPz?>kL+3QY>E7(|HQ%OY##6KYWsO@WislSDp;T*C;Rvqc zuClYEwS+2EY}a;GGAqDHd~BZW!Weo`^r+e^wY?+)?wW$d4fMIMgF$TW z=0xf+fSX*@LAkomXW` z=bsldFt>2uo@l*!!z&!vru^HDcMJx#v^0EK8-Q4C`!3w2e#hNnREkgSbmR&LzYBf2 z9t{k5|53Mjm*_m1jia=Qyq296^tKg~*63vEi78`~zwhxNag-{{-hcm25HgGN>x(<1 z`S4GT8h?+gWunKOb8I$H|Be*GHHzQMDb$Yk98a($lZ2yFeEPX|WR%Utsr{{$*6^wX z%Q~{japjRoX`cY->VV*%tNZC|T|PzFn;3X20y>pU$wg)`h5pE*A1Z^_pToJo zyFB6{;T&DXG|QEiO^n>m(IreYHIv3cbk3x6X(`lzrqW#tu5?hHJjw|aH;#i)hww_5 zcWMXrC@0*5VHbI|m?KcyyOtzJKxqTPr?fp?A0kVp8&=BsbpU!j-r7_6s#kbwcZ2=& zqempGUx!?Qbjy;9HY?AzdzZolALgv^fn!e|jngjm+a`;M$}8god77>R>2C-ix_^ zt~j;?#zYQMJ%1FR+k@)i$>Ej6G#pIdeN5tuIBEO%d zM6RvvctX~EFm?I8y{_q?5r8$LYh9X>XcB%H0ZB#iF*zFco5td!8Z%^%#+FL4zu z`E_|b8@6QF#!N%reXJR&QIene#VmGgoSz*;-t+YP_0T5wRQ|oG)QPvzyKqUFz z@kTKO7L}dNB=N#%KfM2n`)LegJal&r#nlb5z)H@s>x?tPXHG~Wl1=;E8L+*qv;K_A zBN0H7wBPdXPkXkxREwJPPxC&Wu}{ zQp}%>M6DVbwLNZ(xGhJ1=yAAX1cLxWu?S!lCb$098Cp@MVQbrh#eI%3i+nM?SoB z(}WrM;QX5e+O*B$?%+;ld=yP8E4f3QW>-r0#nl6IHh#Q%)bTjgJDk7L@wyUb@Ht@L z{F^7y6D=#c!2m-S8A#MPs3=y55vAvl(gdEOL+0cNElXnPh2S)uEZ%(pBF%okt$gQk z#?}UX3_uoYn{gn++H7qk*_b)tO%-Wu%s&4H5rb`F~<EJYM7(1-VKmVuU_RC959n@7M)8fT1W#50l#FGItE=6>iXt()Q`F{&R4VA*p#O7U zNgoO!eP_71%M)TapS_dPKnWl&(1O5RXOAbPVe!(}w><70xgTV>e0JC0t!3OFEBp)` zqWv0#=LrkK8d_2-dh586Dpa3miqQ>6@efVv+!ez&6X_kEQChq`*61G?qvy?n_nmfs zvY&DxT}^jWaB%Wi_Jq~IvTB&bc8MzTZLlCfWE0zkSj1|48bCgTb>rNhJ@yK|YGstW z>0C~M#6LgS#~L=sTT`Lx3|l^Z^cZ)9S%9fS2+vgRt zZV-pLO3zkHH5#=IAD8Jxyqsopg)Rp3BR*sbCE6{B;;0@$1@}^0#g$Oq+K!*%2{%@X zWtU^$Sa_P-JQdWRxtn-gD}$F+cDnk~PvQ$82?yel;snC5U`*R}Xg!=p(;dXk_p}X0 z?px{vWjk^HO-zJV;ouBheE4;;VwJ5gn7IJ$mV>znZI{DQh4Ry9w^EknFe2(PDl2 zzAXwhjOXND=*V+lh~Bv@#<56z$a7yaX8kxW9Ix#+vD*t{`;r#B3c=ic)=3;B@9onX z-UXm@2vV+7jF-8LCyN5Hj0gTR}`puWf-?&C|G2y!v6}Ctlid zoEEQR34Vc>PhuHf+JDB;GPc`g<#*p@bz_oNj`1aT5o*stXd1A{dRni?T}r_#pK6Q~ zbLq3MnERvR_ns7{qI=~cG~SqWw(L6)@(G2sZ7Dks47U6+_o zr&(wLLIho72GwnytgFwsn-;Cb=_>bCI3+v^o8%x@SlvJv{kAp#0>2&q+&Hb$L^+1J zP`_I|11h{jAH#;nosQ91pU3-;tQrn&;uqWidlJ3_Zq<@;e!lrmw#1I8LZ9xwggK@q!GE2_eHj{U6=a2^fmD`k`^y45b^wTBQ<+_H5L1K@gihGZ+kqGI zn|4U0rZppIgeyARAxA_A$>F#vmR^QLu1(TTTxJ#zYKa9@jA$qE0j9OqAqjk4tMaeN z^{Tk*5vaaF&>>0#qQ7iK^&ZGzW@k36`1cZs`{S&Eaul*X-v+Nr^r-u~r}{9>hTu0b zA4$YUw;rE7&248whc{ft2l zNaXl@z@pm;-2Yb$`o9(3GW;vL&5{Nd-J%6QKBLjl)<@*pcJ7!b)`!WQmxm7@qz$O7 z7>Gz1!b>s`utdC{&BLF1Ot%@Sp|fjn5Z@Yov=Ql(C|JP?)O~o;=Bpx z*0}GeFlgG`=;VAJ9&Ral7~N%X=}>9Ga(&N8(0l10)ua1s@5>*RgV5r`Pb&n{(Vvm9 zX0ht$u1V9--yzeW$MRqtaK+qoS?@A?3xLk6yNp*Y{32dpfW4 z;>8m8TmM6%HvC$sQh$Z@RJz(yTh|LOdGp24wA<^v{57BUddY(+?>ke@-ss@7_EXH> zu4h-;%gt3k)q2XAtLUywQkJU zGj{T=7dy=y*0{7dzv|c5{zyOiZ!P`rz`9$vjLU2F?YEt+p@-8A&!teglAFt&{+y84 zgW6|038d4-ar(c%At&+pF_+j|c5t^Imgbe>lparndroSKeIHI4uC9s!9Alw+%{d{H zO3)R5+dI}|ZgBfu&`cZ++EUkRBe(zcFGnNjTMRU3_MDZnnk+;RLO~knxK>3z zri&#QPf}q68eu`>QW(OoLUfWow1xVK)EQzDf^}p{*r9XkG4Usa72ra2qv=w|y%bkj zzceF~=%u`h#7!#2Meiw!@SxfXCrlzoOD7KU>zm-Dt!h|sn(FXaXA5GdVTI_*I&+hw z#(YR~FhWeqD%$XV*5Sd=3ojxB1>gmH>td=HE3PLSXzWN=hq^72jU$N~llG7(#}i*>Mk>-zRc}bSqH>IWI zGgMYnJvZlRUpf|X-YiZnn8~1)Qc46L31K5kv8w1u129v(n)21PRHi#EVbFp#X6K~m zWf^jQQ04_6bT5$9HCJUnFQS%1-=&K}z{42w-EeZKX==M0S>>yHsZCE*G=5JBf>DcO zRYV=|W_VYj6U`fZ7P6ABgs(LFwkQn9J7h^f57rk@y3Lsf^VJ&rTO-v0FC>frFuyQk4S4!loBCMbRPCg()UWRT4C@HBd4(AQ~CRM#=@Fg122?T1Y($ zk!hb3Sb;PztWFjWObQLe3GSFE2mlOh*=T=FBhz(n;Q&yr_%o3CVGYC~!1-bQQTxF8 z*M7mK*)ujK0-5u=lK8ZOYzgCUc#kAv;LGNWwSAMDpXZ0|f zd@K}e?*BcYf(8V*LgA}A@)Ri`y2jWtrb5Q+_1}ORP?Nx3tYBBr>_+u5GHs1BV(&~q zDv&B*W;GxN&C^+)gCgrVG3Ro%(+^h7YnyT=!&HKgX#xW%n!HI-=o*L1qJ$e0rG3ip zy_u}UGmsko^-Cuj_JqRNT(3^#3wG>wkP4$@&fyT4pb{~|LKX2xMA%Wr^-Am+RMDbvdFM(OpH_Q1PZmZ6TV5$mSh0;mHa%~S{55IX@B41Md0 zQ)WqXl2euNHe#Jr6TF7Du584zDzb&`#`28~Gh>Pw>4v-p znR3#krddFFM{)dCo?0-HM;z>ZOOg5Kscr6NwCde@iVRnRf1Ds? zA3jXThe~G1j`GNn)-p@$btMzP5$l^Q$e4&=hi|Ezg^O!RdDK{{Wou*Z#I_}XtqB~@ zeg%g_+nV2GqUa!#zOiI@b>`5z+n=QoE~4K<5#>-xN9k9;aHNxL#$u8d&T8fqdu+bE zaE9bfa!^Le??9?Xo)pWw3Ro*~EyM<@E*vAn90*ksh5~F6r1b0E##Ai>8#CBl0gOt zRoXR%CR_x7pVcn6_R?(P8Jt32bZsV(W$iB)daq3IIU(K2mkVyqP}Eg0uUF?@4MAx@Qte?zbm=wyG^f9qauo> z@=cKpBLWhc>quMC@5Kbo*Ohot^SokU=`N8K%rMUch%w|(n|ijr+{QnRq_DG6fKs*K zzXZcP9B8g1rIKYb928Xm8_9Rl1=Lej>XkXiiE%V|TK-b%M*sb})rI7NFeyp%Z8UT{ z`3VoKT1#klX+=sMV9Q+cM34|~9tyNRC*~k-rI|T2JC5;WXVPMHGf9GO5s5Q4$izoM zYX1XGP)3KME+b{pvo3`781(`Q*H%;Fl~DvIf>$=8Eqc)+9-bAuR(?|=dN2Xqr~xR% zU;xSWu|2bvS%eLB)ueTJH*yz^zfi$f-DE=<)Jqd9n_vrz3lnLU8UZ5M?z!t^w}mSHYPAl9HzON6A1;A4&Rbksouw3jmYcXSpRE#I>fI zL$*y8$#gB@K$9*ATN^(ae5(!0MhPlR2T0T)6II;RchJEdXm58^oQex54Xw51bP+=nieyH~Z?K+F=)^a- zUBb1T&iMn-mR1;AD1i}i>SCmv=U;_tJ#uv1uk3NO)FN7Hs%)$QJmqkMOk|@5jgk5{ ziUxXgecxFXNEo+tk~x%t4G|MeBCIL4 z^7e^kQMZ|p4UNP=72Wg~9W=TcpwAa0h+E7!3B%FI#stSuiSh49X<<;68#Fq3!8kY_ z?M`%;(Zx+2TLXMu8Pk{1)IzWXq1skt9IA+26C41t75y4wP6UXA7^w**BnuR}+Ic@2 zK@fLViV)>1Cd;C4Goh@C7y(v7q9fyeyuO1KBvzR0U!3>p68hLCf?m?^-bc$S^5`oTBVdx+#v~~xw}&&D>J+dwt6%uODKx|(nuHc2 z&fK2SE5+5hLuwTar#0z0kKXJXxLZk(m0V7>Bu5>m z@n0UoIm+Sk972X}SgzI`pHb;3pKA`$n1A&Uu%Z zZdnHUsKxfD)T8SU@e{hSok4;QukJI!>3eX=PR#b3bTS!!XBQ|Dar?TlCn17$uYrBn zr3_Jcj0`XZRln{JIR|-0ufQ$hF!x8CDTW3WG}};2#(~USN?*K9KSH}B8OI=*HI&C? z3PePkq)8U0sW90-$*h+5il1nR^oT!!MXqKv$2S0Fz*u5$S#hXOwOH z8gTCoXL$0Ai4kOBZ~x&aG; zZS?nIrpH~UQT72$|9&6Oow}|-&yQj}X~Hy}iX?T*chI|iqihmT;4=c zs@l7qU|K~3+8cH=870JbB&?W~I^D*~i4cEEjPStT6@O65~GRfTrdPM!b ztu#iHaWK`N2!lEsNJ74ov9X+BPVk5)oiKV!IU=jTP7LulL{>GT1V8lTndae7BX8^D z5&Mw@XM%}SQZ^g`I@e4|YTCp#Vw_zxkq~8o7x+smn@Pfa_}5e7uSEl?@Lm?H>LDJr zH1hC%o)CYJ=6c2SB+{=&%Qyu{odXkHP(e@@6IBeO_=k+!qYcTu*>q8nI`YdvCpELQ zD&=UG-8zv#Vu&Z4&Euj$RT4{sg~^^kTpTj}!~V3j%HxGePBGjg%CkPmC>LfUI*+8> zyQ;PT&n$GUJLlgv_;JsZy=zPE%)m{3{m+JFR|hAL&go>UZWrv56yNhq=xxaj-57h+ znO^9|f=%+f?dh-?A-dj+gQngNhS|=@2H@k-wo@bYtKG|){HnE@5HTm-f$y6W_Me?U z1MiX*B_F|B4;HC?T?ShNB7Er!?%0gc+C|kW!mF{ znh{L`zK#fW!0vcJr8Ah<@%ii8^78D;`yiKIHFWvX)~xf8G3mH$+ke%svkc#Hy|R(# zM?HO6N5#Jp>Dm+Bmb`HXaR0k+xm>dccubjZ@6;r)~GzzZ?43_h!EK!qxAktfy_wdGBUC z?e65wZ!0^87Xw9_Cwt;U)ezN$@#A&4Z8;S9?N(h~v!^>>O#W$vzQO+-_y7j)7Ri7$ zu8&#&ua|BAml{{5e+NEVI!?Q-$UZ$i0lNk{mzd)}{59gMB!!Seu=qk^s@m#bJ5JZxjLW8bl_%e|uG|(P=LA7dHId}_ z*SUOCWB!c$F1fqvcin1D-cc60r|41+5!144PH8~W7-vXmHRvQ`caQ59xH;!^Ja{3m zY4lEaeS{;N-(`3?YLk0PJ67sFCiIpF+U&I=!FMxfOpgya3Xj!1FEVG%o1c&`6@X_r z67;OMUa~XYxNNz)L+@GCfIB;>dgFvGa)7IwqqEiK;B&bUES5|D%vP%ID~j z_`G%*-ZluuwxRCD9^tfoqaM3Q&vQ`Gj)AdoV8p~9?I5kg-aYGS^W7} zMh$IB%BXe9W;6=xmpw<{hRtQZGMFpOEH{~TIJv0zs62ON-t5ACvfbMk)pZVyZx88% zvl!`zOy)^jC3Bija!iD8nv8lkzYdn3C)UZMca*Yz`!8+V4M#WgSOBhAxi9jCyoK;A zv~9EN^KOd&PLdOe*E2OV4s0F6x^VJK7DwI8&U;zmg7;kBIfjfrw$@f3gch}FUG;}u z)K|`pu5dL2cny|G4yRrQ8}|9X(?4U0+1>14tJRz^6qX0CNaQ> zw2@k4rfQ+$yd??pS@TMorjeNSP{QmLW?1jK&V)j`uGFLybZ6&&`AOy&+%VssV&|W_ zHf>^A8}I*S75RN(aRik{-yTxh_y)bx)l;K#m~bq%SrlTvGilZs$A?_xC#fFivVpK{ zMJrKiaeaSsg4pHG@YSR6Jc7K5gwr|lZEDZ{rr$PIrD0}h}xcx*g5b)&_K>-lAdx{b`a2F8Q7pjt|D3pfv z&TAU>8~DJ#ZE;Gr2Z`LACIltxhgH@E88Yog{)7eS8YRs~Fm`WGL1lc?31M?_3v zeNcZ&FjJdjFQ|z;V-SB*Fx3l`Zg%=}FQxrg+q+}fCp>8?@0iiw-D>*?GNM~XzD-x) z&&sd5Dhval$6l01#zI@d`f&cxV8w{3X}}Rvg-1a_rJ*V(P`a8Bqpj5oAyb5rj1$f1= z(p=nj5F(=>8AK-0kxGiyJRAZh@p5pXWGIcKxINp}ds|#ak&T(kw=nVCvQvnOWaq$q z{a9$!b`V&S4FUL}7M;|3eeE^H-5Wi6(&&WWow2$94FW%_b6n z0z2mM4%B=(_Ll}y_*@E1W6)rTU!am-p%mj;ev}(h$mc@DDvE(0%zQz_A~p_)r4%w1 zo&5&?CGP*Mj{R2=yK}g{xZ0A$!LZ=x`bsZv%3&ZxTvF5sVx0qT`D*Gv2eOT|dq8en zii~9xB7;gJG8UT&p%?luf~XxWmr}Gn*HQ{!?e|-8?oZ(v@*D4{^`%z@U9M6}ZU4f6 z#k%%I6B0CfIc#H&#T%QVMcs|D5~SdGX&9Md9aUP+wD|<~zYe7xU!9H4Ple6dU{? zZ}{~***W59SB5d0d!I8%&k~l&+C3u?bLi6&U=|ALnm}yVzIZZZ))=rb@w^uHJgP9! zJWJW_PRvsm#;xaUl9AcK4OeSGL)B%6It=>gJK5rmJ(0D=!pj+-?IkT+XOl?~wR>l? z_kKwkw=_>2wDKXDaBkxeU8x%xngu3lozdkPN&7(73ED~cH57w@GucDsQ3DY?8RbUH zzUpC`KKuP~F+4&koRzy)3i8X+f{Wb>9pBcdS+5b^@E^ji(3JyNQAP~6?tTFNmLwlE zr17M8D4EZ6WL)wYAEn}?D;o}2Mi8 zf7>NqCG^lnpX+}7JLlXE7~Nup{_^Dy_x~&P`oEoX{<~~5m<9ZBz8G@I)ho3+*M4J& z>5pDDB1$xnvq@D>S1MOF6|X=^386F+OvHG@kC!a0)5r}w?lRu{OG2wS1jt{Jz1vx0 zMla{D{A_1~I{X)*4qm>7C{FdqE#nTX)-}^|zVFvBDlYZQ(;Ke8tA=g-d~e&fa=iU+ zS{hy*UK)E&UOjejmM^E}Y!5viFHTN;J?8D&eV8s^sy+@aGubxIKQgQ39y`jeRByyH z9xNbImp0Db{QQ{D|HM?i*S$zzR25%t z;-BvQ?OY!Gb3Li#wOIFut=|#*aqo8~&G2M@^-V#g+*!fiI?cyev`zcT{KaLGo%<2O z!->&7YsK=Ujyv^#4ccZ|Yem~j% z)5+S4_mVs3*XtenJs;+3zk9`}?uXmRk9*yQVT9tHm!Ye@jK7w?mX4Qv-B(NRj+biU z86IxjHSemMew*I7OLDZ8FBO-ryrDkVYd9st(^qeFIXTvW`Bqzpt*~q6FArR}C!>Z~ z%YM)BsF%h!Cb;ZZDI2S2%KP+xy>a{id~lxKCwwt23TS?#n0}){6+3$zzA*T~ssIk@ z8-jrD4mxd4gjf6e^4=)~aJAB!ZlX(sI=d0m{J1$oozi#}- zYpyr8%0rwUJ2uLS^+VBge#!&6i5Q>Q4Zkch-#xuIXpgsj!OI(hhm60~dR}~&bK}!* z=--CjJsZCwyw1BixjC@?e1!F53s`J<^;pNvEdlV@eVD3Oy%EHkd4HbF{p+s(kEqecWI6VSBlH9zD7||I#KR<26nHY80J%o@#-#mz}Cq^D6B*|pNAI?P9cso{7(Q}q1jEOS=)X+uMkQc^;7p4&M0v(qr zoLQs^LSb4Cx@5BztaFd5}-#Ib*AWA$+bJ2n+G}@E`{3)=` zC^K)xGnf?+RiB~1p@BP0aY&-t7+Ertz-V(s`;h9%d$SMKs$rjkFe577#Q@A~b;{0%#uSX{{%yi8$0MY;9x`t27*VW}9o!pVh|Op>H!adTobs@6wf{r|k8eWTX7lZ4j*D z!i(lpqy;>PWxH&@GMv3zoRm_`Tw;^M*RP5#5|LY}%L!i2o3f$>8|fxyZZ>NzYpY@e zP?R-i0Q@tG=pK*-e8uFB7~y|)l8H{{o6bzA&M{RXLeaH};$IW>xx@jT zX)e(b0qfS5R%9^s4H{IOZ^~;^#lNN$rCq}b_|Ha{IU>(1UC^=~zDz|L7D`B!UzjOv zn`v;M3;Oy_Wa|@hTfvY)e;ZMaCt0;+1Gh~UHAX@Wkgm)jNYPBO-u&9u$Rec7_S?0A z(!PO)CXygQ*;+u5tcmI*C@)w$UF#&Rq&aQ!N192T23T-G(LCO-V2Z*bGH^!=Q}ECn zi;fjI%+DWgjKwI*|7=4<#Ze?kN!PTuO>54Y{Gs&O4P2p=Y^3PW0uUG*+n_?Z9?kra z2%@j7p^q+TAd-iUZ_j8wP>naRA_RkN3?%WZSQ5A?66z(db0)a%dU7KHtc1p|Dcz?3O{$Rkk0Caod7sm8g4|0Y6k(#W!vVE0J3gM$e+83>}mhfj|HCcpr zTwI*vsIW0(-d0}e#{=_t6(sM5-wt@)UW6a=tU}duT=iW9sgTOC(Ipy*RGec3x9|0> z%@mtRlWKkCu;D+GFBcRQ_4jSIzrXz2YR+FuhRB@8a09&XxtJ#t7;g!BVJ&#I4!`}@ z%Y~h0L1=cW*h}QjQ!ZDx&M7x#DytHRfTU9#W+)E=A8NM_{G*%K9K9=PNYzlZ5RAZ_% zv%%tCV^?KhID|6lu}PbtAo}lptTT#O<^YTFrY!4kGM3r<&WWPx67aco8oz?^e%bQ2 z@}4MIRNI(1Z7bdd$(qw6q2oQzok7|QqG4BCI(X$%t(vky^8NPj2698}YuuN+VM{CQ zx}nMNeDjPI+$Uwob{JVUeNLSpu;sOxz|X~%Ml|P4`m0O|sQE{;70}bM0vk}BBcj$& zR22O7VBLSi-J_XXD4~x*YRd6aDqF*b#QkLZf|n$TJPWe z{+>G3T~$5Zr>A#U?ZBzom7q=%q|Wl9$uZs490p*|@4b~`-cQiFj3|E_i;G=gy9X#j zY=bhHiawpRf=VXhOZE)lGj#ik#R5>Z2iK_w&XU#cJoC@&PyzWg1yHow9vPKCIL5Bu zr)YoB7O_v^tyF^o?h@Q_#Y0NC|2_q#)t%;Jte2J*5~}2%*`jVrl~J=_0<&#lIm~Qn zBQ~wMw$hdJ&umc5C3VCkR7TfV1JdwAJ~ReI6##lgTBkq|9M7XDVbffT7Wr!fvs5R% zeo`SG%wq^Bmqn$E>4ffbjYUw28eq7z}Zb+1Vy}qnppv0`WIRb zwUj;_r}rTQl+MypwQGnc9y)>lQH~I#sD#>5D$jsUyP^cz1SKeWLSg6lPxDjvqZ#2M zIjdqbc$Q7^*26a^5nj*^=i+e-&WNL><3K1t<2kPs96su~D$DHw)<1){V*>Ocfj%Y_{RWEBQ>hsZneBnTjLD zG3<jgk{Tx*3qQ?UN5hwddqLwI0Yjv04~55*ACJ>b;uYb1qz-XxJ0)R%6b7y%dIO3% zwB!g1wWSY=N&1Wl;+l(;PJ>lw@z}ZZU$6~tL+_tV2YKmm#f@#>%Lx&3G!p*4C=?DTqU_ZUv?~i&aCG2XuSJm?279hNG5Q zDCS+r^$Fc>lAI`%<{Vw{=t6hVbpUfgLV{?KH58s2{gNq1KvcQhzeRwEK!em*8sH&; zY1{*;@0|kmeV7STdfL5#2eOtwg%kJ-730AhZ&lSK=mNS)o+AEr)@hIK!x$$<$;hCs z^r2f)lzd)Vj_D`$^j$rV^FO6DYO6rrfDkRaM{*__Tsb~c2Rc32)X~1U@asgsrD3@a3&_3DD|;52I$@7ik3wde`370;QCl-^>`5^ zBnXagvGCU!%;%}0@V}J>k3jUAaM144?PDn5JPow#Nc+?Ki}LP}V&?=~siVAJ;rb?M z_2N+=ikdGUoDI{ms%j!3&9aIZ-`_iZGilk|{YC=?aFnl%gxT!%US;kM>ZXt8{?sVj znG^*5*zh$aoE$ZUUtC`sB~TM&gGI1Wl%Oe4E8Ce91nt>4cScDsjB3h53uTqi3u98d z#Uf+Si0-sXxh!P}LJ*h07wzw^1ZQZD+hP%XEi1GNTPRJ{U?=~TvQe3T^7%12m?;7p z|A(&=%U-w6tE5SuHGa(-q$aVvq`r1kk_e%sv3{`8-_G|iQxo#$ltq*uU8(m3!-RP2 z_E-eLBeo-hhxll)1MMCb0#G5RaGD4xt_=S6p%CvV=IfiDWctLR*+5G?LG}sB;a zMB%(N-C4Hq z3>Y;I8jf)XnafcI?eMmV%$WJw11BE0!bQsPbibzmWh~IB;j&b9U^m>s)*|xuj3g_P z*ym$fI`))|`XkRKseNl}hNpqF!=vibSr^^8kCut*lyJ#G06NS{O0}K0i`7x5i%y*y z&=^`e&Z^~6FO{%mPhGF8KMomUF2@_po!y=>6KL+PeMqZ1MA505Di|wjG^j8P7!NWv z&J*TimC&sHCTQYDF_EirILIPcrk$-(BWWoi&#p2-vPi-7cmp%1Z;GZc4$%Ee6=VKm zJ}O>Eg<$;pfsOT(<_sM)I?QX*>g6+zw5vtEdi5n@S__Io~>48 z`U&07Heg1z`(=dDyl>ArwYH!89~YnWIC-oYJuU%Dy*uMY#>&>J1{Ah*I z)w$*qEryXhK{mJ%I`6ZS4?!@!!`_9spB*E?hB5bG48GU9Y_0C^={A=zUnTZ#64&@A zzVMB|VJ@s)&tib*o%s4z#cV(sZ50RWpwq<@%T@cAi&vecSiSe!$W)CbS zA!mJ$8@gx(%-g^HV<$u#zqvnM^S|ca@BC#jM8f}Xh2D33WsMgI_2g34|8<1+KhR6A z|BqhsBj<79F7=@6L^>%%tFfgE19fo6@-8DcG0*7RAbZklmJ|V z?}U_B{MTPk_E{o-(|r6hn{r65=m^f_Uh_Tvny?q@)Y%{IE)39GQ0=%?yW;gbqHa&~ zX0mBS7hK}b{_nt|{ckG*Pg@Mb&nBNMc>s>XXa~q6z z>;39uSL&e;KaB+bhK0{;EEo-{Vpn}JBXo$$FKaL-(abz>e~b@w=zIYC-M1fl(9zzX zBKkeC4lQ-H$7d^VFRWmwk^0AIQnJ~x$+fhAZVVryOQNzna{l~^fEpdkZqHOQ@%i3x zErZn1*lgO><=`)yix+MV77!=8ZAb2mGNS0HI*gI`#4JntYgc#gT>UT%6xouKkuO64X$HAI>h|zIP_4 z3(JmrFy$S0$H`b=s;J7L!y)`>x*2WMi>HBlMBaRB%~NL!U}oJc9N2a3!;Im6>+84z zd`m&bTKw=hDp=jc$~BuBiB-nBO>TOb`Wwh+Iu$y?yeKLyN4*@VgyrOL6yI#~9WrRo%6DmCmM-MK+nvYNtk1c&;s3 zw0ZqI2k>eUV{e1ncQS#>uyb#X9Ng`Qmu+-{jn7&)NW-IlcOsI|`>W_`7|k6z&V6fo z!HfE?=Kc^sN>cUd28ML4_gBTO^_I~^JRWJ8QsojkzVir5s^Y;6_Y}N7WkaR>jn|EI zScrHtHa~(a{-sVeoLn=2+&oW#zX@2<`|_rh($_ z8Ys|#KGwy5GZ=i);R|UyjU7$_hufG6U$`+CnZOd*N#MLqx)+|S*xQZ4P zkNCcjW-=&GBuQ}XjVUuU6(%szB@f4A3Dm2^q5+0{|FAQmZSx!NotCfh7Y`_oC86)$ z6T2$Y;Doh=9}oK`NB?w4*Z$gx_0`tY1^G7!^4C-_6YBtl@+Vn7qz&t{~_eH7gr-jM6>Nd<1A(IvO zyRCm7>G9%P#K-kvz6XqIz+Ukn=$)#Qh?FPFB&pe_(a}DCt?m&|gvz^?9h?ee4C_XM zF+)-$E_Fpx%pXC6aYJIx!eRVgQ|YSp%k@Io23Zxb{zZ>JRsMXo+LAVTAohXOj8qZyQbMT#b8 z5AE&`0fu!0GR7fbZ+EXq{#P%HqAxKsA=QlNKFD1q=H8E(9n04+fUZU!hM=NoBLB;>0YcVq|JMgUhcG;fv_~`K3`pHrnYbUo#Ei8H&MM!TWrdz)(C4; zt^4y$=^r#mwTL?>@piIZbna=m1P608!X)PZw%nU%{{LGxrlZajk?1&owf;h-i#Siz zA?8rNkzIO1u$v^KwF5_$$Pr}0#ol4?!H#)OaMf>e2sXg( zfhGh6s4^O3t|9TmIbN9^IDt7(Wrs0Zku~Wb(BTm?gf!jr7$k4Rh4IP9-*SktuNICQ z4?xvNYtdkWoMp!`MFW>2PGzC3QceREA0HHrYpzB`4qcgZ7gfx{Ah_*HkjnRwMFIXxYl72bah1=gNj>I zSF3Md`=vQ8=MRYBa2o@6LyizHseGG)Q|)J6kRnQ9xktDnZbf>~IIg*>%yH!JyIB!) z8^EMoQ%{w*iQ1QrC4rB;LRTEq^ZZ!X=Ea^~8*bH**llr2kCZ7#bXgMd)+=5o@)$Ld z4^tor`Nf3cI#&;fr($SB$0V6Zlxadq%c5{<{*(_?XM&>qGGJRw?gp=;9`6OO|Ex+s zBPB!ENX7GCmjcg9vK|0f1IO9+0(wf%e-?(&UrX(*H zzLSC4J<0*!u}01=-F)E)>DKdmCa!*4c{ti~RY-0!T+1y6KPB=*GX{5 zv7Yp%=fz*dQo?3r5og(9dhv6Kpz_t7^YzI&*}vS%76A0!i!ux-182=aM`k(u5 z0}w)2uv|*VMUC+xdkK#^JfO?V{BvXY?VY{H3W>wy*Zy^Dta<_n0)V75`+Cxhl4O2l zA^LrYc>PcQ5M?5UctOCZ*KPUrHrxA(1HRGIRSV%=&7{x%AH3H$FKws0T*KVg*S<`x ziREqns=JeU_oe%qNx!o=EC1G)xTt577oU!^XB#Zo)3};R$C9JVwa3S+C(uS!?6ULW z{Z(eB$!b;c!@>XE?vW1aAC=X3WoLyaqPIlX#2BuZtexj9DyxA4AukPv&_!HIgUaUR?eqm~uS1 z-<~-0-C&au;geVoSuf#FLj>X&VG z_4vlJo-m|LibSSl{`>6rUvPM?^3kK!6;g?vu)hlo#=&e=@%-KZ|0>(|>t*~&`wsW1 zQeKIakI37ZW#{?5vQgI520tXjbo&)t{b8skX7_qqkmUT?qhrTs?qSF5waL#BtodT{ey}oWag+02>EMUohRcr}<_?=xSOhF)IhYmA?#mLhwe|*Nxzgygc^e zyZ|oLgn#s|{$w-0IM+cz#)=Xi3*z@T>7CaxIMn2FmgFN3p?{c=udl}wgn=-2(zfL@H|R4L z90$CH$TVWCr4>R)GuyCzRJ5zUlEiS3py&TeQbrBZ*VNh;Ohv=hXASy>rs+|`9k-Ac zmvTjsi5R56;4y+ImF!9Jtd77Gbf1NBQAv|R6%Ds6iNvU;CI_UiL@DyPatCOsLl`w% z&;LdPmKBj0<6*WFdydPKF0dk_UZWvYn<%#e6h#3kL8Wq$i3V(8JWB3e04?sSnP)FM zgJV=#ltzH`04=#*cS7$)A0<3wh)CB-z*sA)@M1CYfKm3%0y;wxHyR;DBv$tvh-J zm>ZXFoL!H!P^NOA{KvfoQ(ih#Q1V%DAU#94LZRHUtTC&Ixvmh$WGOZa)6lyXS`sPg zqbxS4V(sf~Lob*eB=TzuWYg5KVL`FylGi*`xM{Yo|n%+hL(4?iq85pLo zU9lWgsv|eSsX|?p(jWwvitWZOTHLbgU39}xxo0nt#8_xaNN-q0jKYk}x|e6(R{x8C zLy!htNBd+sNKWIQBCu`r6uW02wmmcwIr2uMBKjxlO$Icj1_jTUczlvt*B2yK#tv+G z6MiyVnMphd6(6}8u37_He=#o-t8INj5}R)1jc4^=(U7J*mT=AF@|Va!H3ew3Qk7fR zw$5KI_^$gj3=2UZa$VfxSOWUaF985Xbuf9;#{thp`XEp(UL*W;xthHJhYB|NWx-w% z?9a$T{unGf9zD$bj4?_Pgve-hl{^^>TLwEU!AQ5NMML@pR}eW6m)4tr-u632p>z7m za1Z%FEA8U(BE)5KpoS=p79dGLCl^HBA_qLDVE`Q1vK-+-WX44ZG1MV}oM~zX*!t81 zJxJ->S-SpM|CKcTlVDir!|~aDPtPgh*DC+V@!AbUXOu^Q9S9WtDQRJgo-7DBm`l*U z$%*W zVkyC{3~?~#LCm=6RN#p_|e>h83M^vGS&2NuO@#bSAK zYcYzb+ElqJ6c|>Z(WVkIC%|YR!KG>kQlrMKAlBa= zQ;-bpv;y^RzUZDnETNQBv)%>;C&Bd4sO?&JKtID@ zoeo;V#BZI{(&{W6(A`U^B#=mu#I=Ez_Y2B|7iq+;c0RG{PA$|{SWU2=2yh5toayc3 z{KDvLfO-LuW$MSfCO7p~g)bzTS%u0o_&h>kttv(m(_DL0PrI@tH+5BoPci3Jv8$KU zBu9p9VzXc`UU|51m;IIaC)1V*q7K1d8eK#QbWv()(Xa|(v~$tJ%1$@?qB=(}ETO(C zn1-je-6V08&SdAQSC;@MkFr=<8=T#XM5n(3N(Pm0=&opTbD@3?Vbn~6-eT`X!3P~v zwvGBUz^0@nXH69{n=>#(yGVYk`o0o$H>$g+scs^vkY9wL5-)BNjq9ay(b&5)s=J^m z9SHTGYj-= zd#EAe+uABvuUa3S|nCowPzo* zq6P%OL`>of3j+3cu`gn~EoFlS!<*8oR5c4yX!4Tclh!_j#P^W*OcbiG>`Os7WMvH) z5Jli5`N+0`cnJt_d|zhh<$tW`jx5kKx_BsxvsPHF4J7nZGPw3;Z|(;c@g5lJp)M0? z6e$*B%B_STtspPfxfV%%a^|ARh^?C7JC~G?VBmuR+8N|!I}?I?7Yy_V_gBz9Ik1@7 z0g}a$XG1hze!)c9qWGmtAf4J5U zAcmcpVw$&}C3NqvivAVQ?|oA9?$K3P3bj`uZ-_-pgx7Wi8b{y|ykV`5M=TabJR&rj z`@<*-ajN5y<0}}Kjeg$85e&+ljcqD8`Dlj)#`I;pfv6?33;k2`DWWgaW*Jz}jao{f zS639~RM*6FogfY@D%Vz_hvQTBq@b1G^|-UW9r`5nNyXRs|0MK;Ac zM92-yQAt_QbXX%ZCnHNull4qg?gD{j5W;g7)iTceVRph(SY;Kr zG7T=y=1OR)RcY~swGS&YwrOn>*;ypV1efXo`4HrLJR6S~tA>+JUZPOUv_%~QG0KJT zQr$IAK!x9}8U7Q%UTOsmx6OE5!q}#naH%i_TA6FqHj(3A-&uNSw4VjuLWbss87&nw z6)cSk+lBoMgJe1$gHIe^pZ2?mz5YCGYbFDuk&wJw`g8sn>rr;=YmgLjBrgeEKSB&d zt03fw4yczq@jEpFP#U}w%v#c0lo!!wb=@C|(X$v$z>)}K&ptHNjopVOLjRvzTRZUf-wXsk)L zuXB{-Da~dr=33;>HL=iErna~8oLay89~9hqA=|Q0c7tW{#ZlXnOjrDcs z=obGycEbWC(^lqE15SO;tpr1Q64)HYFLO#G`Y+gs>|alJ+)ZoCaQb9SiB7B1mvw+& z04vTT>z>gq0VAJwAzKh00Eoc0{v&z(P=L)q3sWN&sPmcN3Px&2!In8ip)ZrBuSoa% zk?9o2W`*Z;&I(gHs?j#0ti4+L<%9`s%GONIYpH4J`9xDyc1J5}I$esfb(zBJfUEY* zxC^V?P*E(jk?+_;f2Ll%=Qb(=D;ZjnyAhn{kPGhqWlO8h`r$&`-FjQ8cn@|cWH$u$ zT_tkNu2r$Xtb2J}0USP%>7C%Yje&q5iMCshx0h`SM9{n8+GM&n1pzNjS-m4Z5!fRQ ziq}=dk9|x*<2$hbiO=XArBb1s(0WQEYO?uxP+T=@82Tn*i;^Q*@%$@VT6kF_{MGtu z?l?{jJA1uZ9=+9cKpIgJ{N*X+CpvF$S1k(MuTOml2|S~K72s76|2!%g!R5GmTWPKF zL&q(bQ(3XEn>sOYKjtBjAOrudmNpK07SFyMF`SQ&>876_jaY-wn$-f@)Y?QkY6sfU zAJ4S}*~qPrQ+d3v+b=b6pT&-b1CH;xymu-C5$&lmq17gx4#Bj)G98?fKQ9oKvR*c2 z?$M3O9VO&+uD>4+;L*1fs`2`7g(mEV9$1W~PtMR(HP*SsH|{g`tUMXh7$ zbg^cnH^0XZ>_Iv3wrQrZfNi}rrmbF^pvl#fahwf~I055*_d$10lkTM2?hlcl&f88eSQ!m~f z79p6I@0p0rQ8T}l*ovG%=V(sKl`{^@Vt_Obc6H-w+)}4}lJrd*|HjTieUo-=4zdtO zS!)j*C-&i5iio?}aoA8^v(+^)Bp#gb^ZK5~+xOPea;9}M@iu#Pq$U=Vc?ap?Lq@!EW9 zy^_A)$(?l$Z>A&6n^%61YChg!AMoz$l24tEGlE@3>-&3p5oR`o+9JgKp+ZWmYvX0% zx2S?HU5@R0ZRn9D7imc@<>gTO+R)>{QNvN+<(Q?&n(S0xZd?`BTXt{P#{;vPu; zu-`i?CuZh&O9Wgc_E^p2hd%z8iU|OlNqgJd%d6k(*qP;VE?C<bd+`GDsd_1oZh+s8n+` zPLn!fkdfZyA}h)TEgjo|M)1Hpuno*09BbyOz_3Uut=uD8-X|Jz&%(La~*!A#0v*l#k*KUb<{T6SA6Rn&@ z`}<18O!yidcq$>*QT5*Hmir9dTJBl8AGHFLRMbn3HFcc zb5{STx{uHtTaOF+=J_>cYMkJw?@e=m#E>C}fC&*8!aurBX9`T%HB0VKLr2(}NK>0% za0rz8)@_fz(bc5re4tTx_znj)XmOgZK<_!m^zF|T5aRveP_lfpLqqLBKeNB9{P7*r z(>+-Wtx}CxaL39||7Kf69fq}PtJ??-=*}7b;)lUtSeJcjF#7jA6xW_f=T0i^p@ES%C&>tAjt6$hNhhV-AQ^?rvDdK-(@4{md?kngNKt%L3 zM@Q>GsRy^jXbeQiYyAe*OEp|O|4{)|I|V&M4c6LGAYd4YHb_<68Z&d4*~D0f*BVHa z*V+V4goTKjut`smvMrIKSj+s8n+7no3WN@!8iqL$r< z4Fu%1YCuO0L3PuGT1n%Cl_5f&Vdk~sLIY);rTwr!4d+l76KMZp;0f4Ifwfk|kfxxK zNYgGfLx$m|fx29UfqJImHx-lh1JLbrl`z08cmUxxTV)jgVPuZ!Ex_j;NlKwJ%nX1ktHOgsm!-)kw}%N1#&VWv<%sFs=H<F~S-RP^^u)@l z{5hGuR|FwnHbsePHR+g9hQ0t|4~m_IWw*GmcBuRDZgl{$CG=V2pSR4Tdl_UTFty*k zu%dcL03nI33|Y~t{6$l-!5ImW+R{qJ;gHvM`)OSh@52W+`nR2&YD?9kIuaI}44b~+ zF>BO(%+gA}m}D9)-U}V^+Y5_&iO}L?S*T1VgR&J&<$lf!X>-B;d@QY=!h&3T`ubqUuJVCHqpafEle$3CG-)OpmX0rZnFK9lh zvC^pK_CD%2hJIJqgu((p+4A(`_*mo9Emyl3pv)Ta)&=P#w^`xhRMyiz@zIG?LzTGm zRlfbqhozH3Y3XbuQ|A@--{%fiAVs(gQf}3o>i_!O{Vz!DKbNQm48{_`gScx4Oxg{X zjJ;ofePr|IW{nTuRv$?jOV}wt&7-hHph?J+h#tINENK^*^qx%C&{;L#3g1mf-OM8^ zaT5EpeD8117p46Am0)mf3@0-^QRa6$!D8R}@!m+yh0*U)WxTLfa8>(6%ZX8r&p8I& zM(+FBse6_vY4x+8VK7vC-&o>_=eobQmsd;6Ii%X^$NN{-7gqr#u;T}^l8V_rzvK3A zPruIgx%rBP*WCNgcL}z@M|P&ssi}Q38?pF&U_U;xABwNVnSEzu)nTt&qAO%4HIdCZ zZQ#q&`}><+Jn#-1##N=&6{v53n{;qYpq-%kd-Gs!y?{fG$idyVoufVYGnvyJo8+di zM+-)uWtv!tx3GYiLXUqAUTUA^c?sFjHxIVdwf(8Ejk`6C_v&2#wUUj4`<=-x2r;tlj`q*Tj0VB;Esqo`SfdNGWN)*Gf6jlWg;tz6$2mQXJyPth`g$xnJw>$| ziM5Y|Gd*#tug`Dp`dU20YtPx*Gbe~IDD<7O&VRoH93S^aSUKB}Ifi^Y2Fo|>w-eh` zM%gHzjJB|gAca;1V!_|>*J#-_@RUX0lHPKB2nl^>eMz0L+45)7Fj*JEFm@g|{BVC| zJmk!nNr&DWR0@6n?oxl)+noEfv(|B?EJpVJ)#X8?Gw~AK#}pNq`}X{{)}a(a+i@mD z3xoO_{p3+_HFcuAtyU%-A451~@mh*Z9z*OvrxffTy6EygL9)CPf5`V*;)ip26q@6Q zU+wJEHEYG^{9Vj}@B4w(tVcW2MK3~*(}$ZDkswmmE05O`lg{(+7-GcJMlJbY`L@;^ z+90KL1F~`r`o}s^7KI8cLd8Uboy4;B%qEq@LcBX$`k1k3{bO}VIQ9t#MTQ!YcF5RE z0s|3=TrG%P@4^LIpJ@VAu-}Mg{IIU0VM-JO&A#t5!26@?yz&&jQtlGM8>Yj&7Y3Zq zWOvp!QBXT$N>oBoatTy%o~6Qw{K{7;&WGYwhtCiEp}0Sqp%SPvxR;|6Xbif8-~Xk) z|4Z6u%CtvsGGAYo}9=eiHj4G0LXwu2+i3xL(Sxj)97W3aqWRj*NVN?PW==NS>ao{RO6V!r? ztL@=#O`2p%C!pyXQFUO{H~VKYewgqiH?j1$mdB$+f|#2=#P_10d>YuFS5w2Rv|)BI zqWCj!dNz$$j>j;cl?bfbz;r0)|eSxDIkRXNlgoWgFJ2s4`-~u1&!OPz(D0 zc_RJLklyf>dal>Gy1Z!R7mF#2T3sW$HjKIl%9t%i7`z%#Q^mM(6h&~s7F8!IsnP@< zzD#*6R1gY}-^NxDFLXapEwZ{J_DhN`lU^?2fBRNa7&c}X0fM(s_0hWE9)@%?^X;9Z-#-f+=QE+pB!k4Ry zW#kJ$EmW6fWLR`$H{F8Qy>QwNSy=S*8D%G`EG_{0a3wYiC%;OmO(0<^%GS_2Y5u8f`m z3cq1RfChfsepar~`a}n@kWt|erHaQ&s3uuJ6iZymO+Ka-lYF~?gTzUIrp2-jTx4Ob zrz^F3lwb)JS$KmC%U4k)-+8F1a%Q0@@xY{n>RhN6@++VM&LgIk0S$MflHQbHo`#M) z9wgdd=f_btxB26E8ZoV^k{aAsf)=2wfV0&Ka40b{eLxh&_WiHiQ<7OtGm34qc#R*d zH9*%$fdz^tofv@f&jUod!3~4*h1RILh>eT}a!u0Y+G=?!MaZFey^1?U?hsCPL2`|< zN^MFNd$mJuf^K*v;fX(xu58)DeM(rYNv6u}dl3V-gBd0u*?Z(P-@gtbZY$En_;i5s zZpABfXVf8MQ0}wx2&Io*9*l#;RfJ2+*8$48wQiF5EYRZx%Cq4Mh!RX@*$(30DIz4R zsj?E$byQJRtIe^XB7+Q=haiD9#h(_*L+}4+wMxj#2YRJUq}4#N{!GAEpOnlRiBVUZ zTO26ZLr|ZjR2fH_`arl@@MK(Jw#BGRWlq@%%DAvULpk$Pqe6&ORi)rz_zZKH0$bSfkvIwa% z>%EFjO;`*8Rk8$_Rtc~n;f01&et;&fl;Y1}$m)**HL?WQR&livdqfz!NQjaU!RYT6 znG5k=nue+^)vH=Zfng387|kMl;ka}ptRgj`@N*VsNPiDpNouiD*P%N2>OmdpT5{w6 zmS#`%TuFsQ1{r%0HQI{E=G`ct#RWCbFe(~FFgS9VS~IHFqpIw3=&F+54fVFlSlp#v z5Ke;uOpI(CkCPJ7w^fUIbM zXa=ticQH{Ij3Ca-#cY6X906Ftfz_uh`kA2(p`LY-8KIZ(?n2XZgGjI!x=qnfilo{Y z9kBFVB;*&*pu#8Y<%LY46cUM|v6)Reab1DQPZ9?DDk&Yuc_c;xv$s$wmfhOTKV&NT zdW}o|^@X4GwH_coBY~fUO>e?ta5V?Bs@jXvnh4bE)6`eh?8xfAK~0NWLKxR#lnWRns4t!a_xO#~i63c2m-P{Va(J8HNZf2V^}r8Jz}G81bt^jPfNYX4l>s zIH>RALMS3G|MXZHj!f;K>b}}~!i(E{2q$@^qc$yqXJ`TiSGDHZdoW0R!uN20AqyCo zr#}sb4N%}RRHFqg;MMU=m2e-0v!|CRaA`uNXdX@(B5q>S%?Qg@Rhih4t9Y(pcZhs2{7O6dp__(we&}7`_3t6!&4?(l48-0J(e}745z#-=`fprX8ks}A_+nuN-iPA zV*K^&rUiv7pD)y^7Z6owEKB5o3xrbiA7K(J!r~xUormRnv5W>|nyrk2j9jtVrmu691J|P)0fRofXrWfka zf0hbgg{u$>QDf)LB*C^Zj;^wye!s#IioG|NF{0m-m+g1>Cg^dj!q;@<}Wcn+Vej~hDyE7L1*?bah zNM+X#g4&yHKQSnPa-*dNviFbVQ*kpm#s0aO@Xhy4szF@(&%ar)hJ#p4k?_N}=;$ep zsf&~T)YU&(nszTmjmFZzz?&|4KxG6!7MSlqo15SbWvJEvIew0Sc4Bj+gDf6qC(>F- z_>&t}$cS*!{o#n@+P=yhn-?;lLKWcZuT*Gd(Plc~OXVJ<;itoTj=_=8QEZN*h_Ag% zc)7T}>6OfBI}9*ga#W1+>qmM~(79}zo8jg)`3EDFn5?7+qx*SS?ASX+eY90wzX>j% zwjFb)_{Z6YjDxv!`ikW-S+6Oxhs|zD1_Rdc8_2}T`(izHDG2_Wi+AIX%u3rE&&jYk zznE&`A_3yEc5jg)%uYx?(o(oJ@H=8wq0VOyGS|ME4$?xT_eBuir@GZTd1|=mj$vH+ zHHUGS6Sn=JAL1^H6tnJAPUD2SFnVx4@k#}$p>fA4W_U~f9Fx>=zy;K3f;0eY3p_n9 zhg;F1S*fFtWgt9(+md8n;WZ%#JKgHkoKjQ(+srhKsfHSUXE#FhV;zMGB-50`8NOz# zkJ{c6k3K0>{`k%ePdkv~UKB3!2T_|G3Ism0XJCY(O>LGuu9{~VX0C-b(~Ls`ERJ6B zBG85`>$I@I6vIAJPgk5vS_V=PG{DP{?*>LV$K!*%HINQ-St%*{OUDe&$p$~0*WnX# zRsEPQIHICL7`&;*0~>x@L#^xy*kR|THltgrHf|wT_8=wx^mkjQS#vFE9Fi!ysS@Kb zLcCVm7PPf}O?d8&LG>gl$lYD8m#AZmgMcAJCW@L_igZS@$}!njsAqI8G{X<26JaaP?JNU_()I|IPwh3Y zT50Wd7N%T$n54fZH_rE#w`b~Xa$9=-!FkRU@H$*aflhQGtWe=Es2bpIZ5v95_cKee z5{YLbG?Q^=-T8K;&=c#E_3v!PvAtDD46NMe=+~Yb=JH)z|9;JD$$*5E^wySW!Kt?) z$Z7qS;!Su>`f1SS!EJS7&2s)?-_MKM^r|d(e=F$Sndtwq_MKr(CED8b8X$m@fRrFu z5kjO20znW^6hu^1kP@W#BE2gRrOQY!3MeW~rG*+wC`#x`mu?V|0Ma4Aw*$^Ob7ts>25`9pV>mE5{NfyFAP;VMOz#XQ>Bq)68h|CA=)KzB8OL^ zAJvu_WSefEa9`Y9C^bJ8boqUkqL!Hqbgv6}9TRvpl%GA&|~*)4bk~ zG2Dr!O7ZWuTOG;kB7bAjJO%5mWDC6THGA7_p#=lH@O9@ow!Gi9d!gw;q2~rx&mud@ z1cjSuB{{GQod{c+OV{nIxM`8Coi5>1$(J4V>Tt>qgiQ9yFsriEzv!xWvc5CZ;YN-lbj~z=KL#apZiHCVy>a!p7^EdEMDT};@Za_PSK!_4? z#HlY1V}W7E5>dIl3^kK=m!EuSSI|~F(H6}+&nwY)0n;2E^t{jWGz8i}coyyzIHz3+ zVkgA0w>5a9=7j~>t0#40OkR9|QR!w;RA0IvHe-n$cW(%zl|#OgN@K;fIA=eU;awg# z6Xr1Zp~`YN?Rv+?^|q?@9J#`;3N@#N(;kt8Xxg4(M4zcD9116%maLt75DR|&217tB z9Z|l9>TBs_RWe>yklFkeGZOf0cqQ(co-eaqW7vhYFM~hvU3iWesC52-X+yE_{68+a;+?1 zta8x%=6i;+?fi#T17Ezy6jma%_0=v<(J3s}y`hq63_X+yua8?iX4j?T`&n4`!3!Dn zjqz(x1Ny*wQJSap7K!CPA7hj*s~8td$FmM?8M>R>X@QE$$0=pklu=K_hWd>swS%1M z!IG0qHszGg;sKglR1q&l54KijdE8%32*Of!7b`Ellb*Z&gQ?}nRZDIrKgXxcNfYNz zrajTR{7BmW;yAR>JacKA4N1qc6p>+2qHfBqCYMTlC3$Pigt2GKS&pSj0U2>J9`1m_ z8&>36Lt5nzbY0_2!6ZGUmtx4Z-Vp14c>S_tR#G9So=Z=tT$b>i5^_#b zLig+Ekg4l8r0zh>4Ms&f*DB8`DIzwU1hzWPDG{Fu@KGwAL9AU6sPq**sxWUcQCh35 z4e}eHci>xqcPp+5;oG%9em(R`?`qn;M(+cE0{=QpuT)agEk$jo}o>S%}3vUdK+)IHP=VPi{g3@>-kP+eg%Nc>*%A*s2n zr~Jx+rPeOJCod0DJuZ#&I{}#tmI(gJq(*Z}PL6}Xdp=`3MDH8HM%aypLpM`>tJYPT zPw#N?ouEhwmoC`^Y5$tpI1$)lUg}5ms5G*!>|1V?S|Q|&Mgwmc{g0ql(U|AQr8p!6 z&z%%iba-TI!|$%?YcySDQf#Z5HuLpOY29SxdZ5CKgwIse9j3|w6cQ4mLn+Khz?3HC z&yRbR8!trt_R{>Wqw%?KFBci^etTr$wf6Y7k;I#W90hi+%l$T9PKlgX_{$%cGv*x` zKU2H>Old)ofR(_HR1gArXTXwww0Np66q9XV~Jrg z($(Jhx3Vd26n12S4}UsiNYbyqhE%~&B^@4lGicqPUFt;Sx}Qbejko6t^pBlN_VikZ zlgm{XzP;ayhJqrN?Z1^P9tsKy4_mmAvze_6+}*+12Ib&jL#|a~`1D>BtP#q-ju$Q7b6Y>?r;%4SR~1(6EHQ-gW)aOtE1v-k}Jgtb6gS zdFd}NMTl`K&2+T0|5#aANNMu7bSYuU*o2VmJcm}PkK-S6bLu7>lrXm(wCI#Y&CZk00XhAw62X!K9)E*Iy zpd<27Cz>V{HON82%(B1;sS*C8;Z#)HDYu z7#J8RUaM?e1&sW!{|*2WU~v~q6KAu#x~|Sv_7*N=gFi{=)EX2&5Hh!V;Cj}ba{~uD z9t>ni+R=3%N7Kz_Bt<(7;p*N>3?6aS^Nv#(NW05=kW;VQUu@8CYO-|m%v*^v537%( zw{9MbNK?z4Fp&f&C13q!&GQ+u-kEJVdbazBu3DH?5k#y!!8bv6ivHQP3ae}0BWX=< zCyFf-`TshPFDGV8??q zIf?l&53`G7_8JGnjU=Xyf3IhLxXsuZU!g9mE;uNEBg0OoNIdmTd>^*dKC$Y+yVp)W zZNH(~>hJsL6@v2$77+ME&IgVKZA(&M-<*UwJp+@oy7R`vuk&+tPFB45RMfSYbi2rc z@2zl!-+>RVGY&@2-nDkRhl`x2eazCV@Qfw>_0if6M;WhZ9?lmQr60uWt}c|B@lJUc zaGk67Nz1Pqs$28AT&LtOIHq|!;cQh`9ml)a`Lka>v6z_~pKU&vS(m>}+K5QP+^Th6 zy@Oc0E5AO7*pXmbio63KvT?pHypn z7j%1mVu|u{>GsTH)0uXCLs!;rd#z3}z1abWx3Bc$4&n)qiUT24nm5nGPw)sInY1*S zK4+NVdq}{*(WW7@<4bCdGyTv#(Tl4k&bGP&muTO&GF8JvTWQqVuHQHmW>-G-`sES- zE~+67dqouYjojLm!lIVdcJ?U*_nP5_J3)j~MC}lmtm1j)BGVwZOKN?S*|)sh&Ls)Y zUs`7ysV`)5^E=;}KcS1UL5}5n^dQotY738g^xS>m&KG!xZQ!W`gjKxfjMRyht90@k zX3QXO_wDf1#X>AO>M>`oUMQlXpr8Su(cecsI}r7E9Zat{J2<+)O&y%g$RY20wMDC5 z99+40FlH`t;x{gyBd@MqDZ9e>@Gw|r!d6#h{AS7KhIfhu^R*#2i^f8DQ=!T&5BUzY zYp0bzvPIKB)=P}`3^KgI>=Sm@G!cJO=YmEDJ1FV79zu`3K=SPL#lRA(@Tu^uhnR~U zjkgc7qt@syn)_r&M;hpr-|cxWckIyuJdT?2zVW$>Z%&!U#SDORYT56_aSNRKbOREh z+{k#~N>EYAmGsB4Jwalv4fHH7FHQw3oWvZTeXr~*jsg=`z5SJ}v-15f4#!2cx4yjD z>~)>@3Xgk)ssVLjv}YU4x@8$Z^OfjVjI@Gw=<|jnstjqnkEf_*PJ3VSt14g_#B^D; zrg1il!Ka<{j{3@~U5P+?jh+0*XiOiIK9YHLEL|YcZ+BO% zB+0~V1yrZcfUo}EPvAfL$;8o-?55P{R%^gb59WNCgq(}NKzmt~Z&;pCpdGlc?ZGs73B4?h<0%}C z@?YO`bM(*4uWg{qWmCHcIn8=kGBnsbGtaKGpNJ@5;fY)E*E+JM$099 zCz@(r9HcJ$76~c;uJ4sP@#+C1n-#HfKjA@~seW=PMzYkh*LJr#jMr`_d$n`d5bL4))0AC+~UX z>)6XqbL%Mz#)!n8**q3G`?wgpMe3}3e(|tiMQ@kwr>Z%H&Eg8#aKEEvSIhK7ET12E_vYYz6%{pZ?A8CQEi~ zWmW&<$(|?XzB@{^5v!Ls&i;16dQ-feHPp1a<#6ng+cB566HmPQs67&+;z83U_Xe39 zqXRi&<>Vqi+G2W)YG;nk-+yyuLWYgSZ*#ua zVP|_`Vs2+)YgNE+ZFA6Q#Al88dCtM#d+nG~mG{m}aunOn;+DVf&KU42wGqe3K{IyM!QXRnVQgNBv^6!N zbk=P%T>!GYxv-V&uaNR>V&Sa3>RgLb*{c3r$6Rl^zsC--z9L=GZ?(R{2+PmY{)4pT z>70h$eluC)=exL#-C5Y&@v>%s{dxos?p9D;K`!!s{;Tp-|(0sRiQq}ru zg};xV9>1UE4K^jobU*&>#m^Nx+Yc1)-SPdgv@WbzRgcB4FBL8>L#ww4t<+mngYYKj zTLtO&;X6bbf$g34tBPCo6-C;4={u|HGPP4tt@q~&=5X~D9b2S{CaeZ+ zXSpa0s~#{~{c6>taVm6dcL243#?NVfN@timl;wTzO>E>r1fu(2?!`wZ!XX1_;xO?ru&l?W*vIsw@69Y>h<){OrN#(bpK6K zx`5*LW^7vM&PoB?j=#-#b-jM0sd|zyqiJsoFWa!+I#xNk0{kHg_uM8H?MxUstu7yQ zUx^(`+gXbr^7nmTwJhxJUw47Ox_Z2J<5826^5nvd2*1(g$>|x9wA=#B2B+ZyY58FL zN>m$Rz6m?&wJb|_V+EqH#aQ4epit89vTeV4%*UrEs?fsjkmA%_kAI`5B5QiF-3D*9 z{1$h?x~yMM$-2unk#sCPeR+a(Ymly^-og^Q#c8v{bH8PP|cY3^sG6o!BL+woZsR?E8y_$&)90uowB8tF#oa)53gl7L?k^Q z6;8c=b=zb8#}~f3+OY!yZKUoN-*Ot#{Q7l)?ayp%OX>ddd^XEL{ObFg^{o(*fZ}ooL1bFfdto6FnpH zTr`6)-38>;Xpk`d3FK(Y3FUm)L537L$8R;SsIysr7sOJ^9lzDRV$R;bQ2UBLn?J?N z@!P%y#gq-lZ}qR(viB|U)L2nuQ>M^4?q3j033249vtr2JzffyMlg*x@=E$>e0g=+^ z$Ww0x%HFq-RAWVz&6sl3asR@JloyUkbyiH-`xk1h=(4#}%pH^VEu2XqI40Fwv1adE zxLspKnN6F*<+y(VB3o56O{)cW^a|`|PB9!^qRRgN|Hz6l`$$ThYprOr_bqtc?>>|=Ji0`eEhAf1JI$iy;JA;EdK_=p zTd`zIrR-mz&SpuGb{wd&+P6^RI8bNBoGqHNe}O)mFU8Gqpw?>N!iwWSy%k%wLdw2{ zX^L#>6jn#Mn*9rrj&gO=4B0{{`xai&yyD2c*m1H&u^e_I=oX{(5zG^qUeFyzuOn+u zU^jzI9*V36nKC{;ax>0MYUEwA!>zVb+bR8?MbXXmI9gx(uVEq^vEV%u2n9as` zS~cb+-2Piw&c=9tH6|BsKNB{yF}lq9wxFm-d2q%g4@rA*=&vvS7R`6dtjx% zIZmv`RKo4&!e%zdx2rKVaQpc%5z;s-7K4M^FN6VKwc^KOn&I|8!g5ICVpt3wZoe2d zLmF4aVmjdVOJO2g<62nEN4WiRn9bI>Ar{jIw_gd%*&4UUVus-Mt6?)+<9=AoDBON6 zOk{gJ5{sFH+pmY&Y>%g5F<;^K8(}%y(?2NZzF-vg! ztuULN@nI}x4Q{_3ma{WX#9~Nr`<<|vo$+lflmg62fucd;DbRux2wGSp1&%iWN&}9i zKpjBhsn8}A2o_i)CGKnhlmX01i4sQQY0%Fo5C>t6R5*hGCCj^o2tHUN zHO?mh3I=mhp;VE02DBh0;s~sf2A2{5JpcxNG~*f)&xAIiM2Nx~X>pYSP$-y_8g&M%>vz=y5P7Eh-C%KY)Hlg}4rDWWpH)LQjEXX;DQ;JQsS5 z3ULS4$c*y|go=YXf$u>g@ldoNHSkMkjUZe~AXE|@ONaW1#Pgs{s1bIsMiyLUAXFC2 zNspRD;(5`}s1f&IjjXt#K8aTBRlSF5L5%q$%qnG#tWmL(IB3{8aZ$VLC{O!SVokj zGX5xfj0TYkYvjcF1VOKWIhjzZ%J}1GL0ZIfSmOa)N)YrKIF^*18^)e%2gRJh909uRKXe{I8qSQ7|aPmJy6Dr zqXp>@4X{Qij`u$FZin#u`K?X&opPmo%f$~-A_G2(k;{csL$={lJF@V23_Kn`{Svy`#bm#R zu6CdLHFQOO>etZK?o+>nu68lmuc52mr+y7xk)QfCbhZ1`FQKblO!jN&iu}~C0IPo^ zvR^}22-S=zz;Kc7?nw#T2)tC}EaW*V$bDU6(DTfn@VJ(~EE7h24 zIB_nFnKVv^#ni!x^I@8#aV{*T5l&nP3nPsm#bQ3di9f2b@R>)7%;F!D3e6#I3NfopAyd zvjHb=hqdgCuV69TaNKrbdAS1wg65x)dl75>JU%ra&;l)F^SM0-$u@ZVD7H z5>Jf|q(HF4)TnTm0-#J_T}sp`B%T&sOM&2qsZrx>1E8$nZc5ZyB%U5kNr@1IsnOuV z1E3sWT`JTiB%TqiOo=!FQ=`S@20*#M-Bc(8B%T=^NQpqe)aY>d04NVwml|b@#IvAl zDG_I2YV^480Z@K$H#N!!iDyGoQX!OKY796~AoMU;mj)G%#IvK7sSp=nYK*v3fzYGi zZW>ey63>Yaq(bPx)R=IW0--0ty0oZVB>o_}mI`qTrpAo34TOq;yJ=CCNIV2hNsTap zsey3efzZ=nT{;vViRVTuQzNWkYAm?iK&Ujhn+`RE#2-QjQX`yTYOFYXAXE;lOON`F z#PgwRsS%zqH8$M$K&T?Pn;u0%;swx@G>AZ$8W;x(f}R8GGN3@pctNx>4dNk8jU9I? z2&x9|WO90O8VBxD5cDEgml1VJ8Gi&_OM^&+sd3_LgP>aAZbsBuW&ANT zB`x9^Ozi+JJP3LftjmPDq>Mj-R;ER~f~g(E%81t-ir1`+*CfSj2E}XE#cKkejK^y}j@Rsp*L)YR z`6FKQQM{&@{-Vm)z#*h{G+h?$G}0@Y@~-4VAuv6Tw$}5Eq6P&=kSYwJLG?K3F6@j3 zC6$pDqciO*HM2<_(A@|K+)E84d}FUvRT8qiItwSVD3 zH@lX)EZ>;xzJ((iPmHez-MF>VN&A)qfANY)Z5~Y-$M=gJBDDoHwHzQ#gE9!OX7s7r zcc*gJ<39VeI9Hp=kGxBB=x;AQ_0>hi$etthOFbG*)X=w0uaxpUa3~^s=_~Ps2ZDcS4 zSzT?Q^>ey!WH1JCUu!tx=M-jSFacRzYdG)c6l-Mg1>(NmVCLtPY-BJ6SzT`k_H)WK zGMI+AZ!|pjbILI?n1QTrG&J}*6&e}LLfkhSzW6y+7#Yk#RyP}H{hjKK3>F~nq=qB@ zPAx_Ti;z`P!+C$FZX<(bi2GK9nZMJZk-;itb*mxR-)X|gU>)MV-SFJsX~xK46SBJ9 z(BSX1Xk@Sjao=h9;_tL+WUvES-D#i*NT2`KI+P~wmQ2@GH%O4Ly#h!*{d0>K3%P~nUN5ZN8;&9<0SOjjK+!3K1kopG5Fs!E7zYbV zPz7f)ptzJlLTD=*L?n#Bjzb0|Xn=(nQAd?QN6@cm5OFX92hKPs;SxBL5hbk*I)W086<+XqDADx2nTUBK?yg( zLd+<0WsoTP6)mC!M&QDY1|=APf%(Ht83ad9(;}*21PG4eeu6Pr2!skz1|iTV=n#!C z0u%?kfAm7g`|d|>1*D>k&r=g?KN6Bh6qN|(c4u?HYBmsVHGJ^6(HZ}!-iIyfV9wl) zoLQpf*@CYPT7gyFgu9A`fYf;@`*W>_eP>we<3uf+#s2efw-4V_d!|wsNEwj4gB1no z1-ESCQx~39Dn9a~`83gaHYl0Vnp5(q<>ijVr!uw1L7g-lXq&W%vx}~inMWxYl@CWl zg()v6pN{6uq6j8V$(Q|q?j9~IQUWt$Ji3XZ>%Q7rAPTIkH@kD5`ub@@v2Q-rcj zP#aAZBOPb>(P*T>qU~fN@a<|TN(}~%Kpc!wgXwYLB#f5f)GL~@pldLhXr4Lk`$=3< zeAZqcK`*&mdDP7#CZ5u1rA}!bi(Q`o5W8HHu4VV&aYhf3I(O(o<<=)1V%jR7NjO&{61RSRjVb-z=f6u4qja4Hl+)sLT<4K$!Zy zG86db)m^}A50e^Br;`%3mixH$lKYB8l2jy~r%9P5MXo(n>&48%lk6F%+Iuq#4eMS- zt)boP#@l%#H&*9`>I@$%V90E;4_BWJqwOE z6DK|a+EV*U!;K&-%-^?IF~#L?j3m1qY{F+eOt5!fj0_|gP1pJL8z@bzIfuOsU9i5? z8+)%jEt1})JT1K4e%S-MYGNHUKoh}uo745^*URDw#*%?F<4N=d1p;+b^#}eE1z9iu z_b8}eB7LY|vgJ=?94cH^_brrCduoxRpVvkhvE14Xf{FJSGw7~eB^)xuY~%4ogV6iV zCKa}~DoD1;v4qy&#yiKd`Zr97JhNgizIV~+abAm}_Y!!1^yTG_gr`!<7D2-__ZihV zHDLLk^BWt2zKR!hI0GKQ*fl_p1F~S;8mw0XkjbN$!P);)jyXclybRQxD(ilK{7!+P zXPlo`?eyC~jL|~`I5PYGdaFuLU8n%c#d%Fro^B;FC)P9dpx7+5^&W1OLv$8+9p6xb z%RQ?m+mg(6-}6Syt^L;FJr$j=;+EYU3?J0_k^_$z>YZKylhUB>3UY-hG*g@o(ohv^ zQ;A9+naYg2PN}1DfW1MLQRm`s>|a!A*?k|KJD>R)ZLcadQV?=oG)L~naxTwJsf-VA zFNudmhI~>Yt3<*xcaxb%FY9V%w<$`4j6oOmfZ1<2u1-KM`k;UGgG_tOrD{a2P zXQ6mkgJkRqW4v3qxm^B=jSCa}J6Tm3!+2@D`JwTP9;SSC1d!hWIlEE?haLh*`cphm zE5G?+v?cn4|7uc!k@q0A>&OEf=T#9p=YHcbQ$3@jteT#2rSs*Kq&OvanD!b05-@wmRxplOzfjhI0Uz2?O=&Rbb#VzZbpWeMT zz25#h@Vd}z-WHPc&GUn8xD{6#tlJNp2oG9xMG5WWw$RycmXXFb&Q?`27NOW8Q}J%6 ziopa450fU#7ZU{I?Ib&^rn~u>WmhVSOr!@p4AyT;P_9_fBy;vXrt-FQ?@JVMfxLtR zr!1eg9MjFk52OCQn_)Q2UM9~s4l4CmW7rl)&5E9+Cp(Rptu`PtiIDJgS9e~5c#w_lTxzlcTo zo|YczA>v(k|E#5_s-n){dAu|8<9o1qNBDKV9IqQJxjZ^wZXQjjKRMu5Id#2T(8ps| zFualuUEz0$cqzMyXxnD2|JmC2^j!D`^C3D3mQ?}{1d$Fm=OIQ~xX{3D67W)zQ)cCF zOr(1|4APsiTuIb@DcGpf*|TjT5>rlrE4wMgwraJV^p_NB7W(m!>hBE6|6GdzfBhep zG$dPcAx-b{)SOLdR}b1H0ApigZXI>xTKny_`EL6V^R4H6_Y)&SIqm7--=VFpL&oIq*WEv zQ9ZzUMD>J@+Haf(RhLdM9gKK=xSU<#V(KLm!l#>m&hRF0L#fodf>Z;2A$qFu{JhTB zpKD1iB^IJSYgRIxEZbd?fmIXr!BWKYr^q^uObD$yIevDMeO>i$3ue^SV=4(} zWd0D3iM#PgwqoeK&9UJgjcBqJZEZ>stMzAX#;gl(Ip75=-qjv2~93$b)qY}P3&rhxlShs8T_h}f>6>rrl zOY|iqM{h9;_zf()OxX>|nfvQB=;wTyiIHof*U3uuI^B~Fov(}RH&9>PP#U?J=`6B% zbuHg@zyUj$xGDt0?s|N}H>nQ&VZR>NP0%^>2aj``{GK=2^ET>Vq?-YcAF^qj87n9x z6cBQQMF^<9yg9VkXtC>Xr-+wByCJzKb9cIntfPyB+{n#BX9B21?Td71=9w+{6{8>n z<=2~?imk?~UywY}Tv^o9%5>4}s)wDO_<=ld#VbZNJ*+Qaoml9gpLx4w+h_# zgAghg|263FVGTe{yY;;8#NIjp=&n34Y7r&F@gZU>TpG{_0J@C|V*sE?j1+NslTF6C zO_uhI4t9ZOOh4sgm{VN`9ZCo;PsDz&jl&k=f4ram-!a91I+_l8?5CsYfTZ4>u-J8U z57&rXs)ueL;O9I?6_iy|&9GA#jp1J5HuV$G-)%3Qq{A3jUr(&Fj26+jr!<^>BD|9K&m$OrjP`-Qh2fl1s-imTA30f6g`!QlO;Su)cPE7t zq;rPEsPsApAe;5|eP&$8-5wM>7OOPZ06qGRJE`c7nHDg50g0^dk^|e#6iY=>1z;{q zo$}ak8sBUKJUrVva~jAK zz{TFuJKOx^Dckj|vHI>5BjolG0F35Qojw_xJzQ}UKy?yv@8iQKt3oip7sC+ocmGG3 zY-91I1RXKJ3s8yE_!gmJtw0uz9_vNqsmw4fUJt7~(SF0K3~TJEgjj%vpe$04tRq zIkDT5i7N(CH~V%+eysfQ-AwkV@xtxl*oX4#J#oNqRRD8sqCCGeL9Lng+g_dwWOIk( z|3RK`8>blWaX9) z+Us{`wLNTF@O-C|>w54*3*jxx%-{ETlNxPPXyTcF-wEs+GStiBb|J$tQ;$_ZJH9$V zySAj|fgdw*dBHhbwUvY)@ou2+eD25Y65_}c{&;`v9-1i>->rd`Vk-oBeREc}jZ?&n z$F{U)gow;4Kart#dfi`nvR^CG1FwG9ZDk-Ie@xf|XmZqWjBK{^|x>B zj!{lgc0jW$EHgDoTn%WmiI~Wtu8bp zoN_;$`>agc$j(AhjfMDoe-jMv_y^`oH0J#Y5d=vC&&v2R$e96{kFT}%%PnR-`bF>X zt>-M%-t}9xq0031F zyZqlk)v@AGak73ygo7lXKu#g>ZZ1&+KCQLJ&F6g7-c4KYeK@>!HDqr;8@30fxu1|B zR(|Gs>ZkSIbEcqVi8YWhokrCe@nRjD5pM zVcYP#NbqcKYv2I@!~iM^h=E!WKy04wjft;gCc}hQBMqPmqFCATMTi&EsmT5NqMH9BMuE?0G ziS4^$whh2YA^~6+cg!A|@kH3R;Acg#DL~Hjq*uorfYdkR1Ib(nrBZ~+UBbS&kbe)y zUe_u-6+;peO#$+Kc=7dn=rGpJ+&=0!Fu<3d$3!;OfAGnDQ|uUgHx655V(j42=MYi1 zH#hl9Lu`N2oTo0ulPSdUlKEk-L>Yyl>V^a^~Zk|De4n z|3!PzVck&nQDl~(lok^ir(U7Ytk+b?jsIy$^+hrJy`0gj(D24_JJYUA0xNw7L-t@lFdj1riSG;c?=rD;gg+99yStX3Oe|l*pwMNYF4_s^Png*F zZB|-{8l?6R%wFszjcj6jCc|!JJbaB~Z;2tGo45zLR?q#Y5|t`#+Co=!O&?IS^AHX1 zE`eBA^X4V$b@yXwU3e|+pz%?x%OJ4{dTFG-P;!> zZ^*tj;KLiWirNC;mEX<$gDgPdBwAsl;QHOcEQMtuX#A{QOqqgA@SI#W=UVuA6OZ3l z19bZ=sk?nXLzS}cM6;^)xPY%)2(;XJcEP?_!%IK9UbFI!C> zhV8@2UaoT7Wyn9UAn0a6=ZBS3mU7NU@~~2MM*uYpa_BelVK3AJZ7&tCd2x4aTEIvM zWF6YAIQ)?Wg>OGGVMQ^yaF+;)`Pi|S@vQ~{fLhn%K3uZukEkYQAE-t_E;Zcb=^q$5 z)k$!f>adF>UwvpVe|>Xg0A{l(p!2SeEgPYb4&d3pRi4HYy7r19|NI+(8wM!s`u?Fi zzhj4vJG@Y5D;E2mC{<~rM%RAD8Z9~+< zgXf&&iIgKpw5Ete+hI8@(tVfE1jagd_D6p<;MWD+&F}P|E&g^JIg;}4f(WpM>}OQP zI)NP@vD)ppeN-+3kR2gq(sAD49`RmJ2gT^lJ^Q7#j_3sgG?xUQjQL$*@=!93QIqy0 zdw8Ogx4z`c5G$}td8og*4*s2)A+y%wf3DPCq%|#baUrL_+4wB9zS<*&_l73+7?nwm z%eLA;TUH-mVR#gP@wWNR#;%OgB*Hm0>X1YN0HT4Oe0ve%$V{f-n)0}ff8vIbh8S{v zag$VkBg$Sn0V<&z@1ZXo`Qx;7_Ad=NioD1*=a2jwTD|(re+-?6ozVsv4`<(l6f52M zi2+X;(B5z8%J8s|V(WW~b9nihumRc?w_}$|9Ca$1hl%Kjeh;0ByD#|cYhHv6m=(_A zUwOYdGKyD!9|R+|yB4*aQ-S(Va`a6&>`y-+`kF>qf&Vd}pYV*apG9`Db(LH$ zp5{k}TOiCq^EVsYHNwX~($u>J8lcg2SBoVa=^aU zRO(|=Qb5%h_yMN_fWzBFhBxl?A>O&4&1=OzYT5-`t+__!z<$0rx-`I!T^2~&hC442 z_nqGR25$VmPNoy0`E&c|m}qi8eV;o>=x>PrzX`(oM)EZ7NCsA%Lf`3I^xGisp1Nfo zHZ!9E@i$z4+m9~*TW&I@PQz~&FLZ^xH&7X-1h94TtfiK*4V8UFi?KHa(c`qkK_laT zZE0&6YW_UaEv-$bh8xq3{>{0_M6&K5xmBUVq0L8<`qCmt>usWpC8mMbZiF^1b+~#Y zEcV_gHgt&g)Bh;;=0;wdzDuFB!AG%orSh|~-tk46<^yBw(bE}j{RZ-jtMR~4;_^L7 zcU5QXT7y;bX#os%{~ljN?EWbAKOA9LxShWDw?`O_GTDFJl&Gt+#%M~uRY)x_NcE71 zaXBN$XN_A-`B>wU*-Gk`y)5i+t^?;m0L1{1{uLkqV14J)USmz)?Z84Me!D<5345%C zt%oATGqwsNBK1Oi`=T?jkQay+v3|Wt&f>|xWXTW5cRz0Z^-kpCVe-+Mx1xDSK-@_pfX2Bkbh6 zhCg+=x8bMuLh;h)2^;$1NQMwzb`SZ1@tgE5^~dspXIj0?6kRNK8S3J5UjgSf1MsV0 z{`nG+$SaZAi^B#=0M(j2V=4BO&u&3xvF(x*#JbIRvE>r5K^~uQI)C||(!eH&?v?VN zSIGNvwDC_z*ODE5n9Espd)5+g^eOGMBCdRa{8D^V{w_h7FHMMd1ZZGj-kT~eyTnVz z`>qBi)PUl^9Pi2JQ}leKgpisxF7`2{mcTgxta5%TIRsFcONailEz!E6nDdt#mTMPO z$>(Z5F8{ftrN#r86)1_olDpeM9d|BL1Iw59R@8t-Khq(3tFdzP%}esNYMqxd0J!ev z-A1Am5N z;^u%=sn9t=^{mg4Ja6yK!6H7qlPMk)ozuX&*TP-kC z>iQcIMm|1z)?!Z+S%8i_PVG$gF?rea56vg^(|qLp`yb2)yfcj)hy5vudnEcdW5r@= zU;+OQ$m+EpExYw*;=_bNFW?v}Hl){)Px_8|!9?oyo$i?ou zSZ)^K7he>Xdp(`2A0J9Q1$5;i`GjN1Kc}W|VoC#t9rRt2GcfX!jl}w$L{mtNjL%`R zmcTZ`jotH~X=(mb%kTV#-ro;%J4@CBUkpVkN^6|#G@qgJtA<8`Imb{ z{{3VO=TDcbtQB)Qs?(@MYSi%A1?E_Y8nu-`1j5PK&WylTmOH&M?l4M1WFKj?6e-2$sV4^&!%Aos$) zf4*U}m@`eT;E8S`i!stad$pI6(g25p$K*yQzo&eDE2MfzBt1mzu*2>h;;!(ocSMj0 z#GUw3dHt)`ZF9Q{^N4o`a~dETlCmHOaTw5 z44EH&Xp)s%kgb{Kf^HY(R1&|FwN>NGlxxu!ubzK>f#ubads%6? z>5Jtt#H^Sl*yX2H$BlE1H>s`O4z%!)X4x?`g@Vy48EWrrA=5f)TYetQv(&}~u4P&f zTh41n>8{VUN*~R7$DAy1Efz^lJ!w}kA1Gv(JjcmVe|8qAjp{p=&5m4b8DtL z6~8?sf1{e)M!ivrpK{aO_73-~7|)%rJdN{9RDe`Mpdl(t5#WmQ6Y$Ew4` z8%JS!%`DEL;nDPWgR)Lc2e@30k}Z}ry{2_ixlixIBb9_d(o+p!QnDY3Eci z+~7#%yC-skC*KA>(JLQ_vA4mF${0@H)|1=RDb}3qOZJ`7&uAL%q4e|8{9e?}c4G&` zZ5X;KRu1*PZy+es%y;@6e>CIc7g^M8QVQcAyTWzOyn;Q+dUP$8=c?v64TXm@iQCa_ zS%FJzJF<|jC$2)DF9=O5Cn3Fc-rjt-Lf?fdjz7OTXzIWiq5=z5WiiWZAjX~+zgh6T zu{_bC(ZB*EG-&YuXnXH?tlu|$xJ6}VMnWMYs}NaD+z3VX-ZxoA_DV*`y6r6^mAz$` z9U&@igzR7%~%dY;$s_xxA)A6?@-j^jMe^SZ8gch-zKY#SY4zm3%C z0Q+YUie9b$0R_3oZsVPp+}q&>E5F3YPqBhYq{18DJu`=QrdUh$`2TQ+B1_D2rDQnRhB*Y7J&`nc?R?GLuEHCLxc^zM9z>g$x0oKH*>0g^_)7@ zTH*S6DT-Ijm(n6Xp`1v2c(=|bNFAQ0-+sWA#y%}k9wyP{$>*_>@;KiMOPtnlkNfFD z>65Rd1W&FJ`Na>`Ht7oHmIPr>T%U;G>Y1)3)IKm7k@IPKqUl}9%6eKR?ew9IID^rM z9NRRFUhJoGv7oBqDl0!a=clCo;jYq9sJo$1H*IiL{2zz9P_<}hAC2HpH$tIqxAfy= zHPX$~p8v2h8*{OT`lfl#PN2^eRFtW}Wd2|b5hWRhUPjL?d~z4K2juQ!<-+>l3-A@5#4Sk)OtHft(}Du}#bs!mIDo zvsj&ZA^lIe`6d~Bxpz;wVahQP+9Ri+6CXlsmiM+FN_^a}Ct`?X(IpZVtTwWL7B2tR z3F(}|18a6RCep}TrCi}fTvBlK$ZSN8U0PvXZJ~an2KHmc!NlTw{M?5#dz-E`3idJ`n%77pYg$;Ixvmfz2_R0ma3uu zQ;M3(T)Bko46KUsx&q~#F1(RK26=wiegRkB?w|mNAL&-L-KYyC^e*=IaJlN^hP3hT z(Ho;F`LZ^NbAq5Lc2?iIAn|{?kuyCz8>#lVM)Xi=ok=qhw_E=!zbsYE6}H2kvL-r( zAwP`Y+cqB4U?+!?%SCh!_9IBs#f+oOMVuxeJ0m0rZaoyfbO`x#V7oYFE#iaa!GPkQ zZ)lBGv7A$;d(@6%0_u*B_Yaq1~#k9J+%9MzOm=?Z+v z5}0<>^bl4Yr$3D7A4(&>+C>xe4$IybzJxN;p>_$EuSw#zU{Qu?oq}%1KdC(}oxpX? z%wil0b$?$K*Qwlx*^CKWMMKz6%^JP}HC2%x`0m!P3@;piy5)&K5)chM#C*n6l)xVe zMx={Tj(^Vt4QMM%7Ie3bh~YV-uLzR6%og_l~r?J;Um--&^-36Rxwa?fdz4{W7Dm1MOVJ zF@qyS*4|&v*f$?@yv8gU8%lIJ_`7eIEU(0P+GEAg^9r)}BspI(E;HpI*Kdyar|+eX zSgD;Pv)0deUpT-AvoKMb5Zmkzrx~>QkLey>gB)H72VD&~$=o+`C&+Z+?FPWqXec@6 zY-~%YaOcG2T)_mvw9qtfd zIkd(>LNwIujrw>Aa0k$-SLMw7rz1crYpRqVs(F=aV4Qt^qtB85i}YdnYDY!b+dCaq zCr4=5puY;qQ2yaO@ZOUp0Am^HZB?tl0z3xqogcA2w&&y`@UzFuen?!A7t@ z3u+_2(yNXrp`gFg>>*IOf-UxH&8RqzefI7@a#sR!d;H%bx8i{AGS;uO#{Ge#!|ip} z%G*5SH!)XVF;3dYgKxA~+Drt+KX|mQGavt)@x|5`RYzo&7B%CBQ*om(a<=8&^#EjA zc60ifnjSkfR8Rg^n%jucLfzBx_b-QCKjdb}l>b-SiAmqpJDRBA1l}*l__lge)Jp3` zIt>pY`_hmUH*=doFiW@279gXK}O=S{AK^X2qN}Pr)j^>&F*9rlEZ_{h_;~ zrRC36?mnUHi4y&M@#jGVC1(BHA&!&pX$40=5Difb3f@Ar-?#XA^;M-!cTRj~w`KH1 zLZR(=QQ@hM%XeQacE4U7;lj7AJg)i@YkQxWaQ^V-%a-U+#$V3bk59!&u5~fID>Y9> zl`HFnGG3JPfPa5H=@hW4~J3U;L;CB2LqV~Rl0A1GMg8FfGkdRrdhY5SQanFzWob|H)xSa5Q;dmxwP4FGD}Oa^J2Hdq`8)0 z{?Xg30enW(HIr3Q_G(d!TBG&&!!oA^5o_|17o`yY70IStt?@5M*`6cxV)8Uq&t{P; zAJ6o@RI9F+kf$B3`nin5rdket22+e~EqG5YtS6vnua}zlB+swpwl~(B){FL}am!Lv z6Bhh$0x6uW)*LbzGXTle4}~1g6Cl)+kw?OfI-m(gXPH0Ew{P!@unDBZpO4RGM;gAs zuRx}8w!Um}>f*X~bj0suZ46&!@IoqwK}pbm6<(KSq@Y35UFqOj9=)=>8>(zsq{{ea zUd6RSdQ}(lGi=l*>J##=qs{W8jAHKE*IL%j)k^3Q>ycR`;X!B==6WAK&Q1Ik`*T}d zBXay%^uUzD6P*5mzUq5*+tUr|=Z{w{-a?m?N}z2= zs7+@sXbY@r-@fasvLf}(@0L5j;>}Ig`sm!G}qK`U5Cn{>w^Jxh!2N4oRQ76unO zOZ1Tj;B9JtF~ZT##(Z2Q%k|_nb)X+c;FLW4uM7ob(M5Z_2&eNls{bF%t@hKZtT(OcmWr8x(%7T()DCSVH&Q zZ|`G-tsDKeKG!U?s|i_4I9x=ICluO^5eQV!O6MWlyCZl@Xv7|NNZx(CI8nB`T<8`~X4|U;7->Nac+i?w* z8xJ+0DeB5=f4(ztFDi?Flcb$%6Pn*bYNdX_Z}Za@l>5v49LMiNXcPxbX2ldsv|2a& zm3qfmuZ_o)LL6>QKK0hWUOP;PN7ry7f!BU40NZ%f+rFg>#e;|8*N*@MLGga+(_%XX z$CpE>>C=M7qtdD>6?-+h(zUOyBi@h}0{jI>+waC-6r#QAFZiPq!~yuTBe5gn$BQ#@ zmUmleT~>{3`r2A(3I#R1=^CM!xc*5=T52Y$qBc00%tj1cPTmRXTU=sESDWsjc)ePA zz9ERa=I)cTiKvn*eM@WV14fRT^XA|B{^hS0-Su4!2FaRnl-<{T^<`*D5=I^uAg%-; zEq6xzSA#SKYDaR&?*XlK1 zi>LQIPg<2Ti=-QG)@!-8KBIm4j*LquuHH$Ycd0<@PA(hQXcFHguDRk!aewLjozZJ3 zw4gjNorkt7MI_^T)@QE1 zh0@cS$B$cW}_VYUKlyoTt=iq z<-61dQFG-2`+RsYqfs$bq8|_OlzjH9>4KWDX2nI_-#5E* zJ<&hm$A7HiSjBM~Z`q#Y@#~oVYr} zIO%!qSK-Lewk-et=Kp7=J;YGI$tZHet}L`8!H zEEAfD5xrDodl!n=9}{^FmWgkxvwZGxEAM;DL1+eM83W zwUY=Oi+)Q4QHZ}Kf~8~o&@qqstFG*squ1AZQ%QZpI++c@++%!3JJu ztuS)BnR?jy-cCXy>u>6Xtr6qK>3oni*L{~*S@c2!MHl}`nO_mMV`m7aes$;5%7px{ zQ^hMdkw+f?UmL8HkeN#5l}uRsOSv*&CF8N1e`-YJ_{GijGcwKBqwf$|>e};DuV~Q7pQ>6K4|18keB46oyR@nh={BW! zK#c>;#_WVqGnkFZ7POFb(e+ucska#k2HeaBC(m}BW~2>SOA0US3wkTT zG`MW|rK#hvrV`a$StGSxI2V4G=H3t=^$!gafi*5{97v6txhh%yiBOp^RO=i3v>KAs z`(`XMaB5^xCx_YSvfOC~*m&^`vm}f5aY$0@gV+DqE?4ruZC4NC;&0pa36@mXe|Ia; z!0Vn0FPIlSc5ugZ+f_D^;~R9a^eprUGlL$fosL&ls#7< zlJjBAZ6{+hf{cCI>)@{H1xWcZ&;4yJ$O9LO{xK4uv=aZ(%iU8K-jqvR>vh`e_-7HH zs-z$x^PE7F=v%^I|S8V_l=<@QNvgK-NI!F3D@|-tS2}4cWzt?BFT_# zHXPF=>3lZ@g>aM8-;7)w_WxczT`F)^yx+D(?P^mJ6#uqeZqc?wQiEQeZv4!9JDLS? z)7K~3cVr&rd11HAFR|k4{YB=3^-uWhmieoY%rC7iUyly)ypVjV>DXsxLmq24v~LvO z8dR0^*cm@xkW&*!5RMB7w&~O;KyG8WIN9qCoE*&rE>*Nf2n?-i_jYV`c{{ z18b1=5o1uwBnWW9713A3gE4~N!gtx9`Y+*oni}n~JAD2f+r@Mlm)%@(na2oZUP@fV zq`pceibJIT(CT9Wh2-lXEc3RvPHh+J!ur+)pOmREz(E3wQkl`HT-!1HZkLMdFMYI? zh3A^r)H}q#8lUVZE@t7{f=b@S)HBvIIJ@2HiH1-3`@2&dd6}vYyWA-b@~1kn{E5`u z+f`!mPJW*_B&ZC0=3X*Ra@u{E*wIpi-QDP&gowkAQJsy0O0*vSS| zAIxl{#xMF|kFNjY9!4re9`8EkLb3vT6@fh^m#JrqmTc4a z>NI|W3wzRgyyz5kQX!T0bQ-A>I7J*~(J zin}yq|7iB>PIHA;5a;l&=1NYGJ|6D=W%mqgx~_?5-c!&JkOz&ar!$4_*-tWpbdnzX zUB)4MM;&ybgq9lt{Jhx)ImeEPxG1?}BI*q5f`b#GoOmFv7oM2h#^pk1+}N4uh3Qc! zCqAeeZhi6KmqBgP-%ZG6`GAJM5R$$@^*2Jg147B!hB-w+m-(%p^JYcA%njl zELi`-E`)7mZhAdkTGLAx0eVko@dD`mgq?Oac8&xJXYzp2ML3*|!W+fKaFOj}R{DYxUDSbUh@*y~11q}gC6Nz9RwCP8Rw30craDhGCHrc4k8?A+k?Uyq3@-fX94;#c02M0A{+a-(# z1#J+9l_fR2Cm~;GNQI87hqY|%9+IYdrw3rT@fzf%?BJ2!)YA!S^9wF(^|zpoY}1daC5mcCOVZjpU(F|&8 z6yn2fb7AF}M!Rn>d%0Akt6t#+Jh2u=3#d$kCKdyH*v`C8e??oa^%t{uZQnpa=K!b& zhVD+RFvQ-p=O_-cnIV|)EFt7SC&0XP1eIgMgSyxe z5k|WJQZf>1b8Js{i!c)FtC{^H=N{OtAWbZW`0fDjhi*h9LQt@9FpB|m%j4h1I-Q{4 zZ($79xBg2Qmspwq31chcuP{Qp^)4nlj5j}i2%Tk7vkJl(c%xFgRRB5X8=!KU<2z{O zFnAKWSFW_F2{WjmwuY-g0XftBnJb@|vK+#f%lex7kda3~*d+=42W$}XsjlKNA&|R~ zkE0OK4v^ntyZL|@$-uS8!32asNY20+59nlq0%Wx|5>(t{JqVsQk zyory94v;W;YSEg*355^EaPzmeUN3>Fh(YBnOD=HwLe|Cod6z^YQ+a8^p-tP)9x)+o zg8P_IRTLlpM^z*U#6m}9u|UNC9ku%Z9!NkxL#=>q<(=N#5WYsv6SiQTqBl<2Zy7hey8-zNp1!`ETFChL666)DLi#F}qfGPNXJf+Lb_{O=`LN^KUD}I_gEdk1 z)KrZZ-4lkV2uvL4M-Z-KQ@@$TEB>9-@e1qZ0Z|}zwtv{8WeEKYOxa>-IoxdmFaxbQ z*Do$rSNfP&>%uTwl?64yr)g1f^>b&!U;=c4n|f0*(4KiDDCU4V1lp=z8>>pFlFZ+_ zUJ2S1hu*EPX$~4`p1?JkdmFLS{Cyc5x!aUYtRI8w?jEDctl&Kk?35B_8Fy^|@4=iI z?RkRKC+etoayd7sS9Awqxj+S*42INZw+0TFm_zfmF56&=-KcNf1JQ|#ZE&wbO%EJ? zEz66zhkxX)`B~!H)aDljpWQ5`UbA-kEt{Wd_ztqUt5#F%A+~g+$^V`_z&`^Ew5GAs z(sbiC2mRk`Zmv$u6W?XBhFS{9a1LBcA#ZHr zG-UoGcuyqJkAEk~Og)|G7Z$kY)HY200cx_&G=o3vYO>mr*YSb|iY*B@XyPO$|9Qj- z_jVE?^FLx``>*tal5%Ekc{nDzjyK;;v{l`uDiTFgo$^7zXwJX>HZ`mmWwnh1AXTa( zw%y2#k*|?0-6+!eH`qjvbpFPX;neteztZIF_bl2+cN!Hl&F}u0R@kp;MaSB?R?0kXnh$1llw1V!$jrL|hW*H~v1@tN(8gn9%`d6G? zvgdg&lvq8yyeJLn|5>+Bh@ju}e>RmW0qB2jtAiSS!xTaG{~iTHKSTAUd*+VOp7-YL zsr%HF8{D2HC{);;YoeAfpoz#4u%qMx-lu}0=L zd8b)df|>$7#A^jtS~_DKD9}Ia|KFzB?Y(Jsdu`gpEKb)- z6MdqW4lf4rI+c-UurJ9Q_8QiSlM)`^->X6SyQIb$VgaI^34FfB3Uo4T;ufCw{Crx3 zLpr`#R^FN?TRTVh>(t0(de=pFQ?B5=!?%ITHncAJzTWE;U!)ecX8+61hsJH4F~xLW zB{8GrsX+uI=pYQdZS6m@b67!rc}vC6#QhqSn}V7RjaFSuKyCt-xA96Yh-kWq&&a{F z(+PgvZz8Pb!`&;JuroTYz5dIS-_aPrhvX!HlS!FTZ4 z~JCgTl;~53veQcVX~_jfUV<~k#X*w+*B~s z3l{(>*IItW49%}-P)fFUJc0}@IrN9!haqXvNsyq;I;fp#*xXCdpr8K~Gy}CW0y;@a zz4zUWQ(s)>-^9_7!0qhj*M{U4^w8IRDd|BO%-iL5HX9BnR;Y186jro1M1D{We8$4j zC3}v?ytFr2WCZrwB-O2qQ@emR4Lm+nW!h43w=j+)mNNUtm-TAB*H*s-u9ag*P3bIkpOB zc-B3W7mw+v$$eV_P-wD-oPM_3I|3YC^DLAJ7HQ)nd$8A45fAdid{C*mnf=dUGu{X2 zuo;+*N5%#kXyV(osh5N)ZJ^05eb%gowk^UnUCrSIC^e;;m!@J0?8I?}Mclr(^$IZv zI1t_d$}ujlh!DI+W+`ANz4@JJi#2$qj|!^k=mf9-Q4BoBMaIxM#+ovZ?6Gl^pd2uP zT0#H%p#P3`kF+)N=K=NL4q9PDgPuzbeZYsIQTT+!dnNn%4&Jgb?DgjX6WFaObT>eW zm(6HhnBSodS9T-gyflJ0$Sk|lE?WBz~Ww z;xp*<*?V*8SljTtPI!`+D$%leYxkUBG;D7x60oLhiKw^k;~ZKjzpb~gm#%;=LYdTM zODuGtT6CLKsOfm`_PcFrq}j05ISGNaMj`~keBBRLm-s*sSm=F%q>U8WUGB?hzCDh^ z@h?VkUmU(cLuuU79K|9_1g;>JUtbV1p{DZ6PuOm8xjPZ`hIUA~7-d5-qV+-Oz8Sr= zQgxGR#UX)}R=v@<0$UsjyDKkj;^odThYDCfGt{Qt)_psT>LGCrKOq+k2noH>Nh|a6 zEjw}AJa&&WK=0^VzR?Gh3GsQ)8Gc(PW$6DYkZ-XH1mO&U`Au~=WzTiT%WUYRWivE` zx~(+dqU~j6aG{+5O&Byr?jkgCxei1TO!}@GaWGJtq9) z)}RAmVPdu3vT@lA(sf!3sM2VT;7myv4LGDEH5PD#3WK4+m7D(%EM4ny1Sh z5n=(SzUqG5Ol+D=vPcSmh)G^3@Q_QMl=E~D~8Z9_3wc_KK3Qs+(u8_g1oAxRwh56(Qn3=^x+l)SVwZ(3Qn5*xh! z*2ncj1oVu?kFSTg(?8f#mUoXkU?*(0PFSoK>FK4rxs+{fEv$0;n>kvPqCg;q`hA_% z*1?$%>i8g5RfN$3=Q=3t%cL;OS0h#*bmvG`)?`9T!yvFCkl+45g1v%F;U|IE+2a`P z2QTcW5NGuagdqWho_L@pZZN2KKgcuP<0c=aJ{MDpXaYZnxte5&jwKni4I|c#adW{! zJkhHfdEWI<0WZ^S_vX2SMBk0apdCpX$QiM!*PYXx?RusU@**g+joDk1m(OaLZ6M>> z7~fi2xZ_@}x;bPtW-Bt!a|pVj2?KJ7=Z5gYKC!T(PEPO!cr+So#eRBH6jM>wd6{V-Rw8hE=bxdXv0tUZ5xf#84`bFvsZ^AYw$i~e5FR%|T4aK}vv z`l{DDO}j3SK(i43nnGESFOkW9oS5~UvP%bZupMjFY65eR*IbJ`!P&^equQ{74TBLG zleOk$o4NW50R`ju4>K8-Zg$>_N{YECPaCkBOrR`2G; z|3V?epzgh2C~_E6IHUPF-hV=Imrl}cZ;L+|7_Dgl?&iah2*(!y3;j$ZrKfs>TA=k8 z`gi)zIs*%_wAza2wzv#cxFhqug6$>^-KcC#Jz+_W_Yqq!;hq|zsnno6EaktHuodI` zG_p?^G!bIoI3P+e>R9Oyv?#Yw^=H%4qAKd`GU04IW@qul&mVN%m>^l`@v{iagk(W1 zCx6iiI$9HFwj-#qiAQZ=U%59X2YK05bbS>54u*e90o~=;5k^`Pt*rfov4^CyK^h3- zOmk0#YH7i99_d4saq@_{ye%Y=Xkj(%iEF!tjEp_HHHc|Gi@9Z*L$$*xWkZF2tZA1oeP& zR9572U=%c>s;=+!jCE(NCoeM!YYqS&Q2X_)(0tgTVh7%CD!M8Eg^I}MFcoLFvNU>? zs7J`&f*!wE$z5K!XcJg-Om&dJ{TTtq2bVY#ir@@QebhxD6jUG)Hb%~d!Vn5>rfpN3 z;7f%sj6cxmrxUCso=OeLOQQIf3f^Mh3-_ghq}Ww<3srPM2$Rk{Qr1wz$k(2q4(KsI zLkr~Po7?>9B}uC~xS{0aU@$bN>PQbdt^sx~PeY(N@a8ADg6xF(@x9~nCzO&GZm7ys zMNnnXq!!{DxMm0^hwmB)ll}7JS~g=*VIIg0K`vFvmr$+|dhe?pXhCoMCx!<)=(Fae z3t=kA41?PCr~98!Lumn=C;Xi1ygmZClrKw0!s`L`v(;n+ou_bVC`s*#s(})ORzLtR+UCz6n0v!I;l>r$0)38fV= z+){mF9kjWb++ghIF!sBt0rn9>?4!nF`j4>BLn16+sYkK+zE{YmkN7g!_xjAAqyz0j z?k{f8>Is|a(@5=hB?vKLb|U_^J#J9mcyB9KRM_PMuCFgG+jWcaD{a#;)O?;26)QDI zE`uvt3_a`>o~A&7gzujL3KUS165>Dy#l0R^0@Nf(xst*e-Vyd^q`mFsecmgb?{|RT z{u}V^{sMfHe}Rw9@-xpM;9sf9OJ%es>rXlfhn+{xoZcP`Z+ip^d=bfQga{|L!$Bx^Eg`?R#Cg(Zvr=nUQjoVB60Ro)2&K=`MTs#M_H7 zJNNK9E0ej&FX1^$LYTdu{+}f6`~Xb=?_Cd#I$5s@wb)2zV1Q=-;KF-hBS?2b>V#5C zS;V2(dzTC4(0m68F*4f(v>3UE&%+r-ZY0P zcj_dql4XNP ze~e~bac6u&q#MZpbMY^k%AZGAuS5x$Tuq z4fW6X=A^x!%KI!YXGNju-VM7-(nom7W@sD|7=$L8dG0{UG^_h-tw z$G`wpgjNPkX-Vx8J*mHl9@CEKg}PK_+p@&5yI&<9eL_P^o%=&U4n7v~Un5#gu*8Z% z0O)%a-m-B4oW2bmf*y|y2rh2qj(++~V{TWFYg^pgTlypsr2Ysm*X;jNKfB+Q*}kbi z)VCT={ZiF~J>_9r5t(h2G^nX&D&eO)2c=B>487AUa$_7|*P9bYT_NWApcArS>@8`j z2H7;lfx(Mymp4A+4q4ch+_iR~?*NJ4jD6}K>oMzVVzKY|LB8Ga_=xJkzVa~I$js%) zB*}-|%s%=%+?RRH+b6eb4_O}q6}zT<*Z>=bplOQW8T6IT+veEl_$h}bU@WyP7N*Cc z!u}k_66e2yOj^u-U+H@;_OKL^K82;_x$Xo^zUFY*P$vnsox(Qoh zor9q=Ukngq%ZIc#Z-U0c1wsIBexNz1N895ak^@ISmE8m(Ds80M7@vW97K|9HUAvDE zbKiIOZN-6KUxG@f5E}oC+o2Va_kFg} z$!p_{yvW)2raIfbWpW8LG}wpsX6B`#SE?AVwj7Jo_%H7QTlZz(yh}~emJQ|I0GFyV zTNVwDNnvUuu~Lh^Ch8dbmM;<376SdOiKuwN>vv;=2=a*ULB@Obvc;q;eDY0h;~aGN zWdAAbLmRWA!eA|^6c?(UQ2wtJ2X#m3zHS2{W&^nmsP3>Fct_Vd^pn!y6UjhnnRa1_ z!^C?nK?~hQ0z(z$0HF~R&xWGFd3jKPCTu-;^$+lk9_HMgY?Kfl=sjhDIoSarFCedQ z7xJh{681$N*p^;^yb@N%;hFw~Y|xH*9gk&xhd}5)>Jc`qX0uUwHXxYhfV(t#`|eFm z55Iw%Z&suK7k&<994%D7>o@7efU&lEV#Xj>S!|=p;1jh921e%@$mqq8%_rSqDQe#i zzWPz*um$aLRc^AaNV%eX?dcFKBya_M1@<&zz$=h2`6X}_#ez^a13;oJV*pXJoYijO(h%+(y3jI0g=M}5PTYku{zJ%~# zevyu9+eBBBnsM8iBzu=wUHX}yTN@8*tEGN?588UkY$A3J3Nd&sc|=3Tk!r6F%XYm@ zg6`8-kdv2lsc85OrIc>^y3M^zGmsI*Glyj8_*m z8PGH^yhw)T2m!VmF0~mGQ2bC~%!|1_k-%rqOo%-?HbT8Vv_*A(>F2gZbKX|+pp=

8ooDYk^CWt(l6T@(Y0aa9Z+OtjL-&V4oAXZIM%WY79)@n@ zw#Z35J9j+DPBxTQTm=s)ZRJxp?uu^@xCsjjhB~seB}nzyIix!HY}+4x>AzXJjy@@& z3?_h7!1R3F8J>b=P7Be(`~k_tF0OxTeVTSdp6vq;jBfBY5pTtQ=|a~Y-NjA6N$I!S zauBqiui3dz4%M*c+zX0(+5F=W!6Lr)3c*%KZ-^$CiMxidv$g{ZXM&VLr^awhksWhj zcNTe~`^WBOfvv5+h-V6y`$VuG-tnIBW{{8-t}?iahqEpsMP|x%5YskxHDs@K2Ma_U zSTP3cF5x)%w#S+G@BnM`J0-C1hZfo=Fx2Zw2I*z~o43jfa%I>n!yitI>ml>PBOv6*e7hw#5AVq~ z2OE+T*(fNF9doI=#B-mIMPGvxEd7Z7hV>eT`X0CHT;_9zpZ;(9lp||}O{ZnnH;fL5 zLxW47!rTzPJhLTWq2>PZOum>~20FS2I=g+{&+J7w zdaIm+DcLBfb@M2<^b&4$#lwu|np1hj{W``Scbu!N)glS3Dq2;crK=AJR;KpiI8CC)! z-?;77RTi4k(2TM!zTQbS$iDudHAQ8iIKEXw`8!V6Z%^nGyta-B;{!Tb_U5kQ;FdoL zw3@nuaxXPEw`XoiOkPuRmv-doQ6rQZcx_v2{>UYkbTuP@9bt?MpbuWwF)!O!2U`OLtW<{MmEYFYPmxF&@ z_USDSXP>@X0ajBAD0cyDquV?e4C3Sg-eTzbmW?IGPNIu zsuyR6I$kmSoa;?+CD4NTs;M!%VORB5(}-hShi=ve9DpLYH>jQw(cX}%<|mze%CKS}*;nbKIzP#AW#27-$8 zDQ`Q{yd{{V7_QVn`>yVY@2hyj7PBTLqq3PcIiV32&u9nD)*pOKslyZ}w#F$x4C~w{ ze0{n0VK`1T)y){GJRS~#bcdX4GBu@0bN%I?wKa7r|Ee;kGba6I}b?giBR-X4q?sU0m>QCRsD@a ziK+ha+&;3pFDMF-FRLt3d@87)Zb~IrUr@qoU}83(2h-wIFG2=hDPMp^g~_C3Io{gA zUev<~bIgIh1?^9(TKLjB_~oz7O#ir^^$R)`06H4U7;ZfN6+$5dpk7a-oh3V1YAd`{ z`<^)r1*E=OQttEI7~}CcpubxE!KZcx)wIHzA)v*sz3N8UMqn_N>kHbSgZn8HRB|b_ z21`;}{eSy-1BMBMK&zqiF4*+DRkfZEr@el?Hn^Dq#B`u5CR|i^(Ayp` zgpUa0&L3gl)fd56@J)H=xV`?x<91Yd>R?d#H@Sf|m(vAFc;VH`Hjb_S>8$FzKO&G9 zmPfCL1S#e{=f-mS%R4n94iro7>I3A(gc#>Hg-DYH9VnjmtvT3l*)WFIHanC+b@j#Y<<*?K1Ow;F!R`xiV0YM6@$pJX+az z2ROqKywGq8B@gU^()4={A==NNduMnmd%lkXrTObF%38}UE5{*zsB}@~Dwx1}DsRHV3@z^rSe}>02DzmJ_jHpe zyHm=IPBQU7E(PsYoOwUI-d}17_Q*GD zbiPIIUlzc7J;w84PY?!oqe~vk;w4W)cIZHT?v-R3QTv(B{FZs_~i@#_gyfTZu zlWhLP|H3y%z<+y8_jYiI=uOX`(y^J%HNtkK69|J25Wi_BizM-#6{-?Ut}|PJvx5!l zYMZe!O4^`+>*h6UL_5QAE3!KMb-1cK$rx{ch7F6Emkg6;dZh)#{7?i9p$NJUh1~3S z(12;!S5bn!q^Sg1eFve;wRZcO;&_wDsCloL!MsecvHD zt@@^Bv+tnHz5ToGhSE}@uo?7Q?2clOoim(+rOWe=s>7ck=|O?dF~XdX(3q>w4(sEc z(PHx~9>_O$;GWtD!g-$Cp!p@g==U#q{6|7s8kemgBb$#dZA_b1%3|9C`3`}|6@ua( zj?f7J+8|j>Pdm)QazD)6GEDl1wEbHKH1lcM?56dr;liOgm`q|2N8P~5!*$NGS1r|V zO`C~E32^@Lk(mE<=A&EH@$;dwcP?I8pi>%~Z#c23EpX9Ny*IxOg6f8Uz>g3A5Z{Ar z$k-Jk{%jj%ooF?r<<DpfHd9 z88=j?Uqaw4dWZZ4)zven3g=;J1fm(c1c0Y1m&3T*?x-mdhFc+l@fDi39mR__$Mgga zSEbVnWKTWz7duJ*$KA)@R)~K-RO`-S<94V$l&i7_?z4hxQco!bfws-3nhX{|m%Z9K zubfbXsn~X}t)np!THoaY&oVF|_>37?V1L9w#{&?@CR%ok1KxI%S%D;6aP>9B#mCGbf+_T+SyLYVV#NDLu+^>V z==o65J7)a?_KF_gXlZgVxum_kpR|kkkvWHcTA~vij4@G#565N1;_{K;Lpx*}lmeiw zqSA6XKiE$QA&0TTG&iHxhN~j!S2L#E{KZzu_JvEXTh#_z=)mo`H&>nu0_z=jsUT3g zmzQrX7b1jnEQNo?XI|53NuhZ!uNbwVv|{#YV{Y(;*}14zDmVfnV~yX4H~ z5*8VhmT72kROkFWG$z0ALSdE_uy7Bn^f$uf&Rc@yd*3@b6;NV6jxxNu+vdT?u0O8o z%hkGh!FMDCEEbmIA}wUyuj-9lRVP`q@0cUqtS4*LrX72)^mT|c4xMxp4|+H@Igiw@ zz`qN=0%14)MWTc_555MUbCGCB&^jXltg`M*0Wq%6>SMPrd68W``dn73=%1@A#-gE2 z?_#hzrVDzBmO6dax{`+u`c%An^(vd`LdT^njImyM=8Q6u*yG3Y=&f~q2E=)a)wdHK zbyqk=s7Yo!$t9u~sPr&bmg?s^Qr5Q-42yq!^L zr;=ElJ)=r6V=^6c-YU0H;YaApr;$Q8V~bw7;0z#cRh`SmuNu(L;#2KXpf7EetIEyS zd(Trm+p%)0voz8hbN65`OPi1`kt*@~!!(a@bQ$xGqY2CpmK^H0lPSUs_r5q(c-xk3 z^k9;rqgk&seV&r89O707^p`{G{0cJ!rd<=(eQCjwPPf!mBAm9!*$E?yIL5-}O(acq z3~t66ogc5P!d=cbJG-fPZB43>DEe^s;cstnbq}JCnIGamtnn!OO$jZTmb1g!t2YaG z2U<4USd<3KOCkicULam=qR&IC(qcauY~Lw|yc|{%8f@cQ^hu+u9MyzJ*x98k)v7?p zf8mq@`ZM~zu_GJOyR;{ydYPj>3D5VcY4<^!H%_{A=mQ)FXgp-!80+HaQJ_lJ31+*57{KXTI#PyxgDlpv-ROKr4jV&g*MRQ)7JC}POz>l zqZ|5sX+O=8AxcL%;#j|Kj~Xt%#oIaC%ON+jEHYvrHFRBM^;w00(MbdIRVe!DLj2B z3>wOnX`ZpdBBv-`EjP!h#)|iNFO_`#q#_!pt zXMZYQ+uk=~vd#|Muik8aG;&$iU?sX1!N$kQY*+MMCSvsmqvQ6ylbp7ZeDY-PK(J`K z(%6jp37}wQiY2YRRhUv64X;wi`j%Dse9uOnJ*sq#NP0hDh&nqEWxP54X}tIL5RDB{ z2FIA<%(VRZt3}dI=`9-sp@UtQm1j6iQ^2P)Iu)!Wx$P@2^pdfGSV^B%@aQ5)L#sPASkL)G$TaAZX2ms6F8Upd@zJrmT}eYRLb+Wq009I&Pgx7 zJLt1$J<5>eTH5odT1YuLc+zA}NO`|y(ZvH* zU_Eb2^+jR4>DhV44U<;_X+7grGv{d_aw%xo1aQcHiYtF-J>e%rZRkumt8+wLj>ODJh(oSz3&=A>2W|%UQp*gtAwAO8uOv7gL{ zi^6!esS@ebcUIXN7SX%lFYIL(DuEo{ihaJ0d87(9QYw>j7RDmC{gD}3a_QxRq9AZ5 zIf=gyYBR2P7o6}se-`(-+R?q~94RV-tE511zDl<^^P-|QO|slLr4J-j?;)X@534R9 zfj3g^?BUWK=w}=5XvaN6e@8>pl*CTJu}Q%%r)N)x-=ObU{35_P_Ka_DnKC7YgC_k= zZ0_5#R77cd+p-`1IU~Dk5cJb>uk?vR&`)2_1nLX){=5#K*e%a<+3JoR!Ug0(pLxO^ zQO$?5cLecBvh=YVe-T9D8xiDQ(%%$}eXaob6-KlxhLiUl+*y-CpZKkWb8V-pvSqR$ zHY>$EKdXLuZk`jwX|@I|NNuo1Q)PJZ4X!2eNS@Bkhc0 zY^k*x253|)rS|E&#z*6k832^$CV#>TCCKqCFv96pM(J%D0KpLEVka8W0>vb6B-OWq zkdIUSX4i&Kzy z>&2JM5$s=n!Ck$CbD906B!GKa<-^rZIV-_1nIsZgc0wP%SG-fIGS^>y88a08cD~KF zV}=|G((sp6ju>}?iqHL`m<+=&YN@OO zN|LcJpZoxuM_{VZdUd*4?s8Svg$bqXy2g%!uC`fVtj;gCS;qThej$F*N(0-H>Geeg znl^U;bp!S?)^FcgBa+n4L0~t+cZ~>)09fx?vV;e7617n-Hc#WD>Pq7pTYb~qmG+6a z(1$k{zidk1IdEFzBP1Igt{?Z64O8Oa>q=Cf8Kk104+H#JeD|QIn0N%Kd}+E8O^98m z0#fR!nA<%dQKe};@yYl4Buy`*Nomczq6?p4L=qYdzO4VWV>HMWaoAY@Vl>!Z;@!Oy z(bqQ?c0M<$S9!2LkuGA1F%tp?cmkDF3De43-LwzN$g=kY87~2_pRKw)p5lpme%u__ z=<+uS+NQjnlyXGr`mw*Ilw%pSCls^oL^sn~G&+oz3LXBSdaAeX?j4HsXZO(kR8S6Su0VfGRdh4avjHOff^Y2Pbw~z_UXHPShg}Vy z$0SI|7t(q@dMUQ*ACt~@jOH*J>|VN@yffI@mv}e+HrUNO6h6;lWpe91!MbY8)G5;8 zV6BGx1W?+-tCFz9?}2yl?hj*A-$>k>P6N;6EfhQyTnj4nI7rbUn}R7;ocPo)@p$$f z$fUQ9_YQ^evsj60{B5vrhfIgp#te#LanjGLR{YWX9x@ca{}qHsNCe))f`` z*;(-!pFF-TbE}$W=^J_3OkOCP01H(V;;~OQNf#A4tfYsV(PmUM8FrqV-bY4O2!LaH z6~ac9zjA*tjKfyN!4q)6K30AxZA5kHN`^6a9yL$q^UyFD4XNUb(vY{vC2=)VJ9b^^ z#N+);fLJRX-Q$c4M?PnKvxk(hK<$;zbv*(}$nwsrNh^v;C!FK7DPvcs=Uk5D<9vo> zgak@98R_JTkuU2Su7aV8?p;Jr z%g4IihBmQCI??4pTi%wbg9#e;zyJwW{)3f`Q_U* zI=W-Z1%iN7WmIdfo4hEEe^og^my+=IKC>*Bz!a5QY;)YeI|a&n59(J=b(H#e6DSf= z?<*dBm|^Odu{?Lwl$)3D0SPu!rG4>|E%$Icur{e7)`eSK>L5+_&U`+Y59qv1S`X`Q z3Z-TMM&@fY-A%Qzz@WRIgbqFb&}4IYl@p(YwQWx_1K2a(xg`FqK!okH&(k}g0#a^b zyXQaq2r|7KX>Q2V5a^}H59`C&P-3}53_P!7n1pw+L}UwpJcoh2Ax~vxmBjaKqq7H< zZXViKp*Wo#4rQbtQH;!dQGGjOa};}A*5a_zU3EB3+GZt22igj?su?+%UdsZdP*DVu z1#&c!+=Q6|FRqz()p~LWKTYXIiuVW|_;*nU_g~cEJC|^t72L4c`~f^hWW=iT3xv_S zC@{VA!$z)wfe*n@;~xr8VDIjhxw!h;;nq14ioP^e3(s)9$b3sJ{1t(YMed@DnX2#A z&!7(44}f)abnY2!+e{ndVJ&k5=TD|2(mkJ^Kh>dVH~YErj#>k2YGHs9S4BoJuTyLE ztAQ?`%LW$$qL?F`GXl+JKKWRNjdQdpO!}K8*ed|2`)qJ|SB4qyS++i$9(MeH8v7D( zDAzY`=d>uLm5Pev$WC^$cPPS;%nZg_G0BqApe&(I;S_SjjGe*^W8WPybU29_k!47> zoSJM|8e3%fp7(V+-~V)(zE9T`U03h3+|T{|?%(~p?{{P+vP^riw-|{U*)_^JgQv-4 z_dTb;9d>YdOzeNIp2Ey~?>eacW=v*;*-SN?n&+iWap&%(y2*`Z z6cm`{LPSSK;+-K z2E2fwy)7_MX2+Z|#)h?W4jT8g9qQi>V8X;$O%V@KcWF?6W>S&Nr;p(Kgr@P1z`K%W z1f(?@flyqQCw&}~NTU>hn`@Gqb9X9LZ@Ihlz(%g{fPI84HQ~OJ#Q(?PP+CA6t?lK% z5ZFfRZP}QrSr`p7jD*CaP{#GUs3(zAojH6WMnu}$ud{~QIGcY-sITjE1>0oVCGaB@%e}=~T*&m4qM(bUyMzbm7caZa5)G#lc3>An88HRiBDlHG`(`($Eqbl& zlG`zjIk7f+;FoUT_+%^Vmpk|!f#Lk6@)p4FH@sz*D*cYhcQ$o<1y%o3zJbuQuG6>K z9+8&6?`_Hx4rFRaN>TJB+Pr^HXo>1ifY)j@o>1lbm=07Di;$M%P?~S3SiYt4AKUr& z1;^(6H0&fnrwdn1VU9aP=#cy+HRKc{QkVTzQ}c;R@spXfl5w6x+p(Jvr!#HK;_G3Cx_w&w#xy3vDuzkL-S@eC&xe&lbe; zid2KuhqE~WD9(6@M7*s9mdo5Uo$6b>8UUMsqU zH%(-3K88`48J7Qj&6k3vp?_KC~;~Dbj zIe?Hk5zlr%8DV1a)(E-w2Wr_hPdZg%<86KC_{2*A+pR!T!Jj;Vok5$ zgTdRRpmV>t38Nq^v^bAnO$cBEM2KE>={{zQ4S*0mraV7=P$nKEHuNhq4|g8aD!T}5 zD3jFmlOCKy#r71yuxd?rl!bGRo`Gj*(<3C;JCjZlvgd!mw>k$zj@r<5Qz;>uZ11i0 z!i**oT=jCNJ+w7nop4hbBb?*dbHVRS>a^4lg8*^Q_;e;itIw{=44$zc+H`EXoLgqcYs8nqC;zM)0 zAGxnCTfO4;HZPFLSe1)(W+<$t&Vo!nROY=9hg}(n80o~LO&ckcu1DJ`h^mlgf5u1_ zCdFW-lWZHsD|&8gYgl9eX|wjGbP*dVe?!{L^j`99X5vu`*BTU;$Y0^F^2*Eiu|W`7 zDK@hiUx1+ZZw8sl5jYdc_7`3|7EN-j*ywShTIzM) zUk*PpoR5@45B4;lPBUNFo(a&rJST|C1LfAQ!g1+PHj|*^?8&Cw za0yl?7=C2VzRJ8-MK%QkY*ee_z}ne?k|NuOlG8%B)M7lpDh9++bbAJj5z(~A?hx+H zb(AUuAK8fPEUnq54#c%rAUvtW1$V$iFLxHPw_+NT;{4;LGW3}?ffVPbtKmskY!+dDU}yJ-1)-yU0#)s5=Nm%9?*L4H)Nxq*I_^^H@8A^i#YuzJdLu^jJ@y!dNL7 z5Ef%EN{n0w8NecRTC(Q|Y16O~3l_v7dHs>-xZNxi;gu*-y$-_0Oones1o~0)8<6Yb zWOBEd?5)6Ij$dVCLAt>4tB?h;%m-?c)y~_7dkN{P9lqp}FUu-?JRhO(`=RR1j9lxe zjAMFtCkn2m(+)BR(G*7;=S1#?C4oD%y%{rP$(g%t>M67 zc=CL~Kf0-U?G1293s*~Gdr}m=+j0;w`mmgt*Q&I+r+-N`+1sW>igz)Ovl6cki+cYw zuQNkw)$UyaZK~M5s)iJ}B#!V#@{QtY@#X4Y^J!{COg1}7&M)^(DnGz!aq*FP6cB9k!T8bk21SI#mH3MMcD9KIIG^@d^K?V)s6g}HNp26}x{>psKy@?H zS+ZK$O=QHN8iG9+(Y`uBnj7NF#{07Y<&$al`}CASphihKC_y5Q;rz)EVPnN|u^7s|SC?{T z5kRx#^cpJu-IZoiYb`hIu9aT?16x zGepv{Cjm5Abx6hx{VHtCa6M*|UAiBX1SYJS6iHwbcAClyfmCNBiMA6_exEZ-zO0Cs zNo~Vrf;6KtfoNS@GY$crDCtd}PU|SQV@E7dH~!+gi_JT*WE17y!XP8a3R3Uok8Py2 zKO!WyvLkxMfiYLYIO7$#(oI)_T^!Hpljz_(|k|E5OkqB`>Y0a7?Ef@ zC8!AagNTgHQn^A2YE3r=TjT96b#y^3wJ;QtDv8yhY^BNua+qpftGJ!EU70O~>1;fAQycC>HI5SsE1f{d7BWdhover8?h%m{_`0dpcKVgmk=#7gh-(eRD@8y8 z^`REa%TDbm0r|Rukz#Y<=kt=)^KL&6U4mc%mZi=sjM_);SJ#U#i`2}{fKoN9O4jz9 zKv|(%S@=9o~-To>6tPnN!7k~B~*5B7(B4f_n5Y96M?4P%RL?!LIlXH(QC59b>4C#R) z`vHMmF*6SL!ymQ!Mxd{Te<=hiLW#)mFO6!0L#kH9=r~)@e3~{=!43r9cZ8x+$ng-0 z6b9bxhTCgY?Wa>f!5LCcrF`tpPq2R|fb|ACN`3lx*O4cc_Xvqs1^$ls6R3DAdn-08!@gULXfn4UJ6y-qYTCQ7v3oFz1eWRl0{l zFikqfV8R`+A-E9w=l`=1syoK|WG=;g{BdpBLaY1(&(r97pbc1~ucdW82iia$-DuGT z%F#*)HoxtGf^0Zq+VeMkpMrNz61mb0XID)FAW8v%*fU&fz!o4f!ouS4T(amga{xt! z9$w{-m9yS*pM#`iS;;8EIHXH;tJ$I<*CR?EQGgxdz|usNG=c5~SOeC7)vuuR-++N- zA28^#NFpVj0GZDxw=$wh!gmYQoe>uy>PoVO1U+k=sz!AxQ+ijg4IC|MOc)tbMqX6; zm?t$;taOztG@p1#vA#NGbEqD{MzJml3roOrDK_tX3Im?x2tQO9{~Bf$UqJb-emMgp zC^knllN~t@x!s3y?YZrdte`6j!DD5_Ht{~UeM8nf^~P%V*gIbOSG$=3y9xP~Upix2 zeAE*NMcU0jr){r>x=qlOC}KFM^IMB5)XPD3dui-# z=?Jwm>~dTA_L4Az1pEU9bQuavbiuF6o%OZ*qq6r<;I+tDNRiro3rb(gvga?)L2V{} zLSNjRD9Mv4Ekjx_nHkSFO4QQGJs8pNl&CS}{AE0pl9 z&dm7gZTr6CZU6VOMh%RIlKQ!!>WJHGM1j>9`i*ik~6}5Y04J}DY<7s)nd=vg0pO^7U^TdGC6vN zJyCGgqEg1RtHJe-p@6j*P*%=c$q4U;1r7zm;apgZvLE-s7Xw}=yU6ntYiK8goWi!IODhi$v!2mRv<@#zJ= zVW?2evFSMnJ$p zQm*!l8xTNK-*pBYJ9Om3lX8GVb-PDR?m>L`kYBF-&KDr&F`QA)CGS#DeP$8TgyHq( z6)zQ1i@`?uZ-*l9zAJ1e0p-6dlHx6>PII;Fm4#$V2V$EDEPd(>R*s@#@{6HX5|k0_ z*cg$!1~9^*T6aZ$l%B(TPwah@tyQ`~N$w?Z?NIyO^Om^zd4tSN-Bk-fl35L};f^U;OBF^QR5&d~m`1@(XN;hAVU1nX z{W0^L`HU?K8@Qu{{K4gWxZ^_pwF99Ha}q6Le>C$ezO7DP%gDO^GdQ0Qu9s|JeWtp9 zS1vI!cDr%To_m75JCD0xsC%aUb%?iq#)UoM6nH!D=B-G z`-&TzpvqE$I${b_p;RKdI+blI(MAqi%-bVrr|kfx61YhQO}zhWCiZ2Q?fe}7gf~$U ziTQIwqHcOV2>dR-<4nQbqZn(YSEV1NT{;^^Ku2-jnGNCOGMnBk|Am=zNW*B+B||6^ zqvp2$M2w}v(E<5KerZQtx$@oEYM2^R5+6$+n}#9zDM~0;=XNBEj4r| z{}-WWC|&k7GH$3wmdSy%qkW`{@dj06(S`Sn9}Hd{N#Men4XXOAsPX?Bi--m~(;=O@VfZ%sH3(!E$B zYujK`$AJY+rR1}i3E?>7<5!{5U+Ncf2&l_#+8CfTIedqFV2g>5h~rt%C{h=WmI?0_ z$kzll#^0nIHrm-b^~u{{$1{`=Q-ZfN&fVQ)9#|WCNt(;&V)I5riZ^oS7(4$)fQFPY z@_|kh6VZ3sX`mvz6kn^@=nGeYYtPxV^18B}7Z@3h9?iAs7PqxV2CXnhWDL>qGC^Bf< zbD^xf_5kj-{`Ikq5WetNyOwY{$C39Wzt{U zJ1%#Z?emosnqlV$lSvionlq>iZz+b4Dxytx5f=SS13moD4#Uk9qUffnK!tD_NtvpIDSURYNv=Mr|t}+^+xlE~IKOeG?Q*>JyU&8+G z{eouOS?98mj6uGr_)mKiwnnwlwqC z1*B$IqBbf@_2+r-rLoN`i^IawB)N2y6EwGt#Bfa`Q&`s_a##0G6FIzEUQl!BMzN{0 zT8z2&i}_;Hwh%+}CiH?{o`Mw(fg6t^EML6xZm~7doHJbNxIc7jAAYe9dBx_|&W#U0 z$$FrB{v~tJ#KBH&F4h9C{V&JYvfW$R5DmCPVZe!;8ZO^ue4 zdMZ>=ktoS@@ZKo@y{G)z#J(W6Fw=xQ8=WO;dFd{Ax5g)~MnqFflId)r2FP)6l9X!q zBt(uy{hr7cMFY<;G;dzi(<@W7YPD^RjkLx5xmr{{h7!q2tLX8qRhB-JD*2lxTc&bp zZVxRh7xARLYT0n z1%Qc_Da`i129)|tCg@uO%J;52Vr=`?ww&kPmYS%Wa%I7gusCrkSGI(w6$0`)>MOL= z)MZj@ESYtq6u?9Q;*qt-75Ot7cbU?26$h;_xk2SBDIGRpItH`(c0v=VU%J^6h)I9n zZc2I{5?P;m(9F+4I4A0Tws_n|SRbJ^1pz-N^DNxIPXK4M@|Z<;1+8Rs3@xr#*s@z` zuiLfLXgcHcM#lHZl=nmm8{aDqq<4pjrMM#036Zv0YleiO3S+a`BIVFPs4sa@*`0N7 z7(m4z3RSfy9vweAF-I(orkjRcbuLQAYqd6oluuc{D@?E`w{KrN)@oTN39b~)uFjR+ zn-dP54PVeBaVOIXjPk|T0an{RUIq!13hRT< z#>Q+$qNUv8LzUN3U7kGD*bq@bHx#5Bv+ag@-4J7{EShpvO9M418|tqW5P3<^x@`|( z@#a(fqz|y5ZNdqKh;{=hD#@M6wIuY0Pddw5PXjMfmb?Eb{h(iF_X7XR${QicNNzRu zuXRlft7Y+fnU7ItVb(^77g_IPg^sOfB2Vq z1=ub<2EB2|E$ziFq6_sUsU%b!9omdD=^${r1_I-=TSZ8Vn|tB#tqIGfQ;grQvkgym z0;$(?u^hK$^wWifeq72KnvmRe~@M;aV&r>&^>eSsf{Yz_JX z^|R({7G8(FV5~H$m-2@3+0jCx#--y2F;F`auEJUFIK`%RR4pLjnIr$Ui>PqmGnga5 za@F<7LG3qwA7~Q_X63qK-DA>O{(b%MPO!uvc#dYyfp*XOekq>8G|W%G*iLvu?IFee zi&B|MY}!K{_MTT|#Co_Md|HElDse%B{*P8yP;-m3scQA)n=xr;iSzfSAqAjedCdWZWv(Co=!vY)eO@Jq_W= z@Gv>F-sBn=?zduvsseP(>Kn5|pjWn_M*F}>iGyQGE1sr_7tEg{mJp8q#SNjT6!rco z3tDyJeVTv-LOEsj7~QfILV_l{QnpBd>1;?sj}QvdPHKI65K?sh?brngog)81-d(c! zZ^kVmk?O`2BJ&IvRm7cXlqO`s*OGQYWe%7OQO!@wB<_9L=XPvp8I>M2^3&88R56?O zi9mnfRLT=gWRh;`PN{>|i*L+UKzmxjy@V&wsbr~_l}Fw1r&G4971J(C7_0Rt;YAR` zM;gl{7?;!|O%)*@ZVD{bO=RQ4iSsi`NIe&_%H2QYEbO&+u@3ldy!lvVUYIk67atJGv?=|5^Bb50YJLNAl%KNlTas=% zES6wb|;EhiG-dWG}plG*%m_2v*_9aeW;Ik z&VH>JY=ilQA!N+$3pquxclu%Ilb%3gQR3*(Hl-hC47nJ#5vfAd+-VT*`qpbtnDs{ZQgVw=~AY1OUW4N1EzYEp!O zC?6mXj8W}gOIWU)|A4b^)*0D2k@x1in%Rof-V?*kq(d>r%E@sL2|e*o-rT1=&yKv2 zT6Mq!DEnE8DV{Eo-u|5uL%Hy+W28T8_Z+{XeEFgzHOC(?V``(~D z|7dQf6yj>pdXhpo0l~*JNoW^~-OJjiI>r!LE9M{%9Q6Jm$$Jbk6d|sq-IKNmb#-x3 zr3)CtB5BVt7MmN!y7x?LwS3+jYcMY>W z4yB3VVbY-nJ zD$-(VEA)*3r%PGpMP_#P>15jqYJjqi48eFxUoYoyDM&BvM|tu2d*r?{t=pSNsfvl$ zKdY%f1C3QaFDj~TMFJ)?r1JNp{p5dMS6Xs=3^<*QHQk^G^tY2DBaZ1CH%zZAmteUm z{W|gV0@*@F<4I6Sypad`o&LNvZFP~2YzMzmDe(y7!v&c)?ZLp18Ei!vMBq5 zpX#w(?+SA!(!S*O!?ig$_Xh z;71gu3MWKk$tzfZgnY(uCo#+8~pV3lvvhEgJ4j#>he3CpjBoM zJ!^Q~gq9byR!5KfYkh?|!L+%vmNZfLiCG!<7A%D|KdBS^rBb%;*--FmL!r*fGP5%H z%h>v@rIFx2wD;Hsb%41%bzBK2es2G z*FS%@f4VY~dt+^K0k{5{9=y6T4Gb`{#5(-PEzIgdCv)#i!+haN+xpCeY+c~$WLR3Q zeNaf<%8cOp#Jdr}^%ucwbMy3B+`>DY&dS)l)}o-p8Y?b%m01`}T^VxFA0BZCsx7Kp zpQK~fyrX2>N33qGEqCgy>jkZv2;80ddHoZ;P$#fz{xvh|`np#NE;v(X<#T7+nm1o| zTHWBpIY zf|mLO$+GM7VUuyd%(LsIflISP>#PRc;yTMB?n>qQ^t-gRPoygTX`PmJopADf7&RUOb-D;tY@Cto>o0&1^jz@bgG}=yaaQMFB8i^4U?E%s z-!6tnZPQ^k-O}~_VuIRWOD)H~9fi|+(^2F%TZ_r_*=|v=rNxwQw-kPH^HJnB8|Lk= z%|psNIXD(HzFo{`uT6(h*ld*b!{^Z};ILmOf4dm3z)eSy-*iujZxNmoU@=-M-!7)& z_f3aU+-xx(Q(JfkfMwcA-!5h(ann)cH{H_~HKHa398-Ysw~N_TxalyPx{NBvaKlG6n#_fA8c-^QOb7Zf2Q;)ZrFMfE{DN#{B=elf+hd zlnpfcUtHM~nf_2SH!K6lv=wZO=Rf1@cmxA^iyLdQniZMD$T)SMrN(R6v z`~Ne-S_cP*6VA~LkMs1Bb;RMZn{DLQRkZv^@K_)iV&8urCwKkN Date: Mon, 22 Nov 2021 10:27:32 +0000 Subject: [PATCH 142/253] cleanup code --- cases/templates/template_wt.py | 39 ++---- sharpy/controllers/bladepitchpid.py | 116 ++---------------- sharpy/generators/floatingforces.py | 75 ++--------- sharpy/postproc/savedata.py | 7 +- sharpy/solvers/nonlineardynamicmultibody.py | 36 +----- sharpy/structure/utils/lagrangeconstraints.py | 69 +---------- sharpy/utils/multibody.py | 7 -- 7 files changed, 32 insertions(+), 317 deletions(-) diff --git a/cases/templates/template_wt.py b/cases/templates/template_wt.py index 887e3efc6..f5eb09b63 100644 --- a/cases/templates/template_wt.py +++ b/cases/templates/template_wt.py @@ -127,11 +127,11 @@ def spar_from_excel_type04(op_params, TowerBaseHeight = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'TowerBaseHeight') - + # Generate the spar if options['concentrate_spar']: mtower = wt.StructuralInformation.mass_db[0, 0, 0] - + PlatformTotalMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'PlatformTotalMass') @@ -147,31 +147,19 @@ def spar_from_excel_type04(op_params, PlatformCMbelowSWL = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'PlatformCMbelowSWL') - - # PlatformIpitch = PlatformIpitchCM + PlatformTotalMass*(PlatformCMbelowSWL + TowerBaseHeight)**2 - # PlatformIroll = PlatformIrollCM + PlatformTotalMass*(PlatformCMbelowSWL + TowerBaseHeight)**2 - - # iner_mat = np.zeros((6,6)) - # iner_mat[0:3, 0:3] = PlatformTotalMass*np.eye(3) - # iner_mat[3, 3] = PlatformIyawCM - # iner_mat[4, 4] = PlatformIpitch - # iner_mat[5, 5] = PlatformIroll - + mpoint = PlatformTotalMass - mtower*TowerBaseHeight - # IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**2 - # IpitchPoint = PlatformIpitchCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 - # IrollPoint = PlatformIrollCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**2 IyawPoint = PlatformIyawCM - (1./6)*mtower*TowerBaseHeight**3 IpitchPoint = PlatformIpitchCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**3 IrollPoint = PlatformIrollCM + PlatformTotalMass*PlatformCMbelowSWL**2 - (1./3)*mtower*TowerBaseHeight**3 xpoint = (PlatformTotalMass*PlatformCMbelowSWL + 0.5*mtower*TowerBaseHeight**2)/mpoint - + iner_mat = np.zeros((6,6)) iner_mat[0:3, 0:3] = mpoint*np.eye(3) iner_mat[0:3, 3:6] = -mpoint*algebra.skew(np.array([-xpoint, 0, 0])) iner_mat[3:6, 0:3] = -iner_mat[0:3, 3:6] - iner_mat[3, 3] = IyawPoint - iner_mat[4, 4] = IpitchPoint + iner_mat[3, 3] = IyawPoint + iner_mat[4, 4] = IpitchPoint iner_mat[5, 5] = IrollPoint base_stiffness_top = wt.StructuralInformation.stiffness_db[0, :, :] @@ -368,10 +356,9 @@ def spar_from_excel_type04(op_params, spar.StructuralInformation.body_number[ielem] -= 1 # Update Lagrange Constraints and Multibody information - # LC[0].node_in_body += nodes_spar - 1 for ilc in range(len(LC)): LC[ilc].node_in_body += nodes_spar - 1 - + MB[0].FoR_movement = 'free' for ibody in range(1, len(MB)): MB[ibody].FoR_position[0] += TowerBaseHeight @@ -922,7 +909,7 @@ def generate_from_excel_type03(op_params, # Overhang tilt = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'ShftTilt')*deg2rad - if not tilt == 0.: + if not tilt == 0.: raise NonImplementedError("Non-zero tilt not supported") NodesOverhang = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'NodesOverhang') overhang_len = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'overhang') @@ -951,7 +938,7 @@ def generate_from_excel_type03(op_params, oh_GA = tower.StructuralInformation.stiffness_db[-1, 1, 1] oh_GJ = tower.StructuralInformation.stiffness_db[-1, 3, 3] oh_EI = tower.StructuralInformation.stiffness_db[-1, 4, 4] - + overhang.StructuralInformation.generate_uniform_sym_beam(node_pos, oh_mass_per_unit_length, oh_mass_iner, @@ -962,7 +949,7 @@ def generate_from_excel_type03(op_params, num_node_elem=3, y_BFoR='y_AFoR', num_lumped_mass=0) - + overhang.StructuralInformation.boundary_conditions[-1] = -1 overhang.AerodynamicInformation.set_to_zero(overhang.StructuralInformation.num_node_elem, @@ -972,7 +959,7 @@ def generate_from_excel_type03(op_params, tower.assembly(overhang) tower.remove_duplicated_points(tol_remove_points) tower.StructuralInformation.body_number *= 0 - + # Hub mass HubMass = gc.read_column_sheet_type01(excel_file_name, excel_sheet_parameters, 'HubMass') if HubMass is not None: @@ -1005,10 +992,6 @@ def generate_from_excel_type03(op_params, rotor.StructuralInformation.coordinates += hub_position wt.assembly(rotor) - # Redefine the body numbers - # wt.StructuralInformation.body_number *= 0 - # wt.StructuralInformation.body_number[tower.StructuralInformation.num_elem:wt.StructuralInformation.num_elem] += 1 - ###################################################################### ## MULTIBODY ###################################################################### diff --git a/sharpy/controllers/bladepitchpid.py b/sharpy/controllers/bladepitchpid.py index 95a9ed5a7..92f3c6a2c 100644 --- a/sharpy/controllers/bladepitchpid.py +++ b/sharpy/controllers/bladepitchpid.py @@ -99,11 +99,11 @@ class BladePitchPid(controller_interface.BaseController): settings_types['pitch_sp'] = 'float' settings_default['pitch_sp'] = 0. settings_description['pitch_sp'] = 'Pitch set point [rad]' - + settings_types['initial_pitch'] = 'float' settings_default['initial_pitch'] = 0. settings_description['initial_pitch'] = 'Initial pitch [rad]' - + settings_types['initial_rotor_vel'] = 'float' settings_default['initial_rotor_vel'] = 0. settings_description['initial_rotor_vel'] = 'Initial rotor velocity [rad/s]' @@ -119,12 +119,8 @@ class BladePitchPid(controller_interface.BaseController): settings_types['nocontrol_steps'] = 'int' settings_default['nocontrol_steps'] = -1 settings_description['nocontrol_steps'] = 'Time steps without control action' - - # Generator and drive train model - #settings_types['variable_speed'] = 'bool' - #settings_default['variable_speed'] = True - #settings_description['variable_speed'] = 'Allow the change in the rotor velocity' + # Generator and drive train model settings_types['gen_model_const_var'] = 'str' settings_default['gen_model_const_var'] = '' settings_description['gen_model_const_var'] = 'Generator metric to be kept constant at a value `target_gen_value`' @@ -166,22 +162,9 @@ def __init__(self): self.prescribed_sp_time_history = None self.prescribed_sp = list() self.system_pv = list() - # self.nblades = None - - # Time histories are ordered such that the [i]th element of each - # is the state of the controller at the time of returning. - # That means that for the timestep i, - # state_input_history[i] == input_time_history_file[i] + error[i] - # self.p_error_history = list() - # self.i_error_history = list() - # self.d_error_history = list() - # self.real_sp_history = list() - # self.control_history = list() self.controller_implementation = None - # self.n_control_surface = 0 - self.log_fname = None def initialise(self, data, in_dict, controller_id=None, restart=False): @@ -193,10 +176,7 @@ def initialise(self, data, in_dict, controller_id=None, restart=False): self.settings = self.in_dict self.newmark_beta = 0.5 + self.settings['newmark_damp'] - # self.controller_id = controller_id - # self.nblades = len(self.settings['blade_num_body']) - if self.settings['write_controller_log']: folder = data.output_folder + '/controllers/' if not os.path.exists(folder): @@ -268,9 +248,9 @@ def control(self, data, controlled_state): #cab = ag.crv2rotation(struct_tstep.psi[ielem, inode_in_elem, :]) #FoR_cga = ag.quat2rotation(struct_tstep.mb_quat[self.settings['blade_num_body'][0], :]) - #ini_rotor_vel = ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, + #ini_rotor_vel = ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, # struct_tstep.mb_FoR_vel[self.settings['blade_num_body'][0], 3:6])[2] - #ini_rotor_acc = ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, + #ini_rotor_acc = ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, # struct_tstep.mb_FoR_acc[self.settings['blade_num_body'][0], 3:6])[2] self.rotor_vel, self.rotor_acc = self.drive_train_model(aero_torque, self.rotor_vel, @@ -292,7 +272,7 @@ def control(self, data, controlled_state): return controlled_state else: controlled_state['info']['rotor_vel'] = self.rotor_vel - + # Apply filter # Filter only after five periods of the cutoff frequency if self.filter_pv and (len(self.system_pv) > self.min_it_filter): @@ -306,12 +286,6 @@ def control(self, data, controlled_state): filtered_pv = self.system_pv # get current state input - # self.real_state_input_history.append(self.extract_time_history(controlled_state)) - - # i_current = len(self.real_state_input_history) - # # apply it where needed. - # print("self.prescribed_sp", self.prescribed_sp) - # print("filtered_pv", filtered_pv) delta_pitch_ref, detail = self.controller_wrapper( required_input=self.prescribed_sp, current_input=filtered_pv, @@ -322,34 +296,8 @@ def control(self, data, controlled_state): # NREL controller does error = state - reference. Here is done the other way delta_pitch_ref *= -1. # Limit pitch and pitch rate - # current_pitch = algebra.quat2euler(struct_tstep.mb_quat[self.settings['blade_num_body'][0]])[0] - # print(control_command, current_pitch) - # target_pitch = current_pitch + control_command - # target_pitch = max(target_pitch, self.settings['min_pitch']) - # pitch_rate = (target_pitch - current_pitch)/self.settings['dt'] - # pitch_rate = control_command/self.settings['dt'] - # - # if pitch_rate < -self.settings['max_pitch_rate']: - # pitch_rate = -self.settings['max_pitch_rate'] - # elif pitch_rate > self.settings['max_pitch_rate']: - # pitch_rate = self.settings['max_pitch_rate'] - # delta_pitch = pitch_rate*self.settings['dt'] - # if control_command > 0.: - # pitch_rate = self.settings['max_pitch_rate'] - # elif control_command < 0.: - # pitch_rate = -self.settings['max_pitch_rate'] - # else: - # pitch_rate = 0. - # pitch_rate = 0. - target_pitch = delta_pitch_ref + self.settings['pitch_sp'] pitch_rate = (target_pitch - self.pitch)/self.settings['dt'] - #if target_pitch > self.pitch: - # pitch_rate = self.settings['max_pitch_rate'] - #elif target_pitch < self.pitch: - # pitch_rate = -self.settings['max_pitch_rate'] - #else: - # pitch_rate = 0. if pitch_rate < -self.settings['max_pitch_rate']: pitch_rate = -self.settings['max_pitch_rate'] elif pitch_rate > self.settings['max_pitch_rate']: @@ -362,43 +310,22 @@ def control(self, data, controlled_state): if next_pitch > self.settings['max_pitch']: pitch_rate = 0. next_pitch = self.settings['max_pitch'] - - # elif pitch_rate > 0. and next_pitch > target_pitch: - # pitch_rate = (target_pitch - self.pitch)/self.settings['dt'] - # elif pitch_rate < 0. and next_pitch < target_pitch: - # pitch_rate = (target_pitch - self.pitch)/self.settings['dt'] - # next_pitch = self.pitch + pitch_rate*self.settings['dt'] self.pitch = next_pitch - # int_pitch = self.compute_blade_pitch(data.structure, - # struct_tstep, - # tower_ibody=self.settings['blade_num_body'][0] - 1, - # blade_ibody=self.settings['blade_num_body'][0]) - # print("int comp pitch:", self.pitch, int_pitch) - controlled_state['info']['pitch_vel'] = -pitch_rate # Apply control order - # rot_mat = algebra.rotation3d_x(control_command) - # print("control_command: ", control_command) - # print("init euler: ", algebra.quat2euler(struct_tstep.quat)) change_quat = False if change_quat: for ibody in self.settings['blade_num_body']: quat = algebra.rotate_quaternion(struct_tstep.mb_quat[ibody, :], delta_pitch*np.array([1., 0., 0.])) - # print("final euler: ", algebra.quat2euler(quat)) - # euler = np.array([prescribed_sp[0], 0., 0.]) struct_tstep.mb_quat[ibody, :] = quat.copy() if ibody == 0: struct_tstep.quat = quat.copy() change_vel = False if change_vel: - # struct_tstep.for_vel[3] = control_command/self.settings['dt'] - # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] - # struct_tstep.for_vel[3] = np.sign(control_command)*self.settings['max_pitch_rate'] - # struct_tstep.for_acc[3] = (data.structure.timestep_info[data.ts - 1].for_vel[3] - struct_tstep.for_vel[3])/self.settings['dt'] for ibody in self.settings['blade_num_body']: struct_tstep.mb_FoR_vel[ibody, 3] = pitch_rate struct_tstep.mb_FoR_acc[ibody, 3] = (data.structure.timestep_info[data.ts - 1].mb_FoR_vel[ibody, 3] - @@ -416,13 +343,7 @@ def control(self, data, controlled_state): data.structure, data.aero.aero_settings, dt=self.settings['dt']) - # controlled_state['aero'].control_surface_deflection = ( - # np.array(self.settings['controlled_surfaces_coeff'])*control_command) - #print("gen torque [MNm]:", aero_torque/self.settings['GBR']*1e-6, - # "rotor_vel:", rotor_vel, - # "pitch_vel:", pitch_rate, - # "control_c:", control_command) fid = open(self.log_fname, 'a') fid.write(('{:>6d} ' + 10*'{:>12.6f} ' @@ -467,10 +388,8 @@ def compute_system_pv(self, struct_tstep, beam, **kwargs): elif self.settings['sp_type'] == 'rbm': steady, unsteady, grav = struct_tstep.extract_resultants(beam, force_type=['steady', 'unsteady', 'gravity'], ibody=0) - # rbm = np.linalg.norm(steady[3:6] + unsteady[3:6] + grav[3:6]) rbm = steady[4] + unsteady[4] + grav[4] self.system_pv.append(rbm) - # print("rbm: ", rbm) elif self.settings['sp_type'] == 'gen_vel': self.system_pv.append(kwargs['gen_vel']) @@ -481,8 +400,6 @@ def controller_wrapper(self, current_input, control_param, i_current): - # print("ri[i-1]", required_input[i_current - 1]) - # print("ci[-1]", current_input[-1]) self.controller_implementation.set_point(required_input[i_current - 1]) control_param, detailed_control_param = self.controller_implementation(current_input[-1]) return (control_param, detailed_control_param) @@ -494,28 +411,15 @@ def __exit__(self, *args): def drive_train_model(self, aero_torque, ini_rot_vel, ini_rot_acc): # Assuming contant generator torque demand - # print(ini_rot_vel) if self.settings['gen_model_const_var'] == 'power': gen_torque = self.settings['gen_model_const_value']/self.settings['GBR']/ini_rot_vel elif self.settings['gen_model_const_var'] == 'torque': gen_torque = self.settings['gen_model_const_value'] - # print("aero_torque", aero_torque) - # print("gen_torque", gen_torque*self.settings['GBR']) - # print("error_torque", (aero_torque - gen_torque*self.settings['GBR'])/aero_torque*100) - rot_acc = (aero_torque - self.settings['GBR']*gen_torque)/self.settings['inertia_dt'] - # rot_acc = ini_rot_acc + delta_rot_acc - - # Integrate according to newmark-beta scheme - # rot_vel = (ini_rot_vel + - # (1. - self.newmark_beta)*self.settings['dt']*ini_rot_acc + - # self.newmark_beta*self.settings['dt']*rot_acc) rot_vel = ini_rot_vel + rot_acc*self.settings['dt'] - # print("rot vel acc", rot_vel, rot_acc) return rot_vel, rot_acc - # return ini_rot_vel, ini_rot_acc def compute_aero_torque(self, beam, struct_tstep): # Compute total forces @@ -549,14 +453,8 @@ def compute_blade_pitch(beam, struct_tstep, tower_ibody=0, blade_ibody=1): zg_tower_top = algebra.multiply_matrices(cga0, ca0b, np.array([0., 0., 1.])) # blade root - # hub_elem = np.where(beam.body_number == blade_ibody)[0][0] - # hub_node = beam.connectivities[hub_elem, 0] - # ielem, inode_in_elem = beam.node_master_elem[hub_node] - # cab = algebra.crv2rotation(struct_tstep.psi[ielem, inode_in_elem, :]) cga = algebra.quat2rotation(struct_tstep.mb_quat[blade_ibody, :]) - # zg_hub = algebra.multiply_matrices(cga, cab, np.array([0., 0., 1.])) zg_hub = algebra.multiply_matrices(cga, np.array([0., 0., 1.])) - + pitch = algebra.angle_between_vectors(zg_tower_top, zg_hub) return pitch - diff --git a/sharpy/generators/floatingforces.py b/sharpy/generators/floatingforces.py index 1021441ea..c296d97f7 100644 --- a/sharpy/generators/floatingforces.py +++ b/sharpy/generators/floatingforces.py @@ -145,12 +145,9 @@ def quasisteady_mooring(xf, zf, l, w, EA, cb, hf0=None, vf0=None): inv_J_est = np.linalg.inv(J_est) hf_est += inv_J_est[0, 0]*(xf - xf_est) + inv_J_est[0, 1]*(zf - zf_est) vf_est += inv_J_est[1, 0]*(xf - xf_est) + inv_J_est[1, 1]*(zf - zf_est) - # hf += (xf - xf_est)/J[0, 0] + (zf - zf_est)/J[1, 0] - # vf += (xf - xf_est)/J[0, 1] + (zf - zf_est)/J[1, 1] xf_est, zf_est = compute_xf_zf(hf_est, vf_est, l, w, EA, cb) error = np.maximum(np.abs(xf - xf_est), np.abs(zf - zf_est)) - # print(error) it += 1 if ((it == max_iter) and (error > tol)): cout.cout_wrap(("Mooring system did not converge. error %f" % error), 4) @@ -187,30 +184,6 @@ def change_of_to_sharpy(matrix_of): return matrix_sharpy -# def interp_1st_dim_matrix(A, vec, value): -# -# # Make sure vec is ordered in strictly ascending order -# if (np.diff(vec) <= 0).any(): -# cout.cout_wrap("ERROR: vec should be in strictly increasing order", 4) -# if not A.shape[0] == vec.shape[0]: -# cout.cout_wrap("ERROR: Incoherent vector and matrix size", 4) -# -# # Compute the positions to interpolate -# if value <= vec[0]: -# return A[0, ...] -# elif ((value >= vec[-1]) or (value > vec[-2] and np.isinf(vec[-1]))): -# return A[-1, ...] -# else: -# i = 0 -# while value > vec[i]: -# i += 1 -# dist = vec[i] - vec[i - 1] -# rel_dist_to_im1 = (value - vec[i - 1])/dist -# rel_dist_to_i = (vec[i] - value)/dist -# -# return A[i - 1, ...]*rel_dist_to_i + A[i, ...]*rel_dist_to_im1 - - def rfval(num, den, z): """ Evaluate a rational function given by the coefficients of the numerator (num) and @@ -247,7 +220,6 @@ def response_freq_dep_matrix(H, omega_H, q, it_, dt): # Compute the constant component if type(H) is np.ndarray: - # H_omega = interp_1st_dim_matrix(H, omega_H, omega_fft[0]) interp_H = interp1d(omega_H, H, axis=0) H_omega = interp_H(omega_fft[0]) elif type(H) is tuple: @@ -269,8 +241,6 @@ def response_freq_dep_matrix(H, omega_H, q, it_, dt): # Compute the inverse Fourier tranform f[:] = np.real(ifft(fourier_f, axis=0)[it_, :]) - # (T, yout, xout) = lsim(H, q[:it_ + 1, :], T, X0=X0) - return f @@ -357,7 +327,6 @@ def noise_freq_1s(w): u2w = u2[iomega] wn[iomega] = np.sqrt(-2.*np.log(u1w))*(np.cos(2*np.pi*u2w) + 1j*np.sin(2*np.pi*u2w)) - # wn[iomega] = 1. + 0j return wn*sigma @@ -582,14 +551,6 @@ def initialise(self, in_dict=None, data=None, restart=False): # hydrodynamics self.cd = self.floating_data['hydrodynamics']['CD']*self.settings['cd_multiplier'] if self.settings['method_matrices_freq'] == 'constant': - # self.hd_added_mass_const = interp_1st_dim_matrix(self.floating_data['hydrodynamics']['added_mass_matrix'], - # self.floating_data['hydrodynamics']['ab_freq_rads'], - # self.settings['matrices_freq']) - - # self.hd_damping_const = interp_1st_dim_matrix(self.floating_data['hydrodynamics']['damping_matrix'], - # self.floating_data['hydrodynamics']['ab_freq_rads'], - # self.settings['matrices_freq']) - interp_am = interp1d(self.floating_data['hydrodynamics']['ab_freq_rads'], self.floating_data['hydrodynamics']['added_mass_matrix'], axis=0) @@ -643,13 +604,6 @@ def initialise(self, in_dict=None, data=None, restart=False): # Wave forces self.wave_forces_node = self.floating_data['wave_forces']['node'] if self.settings['method_wave'] == 'sin': - # xi_matrix2 = interp_1st_dim_matrix(self.floating_data['wave_forces']['xi'], - # self.floating_data['wave_forces']['xi_freq_rads'], - # self.settings['wave_freq']) - # xi = interp_1st_dim_matrix(xi_matrix2, - # self.floating_data['wave_forces']['xi_beta_deg']*deg2rad, - # self.settings['wave_incidence']) - interp_x1 = interp1d(self.floating_data['wave_forces']['xi_freq_rads'], self.floating_data['wave_forces']['xi'], axis=0, @@ -657,16 +611,10 @@ def initialise(self, in_dict=None, data=None, restart=False): fill_value=(self.floating_data['wave_forces']['xi'][0, ...], self.floating_data['wave_forces']['xi'][-1, ...])) xi_matrix2 = interp_x1(self.settings['wave_freq']) - # xi_matrix2 = interp_x1(self.floating_data['wave_forces']['xi_freq_rads'][2:4]) interp_x2 = interp1d(self.floating_data['wave_forces']['xi_beta_deg']*deg2rad, xi_matrix2, axis=0) self.xi_interp = interp_x2(self.settings['wave_incidence']) - # xi = interp_x2(self.floating_data['wave_forces']['xi_beta_deg'][5]*deg2rad) - # print(xi[0, :]) - # print(self.floating_data['wave_forces']['xi'][2, 5, :]) - # print(xi[0, :] - self.floating_data['wave_forces']['xi'][2, 5, :]) - elif self.settings['method_wave'] == 'jonswap': @@ -764,7 +712,7 @@ def freq_wave_forces_variables(self, Tp, Hs, dt, time, xi, w_xi): """ # Compute time and frequency discretisations ntime_steps = time.shape[0] - + nomega = ntime_steps//2 + 1 w = np.zeros((nomega)) w_temp = np.fft.fftfreq(ntime_steps, d=dt)*2.*np.pi @@ -774,7 +722,7 @@ def freq_wave_forces_variables(self, Tp, Hs, dt, time, xi, w_xi): else: w[-1] = w_temp[ntime_steps//2] nomega_2s = ntime_steps - + # Compute the one-sided spectrums noise_freq = noise_freq_1s(w) jonswap_1s = jonswap_spectrum(Tp, Hs, w)*2.*np.pi @@ -782,15 +730,15 @@ def freq_wave_forces_variables(self, Tp, Hs, dt, time, xi, w_xi): jonswap_freq[0] = np.sqrt(ntime_steps/dt*jonswap_1s[0]/2) + 0j # The DC values does not have the 2 self.noise_freq = noise_freq - self.jonswap_freq = jonswap_freq + self.jonswap_freq = jonswap_freq self.omega = w self.nomega_2s = nomega_2s - + self.xi_interp = np.zeros((nomega, 6), dtype=np.complex) for iomega in range(nomega): for idim in range(6): self.xi_interp[iomega, idim] = np.interp(self.omega[iomega], w_xi, xi[:, idim]) - + def time_wave_forces(self, dx, grav): """ @@ -812,10 +760,10 @@ def time_wave_forces(self, dx, grav): 0.5*self.jonswap_freq[iomega]* np.conj(self.xi_interp[iomega, idim])* np.exp(1j*k*dx)) - + # Compute the inverse Fourier transform force_waves = ifft(force_freq_2s, axis=0) - + return np.real(force_waves) @@ -908,14 +856,6 @@ def generate(self, params): self.x0_K[data.ts] = xout[:, 1] hd_f_qdot_g -= yout[:, 1] hd_f_qdotdot_g = np.zeros((6)) - #(T, yout, xout) = forced_response(self.hd_K, - # T=[0, self.settings['dt']], - # U=self.qdotdot[data.ts-1:data.ts+1, :].T, - # X0=self.x0_K[data.ts-1]) - # # transpose=True) - #self.x0_K[data.ts] = xout[:, 1] - #hd_f_qdot_g -= np.zeros((6)) - #hd_f_qdotdot_g = -yout[:, 1] else: cout.cout_wrap(("ERROR: Unknown method_matrices_freq %s" % self.settings['method_matrices_freq']), 4) @@ -1011,4 +951,3 @@ def generate(self, params): if self.settings['write_output']: self.write_output(data.ts, k, mooring_forces, mooring_yaw, hs_f_g, hd_f_qdot_g, hd_f_qdotdot_g, hd_correct_grav, total_drag_force, wave_forces_g) - diff --git a/sharpy/postproc/savedata.py b/sharpy/postproc/savedata.py index 65cf61202..75e772518 100644 --- a/sharpy/postproc/savedata.py +++ b/sharpy/postproc/savedata.py @@ -196,7 +196,7 @@ def initialise(self, data, custom_settings=None, caller=None, restart=False): self.caller = caller def run(self, **kwargs): - + online = su.set_value_or_default(kwargs, 'online', False) # Use the following statement in case the ct types are not defined and @@ -308,11 +308,6 @@ def save_timestep(data, settings, ts, hdfile): SkipAttr=settings['skip_attr'], compress_float=settings['compress_float']) if settings['save_struct']: - # if data.structure.timestep_info[ts].in_global_AFoR: - # tstep = data.structure.timestep_info[ts] - # else: - # tstep = data.structure.timestep_info[data.ts].copy() - # tstep.whole_structure_to_global_AFoR(data.structure) tstep = data.structure.timestep_info[ts] h5utils.add_as_grp(tstep, diff --git a/sharpy/solvers/nonlineardynamicmultibody.py b/sharpy/solvers/nonlineardynamicmultibody.py index b09ec9113..151e6745f 100644 --- a/sharpy/solvers/nonlineardynamicmultibody.py +++ b/sharpy/solvers/nonlineardynamicmultibody.py @@ -326,7 +326,7 @@ def write_lm_cond_num(self, iteration, Lambda, Lambda_dot, Lambda_ddot, cond_num fid_lambda_dot = open(self.fname_lambda_dot, "a") fid_lambda_ddot = open(self.fname_lambda_ddot, "a") fid_cond_num = open(self.fname_cond_num, "a") - + fid_lambda.write("%d %d " % (self.data.ts, iteration)) fid_lambda_dot.write("%d %d " % (self.data.ts, iteration)) fid_lambda_ddot.write("%d %d " % (self.data.ts, iteration)) @@ -339,36 +339,22 @@ def write_lm_cond_num(self, iteration, Lambda, Lambda_dot, Lambda_ddot, cond_num fid_lambda_dot.write("\n") fid_lambda_ddot.write("\n") fid_cond_num.write("%e %e\n" % (cond_num, cond_num_lm)) - + fid_lambda.close() fid_lambda_dot.close() fid_lambda_ddot.close() fid_cond_num.close() - + def run(self, **kwargs): structural_step = su.set_value_or_default(kwargs, 'structural_step', self.data.structure.timestep_info[-1]) - dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) + dt= su.set_value_or_default(kwargs, 'dt', self.settings['dt']) if structural_step.mb_dict is not None: MBdict = structural_step.mb_dict else: MBdict = self.data.structure.ini_mb_dict - - #if self.data.ts == 1: - # compute_psi_local = True - # print("Computing psi local") - #else: - # compute_psi_local = False - - #if self.data.structure.ini_info.in_global_AFoR: - # self.data.structure.ini_info.whole_structure_to_local_AFoR(self.data.structure, - # compute_psi_local) -# - #if structural_step.in_global_AFoR: - # structural_step.whole_structure_to_local_AFoR(self.data.structure, - # compute_psi_local) MB_beam, MB_tstep = mb.split_multibody( self.data.structure, @@ -443,8 +429,6 @@ def run(self, **kwargs): if self.settings['rigid_bodies']: rigid_LM_dofs = self.rigid_dofs + (np.arange(self.num_LM_eq, dtype=int) + self.sys_size).tolist() - # rigid_Asys = np.zeros((self.n_rigid_dofs + self.num_LM_eq, self.n_rigid_dofsi + self.num_LM_eq)) - # rigid_Q = np.zeros((self.n_rigid_dofs + self.num_LM_eq,)) rigid_Asys = Asys[np.ix_(rigid_LM_dofs, rigid_LM_dofs)].copy() rigid_Q = Q[rigid_LM_dofs].copy() @@ -455,14 +439,6 @@ def run(self, **kwargs): else: Dq = np.linalg.solve(Asys, -Q) - #if (not np.isnan(Dq).any()) and (not (Dq == 0.).all()): - # msg = ("k:%d pos_min:%d min:%e pos_max:%d max:%e" % (iteration, - # np.where(Dq == np.min(Dq))[0], - # np.min(Dq), - # np.where(Dq == np.max(Dq))[0], - # np.max(Dq))) - # print(msg) - # Relaxation relax_Dq = np.zeros_like(Dq) relax_Dq[:self.sys_size] = Dq[:self.sys_size].copy() @@ -533,12 +509,8 @@ def run(self, **kwargs): xbeamlib.cbeam3_correct_gravity_forces(MB_beam[ibody], MB_tstep[ibody], self.settings) mb.merge_multibody(MB_tstep, MB_beam, self.data.structure, structural_step, MBdict, dt) - # if not structural_step.in_global_AFoR: - # structural_step.whole_structure_to_global_AFoR(self.data.structure) - self.Lambda = Lambda.astype(dtype=ct.c_double, copy=True, order='F') self.Lambda_dot = Lambda_dot.astype(dtype=ct.c_double, copy=True, order='F') self.Lambda_ddot = Lambda_ddot.astype(dtype=ct.c_double, copy=True, order='F') return self.data - diff --git a/sharpy/structure/utils/lagrangeconstraints.py b/sharpy/structure/utils/lagrangeconstraints.py index 960278264..9ca9e34ab 100644 --- a/sharpy/structure/utils/lagrangeconstraints.py +++ b/sharpy/structure/utils/lagrangeconstraints.py @@ -322,12 +322,12 @@ def equal_lin_vel_node_FoR(MB_tstep, MB_beam, FoR_body, node_body, node_number, node_cga = MB_tstep[node_body].cga() node_FoR_va = MB_tstep[node_body].for_vel[0:3] node_FoR_wa = MB_tstep[node_body].for_vel[3:6] - + ielem, inode_in_elem = MB_beam[node_body].node_master_elem[node_number] psi = MB_tstep[node_body].psi[ielem, inode_in_elem, :] node_cab = ag.crv2rotation(psi) node_Ra = MB_tstep[node_body].pos[node_number,:] + np.dot(node_cab, rel_posB) - + node_dot_Ra = MB_tstep[node_body].pos_dot[node_number,:] FoR_cga = MB_tstep[FoR_body].cga() FoR_va = MB_tstep[FoR_body].for_vel[0:3] @@ -512,17 +512,11 @@ def def_rot_axis_FoR_wrt_node_general(MB_tstep, MB_beam, FoR_body, node_body, no n1 = np.linalg.norm(aux_Bnh[1,:]) n2 = np.linalg.norm(aux_Bnh[2,:]) if ((n0 < n1) and (n0 < n2)): - # indep = np.array([1,2], dtype = int) indep[:] = [1, 2] - # new_Lambda_dot = np.array([0., Lambda_dot[ieq], Lambda_dot[ieq+1]]) elif ((n1 < n0) and (n1 < n2)): - # indep = np.array([0,2], dtype = int) indep[:] = [0, 2] - # new_Lambda_dot = np.array([Lambda_dot[ieq], 0.0, Lambda_dot[ieq+1]]) elif ((n2 < n0) and (n2 < n1)): - # indep = np.array([0,1], dtype = int) indep[:] = [0, 1] - # new_Lambda_dot = np.array([Lambda_dot[ieq], Lambda_dot[ieq+1], 0.0]) new_Lambda_dot = np.zeros(3) new_Lambda_dot[indep[0]] = Lambda_dot[ieq] @@ -532,9 +526,6 @@ def def_rot_axis_FoR_wrt_node_general(MB_tstep, MB_beam, FoR_body, node_body, no Bnh = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') B = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') - # Lambda_dot[ieq:ieq+num_LM_eq_specific] - # np.concatenate((Lambda_dot[ieq:ieq+num_LM_eq_specific], np.array([0.]))) - Bnh[:, FoR_dof+3:FoR_dof+6] = ag.multiply_matrices(ag.skew(rot_axisB), cab.T, node_cga.T, @@ -823,43 +814,6 @@ def def_rot_vel_mod_FoR_wrt_node(MB_tstep, MB_beam, FoR_body, node_body, node_nu LM_K[FoR_dof+3:FoR_dof+6, node_dof+3:node_dof+6] += scalingFactor*ag.multiply_matrices(FoR_cga.T, node_cga, ag.der_Ccrv_by_v(MB_tstep[node_body].psi[ielem,inode_in_elem,:], np.dot(Znon.T, Lambda_dot[ieq:ieq+num_LM_eq_specific]))) - # Bnh = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') - # B = np.zeros((num_LM_eq_specific, sys_size), dtype=ct.c_double, order = 'F') -# - # ielem, inode_in_elem = MB_beam[node_body].node_master_elem[node_number] - # Bnh[:, FoR_dof+3:FoR_dof+6] = ag.multiply_matrices(rot_axisB, - # ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, - # MB_tstep[node_body].cga().T, - # MB_tstep[FoR_body].cga()) -# - # # Constrain angular velocities - # LM_Q[:sys_size] += scalingFactor*np.dot(np.transpose(Bnh),Lambda_dot[ieq:ieq+num_LM_eq_specific]) - # LM_Q[sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*ag.multiply_matrices(rot_axisB, - # ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, - # MB_tstep[node_body].cga().T, - # MB_tstep[FoR_body].cga(), - # MB_tstep[FoR_body].for_vel[3:6]) - scalingFactor*rot_vel -# - # LM_C[sys_size+ieq:sys_size+ieq+num_LM_eq_specific,:sys_size] += scalingFactor*Bnh - # LM_C[:sys_size,sys_size+ieq:sys_size+ieq+num_LM_eq_specific] += scalingFactor*np.transpose(Bnh) -# - # if MB_beam[node_body].FoR_movement == 'free': - # LM_C[FoR_dof+3:FoR_dof+6,node_FoR_dof+6:node_FoR_dof+10] += scalingFactor*np.dot(MB_tstep[FoR_body].cga().T, - # ag.der_Cquat_by_v(MB_tstep[node_body].quat, - # ag.multiply_matrices(ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]), - # # rot_axisB.T, - # rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific]))) -# - # LM_C[FoR_dof+3:FoR_dof+6,FoR_dof+6:FoR_dof+10] += scalingFactor*ag.der_CquatT_by_v(MB_tstep[FoR_body].quat, - # ag.multiply_matrices(MB_tstep[node_body].cga(), - # ag.crv2rotation(MB_tstep[node_body].psi[ielem,inode_in_elem,:]).T, - # rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific])) -# - # LM_K[FoR_dof+3:FoR_dof+6,node_dof+3:node_dof+6] += scalingFactor*ag.multiply_matrices(MB_tstep[FoR_body].cga().T, - # MB_tstep[node_body].cga(), - # ag.der_Ccrv_by_v(MB_tstep[node_body].psi[ielem,inode_in_elem,:], - # rot_axisB.T*Lambda_dot[ieq:ieq+num_LM_eq_specific])) - ieq += 1 return ieq @@ -1052,9 +1006,6 @@ def initialise(self, MBdict_entry, ieq, print_info=True): raise NotImplementedError("Hinges should be parallel to the xB, yB or zB of the reference node") self.set_rot_vel(MBdict_entry['rot_vect'][self.nonzero_comp]) - # self.static_constraint = fully_constrained_node_FoR() - # self.static_constraint.initialise(MBdict_entry, ieq) - return self._ieq + self._n_eq @@ -1095,18 +1046,6 @@ def dynamicpost(self, lc_list, MB_beam, MB_tstep): MB_tstep[self.FoR_body].for_pos[0:3] = (np.dot(node_cga, MB_tstep[self.node_body].pos[self.node_number,:] + np.dot(cab, self.rel_posB)) + MB_tstep[self.node_body].for_pos[0:3]) - - # ielem, inode_in_elem = MB_beam[self.node_body].node_master_elem[self.node_number] - # node_cga = MB_tstep[self.node_body].cga() - # cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem,inode_in_elem,:]) - # FoR_cga = MB_tstep[self.FoR_body].cga() - - # rot_vect_A = ag.multiply_matrices(FoR_cga.T, - # node_cga, - # cab, - # self.rot_vect) - - # MB_tstep[self.FoR_body].for_vel[3:6] = rot_vect_A.copy() return @@ -1181,10 +1120,6 @@ def dynamicmat(self, LM_C, LM_K, LM_Q, MB_beam, MB_tstep, ts, num_LM_eq, cab = ag.crv2rotation(MB_tstep[self.node_body].psi[ielem, inode_in_elem, :]) FoR_cga = MB_tstep[self.FoR_body].cga() - # rel_vel in A FoR - # rel_vel = np.array([self.pitch_vel, 0., 0.]) - # rel_vel += ag.multiply_matrices(FoR_cga.T, node_cga, cab, - # np.array([0., 0., self.rotor_vel])) # rel_vel in B FoR rel_vel = np.array([0., 0., self.rotor_vel]) rel_vel += ag.multiply_matrices(cab.T, node_cga.T, FoR_cga, diff --git a/sharpy/utils/multibody.py b/sharpy/utils/multibody.py index 9fd31ad62..6aa43f66f 100644 --- a/sharpy/utils/multibody.py +++ b/sharpy/utils/multibody.py @@ -54,13 +54,6 @@ def split_multibody(beam, tstep, mb_data_dict, ts): if ts == 1: ibody_tstep.compute_psi_local_AFoR(for0_pos, for0_vel, quat0) ibody_tstep.change_to_local_AFoR(for0_pos, for0_vel, quat0) - #if ts == 1: - # ibody_beam.ini_info.pos_dot *= 0 - # ibody_beam.timestep_info.pos_dot *= 0 - # ibody_tstep.pos_dot *= 0 - # ibody_beam.ini_info.psi_dot *= 0 - # ibody_beam.timestep_info.psi_dot *= 0 - # ibody_tstep.psi_dot *= 0 MB_beam.append(ibody_beam) MB_tstep.append(ibody_tstep) From f5b8aa4672997886d70d682e01f29cbfec85862a Mon Sep 17 00:00:00 2001 From: Arturo Date: Wed, 22 Dec 2021 09:39:33 +0000 Subject: [PATCH 143/253] backwards compatible restart --- sharpy/sharpy_main.py | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/sharpy/sharpy_main.py b/sharpy/sharpy_main.py index 75f262291..d7ba84781 100644 --- a/sharpy/sharpy_main.py +++ b/sharpy/sharpy_main.py @@ -82,6 +82,7 @@ def main(args=None, sharpy_input_dict=None): if args.input_filename == '': parser.error('input_filename is a required argument of SHARPy.') settings = input_arg.read_settings(args) + missing_solvers = False if args.restart is None: # run preSHARPy data = PreSharpy(settings) @@ -91,7 +92,13 @@ def main(args=None, sharpy_input_dict=None): try: with open(args.restart, 'rb') as restart_file: data = pickle.load(restart_file) - solvers = pickle.load(restart_file) + try: + solvers = pickle.load(restart_file) + except EOFError: + # For backwards compatibility + missing_solvers = True + solvers = dict() + cout.cout_wrap('Solvers not found in Pickle file. Using the settings in *.sharpy file.') except FileNotFoundError: raise FileNotFoundError('The file specified for the snapshot \ restart (-r) does not exist. Please check.') @@ -117,9 +124,12 @@ def main(args=None, sharpy_input_dict=None): # Loop for the solvers specified in *.sharpy['SHARPy']['flow'] for solver_name in settings['SHARPy']['flow']: - if (args.restart is None) or (solver_name not in solvers.keys()): + if (args.restart is None) or (solver_name not in solvers.keys()) or (missing_solvers): solvers[solver_name] = solver_interface.initialise_solver(solver_name) - solvers[solver_name].initialise(data, restart=restart) + if missing_solvers: + solvers[solver_name].initialise(data, restart=False) + else: + solvers[solver_name].initialise(data, restart=restart) data = solvers[solver_name].run(solvers=solvers) solvers[solver_name].teardown() From 826e25beb0de5db1f09c8b52fb17fffca94f5cae Mon Sep 17 00:00:00 2001 From: Arturo Date: Thu, 23 Dec 2021 09:54:10 +0000 Subject: [PATCH 144/253] add updatepickle --- sharpy/sharpy_main.py | 4 +++ sharpy/solvers/updatepickle.py | 47 ++++++++++++++++++++++++++++++++++ 2 files changed, 51 insertions(+) create mode 100644 sharpy/solvers/updatepickle.py diff --git a/sharpy/sharpy_main.py b/sharpy/sharpy_main.py index d7ba84781..08fb819e4 100644 --- a/sharpy/sharpy_main.py +++ b/sharpy/sharpy_main.py @@ -99,6 +99,10 @@ def main(args=None, sharpy_input_dict=None): missing_solvers = True solvers = dict() cout.cout_wrap('Solvers not found in Pickle file. Using the settings in *.sharpy file.') + if "UpdatePickle" in solvers.keys(): + # For backwards compatibility + missing_solvers = True + solvers = dict() except FileNotFoundError: raise FileNotFoundError('The file specified for the snapshot \ restart (-r) does not exist. Please check.') diff --git a/sharpy/solvers/updatepickle.py b/sharpy/solvers/updatepickle.py new file mode 100644 index 000000000..a3ca40f04 --- /dev/null +++ b/sharpy/solvers/updatepickle.py @@ -0,0 +1,47 @@ +import numpy as np +import sharpy.utils.settings as su +from sharpy.utils.solver_interface import solver, BaseSolver + + +@solver +class UpdatePickle(BaseSolver): + """ + + """ + solver_id = 'UpdatePickle' + + settings_types = dict() + settings_default = dict() + settings_description = dict() + + settings_table = su.SettingsTable() + __doc__ += settings_table.generate(settings_types, settings_default, settings_description) + + def __init__(self): + self.data = None + self.settings = None + + def initialise(self, data, custom_settings=None, restart=False): + self.data = data + if custom_settings is None: + self.settings = data.settings[self.solver_id] + else: + self.settings = custom_settings + su.to_custom_types(self.settings, + self.settings_types, + self.settings_default, + no_ctype=True) + + def run(self, **kwargs): + + for sts in self.data.structure.timestep_info: + if sts is not None: + sts.in_global_AFoR = True + sts.runtime_steady_forces = np.zeros_like(sts.steady_applied_forces) + sts.runtime_unsteady_forces = np.zeros_like(sts.steady_applied_forces) + sts.psi_local = sts.psi.copy() + sts.psi_dot_local = sts.psi_dot.copy() + sts.mb_dquatdt = np.zeros_like(sts.mb_quat) + + return self.data + From fb324aa9e12c636dfb3c4e718771843fc970aa0c Mon Sep 17 00:00:00 2001 From: Unknown Date: Tue, 8 Feb 2022 19:00:14 +0000 Subject: [PATCH 145/253] oc3 floating file --- .gitignore | 4 ++++ .../oc3_cs_v07.floating.h5 | Bin 0 -> 510200 bytes 2 files changed, 4 insertions(+) create mode 100755 tests/coupled/multibody/floating_wind_turbine/oc3_cs_v07.floating.h5 diff --git a/.gitignore b/.gitignore index 68198c66a..80864da55 100644 --- a/.gitignore +++ b/.gitignore @@ -141,3 +141,7 @@ tests/linear/rom/figs/ # sharpy extension *.sharpy + +# Exceptions +# !tests/coupled/multibody/floating_wind_turbine/oc3_cs_v07.floating.h5 +!tests/coupled/multibody/floating_wind_turbine/oc3_cs_v07.floating.h* diff --git a/tests/coupled/multibody/floating_wind_turbine/oc3_cs_v07.floating.h5 b/tests/coupled/multibody/floating_wind_turbine/oc3_cs_v07.floating.h5 new file mode 100755 index 0000000000000000000000000000000000000000..275365c5b70068fa645db95a3d5c65e34921fdd7 GIT binary patch literal 510200 zcmeF430zIv`~P=?=2?+BQ_7Gi8l&)>%0#(E?MJO zl4=ARj`mme!G2-SAplhc&E9ks%aJS<@TsG^5sz|WYSXtbY7 z7^84A3QilURi~MONFN(;h#3h#YtD#%sddRhnFsY}s*=tV8vl3id^s4`ko^Z;_*2~< zr1~$H-0DLAs0WK%|3`I+`96Q!IDfwjy>KArEN%bwLZ|4M>$LN?8_f0eZqr@|x{Jrg z&4~6zJCJXOV?@wJ?o&>8c8Q>@x4~8lkBjUM z#fYH_&;2z;5pnckh1wM#Z*i2xO&m3G&K^2WuN#_WH?HMiOgB`{$*Eoxkw8Tv95?xT zOP~wHCb>N*kU(1>RBPz!Nun;Nj))zJkwhgnFP-_LOA=jIeC>y~w-oyQd|t=n0x6XK zDCV`ko;1pO{iM-H4heFdUDBvy)VX;c-ZH3a>(tW^3S`ingQ`-a^<>cv+ZED|#K@v! zW7ns4bjhO9!QY-N@|Htcua_J;@J^3vJw17p#YrBuJ}tSZqe~uTy^ad#wR0;}a|;wu zhvJR;26~Fu}TYWczY|OtZ}A{`mHIaJt|N}uO_9v5k*wcIUlwv>*=Xr zyj9R<^yQD(7!{1W3Yr&Lr~ac$1!axr?r3$fL#U5;cT}WBdghUs?x-})Y2?F#?r4eM zystmHx?}S|{RX{XKksO8KIs8Benl6o9X!~ZV;>&>?~kne%5Df9>&o$7y!!;7t0Gl+ zx6^`tV0Pg3pa0x=_W!SZ{r+=2g8wUdu3WdyNp+ z0I$HHUmw-FE^`kG@D0XfB3RVGB4^-#oeF#ZA1UDV`Om!nXRU|KPoG#nQiC~(5%<-x zUG*Wvs1sq=y|0u9z9$LTZ6JdRf2|f*F{cww7;B!vq zwJiMmG{-Ss8gMH3m5BVgs1H`b|4iWb{fg9iC%qS|{Nw*K<^7xGZzcfOLpN;H zrepQg9A{l2+`ixO|NA|NzwbI_NVB^5&$>=o>!Bp#hVjomfo*UJa26?!=h6T>4DU~B zPV#OS4NvzWOkeQm?-+q?wI=*NM7fcI9o0Gp#}Vs*J+|+Ujj!MH&T&c`p%4CjUV>y%H7e4wUB_Cw9Ek%7epZCetK)1PWM*6O!!t+_=?S0QJ zlouc5;(bv{J|Db@x^)Gje<`0{F9?3mPFzW)yuRKSQq+g@(I`p*I_CK4b6$8p;LC{4 zs^L8OtT-w`<^#B9_9E(N@e+R}A9~Pvf?w;}(lkmwuTD|ahx2jjcm;Gb)BA6B$QPau z@NtXU&5I9Rd8;g$514<%qKP`Iow9!^pS1@Fe*Txnrc?5%*h5ht&L=T)G|;V>DD$$g zU3flV9@!Fbm=_| z^ATeGy0nzwm%b#Ha{fVjETX6n&t5+z8t4F@`^Wx}&(TXf`K(+=aeaetmn)wn=;%se zg!uxmkbO&t@$+T}!B4|6;|kUMgPh+&Q6HYu;$1q>f$8U@vbON!2V7sr^e^+|BWo;9 zzP`ZtnP5cF(O;R0|CQGlqG(OQB(d`?jx&c}XB7|=0)onk|d z@O*$zuI)Kqe2~YJ8p(Wsu4X1dM;Ehc{44p;4W<$Nie=Q!Q}LnuPNuF8Lo~!#1?ZUf z&o*Iy#K&6vBriU65n3IY517}_N)vQ+(Mfgu`3OG$AV;kTeywU|XQ}ugqGlBJ;p4~Y zfGN;{$M-b}=ECyG=@v#K`?^K*zkk4v7iR2l$|2dw7i>iRH5;aQqM2Ohr?o9@dCeSZi{3O9xEn9K*Pd&yggI+G#A{P{TQ zxsF*N(ELn)F^u3>p_q7@YW&cp22<3Bk014~2|zahOhCqah35n2kzNw3c=4g@=|3g& z0nevtGDMw^(bK<_kLW~#pT9q!;nxgVYo~ zBJ%-U-^vqpX)hk}=X37b@od4y4-)>G;1~ULJT)IXkeA2&Q+Qbq=qlH!Cf^+=JRdMW z@7yt)C!gzYACU8d=}tS6sB^4-z@LwZN#zU|fvzuPRvp35K1G|753=A9RN@zr7_vM^6}bhd-Y=jKP(HjUPH~6v5BLYa%5dL{^Ks zK5PiNeK!I+=I8Liu&;DD|p^apkqFtzI`M-AHY>kQj#Yhn;V&AJ|Mr3EI~(qpOwji(ifG!f;|2W+do(~vy(@xbd;Bj5jw{6KF^8xeLh;u|; z=8g>he8lrki@FKMr!k7)CzlaT$%me~i=sY!{8+>u06OOL#eq!W`2e5RcdvNyL6Xki zAoBtDhc9XfI(kL&4gP%Q+tx%0#)n>+M(}H0$)MzeBwwPa59gyh>lV;~<$ZGBTf*~U zu0#5_dGVpI*St>V1IFEVBchHz@;ZM$mx{Cpy9+jcHt7@mlI-iK`CJ`MQ6J7HV^1~E zf!EXf_8*KNaGl)jae)^fB)0P!nGcwsWBL$vV%^gJNFj|>ckAM@#iBod&w06$Ila#;O8i5MahSL zbOJ?vI3N3FGoV`l-aqW0_eXq2ZVu+bCY9bG*;jXxiklB7u-}vNFewH9gC;tqZCI`AD%P3>=@87-+!L^N_aj@ANoR`eAH5@^J{D- z=;-gR6Z(T!$i5}}ZnWn@!N$*(I|RSub01UlQO}~T4@>(gq5$Z?`gMPFrSN>fbzV5fp_r`KH$_Y{Z^eW3=yFLFo+B_H~MJ{0xg8A}~n zfet*LZXaJKJRjhba&9V5KD9@v^A}zu=;-z*2>rn;WZx2;5Ar#Q;8)={B$4v{vGg<4 z^(TOl_dZ z52l}chD6=8WjL-Aq0#5^Vfz5+OWaL=4|Y&FAV5iu&-3HD@D%j(LChSx$I9 z;5wq+Q^7)#2lYD;&xayrE>guoGB~HqCWgJdFE39bm0A;!4N6*^YmQIl$jJsNGf{tFFLFf;s4QoFy zXlKc=lWeL!e{6KmS2rcs}4ceCje|UgL*e?ZqI!KFrSt z1Bg1i#SH%Ar@(0XSpmmS|CI#4VD+h#eCYQ66!qbJ?o763@fm#1PnoThJRdOsoF8e08T+Ca$%>2ZU)J}hhNkaa-Ey#MKEDLfxA|MZQT%#%;P_HFX` z0pqUYAW^5MbDRJ8(QP>KW2InxM2!f3sP%SgK9BS$>cd}>%KhhvzggIgIhSJ@t?H{P42l$>*vUMSgI7yNyL9_W~#@1)xb&xiS(P%(oipD_%I{D4pQDxz-e9YTNb3fZ^z zpKG#PClDVb_7TA^!v8!aAG+QHiu&-JHD42f4!r-Ff zDp5CC{VxCcIojX`vOzFDDT4@p>X$E3^I6-EqCT8Y@R*A%9bJ2d@O+q`(;OmvPJ=tM zw&-&`sPpF@A?WDyyb1l`^kMBcSToEv3dDzg+n?Y^ceqB)M{5aneOLkC2c@#c&*qae zh35lI5}!Nq8b9SBVS)2e}n=-N8coIkN@@6=3#R(T(I#|r$q28j4q(&6D~(x zABIR*{Q=N5YdP<+oFzOTFpoI)S-_Kz%Or~Y;J!&ugP^0kPA2pRe+AjM1m}Z{o=NaC zG=4(O$K95qK0Igi^~XTR{65aA*~0Sy-F(;Gl_wvgP>TE@U$#0?cY;pn4_+br*4fs` zpsfOpA4Fyc(Qp29N+jliu_>ydGV8= zqbH{k`-7Lrwl!Ns^+1GRd@eBvepg2nQ}YSENl_o3Qmcc>6}&%hc)>|{KETH*--8z) z#PI`l{@_BQZq`RafA9(kTkD>P3&$huE)8-1# z2h2YfJ3M*v8P${G`|04i92`m1>GUCd-dVhbnV0>ntC-{9*tfl0GgrBCU56|iLhRGHD{-Bn@0^#|9d8G06 zVxD|<+@Z)1*01RmL|tPpp+9(q>{~akFRIxi5FdKZQ-WVE{S!5x`Hv~;!*gmOAAyc} zeYO7qAK+s@c_~jmxpfrz!T8acM$pmoz7qO_SIE94d1$`3fb&mGJHapAte%n&-Lr|J zK0K#-_Gh32|GbuBf{XCu2TbeJPA=ogr${lE{Cok%-H1e@&PX+v|MP_q>(_+-1iz&! zjg)*4$zBxo;d~1AGP#1!F9uI?6`l_m2hHF7c=D0gqsR~V>}w|KRvHlcgICDDbz$?Y zp#rY&tIY_0)?v+*eCTIQDC)y=CW?LsI_CS&<$u5j_!R2-^W+mci#mV3AyM~!E}=ho zh3s2`&p(K*C&ACqqMe$Lx+`^kSlZ~@Ev)f#a@8OFelGLA$$JG)KG%XM@&nzcB}CnT z5JG?0so>k$PwQ>=2{b<=5n%+sPpUsD`5>RyQPhWLoVK6I6?}bciL|@$*B5xsG}}%5 z9z1T%+RBQe&abhLsAC)?^oP@iwcn?zdHVr@_|W&9Ao%S(&_&H>{t@c>U;$oCu3&!N zbNCPVfXDtz=K^_+AH*$%B0re7re7rL+^-V)1Ir`E{57V|(Sq^O%_8{uNQj-I{Qk4Y z4T}2ktht*JpaZvu$%8zEA3vaKWzij??)gVT zfA9*~w?^wlU5pcqk7*OZukef%B_G7Uo}xZHr|vKbpaY*Tw+~q;{P+R=+;)8xFFuHT zCq;fR?ld!rIt9@@{`WucW*r-oAQ+$3as)qpLm6s5XC?E<_h&etL`f!BCZD)J-~+Cc z^XFFc;zLhTqt0)Ak*HJcP3R9^A^Voucb~zD0`Z~u7((!4_{dT6p<552t`AGAQ6mj> z%zr;q*;DxO1NaO+5X_U$w9yp#!MGDSOw?V~BlL%z3cmeu`LKOw1mlx7k>Ho2twhbI z#*m^uJfqTCd7xwd`+gyRz=!!h&dLy;d^THAGClc_)O)mHGbat3Tia<`GlvHN5yB%yB{b_bmXQ*P{qJdLQsQ z^7uV^R>jAn^wb37L%(K5@Z)y>L$5WVs1N5;eCG$a|6$HQMqa{SU%;onk5kWSM`v+E)XAjTPVSgbss}?`?Ys> zHAQ`RyU5eb`)=m@W7EBbzrMiZ>35TLy!g;_H&f&X_m#8Fi8|fwg#O?avTrTx=h-h) zAU;UJK7yZfF_-(FF}o@1!*gcLVc!3M>uX8EAMgP_i9d<`#I1jA(HEbg$Pb>|q{Y?~ zxIQ^g=nsbtw!8YyrO~$q;zO5ACHRT2Rij+L=u0nB)Q4yHY*zs~=JR{=pYaJ!CiWAz zW^MW3qR0>Ke_mZ7>Q-bE`on3%+BeVXxAmz&d=UA3f}ifl-jsZhfV&j+;n_py_XIld z??^!)e3X7n~10_zl5N<8wbsKJ>Cz zTK9!#->cg`~KOBJRp8f$JFpp?Q6Z?r<|JtIzZ=%jGb(E-^)=uaThYhyt z81}vWwLpC68^s9!eqHgSA(VU&+fM5Gu#7`G2Lc^){!#N0{`vxZ@HzeV+K#O+3dBvrek<<7P+H&Cw+Ehni30951IAf{mY@qX~Yf|8QzPLq|~8 zhZS)A>oA}L%U9ylKi~uIpZ7f>_LH+?3|;E{x-W^kY<)t1IBi(_hpk+DJ`;!!5;>9J zmu^3jnoo`)b$wU?BQ=;@!F3WN<176915A$Fh4C6cbS)!_{9wH_aU|&I+Qj})^NAYy zBDGL3K2eqgJ_!gHK6g-x`ta=Ph0N;`yg#qA^bh!e>no{%&`;bM+iIOeksrJsHbq2T z+hjt2NIt&~Pe1096e{`Mm8^QQ2@+SD{j?tl>e`4Gz>cg|Mu1oOw z&aEDcg`a=G`-f@6H}e`l2xWe7UG5)E)E)LB^arnyeM|8BXZmA5f*)5tvA#U{M5c@Y zT$$^a#h>vxc8J(d_UR%Z@RBa|^|fq0b$wU? ztZ@gPFY3kz3V(e8t`;USJo&^AD4^zJM$plvhZOLCfBufh+TPju0{wl)fRO~hj3rLg zd|ql&*N5?uik$^?|D3<)*?O8)*x&p2Jh}aSV(WO;Uo_P{&Z-jron!ddMX^77jo4%7 zS*;MnHNeZ=)73o??)$A=_G{DA%kNhd!A|JH27F?mzk7hIr?2}muOKhxA3i0&e(Jv* zL_}E5@b9j|_~(Cb6_I0=rYpu?BKhyF2D6|3AKxbPkor{vrlYvwF`E&Jw z`r-Edr%J?pH-Y=y;*a3Icf$MNelA_T?jtWBk^H56^21yy>Vv*IZSsyC`HxUW=*K}v zx6dHyVLNW|>(bT*7wRT))x94+)qZekJcCpJy6XPM+)ub}MAeu2eI@Z+eW2dLdrf|y z5y(Wi&n?!L)v08&`9-x3rd@q0V#eA2m3`W9#S(ITu-&jj56b$z5-}SaW;?6OL3loq zF$lH)C}%s){af103X)fT&EP!F zxxZXKGk9hh?sv}f^;eBqgGqe)4?WkknW8@E*K69Pg_#b6&3rx`_e`puh{EH7M)hTT z6^>|zbJZP~qPJN^rINwv7Z{tdBb-eq8X2NANu`pj57Zad2Fb?Gmf|~pHrXwdTgK++ zS)XL7G7cs2`CJ)MeTsM)l4AGH)>#rW0-bugYaaa?nFPaId>>(z@} z8l*ZHusw{sGG;YwW7BOl-(eyl-NDrd>g2tp(o*Oux8OdvIMBFOwkMn4$*UeiZ)wdT z@d+Qf=Fw1Ta(&RZ;FkNSt3dZP%qet0g(nJ+3mQX1mK}S0;wo32Ol13+o9C6XIsN2{ zPGntW(`|8M=tH?q~WSVv_rUp}JxgDmc_`Q_1zT}$d0ll-S9*UtY=Q6J1( z8)`D>BhYE(U-p*|+`_e=usvrK%}w&k`*N47PPwtd5sA zseaCU-pAs~<>XrU&Ohfy?EIm^=C@Eb>``1@Fv&l8Zg8>!MSU>uC-sjzVu3E&^OVij ztixRU3EOkV8oAu%-7Y=ls#Bf#x?`LB2oj&DJG!m)DY!1lbNr4-_YtJ}IrCY}@mF7F zuFQA*7<>!;bcoF_!g|Y<&C+2c|E?(wNCriHFz@k-8;3)IZcju7-L&Hj*M7qGoN<&+ zdA~6RZ@B7mH%?x5FJF(u=ZfTwF`8_;QO|P5gUWScQdxO`d+_@oX0u$d(E|J zDq{1K??6Z8^w~!8ub3L-TTW3Q^z%|geKUaWNSOPkq+XX%cwErv(xRPI8})&!F68C# zLbVbj5})>o+m!3sbcThuYkQR#k?QBH!z=29;?7)6zI+xb46pCa=GU(wbZo!aT_k_^ z^p0J8>+jGY0#}9?v3ID=XcmJwfMY1i8#HUAV!i-`z zo!Ab2{WMz|seaCU#-m%+`V|@Q<(}y;B>zj7S2iD|s1N47Ca(SV z1<*zK>R3KE%jDWm*q$?PoUStN?TJRNI^~w!`iJ#qBt8xrxmxepbYsGX)ECv8k?QBn zS7Nv`;Pe~|zI@zLjLYw_`DN`bkdg2r^J%_l7kZnbKA4v_{h^5n(4AH2*3fV(n`=K| zd(Jqjh5qsN+*YnS9l2Lpm+ns@@j3jc!}KkiE-B*9lhpf@`0^Qks6tjDWe{IJcDrdK z;@SLctM6$KR3`JGCx3nsOHm)}r^wfPU44OWSBUl`iLbZ0_7k?}jOeB+Z5NN9Tyz*RyBX{F;V^R5za8P4dr; zIP)NZqCVKq&Ei%bbwH=?MBj2Nk^6lNY|j~2S$rRPd>;9^54Jl!ZqUs>^Q=gG-sDKF zO<>c7$3-*^m}f<*ANs&}Dk#OfXM{RmK9hS58r(J)_e*a*a=JQiC&|Cx8nbf8&%yy;c-Eue@OrCYln)H@Q$mduOiV$LmT}C)nU`k$~M?&TFIY}nBh&!FKuZi z(4Sk()fun-^DXYzWZF9MaaIJWPN%GOF0F6L^+DhJ>&x47flhY$f%Kj4gy-{cL+zzD z2^mse=)YC%Vdcwt*4c0$MxWd@13KAshix`Xm(H{1>H~H2B3BN7AS=Q5`YJo-;(ek*Uj8aQ6J2AcIJ>{bwDS*_?_K}Wa0T34h}q1EX)0K>mjD&M)W;J z<}=Kt)1iz_Xa3beN#hiMK665M9bOqK&Y#cnDYLF8;C@O5b&Pv8;Uqo^k*&y;1af_l zkJG6c>vMokTgy^4Pf>V2iUt#hYDsc`?haOo|B%EW=P!Lz@q7fE?%-X&#$*QGA6Oq} z{CX|L=c4HszSmb~&%_U7*!&WwhdUkZ8%E-z6PCgp|x&v))ednS?jG@JWt4|=BjI^|aX@rvg-*2!DKFGr zUl`o~x)(Wr*J`_DT{hhXn+M6D9akUd_af~~-uq3>eEH0NSh!n>&2LrvY)6yO4J7}I z*S@ZmrKk_)>r*<|z!>Nx?}zMantL0C#|4cy7ADx2>8Xc$m>IH!vxn- zHl6BG*vUn-tVb#GOFeIS&ZfI@zIFcw6z>nzbH+s* zrBC+ImE=1=&qy@caFB-k(VrB37-Sbhs&iO%zZ-{W6!l?=nN(>fy*IfHYLOHGIexjvW|>NHgk`3Co{@QCL{$L-QPNJdrrulREKYz9O8R#}9{p5Rn8JmV&(sRQ7=B!)4DEnq0 zsm}VdY4gWBk?Vu?BNs23Ow;qe>PqG$7A0r zUz(HZ=d7basjXgXxExGoaII zR8h|vdj*BZ1&w|uCGHon^^;Sl5r58kLVy{G&zX?tI_$a+qm~^r4lpCt&*}Gl<`>U! zKmL3SZiElc^vC^7cC~Mwv)-5Fe?Gn|F3X=>AIv*_rP%Z9!Cdh|< z-#1_)iO-2)+x*tD=}K}REQlH~kyJlt9nBfWA$!_Y`0{CTR+O357xz;($?Mf_>p}9L zb>jZ<*?r0N!Ms)(9;!cq?*5?C^%eWhpzye$abZw!ejJ_q`u-^B+J&3bj7faFpG6F2 z*J15Q^>fxywBPn*Ssx|7d}a*WrM1|`__yD_D@i`$*Ij<^LtkqH&w?d3`Y97XDJU=s+S{QmA9mto@*jFLZhUvJUX8OU4L$1vr`JZ+5x(C{k>Vx^F zM=TsP6zFn_E(VY7eh`Jn1&ueqM-F*&W%#2wmHYdLU%qIR+x^rg<>%CipIf{JwByTXQisyA zg7$HI`GlP+dbP3z_j~VhUCVt8{=5PESH8D(N>B^AK6oDLV$9bjql>np@VKCHZEK9z zIzL6O{aUzwhig-tCW%j>gn7YQHeK3Iy?c#qnp}NgJyC~OcFRIhzI?vN-#YL79rqia zeM;=`ee(V1l?yk6=YJ>H2lGK)(XDF+tFtzt@VKBcZP$^cSDWRz_RD<79sgr%7eKM|VAXgvg*F&}6 zir6_0eEGDUi-sjl$!C zM*2O|%wt{BT>E8L>AouZ^8gZ`ZpEEO>^k$G<3}I|OpGhaT>=2cwO zdyo6MKM9M_IG{)Jub|1cjCoJ459Tv?r?9yn&}E%C8~P_+1C5uIj#>p`>Lm5}$3m z6{fN4MjktRM9i`mS0Csb9FCE3%-T1ki`*SX= zC!uh(v981_zI-B99jFi3iu-x&Pk!(!ei*6Fbx}*jK|4}?Fkcv|y{8oDB=VDtlBas0 z@VKCHKw^+vxxP3lFVsu>{zq_J!w-;!W>x1W89_j3R0(6eEw$z^6i+FoZ# zt`Fwxyg0S(C(w;6PTALct?<9U6HvDz|I}-Qlo$H%iAY*z>LpL&|J+t?#id z!vy&EPiJV2sXcpZA74J&Yu`yUvi&`;2CFF@Zx7+~HLR~SalLHIJaT>T{E@seg+`!T z-hMJuWb#xL9v3tg1WUPxKJ4PEGpy__*|=YZ#3y^qgM&eAy1RYvKYF{L`}c@oJu!g{ zT7KYRzI^hM56(;8f&0y|lB<={#pi427h5l>esu@AK6qaKUEpX{pxb1!HT2eGORoKd z?Kxw>w}%dXlAT<2i`TBX65dOS#7D_q>b(z}?u&oD`?_A-@1tPevZyT@o?A}vKY23M~XL# zk@!5Q4F4L-rnCJLb_QwYz7E2?TaoVKOU0A<@}W%=3p@T5_j~5}rK(3f`8hgTr~A*7 zU&-~sd?9-1m1XnAjZK7ziU);=LNHK9h3XcmK-Cx`^UOj;O_vbC^);MHeLP&hhtyYT*WYcx8AFGmeiTgST z>sca-CS_-(^X0SP(0L=f3%H-n*xUX(YLX=Wi(GuZ%(y_V59Wiq>2qB(Ge&5m@VKDy zr{$IW3sucrbr(#k?oLYRWN`Y)4Lp>Y$fi?Tne^2xf%`lU^+5|{9jDCA;>+iy@u_U| zDDEeNH2oA0CEw>Cx?OhN>L|HBn6Fbk!>}9BF;@0$m8>6(!sCL*DMMniS7tYH)g7^& zL+dg62ZPh^qpO123O3#Jb$vFejOISiLw(-x>VD2~xB2p!z2koKdu`lr>C=nB{Y~-f z4f;K~Wi3;uO|B1~kGg3)M+4|2_v&2Ix;FrY#|4ce!>wlaz4V={F4*sb`p5P*2B)9W zms^oN*>qStu0Bw|cG!KB1(S36@@dF^_vAneJ};Uwenw8U#jiK$cV6+!*4P$ueenG9 z_a;4=x|pm3p{Fsun8P|0coG6t? zxX)uyhgN+Hl|TNFFQ3nATN_t*wxCeAaBHgJ=?UcDqgm5_d)$W376xp`8INec&Nu~h zOV4SCT!~jjInVRk@7mc>cKL1tSKX6Q>BABXni-rvfk_0% z^m|ammrt$r17Lh0@qZ5kp63_G z3^a~^U;Pc`*3Nus;GwlgzB4$_GdgTfyk^t+4$e8W{s{N$6zcDVoiw`J^^7l{$SLg) z_Z-9ho|wl(SZCnl3Hm8qKpw{&Bi9GdYc888WeIfO2WnN_e=Uo`Y&U*=oT8t-di|T5{1VFjhp*^Uj2DiJy%_$nn;ZQi*F20 zzn(!CDnGL6Ru9Wo1?{-{K>d61py-Tpv77->$lSDbS6+|1oFa!JjmE zT+rBYs3mz!;wO|_`;c?9{UQf_W^kTA6TMvBfK8Wl_TJZRgSc~s`Xy8EpUB?%mM@0l%k2y{~CRGtP!wg}BfKd#pe50{T9^y7@RyLZl8bg7oX zdAyXq%hrcY*Ot2VfbXSRl(QY@ep%uN>G5ay^9dXlZhI;p_v?Q3Nte$cd>{HguvEGc zmrt$_o)_Eo@{Tvqm6j`bpV-_aG@qzLQHw`8kn=+S`<;5mZDVQ}a3983W|Ma6u<1t4 zJX6^@rUr%QxkXdWQBCLW^XD_vS6oVNI__7v_1r>4scRZj@ zyn5If_hkNj-t5n}zFv>}Rp<5}(PLv33VmQy(-`zJwf+MG?sLY`qoVdH16|d==%D-A z4MOuVFu$Q+>`Q)KV4n2d>ts~-RFU$FZ!d)B4L9&-KA2S$t2^WC2M^5=6! zW8lp86x=W4vw`ok)^{lMfiY=G?%Adka((c8vscr{LZFkE6#d-x=9|!bt_S}(nXwIj zouDs_kkPk2NR3Ex4k59a^bYt!3(K)1M5tu)(Ics|p`{Ofw9;ja_)g|YQ~y!MPa z?-+0&#_B##rVV1#sl8UqcAP_gePMeTm*39bZXd&ceGj`-?5wgL_cMHDcjc?|TNL`h zIK`o1ly7}~H^+J!Iih1#B%3tu;3Hrilp62W9;9SXo`!I6q z_DCJO4%(scJhw<2BcoI>j6WZmkJo{fTW~)cB-*H*RzdP_h?dd{+(NDo=I?v$-knyU zD@Zz5H~5h7eD1qdW!C6&=kvA7%I4O}w+xsMM!n#BZMAGVvBw+wF;^N zh$)rp@No=%VT|dxymQC#3I^PV@oHR3?t3=fl`&gB>^n|=ePMeTlu zB1%&tH>AH|a2`K1bIxgZHeIa3qp?BhZ&1#5ocn>cS`*&W`185ByEJ&K0vn&vGi>h5 zy(am8ToUkcqXKt6t3Dm?_ZaAw#w#O(E(_0R(M6Nxxq6kPys%%dT}+;J+LklmK8yoy zAARJ33W_>Q8E_xQEtxsR;cPm^ld@h9 zJIUi8wukZURYfJUQ2yiRv)(elVav);sQa|o(|6^B;@|u5_?1Jq9u8hs#(?{rQOYR8 zXf@E~-4>ghJ4N{QUB~fehnOsPJ|fm#skHmAN%>EY(omCN(`B_pe9^v79{-&6K0g0> z{Z%Rc>(}G7;X6_$;JnWv+WwkiFHugv&A|;?^Xb;O zxAWyj{5preFz%?X`x22*!hriQT18(CFJaRyT(gW?{CD1RcN?oge*IwnxgVEZ8~}8viepsRIN_f!hTlR}47#|_t6Tag zzK}igiUIS%I90qY-keSM#UOJ=b1Zp&fbC)I_x#AE%S+x(g!|m0#n-kO@94gyC;(vk3E4d>f_AqQ|<`QM=V+1E>@B|pZyv&o(74<444nb zvZOKA=h$?5G^L#p`lX_lXG!D|@K`^@JF$eEu{QRo9>fz`>k zPQ%ErA3VRuTJGR&pesw*JK=+;@XzlPH%-0Kqc6TrKwlW299e8LKJz65?!%bBVv(~J zo37fmTgTW;^85hX!`P|#<aZw7kHdf@<59Ui= z)oz^+blV?o4;`TLUFheF^wT+`rA+X30{X&u`9c3@b{}6b;698cXA~AHv+3eb4vw+? z_yUFJxkWQs-6*u9jxV2Ac9-|4uflmZoDP^>w(tqbfAq~7Q-xLJ*AM1jV_Y9t4s=^q zemvCmPB%4*E6lIw%@@7SPqdN|NE6n#P?qlJI}P#xJl^Gqzh zPC#E6Po9wJ{lVus1Mb6E-e=^96gHhjQbtR;4|#oo?O~i9GVLdtv=;Un|hxc3FEcErY=$!~{bP2vrKwlUwb3dP$ z@$eY~?!)+PvCQycY`Rl@-esFTB(E>9J&aEV$=7IqYUa!5phc$0a0i^vhUAv{HDQG) z^nr1BY-1mN2kv}&rSzQJ1a!@7jkhbz5dQu7612oCc_4Q_ShTzq9c(muPkH>%_uHT)Wj72V^Z7dI%=D}q%8ld6c}q!1gez zPHNKK+}_2PPf?$ajT&scs}e-Uo$K`&g+4F_tlE{)pW^j{=claqOJD%qk-qp4p6~44lRuwf53h7<(UjuLXG2TSn41~6pUf45ut)a_NOc~Z>>6<`gIpi1 ze_?#YzK=k+@_yu_W!^u8=ELyY`ef8k{5}Kv!Z>fhisJ_oix_YpMu(`$FXpl7qGbEl zZc8Muzpy=wb>;6Ktj(6;%cpO3&WH|soR90n+OP{l$$U)K-)OF|=g#ND%hzeQfzENS z?3}k z0exZoSRVUk|IikrUuRN%|URcD)P;~t#P z@bv=%FSkEHp%08-%s)7m?cvTxZkAU>IneD)$W#;m-X%1jww~1~>lbt96Y2Ll=1Cx# zk7d5rsyH^?o2O_+N+5qe1v)DJl@pZs@~Mt9AN1M~=aaZ*#-^@dGM|povy!t7x${w< zq9U&s@&Nsj_qe~qQG~=7a^@DFw`MHZ@)f@i<7}5A_9NhBA2J_b$(K8l*>quBt=*FP z@aL0j__3ubi$9-x-x3yBf581p`>OhTh>`iE_BkoI+4sLY{=)N z4twr=)~lsXIYOc1tn2^!zQc4o3lXFnqJ@Fb8o`^05_VdBIPZ2ScDnT#?{-qyX~r<# z?T%xomHLYCZumEy{pIPZ2S)~;|Q?{@HdWsKn6?(Z7Rp*w$*qA(; zti`-^5u}i|WO2QjuHIAHu+Zoh5APQ=mhKhJLG_zgQ9&tf!KFy`j;=SfUG9CW55~O3 z+P|Yc88P#8LBV_4BgtkHZ|@JZgFzR&BS;Nx`PAy zX*E?8A;=G`o*%SIr(+R^Vt!(Eb<*~Fw!YTY>!SJAWK;s2sJ8ck5-)EA6?t>B`e6Zr zIxV;+#EnoL)CH%WhoD!I*BSoRd?%C?bK1L^y8p^_D;v zh)r^PP#}S}KB(5v)ssYBP8|_D5+jL9Y+gF^N0%hJuK3yyZ*M8|`}w?%#|2U-{ZY(o zeLZQE_4-Mpj~o)@I=iG%$Eb7jJiKL4)z+z}9~8)-IR{mxM(fF<8@4N?9f^@e$HuNt z?dXz4rGvjcS>!E;vR*Gabl{yH)p~mJD2tOkYJFOAQAd|N%6c6Y&}-*bsOAxzj{Li;bcZ1kW&2{kU4 z^ZMDPgo+)ElhD;uMq`y0-0=2RMp@%b8TDIJPJ2|Kj9yJjdn1adpmRQKRo2r}!Fa2n z&FIS?u`wzbcNH`*vQGU+mkP=n&)w1LVuw&4@9wBbi}cJRG2KyVn$yUK1>MmSzjV}R zDHipyI0TCb_A>-!ZRlgs6pI#Ew87$ZR;16s_8qbP+1UPEY=1ts@4||x8+P2C6&W6^ zhcxt5Z|peo@6W#k{!s*&?{zTmOQcvgCt%y~SA8O4tOK4{wL`Hefkke|#Sr>0 zzaF9p!n_9!z}oW*RQFT9m`I9`m`d9Xk@{7Ks3_~kP72(&F@MBF634Q7Mqkp6&6o2& zjC`NS(u;@?xj+toeqWe7nB}M;##Ro(Sr38)v!DJS-{!{yjt?0BoJWl&i-#5~U_Je( z@%SHq0sc++FM)pv{7c|3CQ#$JYm=o-ce6*2-;XJ)M9^-kKbIdKtC+E{Zs~J(>!n#{ zJE!%~y<44i;?>Mu9y3I;McneTBz;#H-FV>sNoViljJrvv8fiIJjG^7Mdu8l*Gdt0; zSbpDu%bBAqT6auU&ClZW|IocsCT$ag);+(+gu4pG4As6nZ>0HDXASz|YAU86lHD=) zVFkma%s5W83?Zf3pLpG&%WbO7U&`J1@QQU=-Md&Tu( z*56Yse;~8|dgQzF2J=GN%_k4+^)FR3YRkh%=*<3*rFCknI%0)nUtjnJwREd99+ev( zzOu+V(?+)8T!n`vqxXodJJ)Kvnkmj{cF!3!nxU4UQ#atERW_`D?0}M^rNCe9fagQ4 zyDw?+cTbuwnDLFVQX{do?!f!3YOxlXmz_TuBM++0yS=5scvwT=f#do1nakH7cS=f~ z#9%lY{!~kMHamZ}*v~j;JY!T!N%!>q_P_nJ{ddL9KK^ZYIqiFWpK8BJ&5Tef z;I z8b9N)@ndf`>D1OQX8|wY2m69m(w(ypN3N}9zP^KOrC%^#-+pchZo0ES(7x?MuZn=z zQ?W)Og>GJ$W%=#3>3HyZ_jk>IoV%>fc=MGn&r{2+Gv_DlQn?LY&nte#OEfN8nJrB? z^`;cO-d3w7bX%qE`kVjt;_r&g`mymygX7UAGHl7kO^ht(vDy1?g7K=qZB*%Wvohm4 z>%khkHXCP7>@Y7(2jkIIwB%%}l!4jok8jVVf$=Kyu+V6NqZ_IIQ&L}6Y2U4;S;}kO zSOBi4O}=lE4vg)ZP`AP$e1WwytvYg_RaJ<)(b4C~h}##lOioz5%G-Y+-gN%B-QB0F z-ppF_YDW)aaJ`j1*!=X`emB1LcMp#!1@+V3>|J4$p-_yP6y$d8qm>!2KXfReBh1)z zL8K+KeiW-en_vB${1x_hWAdkA{86h*XY`IPtuvN7rDu4$)Y{ZN-h|BOdj^N)Qt=lFsCT*tqGD0BSNu}O*!7EYT)(C()a#hnFN$5i*__ue z^yfDJbgekeoPTK8{DX4LKc@S8$1~?26q|ptIp-gK^XCiMFy{P8!{$#jj``Dc{ewp4 z{E1@oXEwL_6Rt0u^Z&lF+nMt}yxz>Jv^0xlCYBkiw~icgaig(m?TSOp`5(pR|7_0r zAM%0z*z!onA~H613UmFUVe6L}JPspk{8(Y*$1NKkhmq6&^ozh9h(R%EHz!l+XCjo=40`n7pBpSgaa*!uO`AI?7y>bEf0uPki+Lix-;nVj=aKj|&Z^$W$; zFEh^dOL|v4bN$M~)-N+Y^JgaK{ApNqlDU4N*!uOGKU}}C@d)py%=paznVj?gIkgJr z`h{Za7peY(JwGwmuPki+GUKy;WpJ)v`+ja?u3sp&e(|lJ&-!c1x&HF2pOZhI`v+6b z`v*?`aC~wbKYZ?gOgZm=IL8n4hwB$<{PVtlGv&O0;~f8Re&BZf^11&s<-GsoyndlS zxA}+9{j(|O{WItM!*BlNbN_G3dH>IC{)Fob=lsv-`Nfp;`Gs@-hkT$v$MYAB&-0fF z=ku3%pfB_J%M^S5qS=N|jEqK=%*5N?>^~aN4^2GSkTB=T7SpLJUp=I4L$iXseJ3R~ z^kIxneWq^YsGQyA*)F1eH_E6g#4~%0__qv=8QVOb;_Yv?T|4FSkLaq* z#;ySe19D5Ueq@bkVfyc0ZoV}R_%FF|Q*6I)BhC57(t9^lY8X9@hQICH+=r1z^N)I= zq?|n^&(tM(U6=8N;fXCPb~>DhpB!$ zEI*+%e6z>n7mG88Kb!vGP)RUDKPvV0m?wT_dyS86-QUxL(GsIjxPSTVY%7dU;?*rC zCxCy7#=>rA8)VVc?W1}aIErM4+lkW#>Z>yvB}aX`EvAs2(W|K7UY`Kdcq6n+;>wB) z@AyMI3aVEzT6e5dJGE%3nYVJh*r$NSjCRQ(=O=r+Wk+K5zb|?4EgtxP4N;o(saY94 zKR#`S+GL4r$H&?iAN!~=R92tea&@On_8CVH(>eQtOdVvBZf_VCl;L~ndPIqN5JQsQ zetU$5ui4r$@x~U&3dT~&T`l@*UfDKS{e4#@h#v?3P2v4t<@u^_C1nH7~R6iB;Z(Am83JFTDX8 zzS$O-zkZ`n5VQV(tsPhU>Z_whcZS+$0v@qv7S|><$THs6=WH+nyz19B7j798V7e{% z`n9&JD>5#Y$yn9{9ygZ9O`qcJW>#jaxIP!~x_{!e!tq5*v-e|sCM=WK#H>GFCu!4| zNxe}=oqH!Q{y)OrJgUa``~NS545d*dR79vGq~YA>x{#SjB0|POg-VK|IkOi+nW9XQ zAt6KOKKCt|GNueoQizaJLM6ZJ+~@kd*ZS`Bv(Eq4zW3VK^Z9)2Z6)MAtK-M^)9cxq zt5x}Z*^s>VOwH$S>$5sLXlEPlJ@I2X+pyvGuKnaa52&}_o3PRi@All1y_dYV;o-%z ztn&O6=D*CRhxBKRA?kC%#w?HM(f`lZ{JqQSq^H`yXe%Llb)PkU)#eL-?K`4=n~q=i zVA;5=bakRf$CFZ(A@|1M@8Js)G>Bf~7QK;fG+U)mU#=fRsvj+$Q#+V7H!p~JezH?- zm&rcjYuoN!!*3()h9uqeIb-zJ(fsyToxceM%&+Y!o7dcXAeHN99o3Iweb|5Olsf%= z#BbgsEZs@}Xi)TQ8gbvW^Zj#Zw+{1NP~oa&5u|?}_OERIKUb|EN9K?6 z4EmOm`JX#FEG-U=^s)3WB224eP1O8vf~%b9>3_inM1j@pnpX5 z&qMty^KZ!L0W$w0>R(L#%MPqrT{1Pp%wfk!!M}+5mxumUmOpjRh5SJ@e=yA-mVfg- zWyfz*2c5n`{vet^Jj@?u`I&+)$nq1>{KOzX8H-6mej=KmJj_pJ`G4_=kpGD0KW^Up z-TB$ZzxF21)sGkK@L3!QFZ>Vv{EuHyKRuHLej&;)4E1kcEbxn?{KEgx|Nr;}^&hcA z;1{C&!qC6n8wGxGlwbHC{$&E&B^0|5K0^O4?fOB+FGTr;Vg8hLY?kqhqx{1E$e;i5 z3+B&|T!CMR@(aWKoWTnG;wZnclKf<0e(wAz@C#9XDa^lBYa!2M|3R7y zW&A>vUkdf*`Z1*X(ZWjjl?C}F*UvhtpH&L=VgE|_%Rv6Z{*}#N$^O8={Q=HjnSTDU z|NM_%aQ}h&QKtWY>~HL^CBZ)y-!OB4`y151GXMT#|NI}n;Qk5yt1N&1u|NNhUvPhh z`J*g9mF)iv-2Y*ID$9Q*_X`8>m*U03{etNIf+4@+bn0aH7fbIiv6B1C5#C>!Ny7cb z(ECgLFiq4ex3n#uX}mRBYkYs?gcm$0t4(Dphkp#5Jt;=I_1Nzh`8i_FsZT&xL%r_& zkV`X~8qH4ItqZMMJNCVrTy*B#JS!JY6b(kRLUXHC>eEdQ;J|Bh8FH*`U#jwjH90opibP!5ji*k_A`SS-+K2srjf`LnD>_X7*fl*1 zg=*FxICGFYT&SgKb~Om^`MM|fifJ_GzbELZ`zB9*HY@M{bC_vtM^eAyMd9`bIaa8h z_~Qv}y$<}?yZ4>+q8+#lbaSQp?PW-BLVb-o`}kg@t98 z+0}tqbo22Slhxa~#~u9kjv469_a1xt%01G*-iL3o?MZ#-1JA=J`wT^!m!0fdo85(H z(vIX5yN%$s8Lhhey-|l3mj(@K+PZ~VJAYZ|>A^R$HuxI#%iX?@dlnK=pB3eg--Mk= zy!&N0w_7q!Z@BhK{`0T}(;kreqa4#c)k*yx*`{+}xs5=p+jKGiM(Sy8?Ynxa&rt5b z6NiX8@;wwZyVILvTbK{)c7D4w=Qp1F?NEAhsUantXT@9iDy@$`C> zKfjpH|LF0{OlMMmeG48bF4Ur)u+q5k$K&|x@Dcl$~eYr zck;erZ8Njv`q@tP}@U=pqpc zESaaVl)NW>Z|?uzdzQrYqOMN_v)RGQX|b(!Qn_l1vdHD{A2Zg*huyZz+7 zkG zO}RN@wCL*X03G6|M+=&~-qj{DV;i%4=1y88zTt0GbaYvQ-P|_2Ei;T89N&zsvpV15 z7t`=7U1eF;bLlY6cl}L>-*!Aotaln1th9gC#-z~~iQi72m3ApM`i=s7f4(i+?9ZM~ z7@9rVzmLQ6`o59kfIt-Hz3+_7Pq2Sw^T&(K&b%gmd-tfUh4>A>Lo*WR`bMyyLKj{i zXlLW_YN#-OMCZ@L`76`U<#Itki0TJZ{jjF>&0A)^wsQzIl;zKMB+nmj9_mM#{ySe3 z^pB|iarbqLc4wz-VILO8`zJ3HIkYVl^pB|id8mJ7{&jgJ_!m+CV(MS^fNx9u(s3e( z6Qc$HBI;ir`d3;0^!P3052E>lY5uS#Zyg$XUbSn&fy*t=Am`xD!6Vd$SVSd8=PakJyBFq0wi`%bQ(!&E=P3iloCKXsMRKS%pV z|LC8&H97r{fmL!A?4RZZqWr>e{%+m^zy2@J@IU7NKYqdachruT@e5IYVW=O!E=4ka zag<;9ANu(pzo340)(HGUlwTO?f09(-7f1Pp|Dpf?@eAs|&ryM2i1G_V{|^2p@Qb7T z!vF9ulXkPRd^_P6^sk%NCKjwGzwkfulZkr%ko~Qjo(1#M_@TfrMEQjwzr<=!Wc=bNzwkfupQ&3`e(f3I7tH^- z7=d4i@(V+L&FXke#xIWY3oGGQ7UWm#Xn|jd@=Iy||KKm{AB2zWCj5f@h5aj=|3CHz zcJVmpD$dr%0qzfQ{>t?8kNxL={DS)r)Q>X#|6_k+TbE@vZ}k*8!2J#CUzvaZv48%L zUvU3~{#BMg|Ja}Z$1k`)!~9W}pa0nZ|Hm)5|HJ%*`Om0Nk=-vGyUts=2e&JQZ{l(JzORVJn62bdx+eqR564U!j{6I&4*0MQ2kecCvlE|rj(A_s7 zT5U7#GNYdu_18PKO&ZhVZlC9BbGd6{BOE=p8uP09YmT0_xM9~$9DjGi&90K7{YFy% zb~m`!nj>uo1aHK~Y1`H8abM|{8i$@?mp)0g_PORPCG{P8-mwiQ^*=9JbM`|2p=hVe zrruNM|KdzbTBiMo_u%Xkf*%@>HRi`jcS<7)qZntS&b{_6EX@i~Yx~ST`8wC}Z&b*G zKO1n{?QL=w=#iMKkyp=fbOH^>?N%$&uA>X?5@RxWZ9ry2wfttJ0pI^JPo~ z?=**7ezVt*@X+4;a%1(2y}8}Yt8sJJb&33v)xP9m=KeL;xa;c-R!`dHW6?69+DX|od<|9%T!ZMCn<@^P9~d}GU1Ze~udcQIOzFSe);Ufu2tmpUuQwSVwR zKH-AA|9rl5ZV0LWu+Fvq-YFL}ueo)8!*+c>!O7+8ZU;B+YRuU_=5M?6D*98lR@WS2 z7IfF*7T>MjXJbtUhYzd|TwoZCCI5LIw7hwdyDXJjd)Wu_BmaJ~l)dkCyUCXW zN&OiPd82naxS^d5e%Jbtdg?bthaR1B;jEdCYnsXT3T!uK6>A)3SeHb*_GLe^rZ3vT z3?cQ5S8U(E!afkErZ?8gzUT7NS#P0XFuy#lwXP4Tua}))6in*Z89)EK)WjX#T==NF zn9QT6s88?i*(+WL^bLD*3lgBr==bRpw?n)@8Z6Gqcu^d6;3ZITpbyv0iIy zHj~Wjw_9GyE3}>;;``Rto77*bx42~^sc+)_Bn(Uooh|J2io*H>|Rfz$CvH~sTuu;a!y7Wb*@CO7j7C)+P*BB zVZ&~e&6;1Dm6x)h=MthvlNj#W?V=et;mots!--zE>zDiI{Mo?wwip>9t3T_{;ioeF zB=qmo?}^%6G`IY7o;&fA#~U^04jGwbAKX5!`>9aztS`Qt_QNxF>)ZFgZ8)*LXjrRc zB*uE;DWj}cM_qa?O?-271BSI3{em|t?f;jPSuW`x84P>VW5)bn=( zdumV2>OB#|9a1;$pHBKmbC&DGT$o0dvo!q}w;DkvItGxvMAgUi8>PMOW_a5-9CHhCV zLVgz!{o_kj(qZj14zusATE;oIo$9dRcYHR{Ke9Q!V1y6x6V$&l|8B7p{EMi6v8vp^ z?3{!s+t@G84*&HL{EMi6dFWqd`BSn&$R9-W2dByNht(3T9(eTUM28d8g#1A?e|VTb z%JOq}iIAU&<|keu&rdey*NnVZ=SMqCtP=7Q(fs6Lek#lV=M>PNO@pnlN;$KIx zArpI7OnE=d!Cgnle?;@2Z@%$(uPpzkO)?6Q z`wsTsJX_!wNBM8KjBh=UmWEZhWdg0g8JE0Bk&7ReqpHp3!emjag<*e>L2n8>iD*%vY>wpPYV1(lwTO;kBhFrFOKpH!~B8#g85V2 zFj&SfMEQkbe$H|i_{C9vVVIxV^894-vkHU1g?!0^`FZNJz%NAkg(1HrJp_JnlwTO; z|2293Gh6Sh*vEU8X2JZwbV%SAqWr>;U&RIjzc|V-tb|_@$glN_1b!jPFQxrM{$7;x zm;HVvqroV8xC7)b>|fdZ;r`$&-yhgBjpMBX{Q=HjnSS8@1NjB_AE+N?`iJ}5 z3;F)WcE2j>oJ05p_cy42W&VZxC*&90KcRn>e!~49@(b?&Fh7;$ zKfGVY%kLL9M8DN&*AK%S;QcZpO1NJTyTY^m!ywJnVSNa{X)8|Vc?(_cY z7s!QA&MTcOHsxc-;q=Ipsf?{_rS!{db4lRUnKrfI&$yeW@w+NR!*N{E0K1;UZ*z`! zyiXOX2k@h&`A+Ia>U;Y={&LVn1l7R;xgx2Na_ak*yHf?F=x@=+R0{M7*4wOeE*H6``q!oz(tuM!Tgd< z+EYwO{U_(+h9;8wXEraI-bTkC#oeE^H=NX4Q;>N}dxjtPYhwS{0P?+jKfmi8Q_nH+ zt9Lp5H_t-y;pp|RQc^EAU4MC2NHD&2{lacr@;x=)Hr#4pn8JLf2Dv0x`30i6Pjc`a zGLNGk0)pJX4`EZE?`m(Lb@Jc4kJK;upf|lw!dkT8 z@2($5h@Vs*t$RFb^mC?W*LAVFS)};L=ov}HM{nBMNdi8%?$k|m&~gaYix@0+)pA*J zzv~<6vmZ`&y@=o1^*)tQq#mWT|EbnO|A_XFnl!HFj{6w%2($Xh;P8AgUi8>PMOW-AV-gBdUMwp=!H)%jt8hk7kW1 zZjPrz-vfgF5!F8r^{>po{A9tui24_o%KgjQOt^5O+}6|KgNfi@ME%P{|HApe{27!d z*hnG&5zT+h&;N0}cZYaZytXN^sQVa)ep7|~ zM>PNWz#1cKS^m5IQq4&xdWH4jeOJ@UUB)j&`K55*#eWd^g($xi?mJk2=1HM{j`ojW z|5xSxGp9zrE?w-SD}nt>e+vC0+CPT#uRbmCi=+I)aQ={AaQ?H-2>e2nUl{5qjTQLC zQGQ{lAILALpL=BjzYygYhWantCh&`+{K8QGkY7;$o>GBdi1G_V|IXbZ@Qb7T!qC5y z<^E+B?%ox1W4?t1`u7np@C#9XDa2RD7l!;&IVSLnqx`}!|7+#>&pe!4*?$4y7tH^6 z&jfxU$}bH0)$&E)7f1PpmGDaf`K8q)@C#9XDeWKfx1XH9tWI)MRWjihL1P@ z?hl9L`vZHqkVi)ezu^7==MU>c{lNVP@(b=iP(RA_5BIkU`ToWpd9-}zW5O@Ezd`*g z^Do>#A-~}M3H=M_1M>&&&yZhme}?&^EI;A?5BUZ6f0&;z|Ig$L_X|hw7XgF6_uFZ|pvbN*x7u<(u5>CEstlP^aDT_tT626(F;{m5BHpZ7M}bzh;pm!{#?r#)-TCGfN$0fnw{c_3 zHW;%G{rH zm!JiqgEe*DaaT%QclS6Lj=ek_>ju3l;~w>xKGmjlJ-^7xPZUM^58gE;@-^xIZ#R#y z#+RFrk=Ok3I;38nwVR>bUjY@=;EhAzIXRjc&*{VaE1C_k()I&^tYj>1*e>Eka;{VO7$IV8_r$+dPlXG z%qt+r&FsSR>&)d762Jep&XI(#7~rvo%%f^I`Q0w(*5FqsOWWNg^HTE}eXS-ZQsI5= zTA8Gzh3r7a&cPGTlK1p(=XAEeRS>sd`_%6W^4_|eCZ)M(WH9xqxhJcFTqOaHZ_ief z_Y6%*oTYQx7xy1J{%TXwNABXRW3K$XXodcJH%{-s)a*p3KV-y36Fo{+IvlwhyOh%$ z5;uH4(QCV)w>Ml@9%pv888$cMmXqYuy!Medi5`ES`F?Vk(LCJY2Nx^T>nwhKiIIDZ z!ut+3Sl`vk_CI7NJ)QfS`03!o;MQB#S26boAKKXGV~n_8+RoF<>L1wYc1gW|Ze@Sb z$f(qtU6wkDla_X^-;(iGI()Q`&ko|ZxkLAy^*I-#wEt7SLjQ>NkEN|AWajuCXT839 z^eo%#<}mJF)oIc{nzemwCF!4s{X>7j`Oj7p=8x$7@x(2&wLf>vV2_xtukdfR#GwcI z7uaO}h|Zr^Hh-v}$%TS`5Y-P}ct_9=+c4Ab=y-J>hp)bZeh}3U5A~x=|L+C~`bSj% zILPSq)h%1ISS{xE*bAX69ZLKK{UfS>9_kBJc}Qekt5{FD488LX=+$_Z{rN z{2}Jf9};3sHV4)W0@B;1@^vg`xf-zo7nK&KCHED8DfDZ+cgO zUmWEZhW=gDL+~#n-El-Ui0}*gw_vuwFGTsJQ2)_JfnOZu7l!!*`33Vwa$MjSqWn^L zU$4K$GJbKCUl``+!OcQ`G7cwec3oKODuMY~W-agwQGO}(Z~jx@7f1PpVg9$3=Rb3= z`#$`N=o9Au$?pQc5apM``(Dr&_{C9vVI};MKz`lB0>2RDm(u7j`NRDoTfRTA2?I}k>!!BE0qzgV<`4A)_aDeFxc@-?DAPaO-{Mya`x_gj z`Pub5;TPQBp#EV#K>x!16Y>l0pU}UsKFlAuKSO@O{Tb#Dd|#NKaQ}z=g8M(rPgo!3 zKfGU(G=%$w{bHMwYeV=2@0W;^!u^8i{emIC7M2V57fbIiv6A~s1n;lVAmRQJ)B8(| zE}m|wZPS)F+wgqV+cV_%{uLLp-wt;co4p>-cQQ?sw(-NRu_npfz2VO%Z@Fj5@1Llb zdTPgeJ0l})$F^HXN#b*V?W>y6#66!F7nf%fhbOU%OLJV7O1G{psB!uJT{_Q|! z)x1jLHMU~Xk3Ro*+xTSlHd?B9R=R7ck*n~?4KVUzc3 z=pZVk+-35mh?_TCd$CsolJ5(#@KB z&i=x~!ZskdocHnNoPK_oLjB@rY6GPA4x$xdhvt4UY{~`Kc}7X z^K%6GUe%R~fiqU$XGX8SdtWnblSHk0PL4IHxBIj0wqE&Rcx7PsV58c4ZfR4e{pNQf z_`ydO9H=Ajo89xQK?Ql=TF�=CUL-d+V-@>tr5}>mQtrHrdU6)0!F7eFFO?2ti^FtN6*M7^SY3K_)2?&XodPWzUO}0+~F8f z+q1F2iM(gGRzG!SKH0=Mq&~QsNZwn`r1MIF>4WKK*1xht zea6{!9x_}s=IrCddoFI`vEu_q&iGy~mFuU8>L*TV|K0kk_!SHeLEfRaWc}lmd-umI zjlINrWSpHaaOGl$xSr1@>;B0@WgeZLk^XtuKYU*}|M9CX-zs{%2|a46mdzhKyjZvR zkv-2g_nWtBiE4m@hwXiT`;2n*^-iD71BsuM%^&LLgW2#+1Bl-?4UCcL2QU00=!abx zJ6E%}Wr)MT*c87tZl94`?gg2Cc&H!fFR1^Sv9YfTo%f?R`Q5${{o^yYLcfh%eV-k3 z(70|(mr#ed(lJJxch{nwYum{5&qMvg`p~~WTEf)riQm+AIm!Hs^-Bc*vNe{O8V7^d zI~>XEu-LS=9=W$YFY_-C{R{IA=FeMIo3kO_N$BcsPg(xp6`h3qVKW|#p4s=x)>Lv5y>EdO(U?X2eifASyRcheUhA3TWoZRynZQwYBl?z{NKXM_FSnoz0J zd>OwK?mO7Ohx-%u$>0!fc5H%-Ul{gZRweY$wDJ0}sN0`a64<}*4F8Ob<~+1H=d7%M z4Cn9Np~vS}k2i6*Rc6chh2i`mzu^2QcHaE(^`&wYYp;z7zZB}%wmHAooaC`(^g|iH zFw_s^7t~LTew!YjW_(7v>ThKH!f-zA8nU0gaNf^}S6j>Yg`xf-zo7o71-9Nli1=-` z!4Vn16zZR!WYc9B;bG?Ma2dZa^l!yg!N1I*gRk}(uiqqr{=IsI^}JG3kHp6Z%J_w0 zzMZh}lm>VwaanOv8NV>hAILA5Kdp~9pPEPfRujg__@z+4@yzRC!^l387o0BR7l!#+ z@L0%CCZRlMQ~}`^%+GsT6FQb(_>DNXZ8Cl-)HiH9vFsSxr-BbYl<^D0{C~j-`OjoY z0{UDe{DS$vVa6@{1D_j_MV6P0Ul{VMxx8;mf3gogFV-1D_=T15O9J^N*H07GPn^>J zA%D&O3jAe_)`z%P_%3#U{Du9)_l5I^`@@O=VSiv3^XD8BRRSE~{-A9BP(N`0f&7B| z57ZCz7t}x8-!gb%e`6!jxh_eBUvPhe`iJ$Qf8qWK`33h+=wFy`Fn{3w4EY83XP7^* zKFm+J|3iMk{U7EhoDa-@c)u)tBHSn*x5-YjCMDYIl{n7H1o6Ayhf3pVJ{Utt~v!`lmPDj48c&y3y-ZQz_ zFU5B|R~d?Ld-SQE5pz(w;&Znyhr6b8ZGTu!seL_|x9FKO;I>7r-I3R;U)|{IEIDL% zalxwF?f4J2gMOX&i^Dyho_Of(9U$#BZ=m@?lR7D^A8s1`B94ti7YF&XMc(cBWH*CX zCIuI{-pAX1Uz#wOuLvJCWTWE^=EwryX{*}COWu^uzpFz2+zLjwVw+AJ?zc9`&?d5s zb2w=lm^{XlU*MeCL)L$RT7FP1>HpLqt<@F__oETJGj=`h+?98lf2LoS=0$FIl6I?I zXRY|#YA+1i>ECC@_HuClRgf&%f0$nwF{3TN^U8v%&uwCHT(m>G7F@&Ge5~#;qunYV z_OEwgqW!_H$Iyuve>Z%4-J2h|?taw$1LwFSt=c&Mva;YUKbm!nn(>SY?Q}M2>D*Mw zxb)>!WB0bPY_^?ucUs z{XT(G+>)%{rS|15)D1G8TbLPH6gSh{n?JbYdlP_J8u3`MqA9_Ii;f;jfxyw%yUfEij+^=5DVIIJuuz zV-5LU#hato#B~u0{m*;->&Wc`=TK65(fT?vkHE2$M<4Ebj9dEaL_{r_*QquO<_EOo zF$Y>dPR3+Df!DMq`jdHV{&}kKqTgDq8_@O6C^E05+v5-Yoe-_?zE>Mh8C=)Ah+OP@ zH*O*CIcQkf#K8;qb8Gow3!jnqF3X?R*i!hANwnyDf5wYsiFxbN;i@BRxNo7_R_|PU+;eAK3`j2}TTtxFDJ-;m`dSqPVs9OayrbF-SQe(|R zsxOQbIo+OC?d!cr%=k?o;bl@GjcYs{SmZlr%6_7D99=ieZoKce%;`>v=i-tqb&yKC_-HS47Z zM0SxaugUz;IGbf%F1h~__z>=Qozr052_ zukog_TI&Rnt~~!S&42#r+!u{Qh~IjR{yklm|8PF=zEk-k@C#9XDcpCDM+p4FlwS(> z9jrg4kH9aE@(aWMyUZ5)XQtPfw%jK90Q(<2Pv{@f{xO_?fQ7&>j`9n``9pre`Rm3A z{6dsp81{cg&M%Jg3q$=tenI`j-4ytRD8DfDFLPJm7f1Ppq5dJip#CEr1%4sQFAV*A zN>AVyNBM=JfBPO5{L8#hZNE3WAWZ`Oi~0-v!jxYM{d*P){NgCTFw7swFPJ}f<@~~w zUkdMwn*@GwlwTO;XH=AspUfKP?A&&QUobyU9~Jn8DZdonw?NJ>j`9n`{MYI!KlhlxFHHG`A-|5w`NdIwVI};MKz_M33H-v8UrPIj{GApg@Rz+awf(Ev z8@7oce_{X7UvU0#f2eNjBHJI>x_ieaMS2|&!TkZwAL<|K2kt+RUvU3{`cbBTxW7$4 zCG2l(*M z+C00n-)}pYgZ{f7be<_$TxB~eNK2b9X(-au+!l-R!Td0r`1av^9>bT~B;6_GC9MwL-y7A~h1a~~6WCxC zgXdIEcl?|Aiz`a6xOnW9AOHRDyDzf&eAO(lT~7LEwn=Iahozy%y#xO~zGKX%9ch^! zl6H+V%v!P;J+S20iL0MF_bFtw8tW&m*19KYpjIpX zx5JLzowfz>aQ=7J^=)FNUP41(ZvN&~XvQ=Bo}@ZHzrtN+T$>ojfxL^>yOBRt-Y~Cv z4jPd+D_64h?#9+f&UfS+LJU<-IYr>8gK<+m?c4FYi|@@_)*PxZpWsG4OHvO7oc-o0 ztJl|c`M^9+}tJYiIb0i6zYY zs6Q9ylKIH>(~9aR2p?GM>mN<#rDd> zh4bp#cSjj{?|T1$he^pVn3Cd3&kwJ7NtQSfx4QO=8#>|DniH@5aCSn$v*|U)Hf(NUi3&K3)Oar`EZ8lQ7ducpzaU$aMzm_9s5f3df9y5?2~)$F@4V+tUTU) zNn%?*Y~c~2#|3{Tz6x-ek5B&H_rsFtb#hq4>p4SX73%kS{i@ZWuq-sO@yvrq#82^- zQ=UE>)m7}2yV7(>`|VL=|jGQd$Kd{2qFw$4t{%ZXjw`Jv08^>e2 z{E6RIjyN;F!#2hGu>Xzn{t@jTcQyN1e`n7<*63-tPD{x}(Q)^ZX3{_MzcM~CkoZYi z|8V}J42Ah4I)D7Vsp-k?#{=BmJL;c*5>jzQ&-~cT_KkWM- zy^)D)9{$TpM53=|15X?0-E!jAm%#iqP89fsDZdoz zUzYQWqx`}!|A%K+%JQGN-5)(ggkLcK+pFxC@e5OaDb&xF^NXYW!bL2cJ8(Rtc8@u7SN0aWsMV&jo5P(RwSAf{g7=I08R33G^nOvuPfmV+N$LG1R&sxd z;QjSpet(JS{Utv8X=Q=W%r1P&?_Pt`cdg~ZhYfsp;g+@dVDbF!qn{j>2H2eZ(kRX0 ze$^a(b`=fb&F!)0Y*y9&`d>AsR?kxsyK7QX^hX0e-}Ow2xH1~|n(k@x$t_wsW>3+i z46Rz}nadG=vibvp&K|r->W566J)m~@5%jypQ3cOY=l335xOB;i9Bxy}`mZ;BTk~rT zJ{|lpI+uA_m616h__5^Od#jw|aR&VLN~@`Ld!uo*mCZ}-$+g_QVEuW;>T~&XJ?A<4 zlKMTv;&03PU+LJi$d^BdyrdInCI2$uRW&{i8n)^-x1fEIR<)Tm&;FF=Tv=Agw7Rsq zrO&Zq$<4GtvtM3a`5Tq_<#ETO@S~r*#@ts|uSXR0`iZyl~sze8P%^l!l}G-LCtzH`Vtri4zv z&?vpajao9`$W=10-fH8!oGO0L6t4ZYQ8Ln4HZP`w z^HJySkv!DriT%U>Sgg8@2BtQsedWk5Z_Ae$tnNo-1nd?TZH)|I)5B?r}w&6 zugh55J;(6Vd#{t-^R&ezJSs44=pkE)ummC*&ul`N_llRF?m) z^880M|8Yi))2hd#a@k`8(5_^wCnBp4LjGf#|9t1LHy363-*>_-BU%2#e1P|zwVYpw z@=M{qdn)G_ru1%jOIG!jxYM^`Ctg_{C9vVVFOV zUod}G%lU;VzcAFNmz-Z5Id#WkY8~Bf%<{diulpWMelLRin=<`F|HAzf@(b>t(7(#^2ky_1UvPg`mOn5*;r~?I}zGCnb5xifV<@XDs_ltu5C&=$FDZRhMO71TayuaSM2=|wm z-e2O(Q2|vxeqH$OHIYX$e@1h=JGAYdu*yzsVbPR%v%?YTjOT}DCiHv4^=x)oYqDer zU%KK?RAXX0`>h8~91mEsL=vW+q8(Y^iyt-ao$lb$NbJ%5g>!3zEz*cGM~78UtEIns z#6-#JSDOtml-0M|I;Ce$$_ezQ;;j3N?dtqBmm9l%&p+n8OI=RxHyXk(sy`e4 z2IL$VdX?RxUFTdN=b za3cacY6N*bC{p9wSH0@0`*ax(=hMoe@OW@PDN6gk_f)SXCj2&^Fdwa^2V53YS-Gaz zihuCohi1c~PfXFhqvfndljOthXxGhYhWz6%sqM9AhU1E_2J6D>HTfQ{XHBh2{rRBf z3#R#!`3$;IWPFXxM=xgC%!IbL5!U%C{c@ro-`py|>~zUp?n&1n9iCVY;uC8PpB7eD zGg|vQ&bGVNBDt|#8kD@wfbV>-DQxV=Q0%mAW3KBKU4Czui)(h{V1@qU8x~C2RdN^Y z=r+mkA*tuI;hERLwzoOS@)7fD$oIy1?!TwIsfOu2)j2UWyG2qx>v~^rQm@w{>zVO5 z7=N)j>y$*kxB6$->!Ut~D$KuGG^VA#@c|k)XX@LPWFG2|FJC{zo%W+P|5sSQFe&atCuWXHuCxt@}5_n z{?70IbQ%7#znzU4dGB94U2V&6L@3nPo40VS_xZ=DVEMA-c%sKcQKd2WQciHk`d7>= zBzm12b>d_fRLBIqa+}`h{$5g-W8K!8=<&Qw)GVS$eCGV^{SHL0^~2i@c@iI~@V=2K6{A|&}KvnzEYoBz?IWb>kZWdRi zZm>?gSbVo#@Y7PMTtB_2ej=6j@0nWr^a}Bt=8>}bq<Uo~@CoA;t? z^8OL+pNIWJ{loeHy<)zN%pV1oTeVv|pd0Qs=+^Zy4V5hKbJ5vzN4;o(eEyiupNI2@ z{)PIn{bQKBk@(Hga#R`74|aT(D$@`9U2pWV#x;$iym5klFx3yQOg~WnT{kS*L-dd4 zFF3!8=pXl=v~t+kO*QO^%U{Hsaf|4hT>qHrpNINa=3j@_f`1Y9FWx8VDf2Ho+y9ig zQ>PXYveZ4Axy}H)bSViX{^gbV7v|4%dHx`pKe+p$I$8d(8SSSt9ribgj>z)|)BNFK z{=oUe{LGc-C!+a@+pga&%TKo965ce+tzNXa>xTnl+x5hD{oN0d{N!PN!ul}(+fNtr zAJP2BrTopxla_hxxf@jzbRWJGeY=*icvf&Pe5f?egycUD^B?LH-ghVE{6dsp3isU{ zmo=9T*Z0CIeavP2Qn>G6{|k~AFS|tYps#!CY{D-L`#0`;UDiJ{_UvA}34~v;|IRT2 zzYygYhV@VF`zYB=@=R0psx9FchVzH~g7XiQ^9xgcVK|@Za(;1?Ul{5K@(b!`Shc_} zO!_7q7pDADs9(KlN9|;?PhB%GN+JBhF#jc&cgymhiO*@# z)0y*L0`tE~&M!>)rSQH!a(;1?UswshB#>Wn{q&;xiB#G@*8PEj$`HaYc)!5>hx&XjzrUpP{t_#>zeMo@U#9Je%`0AVc)6P z{9NUj6_Wj(4_5wNWy-Iq|B|%*W;p(7!bCrqR}S2^=bF0ApecHdNB9;YeEOU zPk5uN=-pBt_OE-OYRK#{Iq16RT5hDX3GcV_V)J>QJg$E9`NYc@Tf@?tc-7W9u0c-HWfnXX&uk zhr4dEy>G;iA6Q|Zn;e4MerR-^++x80dHH9|^T;&{^_Q_RA5AAcMKfI;{yR(R{qCpT za?U-MOV8^zOZGjdy*Oa8V*}I6BSkf9rVi_rZq_uF)GP0$y5dFT8vJggzPSzg-a$X@ zpu5Q-{H|5|y2$ji&bML28#4dwbLH#L`s9)O{r9dvSFQM>m0e8cjLG4aw%wK(C7YMq zhyRZMtY_*jnH|eg)ndC9s5z;u*5O~BpI)>5<|_Q_=*IOnWL{CuqM~U{p?uF(US+cS z<4?E+%I0%;CAYug&vRrXj&6BE-gEno1~{TjfAq zK5~2&JY)jV;i@~%ap*x*RX)*cd7rjw@mNzYTk@U~Q{*}%DwtW7G z&L8)fcVWO#-x{`60Qoj(ufuS`F!R|)z-R6qDg|4%aguqAq}d~e+E z!qn#r`oUB`Jk$^L7u3H+e?k9<>K{Mbc_(kHV*@+T^W!Ez9UaCHHD8(5Vt~)YKkoRF z_zCJC)`$MZa{nUgU;M^L@Gpy->XyaK(_tD93I4^@zdZD>vi$i^obdmgEl)^G8{J4wdI8qWOsp+P#(KCp*)2-D!))_KcG} zKgsVk7V?uHf3|-Tyo>lP&wSSilKMbGw!#bimTKL)-|zFzkO|d_e9b zlE<|^=?@9NFw_s^7t~M3M1fzJ@(V-#N6GocQGQ{lf5KD=jqu0GE7uZ!VVFN3 ze4DY=yB6Xw5%oL`voOF=*9<^19(zpxU1Ng%&A%lU;Vzm)b5`RijW@Rv27Iq1+{ z!Y{~Q*uS#*!~Nmy2w{IzpRnpFNoeR3jR{t+l!k%A4_#Bo@tT$ORVJn62bdxXu`-9 zCfrW3-QEn9E7L!VeRP}JXuZ+kZ8pEWd$T!_Gb}l@e^}WV@#Qe@DGN6pmUjBq$@y&S zVouYs;kJw35dLbbLAB#IYTI{ANU3{$dzHl8B>SNUZ^qm1Y>wIK8HTl76J8g_@0O+y zi?K2KQz_N)evv1uzsA#eO%|y?r?%V2)Q7TuCV=f5y1H#hD#|Jj2bZK`k8 zX<=XffT6c;>x1jDUrb-qL}N{U%*zd&yTM`}&ZqQQ%Hk8PAEIU#@46{^CcLy`PTp~J<6ygsjg zUe9r}r>{c)`<}S=e65;?PMaR6nJ(_fe^<}l@p4T87wdKDchu#9e3(jjN}sun%$7AD zBllXGv0CHSE)DZD=6#|(BJ?AIu%lbB%U5K?UnsrV)2Q5^zi~7Ds5Y5@rtJz737NlI zZh>R&ngTQ>e9piKQtwKYYD}SO9%r=nlynC9-c(5s-#hU6_j&q^N08*rq)0`wKm3-Z3#L5d=8n%Wow_&J3M{yi<84@zLI&xeQ#6oYgLHC z{GBr2Cib0Ph+2}J`Wut?ly-Xi`>J_1xA)8Rj}ypyUwOBA-?y9}%=AG^hhO;7gXJG- z_Kzp;sX0la?rE?XKg#>!*nzzF9?!A6R1U6J=>Jy#bxxP|6`|}y5rbuVG_KIHU$iEJ zv*WV1G!wn1Aw!=o8XuX%&Ot4yc^d2u?e>{Fi5{&DEOoAXx#CeK$3%rhud9DyJh3`d zq5dG_Z@MR17o)r`KcrKLpY+Y*-5kn>iw*wzUSGCpySPl+>UxikUF^eFADfw_?<;!s z5wbv2T}dt+B;`t`eB`C_>XzuV#=sD%!^;j>*IT-Ge;8r z@K8U>^xuC}aT?J-8hgEa9nnATf98hex*yH#5RR28GKg=KK-@i$B zmOmnX+tV|(iTD?fdlxG6FZ2cS@wS?`~6OzC3?0%^zM_{=ody-7MrMqWOut-tHjFPc}Hf&+m?r5o42o zd%XU_zIdulfHuib9_A;U56u6n|JQGrt?Qd^E-7YRPcLlk{7i!}kmo<9`Ojx{Kh#;4 z|2JQ(bdlvhoDaP3hRXScD8Cf$yAL{n+r4-*JT#&*ittO}zJvX*mGg_E{KByRGHaoK zrsCt8&L)Iku>a5U{t@jT!}`3OUmWEZhVzH~g7epP#J*dMHF0?GXP)p2!}+w!6ZpkZ zeqpE|$Sgw2KlLzzt;a5 z$oR`@Cv84Ei0}*Y7xoYJ59bf}2Y2r%+5W&@@LRca65$uzAC%1>>Id#WkY8~Bf%;LV zf4INdBVF14#twJv=WgL)#=!jz>L2D0^e@~$A-~}M3H=M_5Az4^&yZhme^!=1FhAk` z5BUZ6f0&!Tb&@L7R01XAJ%VRls4(XTA5U91HZ25yPJC;r)@QG@XV~w$ zI}PuouzrntRD{+0Yv@k{H{s)j_WYxR>doy=zUA6qjr~0`+?vHl+l ze5^zid9|YDMdlse zaNYmA=8|>Sk{^Cm{QnVl=HXbaU)(pV6r!RGDPuB^nV!AxXp*^*A)zRx43!3j=1Bt$ zl15EvmL%ob`))4H6H?NsG%1k`dGDva&wE|J^}N^n{B{01Yp-kF-|zRc)^!eM6~6r= zh`H9be0+(W&?!iI*OggDxJ|xq+YOf#WYSr+;n>@O*zAURsr&IbvHk;}cV4gRSw(mD zom{o9+6e2_Ul@LWUM+hyCgMeJ=i#_RZf<$YJSj?LXkps)Oh;kb+=pj1pX%e02eRCb z7R^NycHc<0Jfw%&wDWX!Mxt2#*U54Xx8~K-@qyp-6-mAK>FS9udRDO!F^f|+k?(Eo zeifJDFGF=->3QFZ)Mu0Stgs{XuC<>Vos*G>rvLBv#Oe?2`gzx|*DLzupD*5JWFGsK zi=@jxKV*Ll-BdM&%xgsG&fuvBrKu5~v-dWiwG(ps8OZA=4kakHdQ^~k{bq*RNMqJ?*owPai4ro@x`b3?o+FWJhnlGvot#?_sYNI8@1X3UcJ{-SZ*utMZrn zyNkT%q7u`iC7YvA?*lU;I>>vEbXnHWIC!C0{TIi*TjY9tE3oA+g` zp6l&ppNU>;@|I_v(ETouJ6cq6g6Q+C_Gs%YqQ~dP1CJ0rqNA!h4u8{z;lB&+Je@su zky!oNZ4Wk=etu0a9oKJmIPuf0`w@wL)N@*AnE<5Y+H-R$RFa;LDtp(@$U zWmE1&MT1pT;uhD`Tdhx+j02NPPZGbKdh(@a^l|a}u>UZwf12+frC00k@EiPHxOJ_4 z^|KT`foZW$GU*>VzmEAJ@{^?g;rz|H`P2OT(XiGrH~YwU3WGjYwscop2s*m{%^&ge z$8i48zfeDCIsMSQevqc#E|Gqi1@oPyKAx}>4F8uu0}+=$aTw|c)`$9kr_p?n=$}6Q zr?HUeAC=ASnX}VhhUqiosLrNrN5M%>|A^N=mZX2^UjgS|n)fd%63!F(mub>{8L(}Q zqoDWo-5&-&)kif-*oF8PL;p(3A7d_mXg+_C*Kuc2{s_-hAI-=qw-e}b`GffU!IJU^ z=4TFQzo33bbNoU)zr^}a;P}Pz{6bLwkY7;$u^hh;&o8n1-5kGIo?i(1 z_u)b%k$w_a~3BRC!d0wLbcnRn4!SRdb`GsKqKz_meS;O%Q@%$2-zXiuHmgg6O z`T0o2SCpTE!zs1$!wA1%ej0Q9LOj33>Nj!xVtIZcnExHuY()7lh@NaDTut-|^ZyFR zFU0dptbPW^FP7&QlEAMD$ge#dzYxzavHGxo$X~Ojxg!1w2bnkR${_rL{FT%{oIl(j zCeN?Qcx=kGawbgkNxf zlcay>U$}ole!=|{`d3o^!2KEW3+~U7@(1Q8-2WlJ;QlWuKVkmE`$f0dLv+6gABEw$ zb(8c2@P4V}?ia-0FJk&v_WXB$G5q~SNw~k<;Qb}L>)-uF@%I-s_n~|C;gw1_O;dYu zZG0iy{cc8e%eVl_LixSc32} z6_MZfo0L|Y;nVB?ULO;mg7$kRSzBz%VbW4pERFPi!@&B%3+-Pi>oBys!Cb|7%O2Rm zFQ#~{@(0$g)y!#_p*6;`2^KHq-U;;bQ)VA^u@cH0aQ?n}h8fO`-F8L2e+r7-*>__^ zPdQwp7!vGnoEA&sesE+0KY>zZK z5rGx!wznQ6_4ChFbk&ghhrT>d$ccGIpSu{Y`fA1yTypOGzWFh4S+$X^&(;`Q;Jrod zR(}+_1p_i|mlR}r2y^ZQY9wnJ0<$KkNI2 z^9eC;>GSK|Xwf|KZcbadJLVbtsnEJl9hukJs9l8-?edht%ssl-H+Tp+{b=+0iA80O zYRSH2UMv0M^G3{?D^`C_wMO<+rT4U2zzS*rdCz9cZfB)K_t@77PSv9K-t@&J>CJX& z>eTybCBe%CLeqTrZS%={4%ws;G3-PHvP=s#2_^5nGs#6kQ*FLj{l|a(o~0{)perB! z8evTI*z3-YXMJ=S_LV($nnm>5+eWGL^R8w=|2Jc-O^80r-A*=4CVF((>m1}~Fl*N6Ql|F7SW9TSp#Yge;S z>#H#23$haQ_&mj#_z5XIzV(dsk0tdF=dWz_Z~inte{^yCjp)Yh(#*zb!*l1v3j_nX z`6GV*SknBVeok`wp?UqF^dng!{V>Z4uKgXf-9s?uU;bz#E`MS%)DQG8)c^bc^&4`X zF=NEX?Fx(_`swbZxG{oiul2Hb*AGRtnaz(j6F*7PKlJYa)33(X#BaWnzv&SFB6Y11 zBL6bChAa*b2puC>&iNPd{>75~3-jk1mp?S0KS*w>sx`?U;S9%#Epu0T2$pgAgZTWx zlJW=UXFZpnG@qYHaj=^xKZS8ej@)WX5(vzz)9+8w8jh}{>&+thiD7<9%KyVBUd~!h z{N{7S+J)plvd=tR7A*fxxK`71(tk3(2<@tqR|G$5o6!k9%AFn_37Rd+Lf1A_Enn}cOD=*825q=@a zuSYjN|CJ_r<|(k4NAe88`9pre`OBLB;}_!jg`ob=bNpg?ej%tI$S;`t@k{}PU0EYB|l^9S+^=FeS@Ux??ISp8)jzgV7M2*_JmN&xvQsed?s zxIes>vJveM%!ALewULBhaDR|Af2be0|3H4h{Rip?`WNaS?r-B#wu|;RhB~gk`ZD1c z+}|YWANm*WpO9a0|CHokm_KlThWvv2v!wii`3d)b$S=76!~B$#|L}e>O^g-YFTz_D zTlKsMzu^4>^B>mlRPjI5G%kRd(cm_i++UQ0`^yd9U+1{{i{kGuYWnR2*_IPM@s`=~ zHL(S!*%8tU)mFv@QI~f`4lbz7V;03yIpdN)v)*n`vj57F-#@t}Jz)AHZRgV{WP;3) z#TEP4eECTow8Y1cCV%wbI~VECZVfAVn#su@v%;?4e^kY66qv`_pCzJHjnY@rufe%H=%ruBGnLkJ^E!`pzwD<@sV&>6MUd% z<@AHfbI{6NK_z{I46xJFypl~L;>7CfTjab-P$^ZrbOLTH7sg)6)5!HtQ<;~VvTwl z|2<3ITfwiv_tIv0s`>tiXUXJ!edT)pbR_Rt;y>-t=VzfPe;Vs|g}nEf*A5}G6Ou91 zKd(pnKRrgt{m7ZFdWC)XaUgY!==Jf8j* zJd^O|x-7lYOE6&dbHfpb`lE#4Luy}$pWytVzo35NIsMSQeo&DA8IgV%eYZt@nw=&H zGCBPqUOyP>2iAxB$NL|}6aCW*AB>M9`bUPxWc+5hDKTlol0Q%S7$^wg^pAM`V@djl z{_W5Cm*)M8W+ZBf{L6S*j(0|+{-nhpjG|pl(BY{5Q;C1EB>%$vQCHsbzLEINzNX(n zl0PUsu1S#c}+id47rAcV{?$A)a4i_Z`$vD#tID=NE$g z-&itC)W6{VtFVskgkP}#69KTqeUkLiQcfeqge<{sB zM#>3rR^z)h5k2R9OuL{Vo1suN+&o8n1uz$$krm?c)2!DkqMrf@ZL-+;x3;T!u zg7b&_L;kd%qWyufb1|pY3BTa}0Ot?=1@!~>AILAb|3Lk~`cVIHe`}d{T(rM25$W-h zDZ&@Hze&AMy+C|B~_(=0Ch&`r)sl z`$ed|vPf|h;TODL=5zN8;_nwR{SW8vFNVLrC<*tM8@#^;aQ7F*-(S>J%E7w$p&~w| z_abG6$~o4fbn~5XsW8gv?Yh7my*$S8ZSbJ=Yn#|Q>%}c2caxuA+Y=M=_xfPx1!)RV zAMY)x&{NRPdpE=yZwM;Q3U)|B`CjFysy&bC@S30PsQrSe&ingURR2cKJ+nAcf8FJ0 zqp$wHPRI3LT zl@(TLKcE!ToQM=;90iZ>C}OusYG#g~#$ee0&D7&_6ZSr%>o-k!Ip@LvjBJq68ny52 zJ*|Da_BdMN*45sQRqNXYDqAOZc148Q=0+r>_erV~XOj2cgYr7f>v~c% zmA%8SM286bd!-dpUsUOpgtTpTvQ#_7`-RB~yr z>qw&4z#E&^MK_Dr|C5!bx_WIBeai3nZ$$hg^=4H6DN^I9wmoM1w&`u4-fn4qGkKA| zb5dY0ddtyeZj(du)a%+eP;#oyu1?x_7*0Rdynd1-_8-XgPxJkwZQK2KCidwP7S%9U zq@~6SENgr#p59SJt?La>lK!!z{^9)l&y1{{Mf`S2v4Wm;VF23m^0e`Qx}J=mMw+4T z>=424@C^$+5;c%P!kI2Ie=KSKP(S-P{m{IAP~wLOk$#vsp=w>LR+PY)(+}eHgQ0$) zzo7nuX6$hoLHy=FZ}2^$e{@~HW$c9hs*LFjHKXV`Qw8HW{Ucug80sI^hyMM*`Ir3E z=0E=;cgx37#J|k`Kp%@`3#SU!bN)rVe=+ng%r}@n_qqI``TRkuS9SeK{xIt;=OpzT z5G8P3y|`cAadTwhTJn(O4~F>z>%;sE;PR8^^Amj%Ocv#*@YcPZ?X8g^g3nxjB0fJc z%uhHUnEyds{?mN^qf?ZYJhJ^H+;c0os9t`&ppMIb#OFVr<`yG-MEv$)P{A>W|407A z`)<^iA*ySL-!@fdv=M%Z-FF%szYxzavHK48zk}l!%kvAt{%h9?MEwhLf6vx@MEC{! zPvZJVeE$f}{|U!0mgg6O^N0L`^G8}g;{?QS_UG2ngkR$IIexJ`zYx?9pIzq*}w z?_^V^NOqA+7~z-Ld~7*>u{^&J%pb@vm_LTzny<5n-%N|;`w@PL)qlnDi{<%+V15QF z*NXC!x<9zCF^ljE=H~^DUx??ISp7L1zgV7M2$xW8SwQX<;ln7}6UIxoU6xW7UD z!}`#_aQ}q-g8L`*uUNi;{DJ#3JD>pr|#vA|)QB-kx9oU3(yQ zWOU>M$|mA#U!HGlA@jN4S*{?O4`XPfW4ZS&U7j-b;t@+dY@eF08QRsv+G-+)o;}U5 zY;~zoPNE`Zt5NvklKO1nOPQNX11l{tlQ1wS!(}GQ-W)RAHEbyMoVdVinrDPq{gs6u z4#tl7ME7{T^KJV*16-KzWj9~>8>YlZ5s@Qyx^@K@@%HL@8WLIV~sn_GK-Le@YKCy8N z5>Jl63ataT&k)tCnlWnCoP|?SS>2xA1>}1L=NnD!?52zL zpMH6HQE*oi9lPPJtvs2BWp{^{_1?Ga+slUQ3dp?P#5C_tKB7jg=m^e!+HbaymDc@5 zlX)EN<@q<-GXmXw((}&*GA{+Y@c!v8GsXIEb-KRCKjA0sXi^osmb~YOz7cv?pFL-% zs(9MGAn$#%PvqJ+@ygW9$%j=l$@`kiJO2Jg-t&RoaS#8piO8@>`rR|~-ugq6-Z3fh zV)a*kF&z2UznRY3U2id+=<&RH*jt9KWJ9JE-SQ@S9Wu!5l!k#crR1H^aQJtSuy6X5 zN*$s{g|$kf^?Qv%C1EEMszrJYEvek`WVTp+50hn2&Gt6a%WGY)77{!_m9G>$Cr;akY+3%e3sH_4-#l`{Ug4AEUAAu{}F&sm zws>V`)6G}I7VU@;4D~5hY1STyB9=I1kojXcf9Nl$9}`YLG_N0Y>q+lDL_bXIsN5M? zb+(|4(+}eHgC*$)>fdkgt}dc~`tB^XV?_VR^UYp``}t~2V71G_A*&JvE}Z@muYW8_ z|IojCIsekUe^HIAnaID)$Jc+4sjg2H@4`6;aZu;j>woESkwZm;$# z${O8>I1*0s6T|$3^|jMnR4$YJZ(@d+it_(8m;W@M|46A~Wh=>l;r!9%<}>~T35>Y> zM|}QcN%;@&y9%T9-WJ4f#?+ImgkNI!oiWER#Pdt+zJvX*w7vSHg5*I$wyq`VAHn{6 z7RdhNSN_m((|VD7fc@7zKV+hn(G#u6_a0C9g<$_Uf+gkK2iAMy+8|5Kah6z5!H6#L`0 zY&_u&oR0&?FP7&Qg8tPQJX7RfYJtti$Qr^g=-=ZUzYxzavHllv{9<{2A(%gqUod}` zj!`u8t+YfBZ<%Wmeu?$p#PN&e`GsJ9t}s|2%1>&1{_l<@gkLZ}2Xp*FJio;1FX8yb z^87+D|DUCXit?W_>wE4)6wxQl|C1cQ5YI2M`raJBSe{=<0>3ICzbrU@A)a4i^z zzjNI6MEqsCciwZaCHVmPE2)1tf4Dy!d+#aQADC`gGuJr6FStLz`9ps}{lNVP@(b=i zlJo=h5BIko2_>TajWK#TLCJ~m3+``{^bh?D_fN<#xPL6q5XpNuAay%71vjKz_mdMNqWlKy(97qzr`#53MT`wDa%trZUy;dBG zGHOm)d}t7!ANHzi(3k+sjw)~N9wvv8Tz*~+na{z99)rw(eW3lH9oxAnZ7|-j@I?CO z`ewFAlKS1K(ZjLIgat!3|L#dm8>;VA$}AA3nOdu^dufHg3`*+#M}ImBcw+r6d67Pz z_4neS*s@Tu`aTzTXO3F_m5w^!@Og#60Eee4T%Ec72fN^iE71PMP*t8h)Zqd9pe^~X;GkC;C4><=k3zJwg~jH6Q%Ct@Qjls&C5v zk@^Lu&XsR0AFVN6>(;hzT4hE_Q* zn{sJ$U&eCR3EP~5NrIwL#cC@L4MIPQkNhI@$CBm`^>cvJ56$ZbeXklR(huWg{&4=( zD+>hMM&=aFU!;!;^2%$8elXMz^e@zZ;M(W&MSeql9lePDQI+qBKaWTBXL>H((`%G; zs=%4kKjQU|q5ffg=-*(@zclY(WEIq3G87fbRl%%9a<{?L5> zpqMtzp(KBpbuU*BXuh;Su!74U#ODu&`6DSm)29ADd5`$5vQ#CAx$z!Reo|U( z{X9kdg8BKF;}_!jC00Mq$76W|*{9~HSqTZh5X}F`_#LABr=l0pOX9w^9SzFkY8|rhWR5YKjHol`33iXn4hpd z%zt>l{JuWCiQF&3B*X4s4B;2NUnJ#!2zP%m{QX5qxWC-s{Z+u-Ulf0TQ3r2HxhKWR z;BS{F8M!>cY*?CskNlw+D%tLW(&RronZEVz;fWdTEE9cp;N0yNSocC(<>Nv6&OHuw z&ad@fR&h9)Iq#ohhZpRxGqTt-9SuFa@<-aa{Y)SE-?JmeK4xJ3%!097XU}*<4`pIZ z#|h-g?=4x;6fv-!b(LydxlGprGZ)%SCw~4Wh%c({e|J0i?_bBp(u|QE&b|3fCKOFa zeH?@@|Hk*mtmgy#BbLUn{-X4VQ&08Y(0Gh*=h4soaQgO~Ph%U}*lo;})=?E^SYf*R zS07Dj%6$Ezj@6Z^!j5id>)Fn>c*@K-p1Z7KQSRN zvt+_o(R{vXKq)uO86q$clovuOMK(R)y7u?qEYjs zBa4uaDPFVvrpfBC2(kX3Cd#Cddh~!p+r32fj1+3u{_63AJ-g<|r{m;%ol?GOv#)7T zS`HgVq>=i^>W@W^B=y1$pH5mI7J*!>(^Rv`_q0o9CDsp!7ONlkVi%Rx+)5i-25&d_0+RJ-!3;-Tfsg%<|6$W9>hP`#cxn9Kv!K2eyk zip*=p6(*a^OKd&`sugR=d(w5+d*+TM@7d9RVM3MO8+Lq)(z?Usy;a8aweo6Er*Wm_K9dc&*->8iW)G`yx$X23Hqjv_Qx``eau`gYlVrf(sy}x$_(QCEL zjLwN@x>)`GkF3WhWVF*0i&XUI6F<3SYk0^X3Zx8tRRcr+tfho&B9<=>uyAgBHR!s{ z(hY7uX8zP#er^k;ZZxNL^4KfPn!x9G0*K#cdlbZ4?h&sK``=$|a%K+ko07CgBk3RA zi@%kUuu*{tePNVRynVJnN$SZ^soA}evdqm(q<<`_e>i`q=P|29ew&wfaxd8V56$Zb#msIK>4#C6U+zAv zY`H+l=?C%p!IJa?_5Vv?eU9j#4(y?=bD}^WO&zTt7kf>E!PdY3j`dk3*n3oCC(%DL zzJB-&(LaXzhxr5j%X0pudHEXltx ze@wXiq51ql_ok$a@`sreU}8J$!g4_wmp_QlA1o<u!>tXkWL| zH@I&gX+*_#vX(<;`ej+|UG0aamADI6|T>jI1{v-K^?T-sTe-kPk$bB|q+ibxz zF8>jq|9FkHij*k-rF(ur|F8Uq_uU|lUo_7z@%xVB7vlLPcHhDNXJs8ZFpK0t-`t_r zgkK2u|GwbNBhtU%{7L5B7LpIJ|17S5#P^S2{V~0~u01AsHsId=*>Zg$77vlLP*1v$`7t8YtLH$F1LH)NDt|%4|zcnm~ zvmyKvt6$6Ui{<%+pnsnVZi@U%Id|^fGK267`gat^FU0dpY(7aGzgV7M2<8vu7tEh} zj$er9mstO&IexJ`zYxsN`GY?DlKi9$pB)Z;L-rGxp9eU8A)a4i^))$uu{^&J%>SpY zLQ(!x&m*gqY6a1`G&nA4K>C_XjwC=r5=rxc@+Y!Tks72iAxB zhx?m%%88|9e`BJ0tO@od{DS)%)IZE0=wG;hLVm&h6Z#kS5Az4^&yZhmf0mR#FhAk` z5BUZ6f0&FTU}QPEiV`T%8<6h zgYSnf@;xvWJ;_040ea-`cPE4`7Hspva6W1ZKDS$JztM#qjU6~&2dDN8mF{QK&dv|k zcJVG6hPTc5dS~5EW$N_pn(RZnGlkkw0Y9V@Z7_aU_$yQ+8iib*b;sJ%5C<+@)A8`_ zM6v!Ws**;_%xtE+FDs2G?5&U0UtcYi*Z<8rUN@O|{j3ol@cNnS-@^WstKH__(>=Bb z7Z0m#(D1dw-f2IiPDn)}3(q^k{D|RLZM2h_Ty3aW{jbAMtmvWtn;yCDona-Zr*5|F zB>5g&CN$bB`rh)ZSGTWs97H*+Y*d*_>g&{x79J(_E(c8BuTUF`qC-8^W8^k3#1z&zEhq2I4oN8U zJ1|wOf6d3MOO^?{=-mgmyDlYqOgy_ve|`HC_Q%K6&XYv1mYp)2rRn(rSOPl#$sHt)$SSJ$awcccjHowmFR-r5J%ZW?`r^p9cxQ2%iL zX~UBb{~~_7etktLnLlcOl|SFlYycyjS0BF5ZIxgfH-E&>A4{4))Q<_$%l<|Dwo7r> zEutUv=gsgvL_f@VW7(P&d6|M5PCtm(4~F`I`2h8=!s(yp^^cAozx{QJ;~*w$itDOj zqqYcqR{M1m{iA!97WG8`Sd#vse^ogD(!77sr!xv7|1#<09=b0f^_Oz~MZAA8^e>!0 z%%6E&{?L5>pdRhdMft;Q(AhG!YYKQKSjxcsE~{6v~_CKMGh|hlv^B>L! z-gozZo_gO*{Psxy(|N)#vHQ+$)|6`wp7!X7Ly3XNPyE0CfBymdzrgW}<@tqR|329j zTS@U(ekf2*1SY%P)VK zpg?$7mlke8_=TW<6{b?(h<_=gfIUgG3BRC!r*Qm2Jio;1w{ZMod43_7KagKAe;#uD zLOj33=6{pp7t8Yt!Te0}s1xNUrDcCM_$c8Q%+E_4zYxzavHsOKez82i5X}FEH|#Hx z|J2kGBmQh4`h@v^_l6vv_S+79Q@P|w_$5}~gyR>>^9xDfR|VwPNseEL=a*Q0*gxcN z(7=2Ve;Mt)Vf#u6zaW2M|4{#M{&0T~9K8R5><`SIsTQwSlYE2wgQWRG{lNVP@(b=i zP(Lsqp#I_hrf=mW+TWP^sJ1S5!WX!|Nzy;`FWf&Nzu^7}{R`(0^9SzFkY8|rmXtp* zKjHol`33iXn4fU|F#qBGaVy_ZC%W#lcdNI$$cEa!_oKJ2~Isw6cUnHijH9^7z% z`QCee{%*^AjQo-W=?A2KNBTRTPEvpMsKhCyxmC33qj=SY?`84ugJbT=UzEb9R=eBp zwKu~7uS&y*KWGv}23`Gg=|+aotEB0gZ;m}yD@yZ`<>=n_Zl~rSn#!Dc0Im{dI@FEOqPPhp9emHwzCB zkuTBSWrsb-X4eEqM4=ab>U%EztAj^N|JW5iZk$;C>07j|G|A7GWxUbV?R8iiuc>`$ z`#ipjZJKmr{MLIWxP4FWc>N$%s`SC2QLo*$3kN;&*m1bi22bzfcIdivB&y9d@yPvR zi2oj%{H8cHK&<|Qz;W+1s#@sCp^d5A;)Y^F#o|m`#dcOXQmD{lihU%JkkdEzNMtMX9LYmxIOXKkBhk&q1-BPLE#c zJ%`l0ntEPMy{d&xF}`G9Ixizpe%x)!!-g}J2-MGHvG^y4AT?LDEn}r9WQk+uBdzMU8=^rv~9GY8Ye@TbD zcb2+W*`$al4D}iB{GhkoMJeQ3rdzy^=&`i%z|&K?RqUz6x4QF)UZ2-L9@f1_iK@b* zlltDw5Pm-3_EV(CWGe2i^$90*Byp{K0MYB_6>rYow~ZF-U**|JP0cPT^s{VIvdB;N zPu&zNgkjXApm#MbQ`b5uOW-_WtMyIwG=W{{Wh-K zN&L1xUElItYP7`uFLM3UeE+Cm(wp42JxWZ9;iGATZe|ExQ)YVK<|(7aiN7jsh@T|& z59fcIn?KFZA6Y*AwN_!ACbQuB75#B*Hw(TWn*D&xA0>R9xQ)yo!}&x1LjBy}^h5Ld zK_~Yv6zPYV)exk)+iknRpVJTG^@Anp2kQSer+=E)Kf2wz{ocqW+Kf`g_`TXDI|VJA z{*f=Ie=JG=(7$G!e`(&oXu}X%=X|K8>2N8iX0to#_1=$~Vc zHf-2gPx2p2%71v@MREK>Jio;5yHt)}i07BseFytDF9_RMLh=BOP#sA4g<$`zldcZw zUvSl;)9@JK7wmsz-ikeq#Bc7K6+aPvA*laKj$bU#F9hcg`32|y@b&5oi;3UfrGGw5 z_$5|c8gr#q#_@Fn=Jw zVEzPi{6ajx#Oj-J{9<{2A()@?+s}#elky94?o=ZDg88|S;}_!jg`hqYIeuZDUkK)Z zYv^B5{!=Slc6)sx`h@u(moPNfkN9nB{;i9IUt;~MbNs?QzmNoeRX~2#a{NL(za;h# z`Ku{+N5o&I$CLe0x`bblzmocg^N0IGz$sLVRC;JkY8~Bl;mHSKX8AB{DS+lr2K*T z3HN`*I#|{Iwf^dhZnAeDtiPXncMetE`qHg_{SM~w zu0t=PU&!DMF>3?#^M>QcGd;RDc^W$3@rjM}^j=Z1?z&a6e4qnvSiaMuF*p)g>DHf| z=9e1T4nvtmN&F-Eu3M#n$z><58B@P(Y?;KF2mv{FQ zZH;vjZQrQj(;d3!tS?C8)|)zWzBCQPTAO-ZE76jp%=7jPy7yp*P_D)6yKAQ%{x0?X zr}_B^G)-4QA#|fI9)I;lOJmq*vHBxcC2fp)@ssu)T%9pEPYahVxmcYZD1}vaKachK zXpG-`#7;cu+n1Vts4X_7Vz1DYs@ED2Y>P8$J+ROx96fMcn5-CRgx5ZGY55TBCssfE z-JB*wwb2?gyi1FOL-07d>2=!sPIlV-;)P{~hSrO)9ErgX_b^2ZYjZpRP{R zvc|@li6Pp(LXd(-+<~HVX8035=3u!@pjdsEJlj*G9(}akXb(f`ZPF?`>PWS*8!3&| zqVJ{4%zJIPT9=yirMNJP)c?BBeDDcU@71lmEf-`0k^AC=*XiVYwI78Ob$f+~)&KLn z*HkhORAPSocOaQZ!P%4z(Jy|oMk!nSh~||Wc~pJ%{K3>QH`5jYnU7&o#C>@(kGLVO zvLA!}(8TKVD>TTw_RmxKbjc@Nto}&%7h`NLNF#@nJCwhZ_uO=4&(UpnKe2l9miG4K zy^s3Zj(uY=h?>|P^Y|@!-^lO|zYy}CW4y+!{u(wK-H_3l;6~oteYwVTv-1&R^)K~$ zwv6Zz6~_q_F(+vn`6nU`urdVTA--OcYxA8Ny?!e^G_)(VCHt4Ac z=#{Q5*)mBpQmnq!{a{PtCuHULdg4&xrysd9-=yA+pybx!e$Ushrmnq3%8Pp1IbZ#8 zbhVvnwws@VOni)MHsvs}&hF3Ya;DBhb9@itH=BT~TN{GK>%;zwxc+Irf8?;Vz&GYf zALfD8;ry9n*9v$)q5u3Osed^CZQT56e*P$WiS)#e27{PV|5IJQ4|WKqaq~y~{IR6@ zL;W1*^h5LdL7!U3i1fpF7rN})U$Iv(jMER|^@Anp2kJj!K)AO9@ms!oF(&#)FSBbB zI#=m3&sOEWFj;&+u=?HO`9%LHXuJFaqJJz&|Ioj_oPTNFzo_od0e#|Mre(va+-_3; z@0)-AMZABpB>%$vxya=Y;`0Y7Xa)q5{9$zeIPd&%X|KSX%OAw&50;caFh5JU{6u_y zqS#+Qu8{m>lvkhls`PM&K#|K&#OEiLl%E4C>Uu0E`7dqeBro!l6PN#p&wu3Nd^`Q- z${)gES=C({M4#4N{*&Je^e_Lhr2L2X-EmLv+$iF=ot;6EgkNI!T_(pb#Pdt+zJq*G z=lW;){t@gyXzLVF|AMf<1n1#|U$B2ZFaGlzg7w=tez82i5S%~c7o2|_$1lY5ORT;t z$1j%W7lQhM{DS&<%JB>F{1U65!|{vd`GuhVA-|yhWjKBzo?l}1U->>@mJlA^*jIj( z@C!lzhR#S8`IkC7FR}WoOytL>5uRUmJRlqN(HOz} zf&7B`6U^}o@%$32KZ@fQ=J|zSej2PyoIvuEx=|FV(@OXS^Ya?VFU0dptp0ER8SV;X zpPJ)cRZRGWVE)VatBUfU>bbDDfg#}+%>RoVzYxzavHFMBOMQtX`yg}oR5alilEAMD z$gkHNzYxzavHGxo$X{ne4*}sXGhlRRatO%>$X`kQ!}-Jg!SPF(Xn$Y|3zwbuB>aN= zgQWRG{lNVP@(b=ilJo=h5BIkkmJ#i5%n|dWIW*x5+}|YWANm*WpO9a0|CHokm_KlT zhWvv2v!wii`3d)b$S=76OUh4U?tWqU`vt-KrI9+inA|VIIWKQz-x#x20Phz``G37| z5wqy-9LC$pU>v!>C<*tM8@#{Fx%-Ra?=Q;kT)fo1X>IICrJ^<0Y;UvgYUch?uS=w) zcFddOesnw2H!kFWT!9?^UGyh&#!6HCUTr_EA7tcg^uc*b9ksFoQwJ}=?0GCp@27a_ZXQ;;b7CtY2A9-|1QWf>wL(_tkus44z+uHx&lU;njHPRa(as zr(C}MNN?&-!46@k#%+@<;hWNu8wmyucz<)3`o;KgWOelq`^QBEk1PrsAKKdv+qf** zd7tz@K)c=T2I*gQ^V)@TMt-5EW~}_aUSADAZLyp^G)@-VRi3@v*=U0M8Qjs+GLom> z>pUC zUXDF~xSKvYWI&)3sdu};caY(xcDC29myXNG_ttDa^Eq&c9@RQW=G}NwUtwWT!G2Qj zWqGC}sfRK&=*eTr_o9wfs*TqU601KN2Tj@XRvKw`c4+({^EkWWOOsT=FV-e!`vcLu zQaTHM+2-p}Z$C^lxK@5xD6mqQ_J+*kmzAZ7+`=(R%S?JCiG z_Im3aA#_L92WQpaBJVw_vd_Ax!C_+cGmfPHJ{K&9glDc^7wM7LEBl{bDXnO^3F#`- z-r$be6NhC9m6zz==p=d+UalJ))Y}eC=q>YSA<=7`T8D!$K3uGRxuxKoYytUu;z#Ny zPbYp_?rv?bSr6ha5VgEC39)7M&{I+@ey}QJ3$fP)n_Dfe`jvn*W${dy@i2Ul^ zEbpp+Y+JADt@@Sl)A&qnxaf)~J+?#J^aQe_{TpSh&y4B7W1}QLEnAYJ|d@ z0~AUAFfyU~LygK03lhhzb|Zd5%UxnNko>_gepd0wGskA7a3$tU@VCFLi~|5be^8=N41qZCqdh~H4?gCS!Krv4O;c2BIhX_6%v zb1`geih%=CH2-Z)2<3CC;Sq-?@st6+GCwYvZ zejvY~em4H@+C=gi-Hf=foA67le%6+VQ^Zf~Rr_jV!Y>5%5BUZ4&+`WT#~awc@%K`L z3xtQp7c#~Xej(`J$Wyuh_?7*|d~q1z7xZsgVW__c@mu>{=TU@TV*QWf_=S0XA(%gq zUod|bEBtjMyhmz7YnBmyiPe9avXmM^_7TtK_W^`o2g>T>v`u1zr^Z)o%JrNnCw%r8A;6|Kf(OBRC^)Hf9k%`_>MTjFPQ&l-9i^8 z6TiK9qp+6nORT<3qjZQO*#|$(U13G|g(UE+0`e;tWq&36A_{xuIE3&^tUl}?@^{bT z_p*e)j8pR2-5UwNAb%zG59bf}2Ltz}i)4RbvS!^_kWcsp_XkPyhx&p059AlzeL2cJkY8|rlcay>U$}ole!=}yl7C_T!2KEW3+~S_ev9k3%xGzy5IaxC`4DDvy~Q;iG`-z1zn8 ziX4Wkz2>Y+erD_(Vf%30sNJh7+CHkjS|8?sCmlhzJ|~2rU-Q$hpF{afQ%`&|{n}MV z_tLsGqWX$)M!Q7yi)H`lRd&|V4ae97yk8pE?>d#X>$g0%ZBVOp{cD2DEh;NMXEzJ{ zyh?4WFXjlF-Zi-Ilyks`Pv6`s)h7h?@K{lxtfGRYwDLw69<#>v12g-G>L*X}>0U|d ze;oHrZuH7;^zo=ypRL3D;>HI_587Mg$nTMqTclTGjMGea+&mwtKxI6S{a)*RM0oL{ zU-wiQdu-wAQfJo?j8;bHw2s`Ni$8wz-Z(oJVLhie@1#lnFA8TWMfE#6ZGOz~X{BAe z`YrewIS?P2Eb9~IFN;euBId4aH^j@%KJ`nnRHuwawRdLqJ}Hdr$lNUqx5bXuHQH&4 zLC7OrAiplm2={Tyborhz4#W9N#VRBXKG8|H8?IbB+)ocbnRIK;tO3%vJ84BmN1{Hy zF>LDo%=KE-%R2w89s|w@M^Ar$B2CX4@6brEnzLjAI(%mQ#9l%(9B6;Uu`-1Gewaxk zE{Xb&IjO!=)c@H^LF3E;(&)D8`A_Yn9+jcBSnot9Yre*>pBedHchO^+`49D|x&w+E zbV+^hb3;s&Nxh7m>5p%P_#t$&B0H6QPrW!PoqP}1?Y2EFn*U~e<*w*`gB^N#2K&pR zEghQm8^}Dq4E5;@_i1HMcvhVg&FklJEA2d=A(W+0!#DjtCx!9BHy&;v^O%>Xy!dm% zIAr_rSXnulSGn?t4;hL#FF<`pxRRH8-m5&H|YAz(MNvE zBbf`8n?!o#^~(OIS4Wq-r5{36sh(52jy<}RBP_l@eY7gk{jra{k z*+(`sg{U&0a*~!5T*?vfenS8G3HC2({_CbL%Ns-dHox&~J@FeFed%IIe1$f%-~OP` z#OH|MD>r|{&mY72OVZE#_DzNn#BUS&tT;^cgEoKMEz%FuLPh1i?|o9BK5^l}tS}?A zWw4V8(GQ0Dk)(fjPX9Eof8^5Zl;)g=dQABAsqL8q&Is~jdYSbQnxQ8%mvj;RW2k>g z{>_Y2-yrf^SgHI*;$O7y)!x0tzs!b!w?iCA{aQC`=_PvBNL^ODOXMf$UrG5hMmxzj zocPUbtaA*>AH+CiO(gll6zkTe{82h7*j|0`(B*Jjr2Et8-BRKwm_L&8(_?Y`fWIwr z$fmZ#ljJ9goHV79+dHtXEzI@KP9-z6MZHt9ecb@&H;^!*1t;fAH)0?n?HBpW$<^N)JTqBi07Bs zefM0(&vA8_1KMbMq1PAUr~m%F|NaU4=l#U~=O@^I;+55bq<_KskNt$-3BO?fd|sgc z@&e93z;gH;kCoq8pXy$}MSgE;Gb$v{%SJ!Y>5#Gi-$IZrN5jTwj~MmGBF}{46~= zS(KmD{O*~(#t?qN{Ct0`-{dIbH;YMiHwnMQ-nTR1N9RGZPkFnxoD}&9=6`&(K$QPf zrq$a84B;2de+SF$pUA$2%1p-k5q^o)*NL{7G>zG|c}&Fn1C{tc%J@332@Pb^#; zJ(u#a9kKZ<-pT}&)o2)1C}K)(dk;Aq6MX2obylmosq>1C8-ccm)>P~lG(YzFVUM33 zsGQ(4IS7qde5!v};{j&$>17SW+%Gd@A6NERLF#L=-cwGK`h7Q+xLYr+r@uGbcLd&( z!e**9E1pIw;*K>hJHI?O#xL$4DN&$X1h-G_9_~3{ztDSel~a43J=VFhYRd$LAk>*! z8n`M|8EdGGezUr-C5H9C{BD1*?AAm(G(C`R%T&eXCqh4-66H~f-SU)6MtE=XU(JmT ziqs@FH*KWLNnvXrđcDUm}k5mP@Ky>r}5O(I_RQ}uhugKJZj2SWynMI1&&wdjP z5-MpPl$1tO6OG1-D2WDzqBIbdO6+GpGKS_<3dvBBP-#H=t^LEfuJ3Zrwf{PQeb%$C z^}b*Cz1Ar@QnvHA-~`5-{+5)Tz#39N?PvaPll))of|RGa0+ZyK1^YKS^&J&tRy;N> znfODKQPl9!$eAcj3GMY*vSRryj;>6g1!tHUQ}L#jp1xu}37K4-umFDUZ9-sksq=CN z2G9Tey$Pr8h4iuIySul2Qcz(swA}BnF&@Eu9{13-B|@FiJ+8D*GhT_RpM1HtNB0iL zc<02<36D*fQLSIXUaPs1vF&|355muld9Qr%c|Lc}kp6%BuPxhTJc1m3pXkA>XH+CQ z1-{2sT`Dk!_q`AE);`+cq(&9A7)7)}{quH3>>#MOU)|Rh>Jj-*a(`9fdqJ}uTH$*` z>c940vrjl$kVNII*EWNB94|>#*UJCJeb$~nmN&1lrJe^?-%_LKUnLf)FrRmaK8DVP zc}yBTM+N3VIEp@NxiGICS%%|bUPJ2pm5N zyj~?tY>Updw1XZ8^vWI7Yva+w7dn$AsG82xqB}vK_fr(o_kteZ*IDTVOB$1x_6;q6 zL9agLHrj4N3z^Q(4yHW)w|8$i!_$A=w$h2F`ND+dTe(C4coOg}KNIG$hFTpLzNdu= zrfv&=Jteo=!fKuH_w0&UCv0w4k3aUer7dQg41GOVBzSlkRrPCb3SpH|{?WIF@XEcdGj!@PzxveBt>! zK7Idw6!50sVm$Isqy*W%=)A%D*~)ZlQk3WVX&Efff4?sL5S%~?4msR|`7`|HkM(or z$JwiTz?+|W@tqNqC2^)bC=&@ZG4t`VSc9;xwX0H(Olq(pMJ3ZE6O*F z&j#Ll6Yd0o{)unz$Zvs8YV@k=jSo|G@34Lzc^G^EelBd-yw~mXfG4bfe*B(Qe)QW5 zc$+@kN*s72S|;^@z%QL;vFz5giFa6$IeQKQPo(sL%N8C_{P@NGFJ8^6ory6LuHJZ~6I) zlAzBG2_-hYXC{-Mejm1h|1;SC@%#twvi*bi*_%RP?}@Dc>YoT8^`?u-Ujy8yO1V1KNKRCaz zeyqKJM9u@=^f^MGd47%OzXIG4c;YU#%zV$|3F{x{7uNreSGi$(fwzTpj?Mze8$6$% z8`_Snhdg|mYnaO83G-WWWNruWOBF`Wul)u2h54Ox?!iVC;LYFngTNceOI&~ZgrA3m zq6Hbdz<|k+Uj+LP&M)jgqp#mT2YFBQl!r~`l-wh4+7c{)zn`-!GZBV{+hr;lz8(iL*hU_8Y!5e^GqyFB^P+?SEOnp{FI8y0$HUxSm}BRjB^@i1e6FZrT#Lg{PNRas#fH9!;9( zPg&Y8GnamFoDQD`a%KdjYh7wJXAX~>cV&gkeA2$L zO`zi780M+q+srd8eFpb0yUR}6M5vQ3++ro#vqhYdyzy~!kB2Zbxy&$XQoI%uo25Iv zJD0Wpk!3iBvo~Cb8p#L;?`&#n(qQh`NX34oWT?VX8taN= z?!(VV&&<2&If)^EOGgdsbsOqa`Bd{hm@IE-Bg=&2?1tXPGM=)DK%#8AF%}vyOk-`rl>8t6&#LO<*dqI_9je7 zL1DM#=(*%2^VfWyvp(~!^g@G|#VqE`iueLv|AzW;Jqb|Xhnjl!vV;Ih_RTlr)jRm; zfy<4)e_VZqyVI}0_e@jw?-4tuMwM+7(XEC0_s@vf&WC#6El0jvZ!wFsPnTZM4d1g4 zaF{7GdhU?<%#I64yc9K(NX+Of{tWX7Enj|NO2cn%`l{inUtnIrUC+ecl)!zL{a&>f z=5yO=wbV?Q#}#w2127NLA`|451@n5VXkrfY8q&Y7QiV#FhcLNtsxHI=-qS52^|G;0 zCpRfN%(ffed-PtfMQbdTDfw?yM4iGd4ks;Uxd6Q9X;Z3 zy@$+yjaJe5O$SBD@)-sRF`&l*y>bWjI^QT@`JxC3N+DiYNZB)$bN;@FRx#)?=|J56 zc$Pk?lKfMA1@wAQcKe0pF7t=X$M#R~DvJgYGWyN8-L1gW)!v6aXXdS?&TklJE&bpi zWqMXQa=}y!t51cIDX%q8*jQXSw5N2@F{;h`lN?9j2E8_Qn&V91ZFtM_wv@B;`SxGt zF6-b8yq#(Pasqf`XZ$iE$UfzBAM7U=vtFSj_Wa+^%#KV2Wums=<_mB01=kMM> zfA+xq$+q)OVYZga^g)@jn`0Gku|A4Fj~A3sCaTSqFJb-+o&JSg#-Yi;o1dpo z8R&;h>Ma@r`k{N`i!Juc+-D8&LM~VcqT5KN-+JgZ0mk-?)B$$pF8^*z?g6;Fs37T3*d9=de;{kUhWcO-Rm$&JVyZ zgZaht!TvM##pt5*z#CgBPP4g5gXGLS6c7GG>)!b383pqhm^dcYZP9&f821T;W? z5v(73KP8yQZ|v zHch{62jtg~`8W>KmEh&Mv-Ag<7T^i{56&;_Kj!6&yRtneksI0U@w~jp{S#wLiEh|O zV!Q2)A-@Rr&+XEZ;ozTCY`~;%y^vo+{L?M@gA4F>>gMk$ynO}F-}m~JK;Vf(Ne$!|-~Ms_mW?!63i(SH9C<8$6!Ht_FYce;{PF&9w%p4N_6K@J zx3hy50nH!th4q8?ADmx!|KX<}tbe?}wOyctV1J`mMD$$y1NnvbH>`iGAIvY_ zKXHEH{S)(x=Y#zR@6R~D@cxYbho67q{U7HS-v6i9!ouVk=FCPFlf8>|T#4XC2Xl|;B>Ik4d`Y1|9(|(C&Nv+E zFQnccw1E01Ci*fOZ|d1Bkw$|U(>|`(skyT!&J|^DFSww0)Ju!GKQYa-qq>`w>}(KP z*nXAsKK1v?!rx|$kKZ-5ltveF=VhUZw!vs-vGuU2>t5(ExPOPtzrJ^4JK0?ix{K8E z#xOeiZLOYKB21!F7x&O6P3EA^yI%O&Vrt_j&9PsoT#m=%HkG4e&6rOTCyPTTxR6HM z)|^<5BD36ZSWD7Ch zqCRD%KT~Jk^hx=~9+0Je2BghCkjZdFo6bI#k1=JA>g7_RIZk9Xedzp!8Jf)eb0+5& z>ky`_`0ROJeaR&wf0;vl-Hb5_i$jKyohEaW#&#+)ORJK(>X`ye{r;T#C26Wmb-U$P z!D$nyj`90vy;3UV9FL^`ju~gntk*bqu6@RA67S9|vKgnx>|L@xbp03y=BD*7iubqf+~pUKLa>D|T0W(8&X_%9KB-qT=9ROBi2k{Z%U56?>pIre$Y%fHu2LAaL>lJx z{op50+x==(F8uJ?cbJdv(-T#^c}$Y;l7e{&)axkxjEa87*IZn*EY_~dI{~vbT zFyraRplII9by^~1Linn%!| z+_;o6DMvxCF}C;Cn)iuQDk**YJ36j%&TW0|%G2Yt2hsD^zR)3|L5imzfL`OLI+}o9 zht&7$Y}6c|ElM=?;%CSLPl^(9B4Isisq%&mi^J&ylw(W7gSP>bt)7Vq_#N?&wF&jP zd2Lm64CR(K(X>F|8f}sF!1yZgcDO~fVv&yPkovfPr=PX1s=%8}pm!Yb#{M@_YxB}R zak{QLLhWGhyP%dOSPHrn3 zJD^cs|&F$`>6vRRX-xz9k>Pe~7$h1J8eG*}5qPdtg3EJ&8rKF{UJV zQf(yo4}<-OpMQ!>oIYU<@KzSk+XenfT>UM6fPd0bAwI_>;e7|*lMM2N{ga>nub`V2 z=m2lcUoxG+{|R%x;%j|%H)m;GwBU*MtE>S%l0lv(Z{7G)3wZmzIaTPt`9Hqzq;}5r zR07`WTQ*lfehs4N~3-=$X^lqLW@Yd6%eajR40?$9$ZCftz#C@FEVxSH@;rZkI!t;L|a`{~x z@Fu)6KML}TVExoBeeh^J`0-o+>^R6Tg7t&*3+rc?g873q;4L8Lkq6JOvHk~mVg`A_ z`p5Z&_20TAWhEPUJMvt64&)cX{JtgW4w{gM8wwf=c|2i$_c}Ga2Y#u~lfN%&gM7sN zM!6TK^LTp$f6f8)`tyq!$S;EZ2j>^|pJ%a~dLi$L$%j+rkY5D*r|k?MdEklZ z&6lo({36&tx2L~*2L4H%(y%G+fc(P#Ik2yg!F>hKXXa-2HeJ}KYGd`&A-@Rre-ELW zP2m63=hr7^euezP{$HmYlU4j1?nl)pUCFR-;rds9i>fQaJ}Acetp@o;_~chU&ab=g zjqEM~Z%K!z%kuU`Tp#z3^S39scOB#}J;ttLbP41a&R^U=zxm_+p+sa72lfZrBdw>4 z27kl*1D-$T3+o5(KRCbe{)6>{=Y#c+_qV@-0rjxI(IT2%7d}IN;r$KkpC7+?|HS!) z_fO0(o)7jPyg%do!uvD!AAbIc_kWyUc>l-#$U|Fa$(X!>vd|20!MFtW#=Zg{sZ7Va;K&;4bC?=OM=`->X5zo@4Bxx!}FEnJ~x z2NjlQRdRc_Dyo{h1yDw*uj}dD82acaGwP#?7*mx{6Tk`5WP-Lm{FeO941QYZbKX9g zi46Ta;<3=v~WXO(!aF4tsm|AKbeLQiWu*$TZzU#1F=W(1g0_2@_u=H3c* z>m6(j#v%9NZK3DlRFeAKBHcG!PGpjZLs7dabLQ!$%9m<$NQ7eAaam;r=BS9a`GMW$ zj9~rVyOW@QFXNZoWzhez6$%9(RJz$MKg&cP1W7aD=@Ctz&I>VrIILmv@cSqKj@7eT zFCb5a>^j4FakH3X9o-yV5pKdb9DlvWrfn9<3b3r&E~~+`ugp{u?66_fgzPr(>X(er z_2ShRigkU~@(_OisQ`fy=jdKlWpj^rRc*1N-=0eRqvBB zj)hA1hCr4f^YpUG*50oU#B^1vW7{EJ#_hoAICqxakp9iSzD~6h5F~#4ldHXIZ?wf@IhaRA-Hg0em2PgDO=tZ*m{*X!?Oy-qs?@AiH|F}>D(18{ zQla6!CEz{3b;tSc*=P6NIAm&@Ib4|Ezb|9z$(etc39Bc6c@l{D}qHD*TbBsWj0C5Cg9 z&fQOKF!#%zKGNJuTYE#^TJ7UDkCdI$Rv1K63SUZP;7TF^0aXqdo4;*DMw%Ogw&4h#1*oJJuBXXK?@g=D$C> zQRf-(*6~Q^B+Q>gS7^4Ce1P8{ayLTm)Eh2qPO9<^No57%FlFaTm_LK(kNL&=DbdHpq@n4LWRZ+D6O z^BH(!dZ=E|KN-+Jo!qZ~)&NgrkSDBve*B(Huhe3}_l}HF&;fqQg!SXRfM5FXgX8ro zPs>_18sGt!!XH?n=NE%*=7?-HK`{zHceejEAgW-)8c z+4b&^!cEAPl{SjtKMeLCJb&z;9B=yaao}yt81|3tYz>m{V#a`f(rbFoO_hT8-8Z^? zPiea;QSY5F8~l^O{)y{j|IZK&Ucuw-=(n*N;QyrenPKTAvwxi2aUMhr^f{nMGRPA@ z|Ht>;{U&SYX5cMt>)!~-uOatc|2)hF^y4(-zQg@DlSm~`@Pp^OH~skpJmLP0irWgH zf0q4p=e1Jc54itoH{%(mz+2)>b$Q4yg6kg*@0klcaThDTy#x70@ceOp;rWLz9QQy9 zc%zo>+YI?du>K1bT6};f?w^NxR|{_}dQoektY@kwiV3;9K`e~NkJIL5+0vikum zi^mi8&+eko7VuBX&BFFsI^-Aj&w+h~4DKtq{+Te-NxXe(s@<`TkY5D*e{*)-KJb4k zsjz16GtejY|ABpr4DMTa{-H%((!71}joy;)kY9vPe&yr*3W^yY1^Xg-d-_=;U6LJA%AHDuhenR!5?t`;{Ne`@ci-qu%JYBCF~D$UHvuPOW<#Kf57v{{9^s! z{Rih4-hZ%u@chmD_cz9;e}5zYV}JWke&PKM>z^OLc>l!th4)W>{9^yX`!mijygy_A z!Sl!diT8h;UwHq={)zR2{U6^iBF+seaKCV@ZbggzXv<>Z`-PwX?>IB;@?^IFy5Yy! z0=T~@KKGXmzQ2}<2GuSyI8Uuu<@vmjzs-$0QeU2#;k#TL) zeyQ2SOIT9b;9SKQV;!5&RU-N+3T<5Qf0~< z`*Nyk)UK<-UEGxmLs8Y8*wbV#U_)sXsCU+aEZJsCz; zst0fTMawfscjzrVE-J|U*kZ7JjB;dG$`HXW8cO2j64L zvrk_C3E%tf`eCZxD^=><>8gBhs6Q!UbJ7>6=eF!v57Z;!(~sr7f$!yfkQKiF$8Jdd zNZYH6VIE|?o{iEpn1`PEi#T2Q_uutS?o2%d^AhhmbH3D1h4LB~Fy#=;$7Z#2c0J5v z&v&7*2c@h?oUE_M6_{7KoHTo4oCAaP)K%X>LOLF*ap~=dGFeHIkY>KU#XMV=6tfQAef`crzJ0EA4>PY`*=M z$UiaH1l|NxN+sElpNNH+F`fL&xnwb{xZJMKZE<{H-9U) zGlIK;w{NwEQ(*oi*`@coRDe9q^%0*FKD~%Fz!Mqd3C|zv6YHnm^64Ty;BDIzgMFYM zBIK@c8uUZY_S>>H`BDX|e;#V2e;!s0)(@_a^?#&lmbNwUwrgen8qhx}zEV)E{YsS% zovd?y)$AuMrTZGupNq7K!df<~9eBd}$Nqr%jqK-_boKK~j!c&4@k{U5J-%cc)DN=W zt^Gt;{wIV*4>K%|Dlil-ri*i^Eq(X`9NBR z5m_3b>G}QQu3ZsJj`L~3x>OT# zk2fnf#QMShU&>B?x~)KzLDc>V`BON2{X%M+utjca&*hxIeHby^MZ#2qDm;XRKhtRI|TSU>fD{d_*;sF9T? z-YG$T4XGc|bn6Q6#FSQ~YeRk!tbd$eSpV()`9%iui(r05j2x^^LLRPD^p1u+B$!|K z#tB8hFZJ8IZJih77v?v#KflPG{`?wJU%&jj67a;>3tk=t`9-k*;QYe=bMeDwHjlTG zmex~{Uj*wX;cvX#0@z2=>QyH}ei7`S7w^2!0{^6}e_mV5%P;JomoN23!M;LNs{KPC zzX;B+0X;HUP7&wEqSpZBx*_K)-TpMygQ{ z547C%Ajc5MFT6kC`D1-z{owrv=NI08uzqlTtbe?}-H{Kog8hw-8!rBH4de^n-@Z0P zq*X)S5bo6Pxv($d_r?6;{S)UG-aj$FxIXqDyg%do!uvD!AAbIc_kWyUc>l-#iS>j1 zAKx#%E{d<Rw`}XY}N#!bCr@KX5G5flPTEacyki zX?k?WNf-C9Y#P@OSdesiN^3p)myv$*h;e_o+V&ndo_L8eH$$z0pBAYxCsOqfycs7% zouO)0LQ}kxDNA>F-a^AgZOHkWo#JtWN)4agd zp7<%~6%`oCGP|$a#M_7(Gl^3>!+G;zPTun7&1Z?|3sq*v zbDIv}Gx@-yrbDlEnLg`Gv$v}VDOP%7Kl`;NbJsiPij1BOvq=2Dx+e5*^X`h{Lg>G9 z>DC2`4+O}Z+lRkTgL*}?73*Z;hB3DB`PmELd%5ikMT8|)sT+To2W+T+pm$U2OsHpe zQ>s`>&xTAE5Plj1->a~_l?LA%GXIk+N8VrTE=1yc<%D?i7?>A#a9+-1tGIU;Dp8qB zjr=dbe3XRhJ~Y8R*4TY{bRyG&7%v7`_Z)a{_=BSU_clu0ckQm64ApR8v;J>*-|{lse>A+O(30ry(?pF4_m$9n zb$IWIl3)M1yV?(_U%NnYBj}M7y?QW@r^f-katHNFHu~+>+#^JdR$u3m3;OKaGS_Sg z=&|$T;V94}xhFbe?iJAM@9A%5E_QbqGN02&Hr)Z9$WFhgLLN{1X38i$l<=flZGQI| z?b<_4^;@I(@Uo$m)7A&Z%Nq{cG_IUGb!^~aO6}i_e+$D>=#V~d;U?fsp=ST)6PXTt z```Y5d1FhL+D=#9BSgR59#rsEK9AMg-#;1XpTYg}oBzv6kCh^Tx2lF4jt6gukVv~* z+ZZ_+x_C=`_XMwpEW_?%Z^lTL{OmfN4fAL4{4u{+Kl}9Dg|&gV;XWoJz#Fl%D7p>$ zp?A%5m%Uy3ly$OLUjD=%2I{3YLTZ$R%eI7aaad zm;6h#@#gV_`Nj3I|6Fu8I=%>adwyoyW#EnYEXZ^M|DnfpW$jCb`J~8LuZff~Ag3Qo zJqQ0`u>ausWB=5uz1Hv^cuP!r#0K8TfPd1V{r<`Nvc2Z&gk46Y{_h`MH{c2TC$5kE z|Gmox)#t$5E&HvGz#FOg@WGffPKY*cuW>8}ed?D@J9VkunD|FotOfsP{{CX7^8Ej@ z>EU(%&HwRzw{3Npy*BW+k!5}WcpGxxB|hs5`($B4reAVVhx{6H-{Jn#xBE_;+FH*w zkZTWv{9@z&0}_P|pnpo}m9zIV@CV#~V)3`c6=6c;P2!eO<=_{%zGfHuIOG?XV_kI! z@{9bB`Tr-s@cbK}r!MC4c0gv*YsfEx^)tW|caSHnADmxUKgIrI$Rolcs%jRuY8CQLT&Lx9C;QYn?lrqh4&wA(4ZZm5sT zV~GIz=rEHKxW6bq_m>U6zY6^ihKdKCrUX}*+ra%rRaDE(uMw~37L-it4E$Wq9e(ci zSczT!RAWqi?4c7!X#X8@GS1^fnR}k5hin_*_w|o|?oaL$s}pI5*Q-k<<&U+R;Qn-$ zA+w|X%Znwsc0_GDJMUOaJRLK6t(S<>4LaKMy%4YdikM)3UVXXjUG5s*_3XQ{YiE@P z{NiSB*ke=F{RB0wz}-;)OF(|0mv$%HiS@i8LP40Z4LmDi6D`cR zpK$jbm#@M|c+a$UFp#HamP?E0syyL1o5fL=LiL#kYJ!24hinN+C`hRik!C_v9LKu; z)nn#$T+Zdy?_Kob7q9-0A9t5IL$0$X``oi_kYFV5({H_UMlyL%8&YN2%1lpJ+4=CQ z2~^*WWV0K0Uvfe|N@+PSpU6xRom>R}r!T3!v0>`7S<1}THwLjQbIpd-|C+n1^Stsf z@?vw?^s3u3OojW?jC^wehV@vd>15q_rt+?4sF90xWEguvJ>oU>atN>9EJ->YzQ_En5^8)2-?P29 z?v2_d!70dLy|064A#$4vy0j5b4HRk z86G8aFptjmo>rI_cjk+Z@pdq;3X8YS&xkx#cE|cy-kp~mkHl3vFJT@A-0_`@bIpj@ z#$U_k!o2oxDt-m?8Zw`O_auYwIq=@x!S|k4_O@|ljs&$O^iF%)geRQp8Q=UW;60yy zF+1tHo%BZa(OdsOp$r<>~RjsP9wNz3aJ)?|YUMgI?bs zRM^}&oZ1!0o+Fz=Rcjs!h_zH(>wgeR;HkEdpjMWl(Q z@5%!(e}>=uv3~5-PVR68-j=?Z)&;zgAHO;Y=!dRTsa2@B^OBXmz?uDGmNMD0_ps0s z;0f!8pZ@pWc(f%Mcw2ZP|1apDq?bGGR27~;7kJRHnhiYO9)~)B|B(1u z`Io?d=(85$Ef?>;WDU%N4Dy8iho65YxLa9J(Zb~HgLh)!pX6oPZd>qAy6r}3;SH51 zEZ2VjBm@4*VE@GP$NnF6^8NNo;H`M-PHEtc{CFR+WBVB~T5apw*ABW2Ye0`=kf-!9 z&H6n5zo+(3gXjO)fAD>`y+6OmKz^ko0v=+z0tJC_u{BeHa z`H$!c(R%^BIeVNBhWsK}KVAL##U02mg7t&*3+u<}L8K6mH>;J7>mk2})F0r98RQA; zALkd=|3Kc5!MwrqucmMJ@$%5?`l0oZUj*|zqsV_V@Jsa?D4mIh{KEWR+i{KEdzRWs+d%kqh&l|3$rm-l%7)Bo>2LjH$; zQq%hVlY{-U?n~Hs$S>lyqD=S^>?^qcvU3_jk6@pQtNP{7;|cq}>TvJ1;Qy4?6uB@8 z@(cU_z`jKW_bojCjV7uYuCNcX@>d^(eUR|UuY8O+1F(f{wWw5#MUf7+t*t2^9Z6rcOc=6~E@)Up2ii?SPk(nQs^hU+P0d*u1+hg_ZW z0juUF`cc#JEAlp$9-)#VLj#ZC&x4(|hxWZXW!6ndjM%FBeqVgtctMMD9CDrtSXl zoiBIm45{C6H?B%&c}0BbxrwHX`+AF!y#8xX9o_j1`qw`* zwZyuD;>+5Ct*Pj38r9eKRo(P~Kj z;BoOwTq*^L4db^<5#~WppFADr#f@muNE3s3)o-OLXX;8(Ths2amdjRiGBj7tZiIQf zvM7m3oM=ie+O`_afq9wOZ2bEBo(+Tb`ASdoGRp~dT#FF>2YP1$>YdZawNE8 z#AbKUYhuY4DbVYX_Z{Gg4Dz&l%+ldbiEF4S-B)jKEZs%TcA|d79Fw=&wn1UoC;RO- zHF3w}@6HRQ41(uA-ysZt?>T?|@K3)KP>p_(WydKnxON!nHnR=OV_Y{&_9Fw=Qsc2{`s>9=1*3Ci%?n>DnyS<=@w2~ z_MEkCnu-(5pG`0qfs2vqhE1n|=N@ZO}gvS?cr4Yl$K~Z)(ut?yEJdYyJ8s z1NvvM{`v8HcCv~_B=Dx-s1^mhkyE=p-UGk%ssy7V`D-<-fqG<+Cw}~5|9RZ+KV-mv zh|-qlr@((`^-)KZzROp$2IfHqdBXmK=Y#$8VsR#CF7UQyb^UMPjgY6>$H718aMrGe zFIPNgm9wjxz&{CF;b=AZCxiVH`#(F)D1+z!(I)$r^ZY;U+=6v^WW`#;tvzVD{()``;@DMF5QCEgK=RT*;M z4e&$;c^dfd|MNe%|ICPUM!*yIb%mro^v}lq%Vr;Uh5o5+`x1{^`TpIzc)Z=G3cDe{hSWd4=D}LviQB8* za1HW{VEy3y!unzC9kju($$QJNOORg#>;K5TvQ{g|ldIePw?Tdptbd$eSpPf!*c(FL zkm9f7#zB4!>ECX7dhHR&!_CPKBHw@~%&(c+oOa-sI`XGr^oVOU9L(?G{`?x`ZAkr2 z{oHQIFQ$9sza@}g1p5!pFYG@xox^J&zsNmP=Ss*gg7vxLgz^&LiHRPizWW65g#Gh( z^(!0jPfBXomPKbFzp#G}7ybYFMF#R~NdEyBGUT|hPmQ*SpUmS4`~Plc`*!eu)|;E> zl)(Qv*#Gx;C@H!DZ#9?K&Ef4^_|{?4)L*#`N`nXJ4h=R4#V&R^U=zxm_+!Rmy6AnXrxY>NDC+e&PEC`#;v_yyrV7IVJkhpN3igg!_x)bAQ?3`)l#Fg~ptDaa5D} z3Z<0Mim;eZ*I6u z?QCf;GvVpRf=s8a ziH67gk&O1^`RM_Y+=?<_R1X(?uf$g>Hh0Da^2QT0?cF6 zxcsiD@ro$9PV0E{7q!WC=FLC9zIj}$!C&^91k;+!zs529RpqBgc?@S<lLuIBhOp5!+RRZTKYNrX_7JF z`9|~Ly+_|EFoO3UQeV?4YRbOFLS$>P#6JG}2- zr#(}FC$d&2GM>lN$|-y7wIe*JKc!0qedTvj7u?2E40amZ~wk2ANSP)Zyn=H`k;TdaZ8HD#FSEwxZ2-% z!3CwP#cHnQ>Ye}C9O-mR9#6P`%om=2-rwj6cEH=Gsq#83V?m<+&4Tsd#y3vbvmeFV zYN}X=#{~z&{E5UI+Y2y%2G1YsAM0moN7hdUc=KBRq!;u~_g)7_K5u@3Wo`7@U~I%zA*4hJVwpW0)FZH_ItGB!s}Vr&WuaaON76d z7(Zt>@XKI+`T0+-*_hPLz?)O-Cn?~K)N#Ur$_74W9{s^}y5C%LS4=>+&EeR9@2>ElgREZ@ZiB93RYi2u9R-8`PK zf8zS82RAI^`M-M0h66nR=XOd8@_6&QVdet#9qvCfYVjtXA6(Pk zn*jZ@asN*iR#`y*)T#o`@|%!fxPP&e|FU&~x1FU8A;25K^>0Y3JOQ4#`#!WOLw*rF zf1F=<{z7-|j_&~8RyBWm4EaT{ehh7M#S6fXt9Sb-@_54f!TE*t(<5Y?HwSpr>bBeu z`9(0lw@mC#15ezrhVzrsfhVkgoL^Y~x4bGWX8~_<84{7ayutI?#0k*@o|ql8tCv82 z5zOzVlv}>QFLmugPstLy8kp86_#M^);M#Zk#!#`Q!{r<_p{yDlozsNv-4XLlw zpI^*Cei7{d;j5L3!2emUg1N%r{~YZ9VcCageE{CXy%rSk_AQ)W|12_&6u>^{pj&(w z@{91vuY8Xq{Nmd`&fk({!)Hn*m2&FN`((7wFJY-bSU-6G!TE*vAAb75`p5g*eUBy!*x%?CuG16EA;0kc zwtHKA2T%X?vppjIoBlDsc>l!th4)X)FF*gm`!mijygy_A!S9Rx6Yu{xzwrK#{S()> zkz98N_9^ZMtzlI>|Ht=>yo_u<+%NQcYR!>jkYD(I;phJj)1-E2NBGjFPoGbR`-|dp zf7#&st8CZ3*rej)RM-8neQsR@bmUX^WO=PW;Z@c6Y7AxEF$qYVljsI6XyXbghm; z`er$*PTG9yn|T$Ssd*CuGO{(8mQFQ2#VkuAH?KF_p{$3S7?%0GX~H<>p+%4De(1k$ z?B{<=pnuC*0r|G=U)b^+ls(VYj$r29elzn~odC0aStk68O5>U8+?EXMWDRP&={_%+ zGu0eNrK7tu%GDXS=s=B!!BffB=lictTRw`J%=YWq@LFw1{imIF+ZSthu>-3MUEjrx zVtPCs|Mt0zU>tQ;?96SDW9oL)e=FUuMO|y^bhm4%=ggY0XZ`khYK(47_>J;-3$ncQ zg!b-X(#-O$^?Ju-^%$24mgf7Q{|TSx++7U)=QqX39yaM=JDyG2Kl{EUvtK1@;RUl{ zjJwX1)az<8%(9e%^|pu9D5s4hq+*vfa;BVLpemX=f%!0H-YxN7GjfdGcCR33JkuxD z{jj;vWJv!tt8J2?9@*(Ve`E&K8~7e~@OyQ)1I>pmkfxGUY2#yy8#y7|8=JUL?`DRt zz{f%pa(^=Sw-|iyu$hj8T(223((c`R-uyXgcP=c2{)c%vt?70dLH0hcxtIs@D4$!X zJzu+vdpvw&cn!?!(Zh@D-O7Kmv?MJSI5yOCUXMSUunXpKa<5KQw5%Q}oMYqe5A*VO z{UcKmZ!x6*PW>YnUeyT@ot;7Ff5CeWyf=67y^rtCYa7=7iL>Nc!Tjlmt2vL|{H9vM zdv;zvGR6C~8gaTg$|nonJ9K7dD!liQ{$D(jjsZQAOv&HJczQguSz{FFm1}oLD~PAp zjEvmu?@u~78g5(t>#Zv|7JXeJGeM6%);?8@6ULEQK4K}Epx5J4{v8TgmQ0kM!UNv> z{_9a##?z;%r~kJ3+9QeD^YD)~z?1btYe{0in)-WtM^$9lcIt@bEdK^$MJvaf@qZFh zciL2XZ7a2N+fOa++Qp4=ilg;ZJtyo3-YmLAgkof^`1W6KwCv*%;7wFr(gXTu@BVsg z=A$PatkL4~3BA@8EGMnAD!>za?6g=v9#6P`%om>j_uODp2jDH?{2B@1jZE)eeSK;B zC)S#h*!Kp9t62j)kwKpL%^&M$uII07Zou0nr|40jA7VaNN&)o4S-3j0aZW=$>!s|A ze>;aslU~+>pD19~KbJYoOG_3?e@vwCi|8}Rm}UQ7@2 zYsh`)-=dMTbC@Q%D7IiW?te;^zzXP}%9lK!_7w69_dh)Fhrn#$ zZN!Or2Z1+&=Rd#`caSGMf1F=<{sVqT2K^4#XEG9xxq}}o$zREU{32LCIKQxd@;-m* z2n62twh29t0l&ujAK-~Q$P?B-&M&P0fxIDud4u^~v8qq;BIM!mkEh#sJYjxoml+Aa znJ-OEZi@0e4*7-o_5XHlERQ$!2`9B7zX;ARagC9}z!M{W!g~Sa7s396^9%dWK;DzV zyvOtZ_1{)d@czS3KUn{Gf7_GaDFgc(Jw;dR zNdn{--runP`SFYQPn=(P|HS;_`D6dV`!mijygy_A!S%6!;{6}z7vBG|e`5c)-{q_x z3H#uZHwPnl`xL%kiY%we!2Lq2ds^jwhWx_!3-*6pKi(-egxLGgXN0IpaDP#J?k^jB ze+AVfe{yh(p}u#I6^wUErON#Ks%AcU%AIlZYJgyAG1sAddGbW=R?1~T%oZ)FQ2P7z z^R2^t1el=k1$#vvk7uN6{x$2&pKrAwJ=yw8NLIdr|BixNCTa|+y**RlnFR@5p7c#f zDw4i<#p-2XN(znZpL;*$UHkC2?36;~9Q2FaEvFYD#Ef$E+~jviH((#`5J$t5?%UFlsToC&#emnZ~PI7euS-P@-?g4Od-V z%aQH7oaU?pKliucxj>H3Wb$fUfbISeVJ7U>+t`&;RhUm6U4Fd!k$D2zy!!Ovm8bq} z`_9%}u;`xfV^PNJ>x){ms$q=o61w2^Vp+!fTxsyrg}T(Cf@arXzebMGt(77+#qe`z zGtz?QKQJTqk0SDNOeC2-t`0Lro@q0c^{hF(`Cq+nRVV=UO(gfvwCnrLcAZ_Y=<7)d zM!r2PXJXl3Zq}mMAcrC;Ciif|%rzS7l(ZPvZkx?VPDI4FKwJ2C4Z^P{q>w=P`!Z{r zjJ(IoGDifwKP_KqIHdkt`v-YYk9}(U)1^*OZ{T~}!S99oc$|6mMVvA}YW!xK#Yc|Y z|E))U^i7kQ3Ez`7yPyc)8&d!7^m@jqY8c_HV&8iM^Vm9luU_}I@7${7zFi_PuV*i! zjvVf7;+*WH%D${^wB$(txo051u>TM2 zTV!zG!up&oc5n{x#F%fOvmw6-pZvcIP)(_r)aDL(aho641{_*~{ zHETsa>~FNrqxo%{A;0kcCPe~dri1>Q*NX=IH~nLN@&1YP3-6zpUw;0B_h+16cz?$J zgY}916Yu{xzwrK#{S*6tYc3_m+Xn?cmmc8xKfYfY<~>;p_Y3W4@TX-va%w zqoPmzKf>NT9IO5N|Bs}iLNcdl63Q4!x%b|oISu9}8Wbu`M0GSFO*Ds;lxQH7vB4e) z(I8`KGL~c>Q^N1HyZ3!vzxVR_UiV-AI%}_My`GQfbFI@k+NVSBqS|&i{+S{hfC;(3 z%;5dy`eWMN5wd47Efcjkbbn!~YjWJ)7rdeK4d%2=o1aaq$6r_%k+TEq+V17BGsBOP zyb!4u7a_t}2236rFhh~~I=5@vDQ$bx_Ru%8Y(!Er94plg7#&q+$eqg8cVe>$b@N-% zo+W|Q{vo>*KRQHGu>OEZ|AeUrKj1sEhdBG?x6*~XZNE-kBf_|yHrRRWtpaoQh^E5v zJT=VHDDj%?v?4Mn=-pa8V>}}hw9n>usv+U?dHTocmYsCqq@`h-3M84}oY3`UsQ)8t z`*hjYUBhkS_7>htA(ke}!>Bwul8e*u8RmFW@Yb{Yl zZVTO5V!T6z@hsmh^SZ!*@UC*~TGc(2Nf>QyVzOCfPP4AzLVis+dqG{RAP3uUGJE0r%xoR_w9eC zGn)BvW1?xL*pxx_6;u21?3ivm<6iUf_p(yV=BLwcCHMcKyG7>sB>9hJlAq|=5B)X? zt9lk1`da)ax#!8Q*7`N_%&+8)_D^DUh$aI^E#=IyO#jKp0h^y|4yxb2Px)C&{~tWO zJZerds<)zCEcr!DH?3IcceV_DPYMgUBO)V?`N*0Kg!a~xJJhmjRZuI|yS%>x(A!*&1UpJ-mRpSs6we>AVB-j7|ky&6HyeWjS3Uhtiq zae4Zg3^Whvhao|wVpE8)|DD&M`f+i0veA1I!yERCtU&L{y*Dj*Z=TMv*COZSsff#a z@6Gv9Nw(bE{*6HI`7(0BW%Qmz@v+u@M(Dl&*v3wLRbarl7;Ilviu5zfpV>VX>4(!J zA<(1F!}{5(2S3ogQAZnDy{c9v=>NDSO^I%{itPVgNY;8iGairh_(Ft~+)^M(n3m37 zGau>o`zMhUku<|W_4)Gp`Q-|+S%d1s{tfJsx+fyu8XQ!`{PSCJ z|MR8iN^ePHE@yjq^Zyj`3iH2QQnBpBWmj+4MEx_cf5;cd6CvQ~k*&U86XH!{C0>Gf zBeJV*>3t2B$Ly+mv)BHp6>K;%QoiXskDCX<`41z^ zf1rOplAZYH4&v?N!hv+;pM;5K{Ym7X)XkEtOgD)t-WI-p5}bcB&_AL7Z|)EKJ_YGf zxnR{CmM4j%vGb;^5h2=cxIIDsPaKrdNb=27qbjr_6^^e2;moGb*g8Ii&*UdDwLiq*zPZj+&Vk+Xz&1LOU)IS0Be|2c17UGG1 zJx))AYYDENc&i-7up`33be{lzym z3h~z66I)w>{2JEhc%m~no}m6=enI`a^&V|Tc|(}HTN$GK8dU$yr#F^}C)!eEZ9mHs zrs9||NL-p!Ai8R5Nqa!N}~KC zV15}dI-HAmVlFg^M6x_V|34iOdZbXZOM9vB^qke<0xgu+X_B2kj5o`W2)6=c4?A`vaUmtPk}A_aB&F zaQ_jepVn2$6P_Ub6Qe_avigVnTU~alyeP`A4T=X^FQWW{`3c|=O?1OFhkJ~<;&+@Pf+r^DdJWKt>CavD>OHg9tWNf>J=DhQL#pI?$|6}{d zDl%2qZhoKcs86g}=zV_IpH_N^f6e!7pApPgRp&EZsQ>;un`W~8FEZD4QVIBmZ&*%l z2@@NjOEv#)lt14`Yq!3V(Xx_bI`)xYH-6W}u4k{PxyDqJitbBur}oG*XN{fjCkN>f z!K;qXbxR+@lx~}OIa~?dv!MR1SyFRfdbQvmZ}jHr$B8pk&#kNZyk0uVTqF4EZCR#7 ztta4=pDuQb7p4|zTu;_`s1+M%%P~J=+eQxYL%&CSPj}(TJtLTi@jk;IqW_N#)_0A3 zez?-46aPZ^Uwl4wG&4oR%=5fb4_znHH)i1m8K$er+NbLcoElF)T!89v-=hWJQ_LI{ zlP}xNOWU@8D>`Y&uGrN7PNI4uavPtadW6XsvpMI`_jb9KDxmK%@O>xTyrBAu*NcCi zzO{v&hw9rmcKKc{^kIWvR)%O^H*!vOJFQlrl6G%+^?u+7Ipd69%n3A)Y^hUH@#wz` zA2>ko)JOBWKcaadn%AKIx%b2c?)O zCUw=c@42G)r28WSuPZ4MU)*GtYM}RCu0aK&_hufPynU(@>1V{q<<2QcKg+v3)pqvw zRq^ZK%G!#TM5zRG;Gs7w}ZF-{??qq9ZoTC1uGKzrEP6@ixNX=2(>@ zE%>*?lM1YK6tQhh2_Bap6!V@oZB^L)rxmxh+IT+)@dW#a`h@ep>^C%c0^*I?JnIaa zKOQwcX8ucUb*urivX?ww&1?R(Clm2ROgD(NL-S|g{DtXf_0zOaR=^_iM}!v+{NP2Br4^_4j3C;+cjdA?3DXbMzXh#cQiXU6-M!o%@kTKAAzP@i z-DGm~sM5Db8+qea7`Y>!h^XF8^(;^Ce)X(j^*{8J=OR}Ba6XXVn~r{qynM>5G)l_u;xGbDwEi$q}|i2TGBDQdz#|V;(ToJnlUS0Z-6B z;rntt;R2q_)}tF8@uqLGZ3FUu;#j7ya%AIVs^U(-lH|T(9;Zh_z!UWULG}3u-cjz( z8?uvG^YN9}0G|Bz#we6ugYG+yCqlrJ;GYxxg!Ru>JNh7==;h-_+9N-}VgKFB9Mn+% zSd7++&g&?@VE>$7-~zvZ`f1ek&1e0r_wLiFD8Fzxf0$oz{%$`v#3R2WvXT^8N0-m7$VSYjVuP))u zL3u;GyUmICNwA$-5%M;|c;Qh-g#4m5!3f`(WD8C@Tv&Md!5d35; zA#1ky2%DGieGAS8)+3(ipSzFevOGcmf%ygfhs%3HkoU0vtXX4i712I&?TX)bmM7?+ zAD)<+A^)U$YrHo|qx^#Y$?YrX_lxoO6_{T&9cPUZPqe~_L;sanrPpG`DNVw>RmqC2klNrPiA=%l3y7xzqoyo5bTS> z`iJ@ZJz&%#l)qTq!EmQzD8FF-!v2NLAMOvS76GEUD8H=bbl+@6`33g}IDcXKf%^~4 zFS!2*(+|`?+~21D`7|BvZ{)<$_CN2S{DS*isn*0kv@a4W`S-0@{lob{e&PNJ^9$~u z!uW;$1NUc`UvPgG=0DIs;r~|a!a(|h@`^){Lq3Fvl zKg>73fnhs&Ze1ZR*O}`Gcw*Z4v|dM9>=^t^wC3HS(iAxU*wk+a{z~2~C0DIvlq|l;GJDtK6=QDc5M@WlkXwf}(#5NIvn;L+W13pGFB3)e zd!>_G*!qPoyj$_L)p!T~H}s);AN@dd_zU~a-*n^GKo?KZam)kJywt2a1{nGNMpc)2 zEqU?j?!#+3$1)T4oN_FiGn06y`~0VSXfJ)?v8N)oK#qa^^XJik^XD;)ae238zGuTP z+EUp@t8({PW_Y*!@;86fawxJ??w7;Ct;!D{Hp@p-CfWImb;mno0BOyjCYv&ug~w^@6_1go4)N zZd>%d;~~98vx+qa^}poOmaKgZzwofv?k_9QJh*vr`WePtkm;o3v(>5cm48Oh%=<~6 zZTPf05zV8tYxuYk$`gs0vm1@N(Y)ln&um!GqBW@h;B0YA^qx3&Az~=|p4@w*e?P&0 z?=KdX(TDOi(C-g?|7k=)4XIHj@4OwoXKLH3e6s~|#I(JOiXG8=XQnRpLhsF_6vr*= zNAvOQx_s^$nh&Q(T%gC4D0>~GSNh!jc3oDlH?-&g7dtiT+qrOsfMKO%wS`K$E7GHW z(QHYiN5bvQ#=EPLUah{)i9~uGRG;IC(~lhUae)C-7-WZ$Qa6gMH}Apb?el$JY_!m{ zDPix{dlJ!RRPng2H+^HlcA$&)38z=#}h8#3HA^51Ltp@V6r3*@%CJ?^+AGqAHD&9{5d#Z z1G_vwr1tgO8ea1Dr#sz3dvUvp^ma6V2F@Sy3-y!yRO@a=L<7F@Q}ZjsrNaoP>j4=^ zKiKHJVjJDOpS&}C{Scgf7-9N>`rqZdvc4Db_M>IJShJHPL5};pIk|=A?U?uAt7t?s z&%h-va9#6A!f!^O;yc9C)GqxrR{y^3;3VPFd%C6^+8i3hvhDIk8S zr6Z!gD&{ov>iZsd+SQFA!nEIBMf@_5Ut#_;?#fnombd>h%H|^fA^t0U>45x)lKeXT z+${YDp8J*Ry}!I=h-LLki;({?!u$vNXWGRkFeFss z%j4dY5bz|-KRZuO*~t2TQr&{XEKhHGcLc3A?8PIOmslbHCyZNvi(~#8)Uv>a>iIWI zc~`AAZZ-cROPJiT{mb$M{U7ERcb6R%+-Fx(HeaG6dhzIU3(leZ8g$>O9R6&RpgoQV zzO?Bq%ah=r6a0kp=Xjz8Ji-1So|-?vL;0mr`rLC1$}iae@o4oFw_%O=(hJGm=EyIg z{(o#VSr%JcO~3rOWO6*>3CQuzfbu5 zk{rJz3Oug^1rl{qI}1wP7#H^L@LT%29q1(0^clLI1hS&o6?@uR;Aw zZf**&LHo#I*NAy6PtZT9u@k=||D<}C2VP{}){xLY9Yn)4*LIFYe=lF28N08*{NnUT z3wVP5zu}kLapeEh?75pR_oDoQ{(t!-5wsHV=Gk)K7rSr4`W#QRfF~jOl>zfBN$PeB zjd*+9oAP!T+81Gc*gwqQOMfSwLHUc_yld*{iSi5PFYF)c2hJbv51U6PJVyHiHW2fK z>OuJh_XjwC$S>3n+<#zx!Tm>=exUy0{`QN%zwx;JjR*HPviIj|R{wUnzCQn#{vp3` z|AhGk_fN>LF#m!3Gt4izKMV68=$~-^hxrBfe_{S#?iFH zZ1?!LH)wjL<>ciC+c#q>DUmOm9gk8y$xkXi=l-I7#rqVD#K$o`r)P#q8*VlwU7rV( zY-2Lsh78|ve~mP=STuxp=d?DFzrRq&C*>d|9W3d+&G#w=>%Zvwoqxgq9eyuBp?OYW z16?Ca_pICgi+;c7*|SyYvP?qQn3(4w+L-*FySl&I%g91suZ+!-)X}G+2^g*hcd_96HZM){U3SNbhQBWe_L~kmyJawzQTQ5ri4o`ZIf*^BiW&w zzOK0Kxn$v3W^dqP?M=x>Shf0yn>s$<$ml1AeYVfXFuGq&Qg&5o67^YY=O#FH(`oyI zjy0Bz9aMkbn+Ua!xplZqczdpaxES-T_Rnk6&`!EmqQBeCUWV~(xYF)$Viu;5`g@vE zMkD$8uE+V~)}t8D;I#>oA2kTEh(ls`*9>7yEyo|beOiTq^Kq9aGB#ao##ORRa#YBX z%=?JM)8}Tl)5d-F@h=~aVb09Vl#;NWhTWciAhF-5l~meoU2H#QBs09F*G^4oDv_vU z_QhO$7}I??XT40a`k?w;JzP+4MqYK%#*5AL?aqoJ?Duq&u5Ay!^OsCr_cmQtrj?vm zoFcsd)$^EO(J!5>PJB}RK4J~}-m44kXC^959aNv22QHY$LFGP)Pq}sUX}6_8hG<^9 zM;g_q1y83Id%Eu5DBegqm7ZCDAI;;IR%Ab#2XVRRhJhcNSKX8L*=Sx&LyhWDf`ER6G z8v8KZ%oOR>As?T8N^UBZ(z-C@M@=a?qHC(m7^KHd_bN9aJremJ9puI!z0NE>XK-?& z_MrNX!Kd93PdI*aWy&nX)68|b;Rf5SF~^4=Bw8GIV}ZxU7yMVc+;p|S2wg21YxX-~ zdxuYoJ9hVA$aq)Z6V&NXHplKE-YjbW6OBGSxIXNEXZgDTmbZsm8h23t_|hiXv@p4; z*t}Q!{V&&)@;IJw0Z*`hVe|K2ky2ufcr#pQ@)7ZdPqv?}duygHmeqWD)Zs`X@Yg&L~}d`!6pwv|lb;x|QdABKkJsiLhU~dj`vsF#SV* z33>7N!L!?O$&W+x5Wj@#x90;RZKqLn-5s;Uj9Yp6@8i-DPek;Lu8D|W2J#F24f@ZX zQ`S0Wp`Cc3e^wsyA7b3=m4A`{P!^RcYx|xz@(h2!zKeJwrl{Y%#_|OH2iAxFdB-hj zL<-`~f3aj7;*HQ*p`(xdliFv*e}eOW2Kqm&&)sE51^3y`+ZT<>5pUl1 zH`k;58g$=XI=n{{@kF>UKInn+YtVfM>$jbjna=t_m;VBBmZ$$m|5y;ee-if3`2{ZU z3pjs{CtAQ0oIlJjIDb+n_H>d{H(vMto-XTmu>RL6a>nJzkF9jpmZSV4pnhO}LH*3S zweH6~#M_Jw3+J$Y4d=u0L<@L=`iJ=i^}l-O@}($mh_kD%=_1|+)#vKb0-hkh`@1*M z*0=wXxaNz!S<>Sst@~z`8%`G97FkwRlY1p&qMhI^B49nZ2oY6co8OLf%XT? zB5BXn-6+4{{_rKgzSj=<-H|jyXS6>E)eqc%V1B{<2kHm%1@#a2H!0Wc2_bj>^6081 zBjjXSd2oLdrhmvU+&^J{!Tl5RE6ji3{tWXA?$6MFV14MHaQ}z-1^0jGpK$)r|Ka`e zev83FbiYvd4v3bQwU_bW{Q~_T*0QZvP^qz~yAcjJA=CN!69Y{rjgAJN(Z?N$7e}_am|ExxX(_4Vj0pTBG_Q z>qoB*L-mI|vfSsK{R)3ETjE;+>a{8&b>w9Dp>q8?^2|M{)z zw)dpSgf{a$PoH}*|_kGD9pRW#}0e%+}=vCEUOT5Z4S6*tm4 z5AIhS)W19B9xsgg+Q zw~4dgOFJ>J==Fn9)C(>B6I(o6$?$6xTR)?E9_T-u|Gal1VS6U<_D=LYr5lS((f0<; z$L$Wj1I+_p@0z}xod-8BS}?D@-;H#Q#Pz6a=Xxi2pKK&sj8+pmXdd?*o*h55Uy(R_ z`2AcjG_U=C%3{2Ar!r8V++^Zh6 zA-!I5c;*?fR*R}J@4K*0rHoWOd0(#<>CrhwQWEKrkeuV-WRCQj_GRc4TZQR^>Sr4V z)kgPq;B{5ktyrE8|7k94U%e6=)xYkFRh|d7e2uKzyU^99>1t$U-={>g4zaW#8C@6b zz&0QCx4-?U1B>p?FhIO%G=(qo-aoiL?EegLZeR`K&1urBrHD6tNb0h%t829|-{Vq` z`c%qzD?UZWSBq8Sc=@&8EKjh1Ve`K{bcBin;;jsm)>F*?jgL;MlbV`fi0zh$UNfVm zmN&kSv@0Qz9uk?8EKil5WC%O|d-|5&*!e@gpni=0mp5W=IByEl50?CP0dwwTBX6BO z`3>=e2lA4iA^k8=KhPgKEF5mcL^k7w@?LW;BA%XZxI0G$@%FdaXA9Cl(V^+}jeIZ) zn>Xd^9V^dPp8D#G3lUF5^PJ6HEKgAXus-D1V0bZ zv!=(bynR!2-S?y4PwDF(^l>@j3Gxf)1N|q(SWecs~4BbjyoA^%~7`49BZ%#h0~hUB&5m&aV7vr}b=6Z%@yk$+O(Cm$i5 z9KQ3+A02s(-jn#{D5mfhy(jcfIG#F7M~RP3 z_F2{To>%KPj+uXUB=LGnPB8L+2KqnLC%o_8kNc!`7x6}w`9vY!2HkhxdT%-Ew~Zuv zR^1Fh`8DXigZ&Rp|7E=v`GMQU&EYIhuz&T$#nVv#n8dkppSPj>g8g%TfeZWs*5`Pl z1w6s|!~BBt=ll*A_#M;_$CJR138){KUr;|UGm6h5zsBdwGxtz_5wL%bCtAQ0)IZEG zsQ(KqCm5i-A#VRT+kto+RR8R*8J8cRJY3qX-+ck`^#9ycXp>alXUms;z3qKmzeGAqXad%+YebDpNAB^QmNPcC&{OSn`dOQ>H zR(SYgD9W!v^EKZCp`V@%g$eze&GHC^9$}jP(P3_jwf1>C;yNA4P*HG8xQVpQ2($#;Le6nQnK< z0o^au&7Kw1Gn8NOeu4fE^;z2|HojxEGc{?_^pxd!hcO}dml?djz8%_PB&F+xl}e{t zq5BK-lTN=C6r4i0`qggL-SCV)eC+m=*043$481I#zlbkovOiw;_2O1~_9HW?Cz&$L zpX^N&?~QdgUAH52vRG7Z#x{{IGl|}z%n^ylOV;I0CBoC&ujZ}XO}&h02(-+iU zy7dC8|8h|*ITO`)`yqEHE;0w7C3R^Fk63z#rAf#zLZpbNb%xIe4(LZ zL0YB=qn|&`a*c5#z3yPk=c!p^m^ll!Y05q_#lGvV{qoAPnVi4Z;?d*fB8*4jo(_et zlL*t1u`$DXJ80)EqdXk)s2k(E=70FwZsd-oj>T@1ID~QBT2^T zP*#I(hbFe>ZtK3hqE@o_d6Zws^?tg1_eB@)L^WdaandR!;Wyo2o#i%0bUc&D#HO+R z%i`M8bWs0XJzP-ld~>7Soz_}iN6Z zCyf>zPyG4hdGiMPo@h61g1*PV_vPk+3+BPiix$i)PHd^>lu5IwXqz{E9XgGqVT^e6 za5Rsvr(dl^^B~%e%+5jq({XKBXU2R_v0JmGa7KD*LYR+oZFsLnS!6O{by1A#N)LgY<-R=T)b$d2Ih$<8=gAr4^K^`QD3;3`iFgY*u-Xyv z#@z4IU&;2r!f(sK|JDCipDAkh5N~fg%c4>L_@fDTb5Z|TlkY67_hc#0sl@P69Pk;n0b3wVP1f%UURV#|X%f8d>;g1!DCo?0EURBs~Q;#L^T>7Rl6hyDQhjk-0_;UxNAY*$bi;+MGZT=pID zONGzC*Ssof<#F|J0Z))$SReY&)f$sgcE*kPx1?I-X<1{4_|s7)$bYDXzs{&%wQS}s zS!Oylb-4(^`0R5-n4oXe0k;p#Q`Cg7=-S*2`T5i(B#W*=H)!Gi3(dcN|ZIfG5G9`w4!+{_92t z{6aj@B|C;%vOK~5wW-Pm)IYW)^=;g+J0D2czY9OVa5H{>;jli(6D{Bg&L8F%od1cC zFVRmBZ^@B23 zLit5N{lol%`nUUihkT59`|*6kIh0=n zmZJQE{Bn7T3-S`y&%0b7WrOluEc=Wu%Mm@&%kKX(4Y^aJ-Fm|t-Jf%<{_8^;qZ$P>7~MW$>ThW0lswRE?|7L;Fb ze}noL#xLAIVSd5=6Y>k|L;r#MGt4izKSTc!=AUr?hxrBff9Rj^eJ_-%5%-b*Z#l5w z3hV#yeqq|K9zgdCwWhB#yb02GyDFMKQbK3wZQ>mj>!lC7>#63T z`m!<8$A+W&gs5odZRbM#>*MNc)^**q;nJ3CSVbMZPul6_z5P;5)V_>LjZ_@_{48Ih zz_5;#aJpiA>{&0pI!Aovr3I6S;OSG7N9fhkWhUC`9^n$q%*CETZ2iWyZ<5*i(}GSk z?Acb1i!Ahhm6tJuS@J5yTXV>F`mAKYVUvMT%np%DMO!xVFtPXB#oyUBlV!!XquPUi z)5G^&&wuq^jj;bIF;~v7iQZxSS-NPi?4bG@$K|u_Z7T73D;p%!0){ctVu_M%UNv;0 z#AH#^n30V1@zF8m<}W|eqR?6oR!uSex z!Vo3qlSXS+?}F5s4GuPy^o)x$%GmFDTUO*&+f1Os_0Jh!Drq6t z2YG8+p?acUY~nm`+3a+EK3jinkkcY|KHNNT!92Km(Sms` zNY)+wcdY`4|^`5isn&sJ!$8My|TpNiB{Wwqj?cwt0Z2(S7UNkj#N^e_nx@mJt-fJgHg_f^cL5UARF}F%KlG+v!|I+R!e(Fp1^C!`HF#^qtJV5 zG4gi1!X=2E&gDf1(R*t;>Bpk?W`Xa!u8ero=T*%?ybY=k`#)Xa5so9?n(E)Rq5kp6^|ddI zmKtJxl}B0?MN4=bPq=_5*uSv(D~Bj8zKMAI@8tm+%^xq9?_zSNnPG=w_c$-WYj|FN z$JC9~tHs-s9xmIBc!Kj6rk|JBCH?m!-fBi)OhCL5_JPk7k$$j%)01;kKm6pi)7C{3 z{F?A?%kP_zei*19Vfuf2+i9yE;w`;vTr<)?@#o7fg`YMPFza^J-225XJo|)(r%QU; zasAdl9@0Mp^$-04@~ic^-?7oF1{WJPaW3MQ$iKWJ3GquAT>sY4daaem)x!lmL4IL< z=s#9`{}J#;yeW^UK>kBb{o9%uZrjW|YgGQGC-^sh@Q+?J@*f8Jk1+q7&G%0MZ-nZf zy-$~5YM1k@-_+ekJmJRAANaC7LH~#O1@F5eetzLxehs?s z9Iv}sBcAYw!FzVFJPGbP!B5!#+B>g?A)e@KXHP|<{&CoU>(kv^QU939bshO}Gs;QW z|KqR+YhD~F!A;!P%dma{=RbUT=lKZaXXVn_Z%}^WaQ-mA;QV!*QZJ51yvtq}P&tiP;uNFL&eZaP+>!14t35AzG^fAx?U zsTGK~lP^*&P<|1RU#=c4;0f|u|0?i9J<2adiTJA{F4%WvomWv$}i}jMEVLpw6Ean zHx+s6Kpy=p1F(M^An7^=pVe^Ok z!y>)(3uu49w(nX0eILp%xIe)83)2tWe_(#W{RiqtnEv7ZCa+~vhxRvY=MS~?GbJrN zxW7UD3*#5=pD@4R{t5Yo^`Za3{Tb#L+@GQU2=h<4|HJ%(`#HRT%`|8IU(IuO z8|(k@esMq1D1+`7YGLELp^YfN;Qhks6&LJ_Fuyj64(qx~+E53MHP1))7bfKXGK2S* zHUIv?n)&w^cA+o0D`mq2I$l>z)K4OnZdIE?9h_r@iMCm#8s{9K7Ie-kd48;#?ig~U(Bhdj}~T22gyk>1HCVf zoXR!9)HU1}9M3E#Un;w~*2;I%3y(iOctu^ESidje#U;Df^xbWLBwV$6=vVpA7p9^5 zcZcMUXX_V?GqJp}Di0^j8s1ohbkVDaP5e)MOBLOD`n z57vn58$Jit5KMcoNIbCuMe> zC3&m}Co6L=TAd%DpNU=bN1F+I<)4|!}cG&ezh&z|M2@3a?kSL;}^fbzty~0 zj2UedK0kWRXL`53hD7bm5llmN{nib?bTBdh{r=x&TggqUqi(*#(JzEBo?e_EqfDF_ zop0nj=O>LH5-|~5FF&Y0R}UA|yL!EJEczbZGU|m$6Z&3Fj;(a!g~?QF;fb_ijZNf< zfWxv!P`%6nr-EVYc`J@ zmOncm?mcnAd;S>ZSrM@+kG>Nyb07QON~%O^*Q=RPy0eLU(>PRJkn#}q-}e*X`$bf*g5eItJedoA|4{W zGO<(IY!Xm?yUC*Z?0h($Z~;%tunn7i=J2qY!<`u895<{ElQ$R`=4@)Ub>V>5=nS*# z!^Lt|+*^rBt#YvY?D`*dRkpFi6!A6(UucSWV+t(GC$jxFS%!aP>%;zA=S91r{&C5o zlseQuzG%LlN#Gk}%&{^dca2>k?=)GXbHVO4Ubw3=3-wRK{)Npy=~h4QCgQEBDCPy4 zKmKY#$;`S%1ZMK#ig)dZDqiokfAhz=`7?0-!t}FW zUjc8#d7tMlh+pbR?P<9>*;XD`59j!0Aiu)=Cxh=l0^W!{1M3rz|4`%sg*{Odnt9{q z`;82E(1w5Z_#?sc1pP;tf7Q@|T>aOK?H$Umt!LE$R`4%YFu@ck3_=KCiD{S)dF z`u{VIHxoW@g#Ur)t*3KMsGcc3_68IOqQiK9#=A`oAn=R?X@a<`=y0mhkfn zZ{z3Jp!<&F2^a7rxa$NzVgC=;`v*niuI z`x{u^_RHUBWc>op|203q==uEo!r}a3e!=-OWbb6hAD{52Q$%r;Uj)=oIzPW?F28W7 zADCZIKP&n9g>(5uK>d&6=NHZ87XkGT^9$<#C_le&F24rV=jsXakbwMlVCT#czm(>O zTGPItO(f)(%S!=o1oR(n9)dh4p#Q-9g8tLU&o7+IF9P}}_nv}%gn<6}QmjH3`6tz6 zQMfV-|0o6R z4_ITlr(_PwFStLz`3utz+<#zx!Tks72l55=5BIkTbIqoq{SEt>WxVBALlY0~Z&3fR zKI9kfpD@4R{t5XN=09+MhWQ2eXXrn|{1fi~Fu&mb5B(F~FLM0*h34)T9NsUxbjp3v z{X$t5K6!sLvz!O-7h7wOVAlV~XE@5C`vr&j^^1RhQQZB73Aw+_;Qf`yzrQf<{=$4C zHBLm0xI=#@x7`?jGl}k)9j0f#-yG8v&l4?P>_c^Ynbxqa^gZo;;oj?m`b7JM|u_KUZ!1bhiI<71d$a zmecsH!{VVg96ISxkzf1wxs=gE2<4XxIwTpRxiryOW{Ew@a5?;1{0C`7Ti&+zuA`O5 znB)v!tV*17eQMY-u8?k`D&pN&4P(M$Lu2lv`ktp=k7fJU*gxUt=F(hT=T6Gp10?!; z$7kJt@;j=8ZW>uU%`S5!b92QdFW+?M{#0gyuEi ztPnqfO=zHx0cvJ-p$T^G)>L#mOh% zht9L0o^+lyNZ9g;JpI4#N$C9Vdoxh~oE~w39&ank1tGoC!?Yf`uzFSYsQVOo+myQ6 zT6)1NI-h*A_<-bgq(>3evhvXAF1#zTQtcVi>mffi`Od@%jA_*FqT8tdB$v%iD(HPV zo^SzA7ggf6neR8mBCP!v7B6cz;oTjhwiOgiR#4u=z_&QWz16czeC#!8kO3JSC@ZVc0witiMF5#d^yp9>)_d;0exOn0{9C z^@DTz!N;|IjYImu;>FG`*;ii6tK;hj=k&us{lNNA|746y!5hTe!T0J*{+lqA$m%zo zXJRoO^B#9(gqUIjPl2z0oYOx8^)HOyqf@=STM=&$eC8@3-iX{`PgN1W)cw<$0X4DB zJbymFIL9v|j9=(KPx$_WbN)jF&;8jk&HDe^)dmWz|3iM^eb>v+F9C0Z?z?t=e&Jkx4f^vt z*nbGWf12wbhy5QaGLJ<4V+#X+gNkTzi=+U2&jK~etywhei2arFu$PwoB8>LbNNL;ejWJv zMRWN@Kz_Ye3}1!#rOHPg+1RGgKtg^4tFB#`p(5uK>aM`=NHZ87Xke<$7j?6z=^ zoH&jApW5kOFz-)HJ_-GQA>aRT&i@IRU+Ye7GH^lrVD7t(rDz`{gydHS%&#~6{KC2X z652n^-}Mt!%2EDeXU9)HKON;4%-?=~{^DHz3Y|aPAEtll{DAfc%u}khbvw#0xIe)8 z3)2tWe_(#W{Rip?@(cA3_qWzxdVOer!*VP`<5f_8!Tl|SzrW$!{w9=PxPQX@g8L`r z7xoYR2ky@>zu^81{YRL8!u=oS7u^4$f5Q9aCjWk+x%&l&_se?4^2z9aq5O}$2&;en zkq7UWTm1V4=k6CA^4r9}zbNkh!i3ykX7K*%=igr#cYk54i>~X~M&6*CgC=?7&X4Hh z2Ujw;4jN#yuKbQT{dGSjQgiChyjwZ6iumar*F;7!t{`RteeFFV#$2pg;t{wDv%ejX3sQ&sRlVS)|e{s3(n3%43yl?dm|3%X~=&`jr zk1Ncx=^LsmPaCh2V6A*c1B~mP#w?$?}Ce9N)|?rM>E>jKt?F6GscuB?oFq zI_;-Lu(Rq=rgSkA*5ntd9{)^D^v;Yr*|#Y?umz7{6(m-d(xvqdp1i=JrXZ6HmI zU}V+8lZQ`OfYlv(`F7{RX3|k(=)wA+V%jTzhoXg{BH=prn}+k{9Qv5`hPHcclFXt- zPqUm+eV?AY6kC7k7nS}a^QiiOA)<`gu02nxY#G|n)p?1T=P;(^n{HN5kpZTq z7r4AhxrwYZjC;|)w2&S%^<%h{s~mBsdO&XM@He!!h}zEu-7&V?(N4DQ-6;(v_q^)C*qIyJcqV;Bx zWreg_-+z6hUFDdSi^p}b^BGd;xq$7Tn+GnKhnG?wJ^xlJy+geSi;n92MY`8 z;(;KwuQe5<%)?H*b!Z+Ie;%KI&?ZS#TxbhwM)MjXxwjh4iwW_)vc(S7?_1R}gRRfK zCoXtT+I7C<&8~Rb{5%oJzIV^V=pwzn3n|&_l6RHFi^vsAqDJ+g_dIY~@dA2JLg!u3 z0Q=q=%gHkI-VD^|+7*|?c#Csz6UC*oA0j;xU-q7?-gT4K6)#@G>h zc*3=Bw?>2^p4K*w`F-o)By8yR?wZqIw_@KLw(Qfo_qgmdpHcH<>{o^+;JMKmOW9!56 zUmWluc^wKS6{vq)F{d~J^-sh8*KGXpik<(%A1B@Zulbkp=Z|yq$Cn@Llbf}7Ay(1w zr9o7zh&P8nf1H~?1LrSHKSpY?k!FZDN%zU7NI&@EBWv1`elVR?c{_Y+D|jM&{otH_ z7^ok}7u5e(zW#Ae|HQ|OpWdzJ&BR8>hzl8Uy zu_=gO>ez?oLK&4NUK^iZoa2{){0j4*>Mg4~Wy7-Yoa3X7k^c~31^H>nf2e~NH!dt% z*vwmZ@LgR~P%+*X^I;sz6Z9Wp{#pFZpz5P}Ha>mZtYGAygws3GP~@M~)sX&g(^u5< z^7;OWbN(5esQ!6=e$iZh5s+WrUa<kK+BHnK4h<|7E9{Q*H|L!9M^iSWNFBOn~ zQnh00VLOKwk<&kQT#!TkZwUzmR2{sZ$1?mtjJkT0lzxWB0> z7AvCt4O4gC75@?C7u?@Ahr9dqEiJ?kuDd&A4B8iAeaJ7|KVg2s{S)#l%zxni4D$=_ z&(ME_`6t}}VSd5=e~^EI`vv+xykB|(npUFwg)-BgPRXMDg7*vbf0$qA`1cpZ-CvlH z`^ya8Ur+e=7slORSk6VlGC=7HExsGSbn-?#Er&JzbPfDTp1C9&XnM?xax^@1&Xac( z4}ElGLb0s`GhQusfo{|RQ~hTr!n@4gXY`F+SmV_gj8}g#yJ9S(L@ZnE+p+`y%?r*r z?WOJGPhIs;4rlADo_{BG3e~^q`7N~kydB+dK5=oul4@Gw{fQGn{YUVRW5z|gw2WjP zj!TvjSw0{0_B*=S-Kmn?W%P5dfoCu-B6H)~lLSQ~x5DN2qk}H^ux$%kZQR;uSpUo6 zO@zXnt@KNeuE()M+v)XpuIAVW9>&8XN-KEO2qt0ttT{5u%diRI*x}hf8pz@%r5BP? zLAZkDqjSc=3dHl;ZUYSsFI<7@%D6sNgo&0lTyPfk-#p89Lm=w^H}Cq`eZ1XtE&Vh3 zo$Vibrg{60dz1ddJI?%967p7@5$`vilhe8gJJm3xUOB#nG&j(fs?9x(dj(4P9!ZfS zl!h2Pdp91&=h}_PpDid(htXH zcZJl9muA`}M_p(8pRn@VN4EcWbD9^AZe!MvzSvmYAk7g7^?oGwiGRzz;-H~Rn2gV==4zgUgtr6PqdI-G)j z|I9$Dxj(A^TJ?4T1N%7tV6}XzV)xOkHKAe-${>)Q(2VPI^^!xZy z%g2*?>$>`zC*mz8Xk)ICj1r^q>0B7wf2pq8HFiF*f16|f`lq@6@#C|e&Tfn&u$B#{ zw<){rCZBr#>!0TOr(yrX=6_9WrYFl=$zk=+h&TMw4)yg{CnSHSn4Y|M5$6{4$VVVg3_N{PQ20^B+Pa;pAN8 zKNRVe{J8I73opy?pa0OD|1i*hg!yO8?SK9$;Enhw6=H<^lkzB&Pu=sQf#=!s&p&C- zKN;wsu>RexD-Buy|2{dl`z_)LEB)vH0^SJQeOJd1ESpc6OJALJ%Bhk!W%fV+r#b&; zUO9yCV*US*opLVg|Bx?u-|aE@mtQoOUxV(ubjg4DMRWNz=)QyfZ*lq8KhE`!!~P$P zO;thtV|UfCs!)_)u>TPIfBn;3|2V84;rlPY1b&9Y`NRBz^AD=|mtQoOUj)<-$CJR1 zai|}dUr;}sUki96p#HyB{>v|%%P#`zALbX-KbJQ&mtO?rcl(Eb`Gs@&ML>QdoahL| zFJ;x_I{*;Qj;i3+_KqKX8A8`iJ}55});+ zXn(`BidWs2=&R{kvaq?ta1H{jy57dNjIUsKl6~ZKqLw!TaUX*MIj5&D}3Jq&`! za94Jior{0_RywgNZ3GiL>XhWUp8rheCv~`nnSacvnViu!c0wucV`ed;{E$5HA=o71 zAdkRaOpZM&v+g+cGtM*V1gbwnZ5bhn>Zj|^?9f+>r1gs1=Pc2#q6e&RWXpWX!TUnv z@=5y7vry82N~0l78cb;}G^wQGz8+Jh5=E3uks)NB$-D34 zdCppA_rA;f*ZHmAS!dsS?d$vbe)sNlR2!!j@Uk<-;1iMkeo`WG??B$(jR&?48<9jx zE=tbI-Y>z&^;f>x_~}Y^EVY@z3MXfcx4}E*XCuaBOcy6l}<9it%ijf~ak9i)} zcHVeUMclq{ql|^q(#VQ~iS_d|oVLmf| zN;z`x`}A=OJ4h*!4r}SuQHFU4=0$|_YTDR$-;F3kR(iqFnR3^H;0h6=l%^%oExDQfxc5B$m3|oIaVV-+b z%j720u5jBR7W7!wr{yN-mAK``l^TFv1AMNp-7{8~ee%mJL|Z#qyTp7>X{SXb=_^(A zwtRjyIWRHZjMM9u{UfG>Uio>+gR}QSeYuxv=eYX)V|L~MPjuS*l~o*1S^w}hM!?&8 z#%jo}4|2NOG$)>tH)#!h8(TToP}EghjXkcAr!8mW#8&^8w;uby|6krnPR@+OyT|G> zA$<i)Z zslfmFioV7lMZy1n=Pb!81-;_@!uMTE)<5}01^M;YeJ9|F3i9i(`wsUn;E4$Gi{SoM z9__P+{u$XDE|VTWe&PP5y8EYs{t2!>tUJGmAioHnKh7^a|8d>mTPA*1sTcguL-EzgDu3WAY#mXIbwtg#6-RepmET za{_+Z*R#KzaUeNym|sC&3VHjh{@w2UB7*$lVgJGTh5g5=JHMzPzj*k41@9@`M|jvj zR~@|M0RGAPScv4LL4INXlrn0Z2Kx$?E;l?0{>j7nb+0?Wh#(!%*A*cXMo{nh^kt82&PVILgrG5r$c zFAwK0wP;ua`O8G9W^3naC&%IZb?nYxD#+g+=a2V?E0zbi{ejV+Q5An^!J9a|KRkQw z^g$lx-_&?=3^#wQPpluj|KR+>`w!L+<_qf|?{9sXz$vi5F>T|%nXh4TwDJCi^^fag ze)0Z^^9%2vm|t8U`w!lqaem?b8T$|B3;QSD|8aid{U7@$u8;j6-!B_1{Z!$8Vb?eX zsu9R9e7|IO-!D{fzYv^X*CKLqW;f1cJ>Ik7{pV5J0g1if@RDD4U0kEE}kr|e~p{t{c=hKD+fn1(%rdu>uGkJB$p-V&ergE*ctpLZ#H zAg^-n6^CzUUXa=@s}_$x6?B|oz|+Ohzg6bsdLHzjHR9g*mHp%BQTcJ^U3aT#ri!YD z`Hc)R&T+t!M7B5o!}7NoEgwypijSY>_cv^a%j(kJo7YlE0+vPpyiqOB>o;&q?TN`L zWYBH7Nug)j=}?O=o6VvA?>}Fix%%z}88$A>NwoRSrpRIAo9Uy8w>$bud?p87ip&lB z_Tmrrj?l5+xr{M%G}!3x-Vk^F%m8Io{{j-1vmq|jS&ldJ<)qOgM|~z$%bb>ep3sYr z>-$DFS=nj5r{f$aB&+Z{;lHb!<)8LBjkwi}Jo)2=DBu4~zfW1A8jS0L;MaY8D&n5X zp5X5=&Lx^BC*FLPFT;B#`)B6afNavT=nCy!Ce8o2#9Nx{Kh49mj(cB0Ju0l%aj!mX zjn;co=yM?LpYJ8KtBvS8kJY+XyT@hR>?AHo+a;a*LL_`_Q03f zPxEE|s^2(2BCemrXL_^JWRwxiWBcKE`MaBw$kB73M7eo=m{b!~X0()@X1zB=BsN3) z;a3G?ZG&$zE~6D|73k+exJ<|6m1=^P3DnS1R` z**$NU{kWf9sNFZfb@wTF&#R{@`B%@hlT8M1gVUoxuSBR<`w*w*tEu{|)&LSaN$Q)n*o$=^zJeYHX{Rj*J(9bQ zZIf8g>rRQ~;h@*Q`WNs-g*-J^?XGRDR%3TfANA3w#Euy?c+e3iQAbUcby0eAdw+=C zbw_srvw&gEd(SoZc5!4=<>*C@x7Us``+>I}`@i>J-iVCxF1L%R`i$T98Ht}Hzs2ou z=^O?;QSs0Vw>X|G4i&ah=-+MP&Kq3+cs_XkiQV(3g87q#J{JA<*qbu?U%o$<%r1gZGUR zdF#mOKl|MD)Q_LjX#U>EuL^;uqyOcNxNjPDN3-ud=Aq81pFG76+WWipPX+qtNB)<$ z9{Kg|=2yrY&#U8HCh*IC|33a!r+0<6pdJd*2Nn1aANx;F{&~tie6Gcf4Em0DSQq@0w?l1K7WgN7t2BOjg+YV%_iq2B z7rOnEkNp$#i~Ya6+yAM+|9M;2Zaa8SXAzsrGxeOORIaVl?f+EZ|9pX7iBPY&KECg6 zq&xQ7)0|237G#D&e*JadHFxJ1739}n_Z_Y;;7RBQ1ouDC;QImSpSjmhH=BX{!u`Aa zmp6jv|FJv2h#^|A3@#=dE;UKO#SaZ z!o&WlnwQug{F602^iAP@R-rcb&vzyZhQPi;WzTzhaQh0bZ$0ST>E5tUxok*qh5X`S z|KIyuVK4YU8=XG9WCY|F_J6Bx|EB`~=VAQ|cp^fcddM#=oL_9or=8Y3{*3br@6XtOdh$=a|Kt3^`#<(itbgqP_m!oVg&aW)5HCxh3~Jza@iN!3zo5qKL^Xe{lz@EU?LW? zVHXX(aLs+5(G414dhomKYXdee^TxDSH+Hd-%cj{|pUEeSqMx2v64;wR|EY#sFT=x{ z7NZ6|^gCY=tGXp_fv4p!a(18S-a09H-tk&@b8RmRW_Dxt)mbhF*l&v}c;LE~I<=Xq+J`g<(^9U+PDTR6Pj-RXF z{SM|e?ERyiFfV@4fyxQdP~Rm^|jw3QakF=xx?kqjfqqzGZ9ndQ=QnsDK=~e#qoxWKQ4cKAICaIRDrP?nS z-?Fs>Jr4P#bqDlFejQF6+86ZtVYqE1=#`(Xp?Q((Kc|nVlseSkt7~R!dnTXmh*vqt z@uXt7^S8ol4OTj!KH=q!bxg>-_Rr&`oHXO|ZU$tnN{j9P$l@U5rN?fF^i!YXvYov; zGhoYc;B8aw{b#^ikNr>GA|1I1c$=X+ZH7p%JW{YKrC-KF1E$Y}#)blu(l`N6RLIjl z$Is9ELH}!ma<6m!_cVXqp)c=t0&hhJ-bXN}tH`6KwT3zY=8X1QxmD9UYU0`+h&j!c z_(U6DzKi2{+P~Ls>r0sbVdY8Q-28je&-L+PFHM2Bn=&20fH%^RIE)4TFhy4W851{^ z$Jr#j*>uA48+};6TBa6w!urAbCl^JgJp}#FKWN`I7xcfrrs+X2@TPLy?*izb#E3oH z7BgFuIom$F-Au_p?%}FD_sZ%5`ch=tP|!br+=Jb_c7p!x0?)n+1pW8K@7qheXGg*J zo?m@X1>fT--|g5A{IV%$t{&`oQl%~6i3)kb{PyHO8G99ZkASy+qe@nT|L_Lu+zSW) zVIOB6lM?r7)xOsH#56U%gz|qZUdr)={ii4YOka8}O!{6f?Nh&28vK)YrRnr0@K1J^ z?65ue54UM&nwa^-#+Om!gI1;7dt(3W$^ZQoq8UHnEu_EvJn(Q*MB4y66vHk@-5g|`l|2V&}{#y;)+c@4#Di`t~zj&BmK|Lbm3G;hQ@*c-8J4!ks z^VD#EZOreS3!kPzUQ(M4mfwJ19`>IRi!>A;LZ0s)V}Bm|w`V(?FvzU8w^A-}MHdQDkB5B3!ra(eRv;Ejj#>)7NC z{#Rk2viX+SrVBh_|39S}KLGrnjhbHm=ZZ$ax{lyf2T72gFlw~wvnz~Qh;V|0XHSGBncN6wOFO|#6n;lu2)taj`tC)O=tyg+G zv=@I}%!oEWM=#BBcYI&mIsPM7L~X9$Uey|6)$V_9jnV)f`K_58;Aq7h(p6unxO5+T zJTrcF6V%Ubu|3JvAGpSBc#!NXdQdiBWk5v^O^*1v$GfwN8m#@PQY5zfvS)SQ-@{{TB=;JM?GJAf<u)au367qPiM80t~~F`HiSpq}7+MEE^^s=bnrzZP4O z*#6mnO@{W?#Q6#xP;Xh$@p7ogTg3!v--qwb4}CaoL!{JS{R`$nh4b(=d*=u9B9VzN z`EOueel}yLi>jEjm+T9RMt^G3PFwG;?E>?V_HyqYcwZos+(ViN87~WHBk=-HJYww7q+xN$A@ZM4qr%L1NE!cw71HH~lb!e;WoakzY z_oPEV?HMH9L{6q!ypnc`Xxp^zO_d>MokCR`Efu%Rj|-^JK_&^R$Kiqxv7- z{(4{Bf2z*>=1}16>;ql^^iMwK4y=3lehG8>{DtKUlIr4`3JM>)989KvtRGZC{}lI+ z^@-=dA^*qwVxcTpUFLM7p=s!PACY{s&$%3*S*}$8sx{?m?MpC^OXdm#` zV$QE|UG&E$BTm2*74p=R{xQEXuAR3p!uQ6gKQjP+$-~U7Lg1HOXZr2Kl3}&lfeTs# zfG7C#6AR3NUq0p+>l6D=g+z$%Qujg{aeeSg@E_jvBQ9;=KkTlcR*?&jL>R$5sE{Y@ zKRx-U#FvaX26#I;Il>*jf1>q?C%bK}^VQg}~#^l|cD@J~MWPn<8< z|0T{mUF}m`L|2y%?hH*4=b5<#|1ukG%(|y_Y6R9bY3nE7oG4aQO>c#<5_^EBjBDG> zcLQ%pXB~Vw|Ht+5eHY)IUqasgy6*%$Q9*wFb>HFo$>UAb!@v*bt31h+1)gyKYtHA70uIe&(^%+6nTD;Q8bH!t>wSonQ2Q zcYYD9A8i9K_u=5j;jIxbA-@RL56&;FpT-sGyPbhIrt#w?$S)q|SHKey@`Uw|^9$== zkT+DAH<;gE-T6fX`9(0ld#*0y_+`J`(DdoB$-!s z6ZRjRU)X;Hc~6CTkLNS>jY<=@kFcS=f*`+m*gt>0`MwkUlXd$kS(_)_p^g1hTvV)B z9(Xg;J?91f$;0_B&?6D@g#BM^|FQ<~e^y1?>FRXIFYNyhMSVYWyj|Kv;TKS4c{slW zJPG$fUJv=Dh4V|WFA90%VSVEMasJ9RR;`8nWe%EJe;5q;h4UBp-_!i@{;+a$R{`t~ z%$RH`w_>S|IJ`gL`Q!RnKY0Ja`Gxl%tRMWoSpRr`6HnG33i}%~P}WfS>za%>yubCN zf6Oo5KXHEH{S)(x-xvE2-k))P;r$u=Pfz}d_kWyUc>l-#iSHNe|M-59Ir8Q?+%IfF z^{bu1kYD(IsoNM5%=!P*;+IvN|Kohg`hHwJ$lZjwz=|A#`-|z}{?fwtSIB`=c2^v& z*pw40%5Z-%#)sc#{P49TPW0#bZ?Yj&?CGcbL*JOQQcEhA7q8#J=BY<-zNJw{BA%tl zmliBjfK}I5FX2KVHD~$xjU2S2L|?22mro zyRvmId!7_Q{mxaAK{-&rU(B+NVV^18`NeYck#ApVS&EI?wwzLO^sDRLT5~b}tMjLy zTh29M)LyB4OsegQb2lswT4rBI+;1FXd`UlE>-+?JBBg z(`ZJ$^PQI6<+M*?``W7sB_urPdXUILQT|kAMJq45ib+xQq5Bi0*bcYQ&$qp6iP^T_ zkxXMB-omhyON+d}l0x0;b5BF-spTe{<+;#*RL9xN+tT&~_O zz0&clqZn_`tF@sE;Cr9Unw^_ld;eAcb>K1aq_$#O`{(l>ZXW3;LdOJaWRr0Akp(xe z{VU&%ziDg1_72{mK8Ys=zjm+CzYyke<5F<%=?^=|%)|TikHNf7SQq%fy!iNi-R@7Z z3r#4YM{^6ayAFu*#a`B0!F!X=o%|;5y?^Pv5}kN(6)fLD=}dQ}mrn7#j)G3ZslrFn-R z>Bl#`Jmpy{)F-xPC%O6po~V$gjfUxal-?|4Q$`IeELy*s5&Jyc;K$iLnqkk5JJjsS zh>Z|=Yi#7cl)dLQBy05cP3(+27pyqmH2c2#IqqS+8T1DD0ifPTo==V2x{z=kBQmf)mn8}Zv<_U_|D-%E2IHvKR9$NW}$zAa7w-W0NOw18g{G3juJ zh!v0RXeb-LpuRynNm4CDE3lGY?jJJ`_~m1Md-9*3Ker5s2i|s^(s=^B@s4`NmV*DV z847}N9g{6Xj@*a7&t_S~Q7qt{Fgg>B*2})Wc zd)K>`PM7i9$MJ;yvnT(zn%Bo?C-BxVFUTJJpI02btIK+>341DN)5*uRUD^UYQXx-e zeht2y|9_z)hyQQ>kMFyaR*x6n)+nR*GGsc;nE^_@dvWL%GK7#zh{a-Vh{F37>=9r=m^iS~ohq&+3o(6sv zdpUk|EAWKpkMj%9-)PwiLqp(g)R-^UkY5DrXTrM28kfM211>V998Xw3IKQxd1b$70 zevSDO@I-_>Vg2L$!uo$1sQUdk@aEoir<}_hTz}~2mY-Z6`t4fv4DyR$eq&8{bNsTy zvTwarJY1rU`BjZ-4ukxnx9{o(0>6LN7tDhQdBXmK^9%crAn&O#@A3N{TYj%S2=)=l z!3BLdp0Iza-(`cqKiPxgs#>j(U)Vnd`wA8AD>%PGyuY1tgng>3)>Z}bi}wckKNZu9 z1OI1p)n>k#2Kj~kUo~~fa1;AF+Oll1IOG=(=a+ydBIK!u{L;et)r)`baXIi7q9ZRl z9`?l^`$zd}{e80*9^wm%0w-MDdW{->SUZ!I=JAO4{SFq3L&GY@!wUwKh`n>WZEL1y>VfW_PcI& zAL`$gnvl-b_nLe0kiBIB?dlhjIz2s$N+}O)?AlR5;+ihE*!~dV_xCB9Ce?1r3_5Y^ zhwpL;HsI`dt=_f`L?lwKHEV!0Z=7!1;2SaTN!a9??EJ_=>iO{Sq+3vbQbNhEBB<{& zYTC?kGN0+$ejfwyWgxN zJL<_9v!8tmeo6Ay)$1x$8GI+N&UG4&fS=FSK1BcOU8o=N=kZUjf48+QS<7>B=#>CZ zrGDdUX-tau^oo&Xq;t;1p?w~A(lO6lF3a^^#cXT-P?()B!)_Nlnz*E_mc+#<-u>D~ zf|nI5J8ExaF)hAn?Tc0L6G9htC z>58A^ZLHGub-Ha-Qu*E14ay4{&%Itl9~QO6nYK&38F;^%tV@W$zuiNem;U@~%;XEd z$mR8~oR`^%@W;F6=iGz(_di;G;pUS*J+n{Qil6jp?^MPf>Wxf}>8dR)B$0uP&vy9U zYFfX!ZOLqUhFt0zV>oZ?IU&#)4)~(p;*_YY9OT5Aj=5b-f zo#1TeR&wirvb7P+E8x%Lv~PVR_(p>s9litgzZzUE;OZX`IW<^k+ArGJxG>5R-m@up z-m|eXpUI8|n&RAhXU)I5%4()HtJEY>G@(Y8;V;%v;oj5ZSayOk{Cvwr4+2Gb@ZJt% z-`^ z;%6H>x~!QQcN(vnD7tB;rL^B~fq(0;?tal^-ybGy#_261qu;D&FG|i~oq)IArPZT8 zJO5oD_dmrZ^y50<&GqJyZ0MgznNI1TIq>_3+j)i1KkK2S^1fUn|NAZ-rg4Wtp}Ts0 zoPZ}Pi_T)d#kyA^mMwZcQ>G`LmA9oVp3v)uif7qoX6CS z|H1RY{@J?2`<^!Nmhe(yI`GE(Q54t&{>fgPG$ZM{x*YSf+drwmKl#`{vH!=p%J*Ln zdi?m+;4$a_w?d@yI)Jz9$A2#d-gx|G7d`2AQ})4DD`~Ig5=?{Z@kR;T1{(M1YAB~i z?EjcweBVu}kUU}myqz#j9Mm6ve(t}&@lxj&o-*3XF45l=bZuC>n^ z1^Gp={tt&wlm?!Nh+cprndi#mIm*aTF2YZmSB4ze>Z zkKMj<|Bpmo6DePvn{VtU!RwkB9Unc_j;U&Wv}3T96N~GwxO}A8?otvpJp59BS!yPo zEG9m}Amlem58t!n)vrIaXra;dr@7|Lwv<;gk4DO}Z;d4GOs{Apnku}epQ9ysj&0_r z^eR%xQJe2R$JF!bj9#;j8bJRlmu{Zp`j>MY47$&x8@5df_Hg@2w_E0|RGU{tW`*e$ zkMr!LtX-|C&BE2pvgRr04*nj(S{FH=81butB#50JwR}WxURguZ2npvr5|^Q-GnoDT zSN%Y7=b5TQ@@ef=g|f``)l@}p)w8dazevODA$1C>?R4$B1zskuR*b2~`6+gK3arkh z@LRj|>q$sb!{yU^#CfyDBbL43m5_^G17vL7n&_$cQz46?|M>$>oSg~%Yxs9{_UkC3 zTA4c44bvLvk>ht-2Bnvhb31SDIo+>?+PRGCo!+U-Xa;>*>X9hQIt52|**a zw3sK#doW1xP<2ox$ypWHXI*gzwH~|1%Mj}GnpYg<<}>K1$5Dm!QW}_;Y|hm)4Gx_K z-y??Yq2C(edpl*X9ACaom%TUoz5BM1PVHv-;UDXu-h-3lHP#k)5ZSc;L5c7^{Znl& z@I5}Bf8V$M7T+p=(HqhcDcn5rWWQLzyod_hUiSs&6_~nZ#j3eh?E8k&bxg}Z#;%`y z>`R!3c)g^@YPTl1Kc2)p!o2Q1-0%tJ#jneJ7RvF?dh)JBNMYJ;`0(=w2h? zy(cQwh{AjGwJOfJn?n7=2UJIM^AYHg3iTLdcaW^Rltf-xPh*yXUOz}DkEZeF?3v=v zA?Jq5Fii?#8+AdCC4(MrII5mcPQT5YstS7Dy0ZNO=#`(^CKF@?^-ZP)ZQ}YD@I-|? z+x6(Fwm_U86F&;Cx{>{DW9TtcDrk+8DfgDd`j;!Oa0p6CmNQOZF zbD|M>3tQ^EYnu`&D1KFY0T ziuFyECo~Uc=MC}A?&X|EXD(IEQ2?F>zs-2T&A;W*))(CTd(zL9u!sHCfVbf(dy+su z#C*Q$8qg1u?c$v`t7RZ7XW*g%`k~K%2Zw@wDAo_IkM%#>_``LMH}7kaut*gtDEQg2KL-ma`)eR{lSC;92O#t8hAwK1zN zJo`NGkBb64)2Nm6Z`*XS1U8l|5dlZPpJc*2057AUIKdkT4v_=^4A}- zWz5`tQMu;qo65j|ha+VfheSnHwTebM_3e8Lj;EPYQ(8FQo~rA&a(cz}@qKs2_xOI* zA=UKm{Q|Ww>$?cP-<%tBS3`bLF$ZT6jwk&0as4qDPnoX;KZrjatOof-aQ~ef8+Stg z%+8O$6H*|*{*V5tpnrnrpO}4`a(-syyE6y;jNtj>{KE5JHDBSnH1HOaU}z7#{Z;>R zcYYB;ei5u6oL^W!YTfxoFLmb^!TO)6aYK&FlcC37PvUsO`p5Z&^)JX9D$E-^A3;4L z_39Mr^39)^AWr!5%Prn zv){E_2H>CUm1_y%YLH*pKm9kVFdT28SNeSA_7&{^*A72DuLt{7@$xH6V}U2^|59h> zP6z*I53Y!upAY$k{a>(eQQ^LY^Gm=J5%SbSere(S66}jqxG&=T#r@;_ZD`>ShWuq3 z8W#ILg#5z!i~Gm>1D-$LA0B!7DZ&20$h&OsqYU|l_XokgNQL`iPx`_856&;V|6u*# z{SE6M?{7O^SGmLf#whXvws=8);r$KkAL|qIi}z2QUwHrQiC^qLcz?$Eh4*LdKY0Gw zKk@#L^9%3)*gvuVj}4Fd$@%~6@L5Tm|Kt0GgsEJE`-KfYwY)hB@(bTDySnceD!5+= zu0MBMYO0~VC9`zAwL9EjOb_>$7QVkkCjE1Nv4Z=HIcwWy^1;HD#FYk3 z92^C|e&n_P%dI7w*tUKe4SG#A9Ax!&C0K}gFH$qVpA+A{*beZEf&3Dj$`}F$L$D#i_O;3vaXJ^sYemm~^dKJ-&Z#{Xb1=VDB?NF(jk8Si^ zQcLQpu(iy`)@i!lUZYq#K*c8?{=2N~VZ-;Bo)qJ)o5;UZ)2D#!R*XIs*zt?rX?0(j z#Leg7F-dMdYs8O?)Ng{H`}uaD)$S9Oba6@V1ybv($dj920=_(Lp}L2fREGAkWo)D# z%v!Ck%%1Cg+2i!G1`^z7(Y<8~qP%Z|JHncrOUWsbzD?;d^>mH#f%JH&KQcc_ldB&( z^pvhq>QCBrbIKz1m336Uy*~U^M>+Xp?(_3lP9v>cS*&!VS)WPY9%U5uL6TLokK`|F zt|eo~+s9|9{~>FZMr=Jf;Wt?_?gy{Ix|K>?aWkS&zfrRH4zB(do5m@z9pyBCv?t5e z`_0=k48BK1eO`~{zSp&4b#U8$eKt?E&B7y~H`BathR7+XXL2-F0qT)MUH6(zUh2TfM}yp@|r-VKYTdQAny|6tf2ZeEv1tSEH*WWySkjlUS9J)HT| z>(ku^n8%_8A~v65>dEmVJUMP&wq+M`mMVzy9W%0?yn+4=x6Dl7-giLO&Mof?s_Cm$ z%ICTFd@^nDxzn?=NRE!NpAWougVv=-?cQryrGe{4HmQta@?=8KaqsDtKQ;AA$1ft5 zdTAv0-ucFB1K_>+Go+{cyoLH>Rw_T{>c5B&4mW;MLtnj+`^xF@Xg=9G%l|cLnjZ1^ zGU)ZqQHP)WL<=_AW4y=4F$&Cqz77_g9%t_?HU~YDj0)Z47ogYF>&1sauY8MjVf9@7 z$G5HHxcUD{N?N4fR6}JHCfjp7J^ZynJ21+K9sF^K=B*_wnaJW1muqghYnC?~g(kku ziCr^((bA|1=4`0-aQiDtYgyHq*G|*}Z-du=Oab2bSpT^H&-YC8p?_L&XsSQ-PaGd; z|DcH$%z=rOrpw1Du#ML%pBNdY!GB+66vgp``#-9dIXxNrm$|yD>3^Gl^RV;2zQEgo zd(TRNH)2NmjkeD0ZvNwY2I!1yncSM;OPGuGbvnJedE)&s%?*!2GfP zv3^olD%5biX(SrDyPT*bwQjR=K|f4^?6!}w+QZq)LvsBaolEJS0P`WBABy!8Wi!@= zh5juD4fFWl^uP4Z{A>f@&E3iG2eBJPi2=P?0Z&xOQ&0NG{Qh{= z6wdM1yW06O@J8MoTG1EyWeeAz)=l^z$q4Gve|bXu_T)d==bUV%fwx{SKN8@LWW}=c z!GG9@dHj=x>dK6B>&tNeWes%73^`NqA3pXUtRL*3=ezxr&gu3~a%-agNAOS9ykTL} zDX&qCfF~;C3H#@>YpU|^VgBukdG4Hk1Uyk8PcZ`CV!L@G%irl3%=vD?mguZB`t7B_ zTsbJM{&HwDU0*nGEyvRvGa}0I*3o}?@^sKE&KG>&bqaWs?dI*T`);jA+JFYt%C_U9 zIiB$Raem?XUwEBd3VuiLlUQrujbQ!gESNNG5%_Vh8u=uSC#)ZwUsylhwLd?DU(=*z z>peKX#{8Z;uuRMl@?@58-7StMtbd$eSpR~&p~Aeu{0iz3Ay1fJ&rPxyfM0f_y+hka z$S=&VATQ~^d5Q8@Fb^W+3HuMuFYG@H3+6=n0dMk0%~~P9c-TJ$?@5F_VgGE`vr7X1 zWUu$WGqoA=3;Sntd_oNPCtVSyk_7(A!}<~EkqCLh{(nh4I34_-m2R|i-T?W9{a>(e zQQ^LY^Gm=J5%SbSere(SQuGK2s{`H|#1F_8z`ls{7x$0z*R$``I>=w<(s(~hOUN&r zzqo(AKj8V}{o$I=5^jHB)`^yGgZ+WU`-5O#q{4j>>mTa}?>{)d@cx7KgZDSAf4sj% zhcEYs{f&`pSO4V$`Gxnlp7f9T#rr4DFT8(ZetYsCyg%do!uvD!AFO}upLqYr`Gxm? z?4LMau6N%rL~y?le7{__nSBZF7xvVUK!-PwU-*6z=#>ihMO^>a_vBSUQPzy7_+^#b zOExh*++SMw{<=~#_|~Hd_UzgSH*!VEk+GK>G|@ZJja;3c9A%d2NB@|9fB)`*Evw=K zKV7+VJ^N`&?lR|Tb>y{#rOdFWt#qQtvHE^L{5AUyT71+g=yz=T{UPJO8@G^Swr<|R zGemg~a$-*}X4^C879B0qm)ph;t-h$@2leA>&o5mL^)D>$mFq^{(nBeVT61&Kse|2> zLA0cn#0;2_InuP1%Ib|xG^<<5l+}F|IkZigeeKg8Z(7|1jhlsO zq-xI+lAoUizfV#l>^Rh)9Jk5Q9O|1>hv|BG+0>)GdRzR3LVEpb-ya_b)e?Wx)Vz5U zTj=x6Cs|W9J7)JO-ZuyT39O-YT)@>YP2}S4>R_V@B0Tj~vKn2X1!S{sd$!mS$gwTs zJKdpvRmvuDuD?G$JlaA&Xmyy`r1Fb`5)Kb}q3H|p$eZRX0`f~GG zH&xWvVs$C~xjQg@;jtQ;(KcDf?P~=&?AtMO%cFW)sj=;3UM~YC)qA(d&L&y*ym7OU zW=I{mUU+MJ(DF92zfacAJKEL6DZ@Xe-_R!d_Qu_Q2cdp(y3s8Qs4wpjylvmt3i`dX z@5RkfuVnp%56f4V5_UkqL+*Pr-m{+h1}PMSVs1VUZj7G9%||c~DxAk1-Wo%g7kQs{(`q=(YrNGVqljZ`Sm!H`W0(7m zWu%m%qrSsDOg5R<1kb1?a(jPm*M)i2ZJ83XBC(U6(K&MDDAZrF<3b@(oKD z^a(%zmO8v=#7G-a-MnlP<#yDGd+#b0vs-UR*s-Fj&n~AJPhj@cj&ACN_k6s2?<(;l zr6iUyYvkVh!#ZhAA`Q9vN8)DBWlL)5YU@o-qd@Wcv(0;(K+xGBbJ9hZomDkCW$^T`9=VB0iBW%gjNqX)d9%pjUog zYHw#>sQwm?<4lS<# z>cXySjsx~xm`9k0xGu3a@0c%n~yCSB)v^4qwg(hT}Pz46{m zu75^i%`h+M|K}{}XT&r*bSa^ z9r$Id57vFNYLaCxtKC}0tDjVv*R5oyPj$C;+@{P-`=U4j^hm81 z)4iM?vH#=z!uQ>@d(8)2fVah-jvBz*U-zAX|Ac1XiF$6%PPN3wRb49yv0dG2KA`yAu7kK`zGP_%WCoDc>Z}? zBF1yPX&!hI$oU=Ck5eZ5au@jV+}K)w$S;ERgYygPN8r~~=+{{PV-AnK3p|n7_=p1> zPgwsrzp(xVc|(PHgZYj4Ew2SUkxOmccXK>penS-|jR1bx>-!slOVtT^&gyH*nb3hPlb8^fA}X6_$R^sIegs581PT_b;pOwcaUG$ zKV!!9xf=?+MXvnX2>!{#`6bXJ5%@pB{*Utu`@dk{qQZR(=a+ydBIK!u{L=a>zqL2It>5KKRxcmw>O?`L?@(brL?jP?D0-pYzKi(f6hEBT+`va4>$7#_U$S=G< z2=+xP+!z0!`uTVN!TE*vAFQAMV}B!p{f*%Lt-fIUYuMkI2kJ@};vv8A{)YA66Tf)> z#QBByPt0#m{)6{toL_i<#{Scjf8zZg=NI1pv47(GMdH+?`}<%Ye0FDIJ-1Kc`{k4R zyl-&7uwA|WNbQ9D!uJdIf1F?4JlQhc``~(}hx*u zHnVOZ)VExb^H%C^3T?c#=DB>DitY&q#iEfZOIZsB>igD^^LA<|= zWoWHg{i^}zrja2z@u+i6d_RIp3+?wMso&E7BDB$F(W>RO< z>rhl-JGuHaL-f+00y6gX$jEdf_&Lf=-U=I_e(Yls%+2S}fE1}N)gt!j| zvdf5UY5(_c!mH?*2S>f_p?>(E!xOpwZ@r6pEgDfq4NDXrjBu@@)+xNgk(;WB&Cep; z*M7CsV&3$(!-g9%19whc{du_pyW8ry^$4kYqMtk4`^AeU(!5#W(vF&HqA$0#W50Yo z{jj^&60Uz%ENwkkKVxEt;iyej)MKlJ7gtYD+V_A+L>Wm|nsS)?p23h{(foKr_Vw!P z25(aaF)wejL$*OZ5^|_|pL{);^Q)n9Bz#Z%Co?AcMH5~5)GwOr-(%R=IBq@-y*Ftj zht$y74?T}=fO(u+ZCLq7wTSfHd)(g>=B1#w@3i8$b!>YtWrcg*lNpTxr=E|5d8G95 zwS602MfBb!uHxo(#43h?dC_y%#cH-d{WD8T_HgxcdpWRAr0S@*zuXz_Jumci8w~GF zD%MI=aPPfuR^H~+m-g)JxT@Xn=TB!eAEc^Wg!jA|v41qYC%JSiBl;M;cg*&MWlsy+ zsicn5Y)7bX7_)dUSHE^!Yl3A-9o-=klf~)rg;Mo=$-60JfKl^GPOtIx#cwA_TCti| zC1*V2#xjpYj4h%-k8@rh`T}|+gJXR@?FYSjS?{~KPQ8=b_0EiQg8J5l6_Q;2KN*#u z|ESi}yrh?Q9>9~S|Hh}0E0?i0azDZhqRp6%Ustj-*B{n=x$;`9VMIZ!7BAb!$6z_D zvS9e_vzqYV-7l3L&GGib`ix#mc<2AOe=6JEKN*)W%V?^k6{COuxU*Z_Sa!yqwe8S9 zJzcLorUQ6-5V=E@<87^|PG`sO;-L;dALymcu!=v$v{BIC;5NcL5T z|NaH{?~-UQ3;9KSTn;TCnDvq1{$HdVmV*A7lQ*XAhW=UHe_yc$UeAEHvCgqy+rTgI z`~^G_Ay0VzIKS}xlXh%O2EU`03PpLG-(mf{U)Vnt`>Ae({Gx=0PJIUZ3eGQq9*K}AL4N(~|I6GLOalLB zLv?4}^n(1t{(o@!2sL-t7MkF6J|6Om;QUfLx%YJ^?1RtMy%xegNP5UGEu3G1eUS?H z#s6pj|K@L>Ax$}uzs$=!LBabVzi|Ev_C=vz5WGL&`Q!b;*fz?Q%P&XwfE@{tUwD7O z^Y2MNc>lrqh4&w0fzKp%~;B!Ta01%b5dUe`Ee^_-3C7`SpM7Z&a|q zk)HU)`zOvXynkYTd-5N=KjZwu`!n{Rp8ON<|2V(!{*V0=-!Itz@%{40yOqHG!mbE8 zJN^XZ7rtMx|Kt4X<_UiN`k#H!j_Kk4(!%$b&W`~D{S4N#(RX9toYiz-!l%y~zUb+G z5>zR^?cUs@RCd%E<69PM+4tX-^f$S!Wxf2Y9+ZkS5S5YFPClI4K%*P9hu@MqubHl* zZ@7C>U2I{w^0E`dTFC)b>(+gyt)!RcjTb$JB