Asymptotic Stability of a Flying Wing in Cruise Trimmed Conditions

A Horten flying wing is analysed. The nonlinear trim condition is found and the system is linearised. The eigenvalues of the linearised system are then used to evaluate the stability at the cruise trimmed flight conditions.

[1]:
# required packages
import sharpy.utils.algebra as algebra
import sharpy.sharpy_main
from cases.hangar.richards_wing import Baseline
import numpy as np
import configobj
import matplotlib.pyplot as plt

Flight Conditions

Initial flight conditions. The values for angle of attack alpha, control surface deflection cs_deflection and thrust are only initial values. The values required for trim will be calculated by the StaticTrim routine

[2]:
u_inf = 28
alpha_deg = 4.5135
cs_deflection = 0.1814
thrust = 5.5129

Discretisation

[3]:
M = 4  # chordwise panels
N = 11  # spanwise panels
Msf = 5  # wake length in chord numbers

Create Horten Wing

[4]:
ws = Baseline(M=M,
              N=N,
              Mstarfactor=Msf,
              u_inf=u_inf,
              rho=1.02,
              alpha_deg=alpha_deg,
              roll_deg=0,
              cs_deflection_deg=cs_deflection,
              thrust=thrust,
              physical_time=20,
              case_name='horten',
              case_name_format=4,
              case_remarks='M%gN%gMsf%g' % (M, N, Msf))

ws.set_properties()
ws.initialise()
ws.clean_test_files()

ws.update_mass_stiffness(sigma=1., sigma_mass=2.5)
ws.update_fem_prop()
ws.generate_fem_file()
ws.update_aero_properties()
ws.generate_aero_file()
0
Section Mass: 11.88
Linear Mass: 11.88
Section Ixx: 1.8777
Section Iyy: 1.0137
Section Izz: 2.5496
Linear Ixx: 1.88
1
Section Mass: 10.99
Linear Mass: 10.99
Section Ixx: 1.4694
Section Iyy: 0.9345
Section Izz: 2.1501
Linear Ixx: 1.74
2
Section Mass: 10.10
Linear Mass: 10.10
Section Ixx: 1.1257
Section Iyy: 0.8561
Section Izz: 1.7993
Linear Ixx: 1.60
3
Section Mass: 9.21
Linear Mass: 9.21
Section Ixx: 0.8410
Section Iyy: 0.7783
Section Izz: 1.4933
Linear Ixx: 1.46
4
Section Mass: 8.32
Linear Mass: 8.32
Section Ixx: 0.6096
Section Iyy: 0.7011
Section Izz: 1.2280
Linear Ixx: 1.31
5
Section Mass: 7.43
Linear Mass: 7.43
Section Ixx: 0.4260
Section Iyy: 0.6246
Section Izz: 0.9996
Linear Ixx: 1.17
6
Section Mass: 6.54
Linear Mass: 6.54
Section Ixx: 0.2845
Section Iyy: 0.5485
Section Izz: 0.8040
Linear Ixx: 1.03
7
Section Mass: 5.64
Linear Mass: 5.64
Section Ixx: 0.1796
Section Iyy: 0.4728
Section Izz: 0.6374
Linear Ixx: 0.89
8
Section Mass: 4.75
Linear Mass: 4.75
Section Ixx: 0.1055
Section Iyy: 0.3975
Section Izz: 0.4959
Linear Ixx: 0.75
9
Section Mass: 3.86
Linear Mass: 3.86
Section Ixx: 0.0567
Section Iyy: 0.3226
Section Izz: 0.3753
Linear Ixx: 0.61
10
Section Mass: 2.97
Linear Mass: 2.97
Section Ixx: 0.0275
Section Iyy: 0.2479
Section Izz: 0.2719
Linear Ixx: 0.47

Simulation Information

The flow setting tells SHARPy which solvers to run and in which order. You may be stranged by the presence of the DynamicCoupled solver but it is necessary to give an initial speed to the structure. This will allow proper linearisation of the structural and rigid body equations.

[5]:
flow = ['BeamLoader',
        'AerogridLoader',
        'StaticTrim',
        'BeamPlot',
        'AerogridPlot',
        'AeroForcesCalculator',
        'DynamicCoupled',
        'Modal',
        'LinearAssembler',
        'AsymptoticStability',
        ]

SHARPy Settings

[6]:
settings = dict()
settings['SHARPy'] = {'case': ws.case_name,
                      'route': ws.case_route,
                      'flow': flow,
                      'write_screen': 'on',
                      'write_log': 'on',
                      'log_folder': './output/',
                      'log_file': ws.case_name + '.log'}


Loaders

[7]:
settings['BeamLoader'] = {'unsteady': 'off',
                          'orientation': algebra.euler2quat(np.array([ws.roll,
                                                                      ws.alpha,
                                                                      ws.beta]))}
settings['AerogridLoader'] = {'unsteady': 'off',
                              'aligned_grid': 'on',
                              'mstar': int(ws.M * ws.Mstarfactor),
                              'freestream_dir': ['1', '0', '0'],
                              'control_surface_deflection': [''],
                              'wake_shape_generator': 'StraightWake',
                              'wake_shape_generator_input': {'u_inf': ws.u_inf,
                                    'u_inf_direction': ['1', '0', '0'],
                                    'dt': ws.dt}}

StaticCoupled Solver

[8]:
settings['StaticCoupled'] = {'print_info': 'on',
                             'structural_solver': 'NonLinearStatic',
                             'structural_solver_settings': {'print_info': 'off',
                                                            'max_iterations': 200,
                                                            'num_load_steps': 1,
                                                            'delta_curved': 1e-5,
                                                            'min_delta': ws.tolerance,
                                                            'gravity_on': 'on',
                                                            'gravity': 9.81},
                             'aero_solver': 'StaticUvlm',
                             'aero_solver_settings': {'print_info': 'on',
                                                      'horseshoe': ws.horseshoe,
                                                      'num_cores': 4,
                                                      'n_rollup': int(0),
                                                      'rollup_dt': ws.dt,
                                                      'rollup_aic_refresh': 1,
                                                      'rollup_tolerance': 1e-4,
                                                      'velocity_field_generator': 'SteadyVelocityField',
                                                      'velocity_field_input': {'u_inf': ws.u_inf,
                                                                               'u_inf_direction': [1., 0, 0]},
                                                      'rho': ws.rho},
                             'max_iter': 200,
                             'n_load_steps': 1,
                             'tolerance': ws.tolerance,
                             'relaxation_factor': 0.2}

Trim solver

[9]:
settings['StaticTrim'] = {'solver': 'StaticCoupled',
                          'solver_settings': settings['StaticCoupled'],
                          'thrust_nodes': ws.thrust_nodes,
                          'initial_alpha': ws.alpha,
                          'initial_deflection': ws.cs_deflection,
                          'initial_thrust': ws.thrust,
                          'max_iter': 200,
                          'fz_tolerance': 1e-2,
                          'fx_tolerance': 1e-2,
                          'm_tolerance': 1e-2}

Nonlinear Equilibrium Post-process

[10]:
settings['AerogridPlot'] = {
                            'include_rbm': 'off',
                            'include_applied_forces': 'on',
                            'minus_m_star': 0,
                            'u_inf': ws.u_inf
                            }
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,
                                    }

settings['BeamPlot'] = {
                        'include_rbm': 'on',
                        'include_applied_forces': 'on',
                        'include_FoR': 'on'}

DynamicCoupled Solver

As mentioned before, a single time step of DynamicCoupled is required to give the structure the velocity required for the linearisation of the rigid body equations to be correct. Hence n_time_steps = 1

[11]:
struct_solver_settings = {'print_info': 'off',
                          'initial_velocity_direction': [-1., 0., 0.],
                          'max_iterations': 950,
                          'delta_curved': 1e-6,
                          'min_delta': ws.tolerance,
                          'newmark_damp': 5e-3,
                          'gravity_on': True,
                          'gravity': 9.81,
                          'num_steps': ws.n_tstep,
                          'dt': ws.dt,
                          'initial_velocity': ws.u_inf * 1}

step_uvlm_settings = {'print_info': 'on',
                      'num_cores': 4,
                      'convection_scheme': ws.wake_type,
                      'velocity_field_generator': 'SteadyVelocityField',
                      'velocity_field_input': {'u_inf': ws.u_inf * 0,
                                               'u_inf_direction': [1., 0., 0.]},
                      'rho': ws.rho,
                      'n_time_steps': ws.n_tstep,
                      'dt': ws.dt,
                      'gamma_dot_filtering': 3}

settings['DynamicCoupled'] = {'print_info': 'on',
                              'structural_solver': 'NonLinearDynamicCoupledStep',
                              'structural_solver_settings': struct_solver_settings,
                              'aero_solver': 'StepUvlm',
                              'aero_solver_settings': step_uvlm_settings,
                              'fsi_substeps': 200,
                              'fsi_tolerance': ws.fsi_tolerance,
                              'relaxation_factor': ws.relaxation_factor,
                              'minimum_steps': 1,
                              'relaxation_steps': 150,
                              'final_relaxation_factor': 0.5,
                              'n_time_steps': 1,
                              'dt': ws.dt,
                              'include_unsteady_force_contribution': 'off',
                                                          }

Linear Assembler Settings

Note that for the assembly of the linear system, we replace the parametrisation of the orientation with Euler angles instead of quaternions.

[13]:
settings['LinearAssembler'] = {'linear_system': 'LinearAeroelastic',
                               'linear_system_settings': {
                                   'beam_settings': {'modal_projection': 'off',
                                                     'inout_coords': 'modes',
                                                     'discrete_time': True,
                                                     'newmark_damp': 0.5e-2,
                                                     'discr_method': 'newmark',
                                                     'dt': ws.dt,
                                                     'proj_modes': 'undamped',
                                                     'num_modes': 9,
                                                     'print_info': 'on',
                                                     'gravity': 'on',
                                                     'remove_dofs': []},
                                   'aero_settings': {'dt': ws.dt,
                                                     'integr_order': 2,
                                                     'density': ws.rho,
                                                     'remove_predictor': 'off',
                                                     'use_sparse': 'off',
                                                     'remove_inputs': ['u_gust']},
                                   'track_body': 'on',
                                   'use_euler': 'on',
                                }}

Asymptotic Stability Post-processor

[14]:
settings['AsymptoticStability'] = {
                                    'print_info': 'on',
                                    'frequency_cutoff': 0,
                                    'export_eigenvalues': 'on',
                                    'num_evals': 100,
                                    }

Write solver file

[15]:
config = configobj.ConfigObj()
np.set_printoptions(precision=16)
file_name = ws.case_route + '/' + ws.case_name + '.sharpy'
config.filename = file_name
for k, v in settings.items():
    config[k] = v
config.write()

Run Simulation

[16]:
data = sharpy.sharpy_main.main(['', ws.case_route + '/' + ws.case_name + '.sharpy'])
--------------------------------------------------------------------------------
            ######  ##     ##    ###    ########  ########  ##    ##
           ##    ## ##     ##   ## ##   ##     ## ##     ##  ##  ##
           ##       ##     ##  ##   ##  ##     ## ##     ##   ####
            ######  ######### ##     ## ########  ########     ##
                 ## ##     ## ######### ##   ##   ##           ##
           ##    ## ##     ## ##     ## ##    ##  ##           ##
            ######  ##     ## ##     ## ##     ## ##           ##
--------------------------------------------------------------------------------
Aeroelastics Lab, Aeronautics Department.
    Copyright (c), Imperial College London.
    All rights reserved.
    License available at https://github.com/imperialcollegelondon/sharpy
Running SHARPy from /home/ng213/2TB/pazy_code/pazy-sharpy/lib/sharpy/docs/source/content/example_notebooks
SHARPy being run is in /home/ng213/2TB/pazy_code/pazy-sharpy/lib/sharpy
The branch being run is dev_setting_error
The version and commit hash are: v1.2.1-344-g0239644-0239644
SHARPy output folder set
     ./output//horten_u_inf2800_M4N11Msf5/
Generating an instance of BeamLoader
Variable for_pos has no assigned value in the settings file.
    will default to the value: [0.0, 0, 0]
Generating an instance of AerogridLoader
Variable control_surface_deflection_generator_settings has no assigned value in the settings file.
    will default to the value: {}
Variable dx1 has no assigned value in the settings file.
    will default to the value: -1.0
Variable ndx1 has no assigned value in the settings file.
    will default to the value: 1
Variable r has no assigned value in the settings file.
    will default to the value: 1.0
Variable dxmax has no assigned value in the settings file.
    will default to the value: -1.0
The aerodynamic grid contains 4 surfaces
  Surface 0, M=4, N=2
     Wake 0, M=20, N=2
  Surface 1, M=4, N=22
     Wake 1, M=20, N=22
  Surface 2, M=4, N=2
     Wake 2, M=20, N=2
  Surface 3, M=4, N=22
     Wake 3, M=20, N=22
  In total: 192 bound panels
  In total: 960 wake panels
  Total number of panels = 1152
Generating an instance of StaticTrim
Variable print_info has no assigned value in the settings file.
    will default to the value: True
Variable tail_cs_index has no assigned value in the settings file.
    will default to the value: 0
Variable initial_angle_eps has no assigned value in the settings file.
    will default to the value: 0.05
Variable initial_thrust_eps has no assigned value in the settings file.
    will default to the value: 2.0
Variable relaxation_factor has no assigned value in the settings file.
    will default to the value: 0.2
Variable save_info has no assigned value in the settings file.
    will default to the value: False
Generating an instance of StaticCoupled
Variable correct_forces_method has no assigned value in the settings file.
    will default to the value: 
Variable runtime_generators has no assigned value in the settings file.
    will default to the value: {}
Generating an instance of NonLinearStatic
Variable newmark_damp has no assigned value in the settings file.
    will default to the value: 0.0001
Variable gravity_dir has no assigned value in the settings file.
    will default to the value: [0.0, 0.0, 1.0]
Variable relaxation_factor has no assigned value in the settings file.
    will default to the value: 0.3
Variable dt has no assigned value in the settings file.
    will default to the value: 0.01
Variable num_steps has no assigned value in the settings file.
    will default to the value: 500
Variable initial_position has no assigned value in the settings file.
    will default to the value: [0. 0. 0.]
Generating an instance of StaticUvlm
Variable iterative_solver has no assigned value in the settings file.
    will default to the value: False
Variable iterative_tol has no assigned value in the settings file.
    will default to the value: 0.0001
Variable iterative_precond has no assigned value in the settings file.
    will default to the value: False
Variable cfl1 has no assigned value in the settings file.
    will default to the value: True
Variable vortex_radius has no assigned value in the settings file.
    will default to the value: 1e-06
Variable vortex_radius_wake_ind has no assigned value in the settings file.
    will default to the value: 1e-06
Variable rbm_vel_g has no assigned value in the settings file.
    will default to the value: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
Variable centre_rot_g has no assigned value in the settings file.
    will default to the value: [0.0, 0.0, 0.0]



|=====|=====|============|==========|==========|==========|==========|==========|==========|
|iter |step | log10(res) |    Fx    |    Fy    |    Fz    |    Mx    |    My    |    Mz    |
|=====|=====|============|==========|==========|==========|==========|==========|==========|



|==========|==========|==========|==========|==========|==========|==========|==========|==========|==========|
|   iter   |alpha[deg]|elev[deg] |  thrust  |    Fx    |    Fy    |    Fz    |    Mx    |    My    |    Mz    |
|==========|==========|==========|==========|==========|==========|==========|==========|==========|==========|
|  0  |  0  |  0.00000   | -0.1051  | -0.0000  |  0.0598  | -0.0000  |  1.0837  | -0.0000  |
|  1  |  0  |  -7.62384  | -0.1284  | -0.0000  |  0.1276  | -0.0000  |  0.0045  | -0.0000  |
|  2  |  0  |  -8.33392  | -0.1190  | -0.0000  |  0.0397  | -0.0000  | -0.0774  | -0.0000  |
|  3  |  0  |  -9.30379  | -0.1133  |  0.0000  |  0.0011  | -0.0000  | -0.0070  |  0.0000  |
|  4  |  0  | -10.71602  | -0.1136  | -0.0000  |  0.0032  |  0.0000  | -0.0100  | -0.0000  |
|  5  |  0  | -10.88827  | -0.1138  | -0.0000  |  0.0043  |  0.0000  | -0.0119  | -0.0000  |
|  6  |  0  | -11.66331  | -0.1138  | -0.0000  |  0.0042  |  0.0000  | -0.0116  | -0.0000  |
|  7  |  0  | -12.88496  | -0.1138  | -0.0000  |  0.0041  |  0.0000  | -0.0116  |  0.0000  |
|    0     |  4.5135  |  0.1814  |  5.5129  | -0.1138  | -0.0000  |  0.0041  |  0.0000  | -0.0116  |  0.0000  |
|  0  |  0  |  0.00000   |-116.9870 | -0.0000  | 994.8063 | -0.0000  |-882.4104 | -0.0000  |
|  1  |  0  |  -5.79178  | -72.3841 |  0.0000  | 944.6140 |  0.0000  |-802.5912 |  0.0000  |
|  2  |  0  |  -6.63730  | -62.4378 |  0.0000  | 937.6662 |  0.0000  |-792.1259 | -0.0000  |
|  3  |  0  |  -7.22937  | -62.8923 | -0.0000  | 939.7866 | -0.0000  |-795.7093 | -0.0000  |
|  4  |  0  |  -8.65323  | -62.8757 | -0.0000  | 939.7100 | -0.0000  |-795.5764 | -0.0000  |
|  5  |  0  |  -8.81438  | -62.8640 | -0.0000  | 939.6554 | -0.0000  |-795.4837 | -0.0000  |
|  6  |  0  |  -9.59386  | -62.8660 |  0.0000  | 939.6644 | -0.0000  |-795.4991 |  0.0000  |
|  7  |  0  | -10.80422  | -62.8661 |  0.0000  | 939.6650 | -0.0000  |-795.5000 |  0.0000  |
|  8  |  0  | -11.01365  | -62.8660 | -0.0000  | 939.6647 | -0.0000  |-795.4994 | -0.0000  |
|  9  |  0  | -12.15197  | -62.8660 |  0.0000  | 939.6647 | -0.0000  |-795.4995 |  0.0000  |
|    0     |  7.3783  | -2.6834  |  5.5129  | -62.8660 |  0.0000  | 939.6647 | -0.0000  |-795.4995 |  0.0000  |
|  0  |  0  |  0.00000   | -32.9132 | -0.0000  | 371.4715 | -0.0000  |-902.7953 | -0.0000  |
|  1  |  0  |  -5.48409  | -8.7241  | -0.0000  | 298.8484 |  0.0000  |-777.2938 |  0.0000  |
|  2  |  0  |  -6.39387  | -4.0957  | -0.0000  | 289.8092 | -0.0000  |-761.4855 | -0.0000  |
|  3  |  0  |  -6.85613  | -4.6263  | -0.0000  | 293.2407 | -0.0000  |-767.3376 |  0.0000  |
|  4  |  0  |  -8.25962  | -4.6052  | -0.0000  | 293.1048 | -0.0000  |-767.1066 |  0.0000  |
|  5  |  0  |  -8.44065  | -4.5914  | -0.0000  | 293.0156 |  0.0000  |-766.9545 |  0.0000  |
|  6  |  0  |  -9.20968  | -4.5937  | -0.0000  | 293.0308 | -0.0000  |-766.9804 | -0.0000  |
|  7  |  0  | -10.44736  | -4.5939  | -0.0000  | 293.0316 | -0.0000  |-766.9819 | -0.0000  |
|  8  |  0  | -10.63000  | -4.5938  | -0.0000  | 293.0311 |  0.0000  |-766.9809 | -0.0000  |
|  9  |  0  | -11.74670  | -4.5938  |  0.0000  | 293.0311 |  0.0000  |-766.9810 |  0.0000  |
| 10  |  0  | -12.29943  | -4.5938  | -0.0000  | 293.0311 |  0.0000  |-766.9810 |  0.0000  |
|    0     |  4.5135  |  3.0462  |  5.5129  | -4.5938  | -0.0000  | 293.0311 |  0.0000  |-766.9810 |  0.0000  |
|  0  |  0  |  0.00000   | -4.1051  | -0.0000  |  0.0598  | -0.0000  |  1.0834  | -0.0000  |
|  1  |  0  |  -7.62384  | -4.1284  | -0.0000  |  0.1276  | -0.0000  |  0.0042  | -0.0000  |
|  2  |  0  |  -8.33392  | -4.1190  | -0.0000  |  0.0397  |  0.0000  | -0.0778  | -0.0000  |
|  3  |  0  |  -9.30379  | -4.1133  | -0.0000  |  0.0011  |  0.0000  | -0.0074  | -0.0000  |
|  4  |  0  | -10.71602  | -4.1136  |  0.0000  |  0.0032  | -0.0000  | -0.0104  |  0.0000  |
|  5  |  0  | -10.88827  | -4.1138  |  0.0000  |  0.0043  |  0.0000  | -0.0123  |  0.0000  |
|  6  |  0  | -11.66331  | -4.1138  | -0.0000  |  0.0042  |  0.0000  | -0.0119  | -0.0000  |
|  7  |  0  | -12.88496  | -4.1138  | -0.0000  |  0.0041  |  0.0000  | -0.0119  | -0.0000  |
|    0     |  4.5135  |  0.1814  |  7.5129  | -4.1138  | -0.0000  |  0.0041  |  0.0000  | -0.0119  | -0.0000  |
|  0  |  0  |  0.00000   |  0.0095  | -0.0000  |  0.0498  |  0.0000  |  1.1013  | -0.0000  |
|  1  |  0  |  -7.62357  | -0.0140  |  0.0000  |  0.1189  |  0.0000  |  0.0198  |  0.0000  |
|  2  |  0  |  -8.33375  | -0.0046  | -0.0000  |  0.0312  | -0.0000  | -0.0624  |  0.0000  |
|  3  |  0  |  -9.30318  |  0.0010  | -0.0000  | -0.0075  |  0.0000  |  0.0081  | -0.0000  |
|  4  |  0  | -10.71542  |  0.0007  | -0.0000  | -0.0054  |  0.0000  |  0.0051  |  0.0000  |
|  5  |  0  | -10.88766  |  0.0006  | -0.0000  | -0.0043  |  0.0000  |  0.0032  | -0.0000  |
|  6  |  0  | -11.66271  |  0.0006  |  0.0000  | -0.0044  | -0.0000  |  0.0035  |  0.0000  |
|  7  |  0  | -12.88441  |  0.0006  | -0.0000  | -0.0045  |  0.0000  |  0.0035  | -0.0000  |
|    1     |  4.5135  |  0.1814  |  5.4560  |  0.0006  | -0.0000  | -0.0045  |  0.0000  |  0.0035  | -0.0000  |
Generating an instance of BeamPlot
Variable include_applied_moments has no assigned value in the settings file.
    will default to the value: True
Variable name_prefix has no assigned value in the settings file.
    will default to the value: 
Variable output_rbm has no assigned value in the settings file.
    will default to the value: True
...Finished
Generating an instance of AerogridPlot
Variable include_forward_motion has no assigned value in the settings file.
    will default to the value: False
Variable include_unsteady_applied_forces has no assigned value in the settings file.
    will default to the value: False
Variable name_prefix has no assigned value in the settings file.
    will default to the value: 
Variable dt has no assigned value in the settings file.
    will default to the value: 0.0
Variable include_velocities has no assigned value in the settings file.
    will default to the value: False
Variable include_incidence_angle has no assigned value in the settings file.
    will default to the value: False
Variable num_cores has no assigned value in the settings file.
    will default to the value: 1
Variable vortex_radius has no assigned value in the settings file.
    will default to the value: 1e-06
...Finished
Generating an instance of AeroForcesCalculator
--------------------------------------------------------------------------------
tstep |   fx_g     |   fy_g     |   fz_g     |   Cfx_g    |   Cfy_g    |   Cfz_g   
    0 |  1.088e+01 | -4.476e-13 |  1.835e+03 |  2.124e-03 | -8.740e-17 |  3.583e-01
...Finished
Generating an instance of DynamicCoupled
Variable structural_substeps has no assigned value in the settings file.
    will default to the value: 0
Variable dynamic_relaxation has no assigned value in the settings file.
    will default to the value: False
Variable postprocessors has no assigned value in the settings file.
    will default to the value: []
Variable postprocessors_settings has no assigned value in the settings file.
    will default to the value: {}
Variable controller_id has no assigned value in the settings file.
    will default to the value: {}
Variable controller_settings has no assigned value in the settings file.
    will default to the value: {}
Variable cleanup_previous_solution has no assigned value in the settings file.
    will default to the value: False
Variable steps_without_unsteady_force has no assigned value in the settings file.
    will default to the value: 0
Variable pseudosteps_ramp_unsteady_force has no assigned value in the settings file.
    will default to the value: 0
Variable correct_forces_method has no assigned value in the settings file.
    will default to the value: 
Variable network_settings has no assigned value in the settings file.
    will default to the value: {}
Variable runtime_generators has no assigned value in the settings file.
    will default to the value: {}
Generating an instance of NonLinearDynamicCoupledStep
Variable num_load_steps has no assigned value in the settings file.
    will default to the value: 1
Variable gravity_dir has no assigned value in the settings file.
    will default to the value: [0.0, 0.0, 1.0]
Variable relaxation_factor has no assigned value in the settings file.
    will default to the value: 0.3
Variable balancing has no assigned value in the settings file.
    will default to the value: False
Generating an instance of StepUvlm
Variable iterative_solver has no assigned value in the settings file.
    will default to the value: False
Variable iterative_tol has no assigned value in the settings file.
    will default to the value: 0.0001
Variable iterative_precond has no assigned value in the settings file.
    will default to the value: False
Variable cfl1 has no assigned value in the settings file.
    will default to the value: True
Variable vortex_radius has no assigned value in the settings file.
    will default to the value: 1e-06
Variable vortex_radius_wake_ind has no assigned value in the settings file.
    will default to the value: 1e-06
Variable interp_coords has no assigned value in the settings file.
    will default to the value: 0
Variable filter_method has no assigned value in the settings file.
    will default to the value: 0
Variable interp_method has no assigned value in the settings file.
    will default to the value: 0
Variable yaw_slerp has no assigned value in the settings file.
    will default to the value: 0.0
Variable centre_rot has no assigned value in the settings file.
    will default to the value: [0.0, 0.0, 0.0]
Variable quasi_steady has no assigned value in the settings file.
    will default to the value: False



|=======|========|======|==============|==============|==============|==============|==============|
|  ts   |   t    | iter | struc ratio  |  iter time   | residual vel |  FoR_vel(x)  |  FoR_vel(z)  |
|=======|========|======|==============|==============|==============|==============|==============|
/home/ng213/2TB/pazy_code/pazy-sharpy/lib/sharpy/sharpy/aero/utils/uvlmlib.py:264: RuntimeWarning: invalid value encountered in true_divide
  flightconditions.uinf_direction = np.ctypeslib.as_ctypes(ts_info.u_ext[0][:, 0, 0]/flightconditions.uinf)
|   1   | 0.0089 |  3   |   0.877319   |   0.593232   |  -10.598250  |-2.791317e+01 |-2.203426e+00 |
...Finished
Generating an instance of Modal
Variable keep_linear_matrices has no assigned value in the settings file.
    will default to the value: True
Variable write_dat has no assigned value in the settings file.
    will default to the value: True
Variable delta_curved has no assigned value in the settings file.
    will default to the value: 0.01
Variable max_rotation_deg has no assigned value in the settings file.
    will default to the value: 15.0
Variable max_displacement has no assigned value in the settings file.
    will default to the value: 0.15
Variable use_custom_timestep has no assigned value in the settings file.
    will default to the value: -1
Structural eigenvalues



|==============|==============|==============|==============|==============|==============|==============|
|     mode     |  eval_real   |  eval_imag   | freq_n (Hz)  | freq_d (Hz)  |   damping    |  period (s)  |
|==============|==============|==============|==============|==============|==============|==============|
/home/ng213/2TB/pazy_code/pazy-sharpy/lib/sharpy/sharpy/solvers/modal.py:265: UserWarning: Projecting a system with damping on undamped modal shapes
  warnings.warn('Projecting a system with damping on undamped modal shapes')
|      0       |  -0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      1       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      2       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      3       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      4       |  -0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      5       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      6       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      7       |  -0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      8       |  -0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      9       |  -0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      10      |   0.000000   |  28.293939   |   4.503120   |   4.503120   |  -0.000000   |   0.222068   |
|      11      |   0.000000   |  29.271318   |   4.658675   |   4.658675   |  -0.000000   |   0.214653   |
|      12      |   0.000000   |  54.780234   |   8.718545   |   8.718545   |  -0.000000   |   0.114698   |
|      13      |   0.000000   |  58.999779   |   9.390106   |   9.390106   |  -0.000000   |   0.106495   |
|      14      |   0.000000   |  70.520741   |  11.223724   |  11.223724   |  -0.000000   |   0.089097   |
|      15      |   0.000000   |  76.917111   |  12.241738   |  12.241738   |  -0.000000   |   0.081688   |
|      16      |   0.000000   |  87.324076   |  13.898058   |  13.898058   |  -0.000000   |   0.071952   |
|      17      |   0.000000   |  108.035577  |  17.194396   |  17.194396   |  -0.000000   |   0.058158   |
|      18      |   0.000000   |  119.692139  |  19.049596   |  19.049596   |  -0.000000   |   0.052495   |
|      19      |   0.000000   |  133.495187  |  21.246419   |  21.246419   |  -0.000000   |   0.047067   |
|      20      |   0.000000   |  134.444788  |  21.397553   |  21.397553   |  -0.000000   |   0.046734   |
|      21      |   0.000000   |  151.060442  |  24.042016   |  24.042016   |  -0.000000   |   0.041594   |
|      22      |   0.000000   |  159.369020  |  25.364367   |  25.364367   |  -0.000000   |   0.039425   |
|      23      |   0.000000   |  171.256102  |  27.256255   |  27.256255   |  -0.000000   |   0.036689   |
|      24      |   0.000000   |  173.895881  |  27.676389   |  27.676389   |  -0.000000   |   0.036132   |
|      25      |   0.000000   |  199.016557  |  31.674469   |  31.674469   |  -0.000000   |   0.031571   |
|      26      |   0.000000   |  205.412581  |  32.692428   |  32.692428   |  -0.000000   |   0.030588   |
|      27      |   0.000000   |  205.419531  |  32.693534   |  32.693534   |  -0.000000   |   0.030587   |
|      28      |   0.000000   |  223.563796  |  35.581283   |  35.581283   |  -0.000000   |   0.028105   |
|      29      |   0.000000   |  227.924750  |  36.275351   |  36.275351   |  -0.000000   |   0.027567   |
Generating an instance of LinearAssembler
Variable linearisation_tstep has no assigned value in the settings file.
    will default to the value: -1
Variable modal_tstep has no assigned value in the settings file.
    will default to the value: -1
Variable inout_coordinates has no assigned value in the settings file.
    will default to the value: 
Variable retain_inputs has no assigned value in the settings file.
    will default to the value: []
Variable retain_outputs has no assigned value in the settings file.
    will default to the value: []
Generating an instance of LinearAeroelastic
Variable uvlm_filename has no assigned value in the settings file.
    will default to the value: 
Generating an instance of LinearUVLM
Variable ScalingDict has no assigned value in the settings file.
    will default to the value: {}
Variable gust_assembler has no assigned value in the settings file.
    will default to the value: 
Variable rom_method has no assigned value in the settings file.
    will default to the value: []
Variable rom_method_settings has no assigned value in the settings file.
    will default to the value: {}
Variable vortex_radius has no assigned value in the settings file.
    will default to the value: 1e-06
Variable cfl1 has no assigned value in the settings file.
    will default to the value: True
Variable length has no assigned value in the settings file.
    will default to the value: 1.0
Variable speed has no assigned value in the settings file.
    will default to the value: 1.0
Variable density has no assigned value in the settings file.
    will default to the value: 1.0
Variable velocity_field_generator has no assigned value in the settings file.
    will default to the value: SteadyVelocityField
Variable velocity_field_input has no assigned value in the settings file.
    will default to the value: {}
Variable physical_model has no assigned value in the settings file.
    will default to the value: True
Variable track_body has no assigned value in the settings file.
    will default to the value: False
Variable track_body_number has no assigned value in the settings file.
    will default to the value: -1
Initialising Static linear UVLM solver class...
                        ...done in 0.39 sec
State-space realisation of UVLM equations started...
Computing wake propagation matrix with CFL1=True
     state-space model produced in form:
     x_{n+1} = A x_{n} + Bp u_{n+1}
                        ...done in 2.43 sec
Generating an instance of LinearBeam
Variable remove_sym_modes has no assigned value in the settings file.
    will default to the value: False
Warning, projecting system with damping onto undamped modes

Linearising gravity terms...
     M = 187.12 kg
     X_CG A -> 1.19 0.00 0.01
Node  1      -> B 0.000 -0.089 -0.000
                     -> A 0.089 0.206 0.000
                     -> G 0.089 0.206 -0.007
     Node mass:
             Matrix: 2.6141
Node  2      -> B -0.010 -0.019 -0.000
                     -> A 0.019 0.403 0.000
                     -> G 0.019 0.403 -0.001
     Node mass:
             Matrix: 7.3672
Node  3      -> B -0.019 -0.087 -0.000
                     -> A 0.234 0.800 0.000
                     -> G 0.234 0.800 -0.018
     Node mass:
             Matrix: 5.8780
Node  4      -> B -0.019 -0.084 -0.000
                     -> A 0.390 1.238 0.001
                     -> G 0.389 1.238 -0.030
     Node mass:
             Matrix: 2.8288
Node  5      -> B -0.018 -0.081 -0.000
                     -> A 0.546 1.676 0.001
                     -> G 0.544 1.676 -0.041
     Node mass:
             Matrix: 5.4372
Node  6      -> B -0.017 -0.078 -0.000
                     -> A 0.702 2.113 0.002
                     -> G 0.700 2.113 -0.053
     Node mass:
             Matrix: 2.6084
Node  7      -> B -0.016 -0.074 -0.000
                     -> A 0.857 2.551 0.003
                     -> G 0.855 2.551 -0.064
     Node mass:
             Matrix: 4.9963
Node  8      -> B -0.016 -0.071 -0.000
                     -> A 1.013 2.988 0.004
                     -> G 1.010 2.988 -0.076
     Node mass:
             Matrix: 2.3879
Node  9      -> B -0.015 -0.068 -0.000
                     -> A 1.169 3.426 0.005
                     -> G 1.166 3.426 -0.087
     Node mass:
             Matrix: 4.5555
Node 10      -> B -0.014 -0.065 -0.000
                     -> A 1.325 3.863 0.006
                     -> G 1.321 3.863 -0.098
     Node mass:
             Matrix: 2.1675
Node 11      -> B -0.013 -0.061 -0.000
                     -> A 1.480 4.301 0.007
                     -> G 1.476 4.301 -0.109
     Node mass:
             Matrix: 4.1146
Node 12      -> B -0.013 -0.058 -0.000
                     -> A 1.636 4.739 0.009
                     -> G 1.632 4.739 -0.120
     Node mass:
             Matrix: 1.9471
Node 13      -> B -0.012 -0.055 -0.000
                     -> A 1.792 5.176 0.010
                     -> G 1.787 5.176 -0.131
     Node mass:
             Matrix: 3.6738
Node 14      -> B -0.011 -0.052 -0.000
                     -> A 1.948 5.614 0.011
                     -> G 1.943 5.614 -0.142
     Node mass:
             Matrix: 1.7267
Node 15      -> B -0.011 -0.048 -0.000
                     -> A 2.104 6.052 0.012
                     -> G 2.098 6.052 -0.153
     Node mass:
             Matrix: 3.2329
Node 16      -> B -0.010 -0.045 -0.000
                     -> A 2.260 6.489 0.014
                     -> G 2.254 6.489 -0.164
     Node mass:
             Matrix: 1.5062
Node 17      -> B -0.009 -0.042 -0.000
                     -> A 2.415 6.927 0.015
                     -> G 2.409 6.927 -0.175
     Node mass:
             Matrix: 2.7921
Node 18      -> B -0.008 -0.039 -0.000
                     -> A 2.571 7.364 0.016
                     -> G 2.564 7.364 -0.186
     Node mass:
             Matrix: 1.2858
Node 19      -> B -0.008 -0.035 -0.000
                     -> A 2.727 7.802 0.017
                     -> G 2.720 7.802 -0.197
     Node mass:
             Matrix: 2.3512
Node 20      -> B -0.007 -0.032 -0.000
                     -> A 2.883 8.239 0.019
                     -> G 2.875 8.239 -0.208
     Node mass:
             Matrix: 1.0654
Node 21      -> B -0.006 -0.028 -0.000
                     -> A 3.038 8.677 0.020
                     -> G 3.030 8.677 -0.219
     Node mass:
             Matrix: 1.9104
Node 22      -> B -0.006 -0.026 -0.000
                     -> A 3.194 9.114 0.021
                     -> G 3.186 9.114 -0.230
     Node mass:
             Matrix: 0.8450
Node 23      -> B -0.005 -0.022 -0.000
                     -> A 3.350 9.552 0.023
                     -> G 3.341 9.552 -0.241
     Node mass:
             Matrix: 1.4695
Node 24      -> B -0.005 -0.022 -0.000
                     -> A 3.508 9.988 0.024
                     -> G 3.499 9.988 -0.252
     Node mass:
             Matrix: 0.3674
Node 25      -> B 0.000 0.089 -0.000
                     -> A 0.089 -0.206 0.000
                     -> G 0.089 -0.206 -0.007
     Node mass:
             Matrix: 2.6141
Node 26      -> B -0.010 0.019 -0.000
                     -> A 0.019 -0.403 0.000
                     -> G 0.019 -0.403 -0.001
     Node mass:
             Matrix: 7.3672
Node 27      -> B -0.019 0.087 -0.000
                     -> A 0.234 -0.800 0.000
                     -> G 0.234 -0.800 -0.018
     Node mass:
             Matrix: 5.8780
Node 28      -> B -0.019 0.084 -0.000
                     -> A 0.390 -1.238 0.001
                     -> G 0.389 -1.238 -0.030
     Node mass:
             Matrix: 2.8288
Node 29      -> B -0.018 0.081 -0.000
                     -> A 0.546 -1.676 0.001
                     -> G 0.544 -1.676 -0.041
     Node mass:
             Matrix: 5.4372
Node 30      -> B -0.017 0.078 -0.000
                     -> A 0.702 -2.113 0.002
                     -> G 0.700 -2.113 -0.053
     Node mass:
             Matrix: 2.6084
Node 31      -> B -0.016 0.074 -0.000
                     -> A 0.857 -2.551 0.003
                     -> G 0.855 -2.551 -0.064
     Node mass:
             Matrix: 4.9963
Node 32      -> B -0.016 0.071 -0.000
                     -> A 1.013 -2.988 0.004
                     -> G 1.010 -2.988 -0.076
     Node mass:
             Matrix: 2.3879
Node 33      -> B -0.015 0.068 -0.000
                     -> A 1.169 -3.426 0.005
                     -> G 1.166 -3.426 -0.087
     Node mass:
             Matrix: 4.5555
Node 34      -> B -0.014 0.065 -0.000
                     -> A 1.325 -3.863 0.006
                     -> G 1.321 -3.863 -0.098
     Node mass:
             Matrix: 2.1675
Node 35      -> B -0.013 0.061 -0.000
                     -> A 1.480 -4.301 0.007
                     -> G 1.476 -4.301 -0.109
     Node mass:
             Matrix: 4.1146
Node 36      -> B -0.013 0.058 -0.000
                     -> A 1.636 -4.739 0.009
                     -> G 1.632 -4.739 -0.120
     Node mass:
             Matrix: 1.9471
Node 37      -> B -0.012 0.055 -0.000
                     -> A 1.792 -5.176 0.010
                     -> G 1.787 -5.176 -0.131
     Node mass:
             Matrix: 3.6738
Node 38      -> B -0.011 0.052 -0.000
                     -> A 1.948 -5.614 0.011
                     -> G 1.943 -5.614 -0.142
     Node mass:
             Matrix: 1.7267
Node 39      -> B -0.011 0.048 -0.000
                     -> A 2.104 -6.052 0.012
                     -> G 2.098 -6.052 -0.153
     Node mass:
             Matrix: 3.2329
Node 40      -> B -0.010 0.045 -0.000
                     -> A 2.260 -6.489 0.014
                     -> G 2.254 -6.489 -0.164
     Node mass:
             Matrix: 1.5062
Node 41      -> B -0.009 0.042 -0.000
                     -> A 2.415 -6.927 0.015
                     -> G 2.409 -6.927 -0.175
     Node mass:
             Matrix: 2.7921
Node 42      -> B -0.008 0.039 -0.000
                     -> A 2.571 -7.364 0.016
                     -> G 2.564 -7.364 -0.186
     Node mass:
             Matrix: 1.2858
Node 43      -> B -0.008 0.035 -0.000
                     -> A 2.727 -7.802 0.017
                     -> G 2.720 -7.802 -0.197
     Node mass:
             Matrix: 2.3512
Node 44      -> B -0.007 0.032 -0.000
                     -> A 2.883 -8.239 0.019
                     -> G 2.875 -8.239 -0.208
     Node mass:
             Matrix: 1.0654
Node 45      -> B -0.006 0.028 -0.000
                     -> A 3.038 -8.677 0.020
                     -> G 3.030 -8.677 -0.219
     Node mass:
             Matrix: 1.9104
Node 46      -> B -0.006 0.026 -0.000
                     -> A 3.194 -9.114 0.021
                     -> G 3.186 -9.114 -0.230
     Node mass:
             Matrix: 0.8450
Node 47      -> B -0.005 0.022 -0.000
                     -> A 3.350 -9.552 0.023
                     -> G 3.341 -9.552 -0.241
     Node mass:
             Matrix: 1.4695
Node 48      -> B -0.005 0.022 -0.000
                     -> A 3.508 -9.988 0.024
                     -> G 3.499 -9.988 -0.252
     Node mass:
             Matrix: 0.3674
        Updated the beam C, modal C and K matrices with the terms from the
gravity linearisation

Aeroelastic system assembled:
     Aerodynamic states: 1536
     Structural states: 594
     Total states: 2130
     Inputs: 893
     Outputs: 891
Final system is:
State-space system
States: 2130
Inputs: 893
Outputs: 891

Generating an instance of AsymptoticStability
Variable reference_velocity has no assigned value in the settings file.
    will default to the value: 1.0
Variable display_root_locus has no assigned value in the settings file.
    will default to the value: False
Variable velocity_analysis has no assigned value in the settings file.
    will default to the value: []
Variable iterative_eigvals has no assigned value in the settings file.
    will default to the value: False
Variable modes_to_plot has no assigned value in the settings file.
    will default to the value: []
Variable postprocessors has no assigned value in the settings file.
    will default to the value: []
Variable postprocessors_settings has no assigned value in the settings file.
    will default to the value: {}
Dynamical System Eigenvalues
Calculating eigenvalues using direct method



|==============|==============|==============|==============|==============|==============|==============|
|     mode     |  eval_real   |  eval_imag   | freq_n (Hz)  | freq_d (Hz)  |   damping    |  period (s)  |
|==============|==============|==============|==============|==============|==============|==============|
|      0       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      1       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      2       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      3       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      4       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      5       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      6       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      7       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      8       |   0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      9       |  -0.000000   |   0.000000   |   0.000000   |   0.000000   |   1.000000   |     inf      |
|      10      |  -0.000884   |  -0.321712   |   0.051202   |   0.051202   |   0.002747   |  19.530439   |
|      11      |  -0.000884   |   0.321712   |   0.051202   |   0.051202   |   0.002747   |  19.530439   |
|      12      |  -0.008470   |  -0.391287   |   0.062290   |   0.062275   |   0.021642   |  16.057731   |
|      13      |  -0.008470   |   0.391287   |   0.062290   |   0.062275   |   0.021642   |  16.057731   |
|      14      |  -0.022506   |   0.000000   |   0.003582   |   0.000000   |   1.000000   |     inf      |
|      15      |  -0.064808   |  -53.732514  |   8.551801   |   8.551795   |   0.001206   |   0.116935   |
|      16      |  -0.064808   |  53.732514   |   8.551801   |   8.551795   |   0.001206   |   0.116935   |
|      17      |  -0.101946   |  68.319141   |  10.873341   |  10.873329   |   0.001492   |   0.091968   |
|      18      |  -0.101946   |  -68.319141  |  10.873341   |  10.873329   |   0.001492   |   0.091968   |
|      19      |  -0.147587   |  83.265282   |  13.252102   |  13.252081   |   0.001772   |   0.075460   |
|      20      |  -0.147587   |  -83.265282  |  13.252102   |  13.252081   |   0.001772   |   0.075460   |
|      21      |  -0.248703   | -109.925782  |  17.495276   |  17.495232   |   0.002262   |   0.057158   |
|      22      |  -0.248703   |  109.925782  |  17.495276   |  17.495232   |   0.002262   |   0.057158   |
|      23      |  -0.293472   |  120.387631  |  19.160344   |  19.160287   |   0.002438   |   0.052191   |
|      24      |  -0.293472   | -120.387631  |  19.160344   |  19.160287   |   0.002438   |   0.052191   |
|      25      |  -0.350319   |  132.903280  |  21.152288   |  21.152214   |   0.002636   |   0.047276   |
|      26      |  -0.350319   | -132.903280  |  21.152288   |  21.152214   |   0.002636   |   0.047276   |
|      27      |  -0.376401   |  138.516954  |  22.045739   |  22.045658   |   0.002717   |   0.045360   |
|      28      |  -0.376401   | -138.516954  |  22.045739   |  22.045658   |   0.002717   |   0.045360   |
|      29      |  -0.494445   |  162.714232  |  25.896894   |  25.896774   |   0.003039   |   0.038615   |
|      30      |  -0.494445   | -162.714232  |  25.896894   |  25.896774   |   0.003039   |   0.038615   |
|      31      |  -0.511651   | -166.238306  |  26.457773   |  26.457648   |   0.003078   |   0.037796   |
|      32      |  -0.511651   |  166.238306  |  26.457773   |  26.457648   |   0.003078   |   0.037796   |
|      33      |  -0.559180   |  175.709816  |  27.965227   |  27.965086   |   0.003182   |   0.035759   |
|      34      |  -0.559180   | -175.709816  |  27.965227   |  27.965086   |   0.003182   |   0.035759   |
|      35      |  -0.569755   |  177.873274  |  28.309556   |  28.309411   |   0.003203   |   0.035324   |
|      36      |  -0.569755   | -177.873274  |  28.309556   |  28.309411   |   0.003203   |   0.035324   |
|      37      |  -0.669914   | -197.999020  |  31.512703   |  31.512523   |   0.003383   |   0.031733   |
|      38      |  -0.669914   |  197.999020  |  31.512703   |  31.512523   |   0.003383   |   0.031733   |
|      39      |  -0.678424   |  199.782714  |  31.796590   |  31.796406   |   0.003396   |   0.031450   |
|      40      |  -0.678424   | -199.782714  |  31.796590   |  31.796406   |   0.003396   |   0.031450   |
|      41      |  -0.715684   |  207.440562  |  33.015387   |  33.015191   |   0.003450   |   0.030289   |
|      42      |  -0.715684   | -207.440562  |  33.015387   |  33.015191   |   0.003450   |   0.030289   |
|      43      |  -0.721193   | -208.623018  |  33.203583   |  33.203385   |   0.003457   |   0.030117   |
|      44      |  -0.721193   |  208.623018  |  33.203583   |  33.203385   |   0.003457   |   0.030117   |
|      45      |  -0.796838   | -224.809928  |  35.779836   |  35.779611   |   0.003544   |   0.027949   |
|      46      |  -0.796838   |  224.809928  |  35.779836   |  35.779611   |   0.003544   |   0.027949   |
|      47      |  -0.801462   | -225.851223  |  35.945565   |  35.945339   |   0.003549   |   0.027820   |
|      48      |  -0.801462   |  225.851223  |  35.945565   |  35.945339   |   0.003549   |   0.027820   |
|      49      |  -0.823218   |  257.880058  |  41.043095   |  41.042886   |   0.003192   |   0.024365   |
|      50      |  -0.823218   | -257.880058  |  41.043095   |  41.042886   |   0.003192   |   0.024365   |
|      51      |  -0.829849   |  232.223377  |  36.959734   |  36.959498   |   0.003573   |   0.027057   |
|      52      |  -0.829849   | -232.223377  |  36.959734   |  36.959498   |   0.003573   |   0.027057   |
|      53      |  -0.833132   |  232.986723  |  37.081226   |  37.080989   |   0.003576   |   0.026968   |
|      54      |  -0.833132   | -232.986723  |  37.081226   |  37.080989   |   0.003576   |   0.026968   |
|      55      |  -0.837692   |  252.830750  |  40.239484   |  40.239264   |   0.003313   |   0.024851   |
|      56      |  -0.837692   | -252.830750  |  40.239484   |  40.239264   |   0.003313   |   0.024851   |
|      57      |  -0.843057   | -274.636584  |  43.709976   |  43.709770   |   0.003070   |   0.022878   |
|      58      |  -0.843057   |  274.636584  |  43.709976   |  43.709770   |   0.003070   |   0.022878   |
|      59      |  -0.855990   | -264.468496  |  42.091689   |  42.091468   |   0.003237   |   0.023758   |
|      60      |  -0.855990   |  264.468496  |  42.091689   |  42.091468   |   0.003237   |   0.023758   |
|      61      |  -0.864725   |  271.184095  |  43.160509   |  43.160289   |   0.003189   |   0.023169   |
|      62      |  -0.864725   | -271.184095  |  43.160509   |  43.160289   |   0.003189   |   0.023169   |
|      63      |  -0.871325   | -283.421756  |  45.108187   |  45.107973   |   0.003074   |   0.022169   |
|      64      |  -0.871325   |  283.421756  |  45.108187   |  45.107973   |   0.003074   |   0.022169   |
|      65      |  -0.878445   |  267.336890  |  42.548217   |  42.547987   |   0.003286   |   0.023503   |
|      66      |  -0.878445   | -267.336890  |  42.548217   |  42.547987   |   0.003286   |   0.023503   |
|      67      |  -0.882869   | -280.833495  |  44.696260   |  44.696039   |   0.003144   |   0.022373   |
|      68      |  -0.882869   |  280.833495  |  44.696260   |  44.696039   |   0.003144   |   0.022373   |
|      69      |  -0.884024   | -245.027542  |  38.997598   |  38.997344   |   0.003608   |   0.025643   |
|      70      |  -0.884024   |  245.027542  |  38.997598   |  38.997344   |   0.003608   |   0.025643   |
|      71      |  -0.886589   | -245.661879  |  39.098557   |  39.098302   |   0.003609   |   0.025577   |
|      72      |  -0.886589   |  245.661879  |  39.098557   |  39.098302   |   0.003609   |   0.025577   |
|      73      |  -0.891210   | -288.915188  |  45.982499   |  45.982280   |   0.003085   |   0.021748   |
|      74      |  -0.891210   |  288.915188  |  45.982499   |  45.982280   |   0.003085   |   0.021748   |
|      75      |  -0.908699   |  251.206723  |  39.981053   |  39.980792   |   0.003617   |   0.025012   |
|      76      |  -0.908699   | -251.206723  |  39.981053   |  39.980792   |   0.003617   |   0.025012   |
|      77      |  -0.910251   | -251.606127  |  40.044621   |  40.044359   |   0.003618   |   0.024972   |
|      78      |  -0.910251   |  251.606127  |  40.044621   |  40.044359   |   0.003618   |   0.024972   |
|      79      |  -0.914184   | -241.156682  |  38.381554   |  38.381278   |   0.003791   |   0.026054   |
|      80      |  -0.914184   |  241.156682  |  38.381554   |  38.381278   |   0.003791   |   0.026054   |
|      81      |  -0.915395   |  290.517030  |  46.237451   |  46.237221   |   0.003151   |   0.021628   |
|      82      |  -0.915395   | -290.517030  |  46.237451   |  46.237221   |   0.003151   |   0.021628   |
|      83      |  -0.933974   | -278.955360  |  44.397373   |  44.397124   |   0.003348   |   0.022524   |
|      84      |  -0.933974   |  278.955360  |  44.397373   |  44.397124   |   0.003348   |   0.022524   |
|      85      |  -0.943144   | -260.320871  |  41.431625   |  41.431353   |   0.003623   |   0.024136   |
|      86      |  -0.943144   |  260.320871  |  41.431625   |  41.431353   |   0.003623   |   0.024136   |
|      87      |  -0.944542   | -260.700481  |  41.492043   |  41.491770   |   0.003623   |   0.024101   |
|      88      |  -0.944542   |  260.700481  |  41.492043   |  41.491770   |   0.003623   |   0.024101   |
|      89      |  -0.953003   | -294.814043  |  46.921357   |  46.921112   |   0.003233   |   0.021312   |
|      90      |  -0.953003   |  294.814043  |  46.921357   |  46.921112   |   0.003233   |   0.021312   |
|      91      |  -0.960626   | -295.652742  |  47.054844   |  47.054595   |   0.003249   |   0.021252   |
|      92      |  -0.960626   |  295.652742  |  47.054844   |  47.054595   |   0.003249   |   0.021252   |
|      93      |  -0.960976   | -265.315963  |  42.226624   |  42.226347   |   0.003622   |   0.023682   |
|      94      |  -0.960976   |  265.315963  |  42.226624   |  42.226347   |   0.003622   |   0.023682   |
|      95      |  -0.961739   |  300.017779  |  47.749558   |  47.749313   |   0.003206   |   0.020943   |
|      96      |  -0.961739   | -300.017779  |  47.749558   |  47.749313   |   0.003206   |   0.020943   |
|      97      |  -0.961940   | -265.596058  |  42.271203   |  42.270925   |   0.003622   |   0.023657   |
|      98      |  -0.961940   |  265.596058  |  42.271203   |  42.270925   |   0.003622   |   0.023657   |
|      99      |  -0.965385   | -266.582863  |  42.428259   |  42.427980   |   0.003621   |   0.023569   |
FINISHED - Elapsed time = 16.3462206 seconds
FINISHED - CPU process time = 68.0131146 seconds

Post-processing

Nonlinear Equilibrium

The files can be opened with Paraview to see the deformation and aerodynamic loading on the flying wing in trim conditions.

Asymptotic Stability

[17]:
eigenvalues_trim = np.loadtxt('./output/horten_u_inf2800_M4N11Msf5/stability/eigenvalues.dat')

Flight Dynamics modes

The flight dynamics modes can be found close to the origin of the Argand diagram. In particular, the phugoid is the mode that is closest to the imaginary axis. An exercise is left to the user to compare this phugoid predicition with the nonlinear response!

[18]:
fig = plt.figure()
plt.scatter(eigenvalues_trim[:, 0], eigenvalues_trim[:, 1],
           marker='x',
           color='k')
plt.xlim(-0.5, 0.5)
plt.ylim(-0.5, 0.5)
plt.grid()
plt.xlabel('Real Part, $Re(\lambda)$ [rad/s]')
plt.ylabel('Imaginary Part, $Im(\lambda)$ [rad/s]');
../../_images/content_example_notebooks_linear_horten_37_0.png

Structural Modes

Looking further out on the plot, the structural modes appear. There is a curve given the Newmark-\(\beta\) integration scheme and on top of it several modes are damped by the presence of the aerodynamics.

Try changing newmark_damp in the LinearAssembler settings to see how this plot changes!

[19]:
fig = plt.figure()
plt.scatter(eigenvalues_trim[:, 0], eigenvalues_trim[:, 1],
           marker='x',
           color='k')
plt.xlim(-5, 0.5)
plt.ylim(-200, 200)
plt.grid()
plt.xlabel('Real Part, $Re(\lambda)$ [rad/s]')
plt.ylabel('Imaginary Part, $Im(\lambda)$ [rad/s]');
../../_images/content_example_notebooks_linear_horten_39_0.png