Simulation of High Aspect Ratio planes in Python [SHARPy]¶
Welcome to SHARPy (Simulation of High Aspect Ratio aeroplanes in Python)!
SHARPy is an aeroelastic analysis package currently under development at the Department of Aeronautics, Imperial College London. It can be used for the structural, aerodynamic, aeroelastic and flight dynamics analysis of flexible aircraft, flying wings and wind turbines. Amongst other capabilities, it offers the following solutions to the user:
Static aerodynamic, structural and aeroelastic solutions
Finding trim conditions for aeroelastic configurations
Nonlinear, dynamic time domain simulations under a large number of conditions such as:
Prescribed trajectories.
Free flight.
Dynamic follower forces.
Control inputs in thrust, control surface deflection…
Arbitrary time-domain gusts, including non span-constant ones.
Full 3D turbulent fields.
Multibody dynamics with hinges, articulations and prescribed nodal motions.
Applicable to wind turbines.
Hinged aircraft.
Catapult assisted takeoffs.
Linear analysis
Linearisation around a nonlinear equilibrium.
Frequency response analysis.
Asymptotic stability analysis.
Model order reduction
Krylov-subspace reduction methods.
Balancing reduction methods.
The modular design of SHARPy allows to simulate complex aeroelastic cases involving very flexible aircraft. The structural solver supports very complex beam arrangements, while retaining geometrical nonlinearity. The UVLM solver features different wake modelling fidelities while supporting large lifting surface deformations in a native way. Detailed information on each of the solvers is presented in their respective documentation packages.
Contents¶
Capabilities¶
This is just the tip of the iceberg, possibilities are nearly endless and once you understand how SHARPy’s modular interface works, you will be capable of running very complex simulations.
Very flexible aircraft nonlinear aeroelasticity¶
The modular design of SHARPy allows to simulate complex aeroelastic cases involving very flexible aircraft. The structural solver supports very complex beam arrangements, while retaining geometrical nonlinearity. The UVLM solver features different wake modelling fidelities while supporting large lifting surface deformations in a native way.
Among the problems studied, a few interesting ones, in no particular order are:
Catapult take off of a very flexible aircraft analysis [Paper]. In this type of simulations, a PID controller was used in order to enforce displacements and velocities in a number of structural nodes (the clamping points). Then, several take off strategies were studied in order to analyse the influence of the structural stiffness in this kind of procedures. This case is a very good example of the type of problems where nonlinear aeroelasticity is essential.
Catapult Takeoff of Flexible Aircraft
Flight in full 3D atmospheric boundary layer (to be published). A very flexible aircraft is flown immersed in a turbulent boundary layer obtained from HPC LES simulations. The results are compared against simpler turbulence models such as von Karman and Kaimal. Intermittency and coherence features in the LES field are absent or less remarkable in the synthetic turbulence fields.
HALE Aircraft in a Turbulent Field
Lateral gust reponse of a realistic very flexible aircraft. For this problem (to be published), a realistic very flexible aircraft (University of Michigan X-HALE) model has been created in SHARPy and validated against their own aeroelastic solver for static and dynamic cases. A set of vertical and lateral gust responses have been simulated.
X-HALE
Wind turbine aeroelasticity¶
SHARPy is suitable to simulate wind turbine aeroelasticity.
On the structural side, it accounts for material anisotropy which is needed to characterize composite blades and for geometrically non-linear deformations observed in current blades due to the increasing length and flexibility. Both rigid and flexible simulations can be performed and the structural modes can be computed accounting for rotational effects (Campbell diagrams). The rotor-tower interaction is modelled through a multibody approach based on the theory of Lagrange multipliers. Finally, the tower base can be fixed or subjected to prescribed linear and angular velocities.
On the aerodynamic side, the use of potential flow theory allows the characterization of flow unsteadiness at a reasonable computational cost. Specifically, steady and dynamic simulations can be performed. The steady simulations are carried out in a non-inertial frame of reference linked to the rotor under uniform steady wind with the assumption of prescribed helicoidal wake. On the other hand, dynamic simulations can be enriched with a wide variety of incoming winds such as shear and yaw. Moreover, the wake shape can be freely computed under no assumptions accounting for self-induction and wake expansion or can be prescribed to an helicoidal shape for computational efficiency.
Wind Turbine
Model Order Reduction¶
Numerical models of physical phenomena require fine discretisations to show convergence and agreement with their real counterparts, and, in the case of SHARPy’s aeroelastic systems, hundreds of thousands of states are not an uncommon encounter. However, modern hardware or the use of these models for other applications such as controller synthesis may limit their size, and we must turn to model order reduction techniques to achieve lower dimensional representations that can then be used.
SHARPy offers several model order reduction methods to reduce the initially large system to a lower dimension, attending to the user’s requirements of numerical efficiency or global error bound.
Krylov Methods for Model Order Reduction - Moment Matching¶
Model reduction by moment matching can be seen as approximating a transfer function through a power series expansion about a user defined point in the complex plane. The reduction by projection retains the moments between the full and reduced systems as long as the projection matrices span certain Krylov subspaces dependant on the expansion point and the system’s matrices. This can be taken advantage of, in particular for aeroelastic applications where the interest resides in the low frequency behaviour of the system, the ROM can be expanded about these low frequency points discarding accuracy higher up the frequency spectrum.
Example 1 - Aerodynamics - Frequency response of a high AR flat plate subject to a sinusoidal gust¶
The objective is to compare SHARPy’s solution of a very high aspect ratio flat plate subject to a sinusoidal gust to the closed form solution obtained by Sears (1944 - Ref). SHARPy’s inherent 3D nature makes comparing results to the 2D solution require very high aspect ratio wings with fine discretisations, resulting in very large state space models. In this case, we would like to utilise a Krylov ROM to approximate the low frequency behaviour and perform a frequency response analysis on the reduced system, since it would represent too much computational cost if it were performed on the full system.
The full order model was reduced utilising Krylov methods, in particular the Arnoldi iteration, with an expansion about zero frequency to produce the following result.
Sears Gust Bode Plot
As it can be seen from the image above, the ROM approximates well the low frequency, quasi-steady state and loses accuracy as the frequency is increased, just as intended. Still, perfect matching is never achieved even at the expansion frequency given the 3D nature of the wing compared to the 2D analytical solution.
Example 2 - Aeroelastics - Flutter analysis of a Goland wing with modal projection¶
The Goland wing flutter example is presented next. The aerodynamic surface is finely discretised for the UVLM solution, resulting in not only a large state space but also in large input/output dimensionality. Therefore, to reduce the number of inputs and outputs, the UVLM is projected onto the structural mode shapes, the first four in this particular case. The resulting multi input multi output system (mode shapes -> UVLM -> modal forces) was subsequently reduced using Krylov methods aimed at MIMO systems which use variations of the block Arnoldi iteration. Again, the expansion frequency selected was the zero frequency. As a sample, the transfer function from two inputs to two outputs is shown to illustrate the performance of the reduced model against the full order UVLM.
Goland Reduced Order Model Transfer Functions
The reduced aerodynamic model projected onto the modal shapes was then coupled to the linearised beam model, and the stability analysed against a change in velocity. Note that the UVLM model and its ROM are actually scaled to be independent on the freestream velocity, hence only one UVLM and ROM need to be computed. The structural model needs to be updated at each test velocity but its a lot less costly in computational terms. The resulting stability of the aeroelastic system is plotted on the Argand diagram below with changing freestream velocity.
Goland Flutter
Publications¶
SHARPy has been used in many technical papers that have been both published in Journals and presented at conferences. Here we present a list of past papers which have used SHARPy for research purposes:
2021¶
Artola, M., Goizueta, N., Wynn, A., & Palacios, R. (2021). Proof of Concept for a Hardware-in-the-Loop Nonlinear. In AIAA SciTech Forum (pp. 1–26). https://doi.org/10.2514/6.2021-1392
Goizueta, N., Drachinsky, A., Wynn, A., Raveh, D. E., & Palacios, R. (2021). Flutter prediction for a very flexible wing wind tunnel test. In AIAA SciTech Forum (pp. 1–17). https://doi.org/10.2514/6.2021-1711
Goizueta, N., Wynn, A., & Palacios, R. (2021). Parametric Krylov-based order reduction of aircraft aeroelastic models. In AIAA SciTech Forum (pp. 1–25). https://doi.org/10.2514/6.2021-1798
2020¶
Muñoz-Simón, A., Palacios, R., & Wynn, A. (2020). Benchmarking different fidelities in wind turbine aerodynamics under yaw. Journal of Physics: Conference Series, 1618, 42017. https://doi.org/10.1088/1742-6596/1618/4/042017
del Carre, A., & Palacios, R. (2020). Simulation and Optimization of Takeoff Maneuvers of Very Flexible Aircraft. Journal of Aircraft: 57(6) 1097-1110. https://doi.org/10.2514/1.C035901
Maraniello, S. & Palacios, R. (2020). Parametric Reduced-Order Modeling of the Unsteady Vortex-Lattice Method. AIAA Journal, 58(5), 2206-2220. https://doi.org/10.2514/1.J058894
Deskos, G., del Carre, A., & Palacios, R. (2020). Assessment of low-altitude atmospheric turbulence models for aircraft aeroelasticity. Journal of Fluids and Structures, 95, 102981. https://doi.org/10.1016/j.jfluidstructs.2020.102981
Goizueta, Norberto, del Carre, Alfonso, Muñoz-Simón, Arturo, & Palacios, Rafael. (2020, February). SHARPy: from a research code to an open-source software tool for the simulation of very flexible aircraft. RSLondonSouthEast 2020 Conference. Zenodo: http://doi.org/10.5281/zenodo.3641216
Del Carre, A., Deskos, G., & Palacios, R. (2020). Realistic turbulence effects in low altitude dynamics of very flexible aircraft. In AIAA SciTech Forum (pp. 1–18). https://doi.org/10.2514/6.2020-1187
Artola, M., Goizueta, N., Wynn, A., & Palacios, R. (2020). Modal-Based Nonlinear Estimation and Control for Highly Flexible Aeroelastic Systems. In AIAA SciTech Forum (pp. 1–23). https://doi.org/10.2514/6.2020-1192
Muñoz-Simón, A., Wynn, A., & Palacios, R. (2020). Unsteady and three-dimensional aerodynamic effects on wind turbine rotor loads. In AIAA SciTech Forum. https://doi.org/10.2514/6.2020-0991
2019¶
Carre, A., Muñoz-Simón, A., Goizueta, N., & Palacios, R. (2019). SHARPy : A dynamic aeroelastic simulation toolbox for very flexible aircraft and wind turbines. Journal of Open Source Software, 4(44), 1885. https://doi.org/10.21105/joss.01885
Del Carre, A., Teixeira, P. C., Palacios, R., & Cesnik, C. E. S. (2019). Nonlinear Response of a Very Flexible Aircraft Under Lateral Gust. In International Forum on Aeroelasticity and Structural Dynamics.
Del Carre, A., & Palacios, R. (2019). Efficient Time-Domain Simulations in Nonlinear Aeroelasticity. In AIAA Scitech Forum (pp. 1–20). https://doi.org/10.2514/6.2019-2038
Maraniello, S., & Palacios, R. (2019). State-Space Realizations and Internal Balancing in Potential-Flow Aerodynamics with Arbitrary Kinematics. AIAA Journal, 57(6), 2308-2321. https://doi.org/10.2514/1.J058153
Examples¶
A set of SHARPy examples created with Jupyter Notebooks is provided for users to interact and modify cases running on SHARPy.
Flutter Analysis of a Goland Wing using the SHARPy Linear Solver¶
This is an example using SHARPy to find the flutter speed of a Goland wing by:
Calculating aerodynamic forces and deflections using a nonlinear solver
Linearising about this reference condition
Creating a reduced order model of the linearised aerodynamics
Evaluate the stability of the linearised aeroelastic system at different velocities
References¶
Maraniello, S., & Palacios, R. (2019). State-Space Realizations and Internal Balancing in Potential-Flow Aerodynamics with Arbitrary Kinematics. AIAA Journal, 57(6), 1–14. https://doi.org/10.2514/1.J058153
Required Packages¶
[1]:
import numpy as np
import matplotlib.pyplot as plt
import os
import sys
import cases.templates.flying_wings as wings # See this package for the Goland wing structural and aerodynamic definition
import sharpy.sharpy_main # used to run SHARPy from Jupyter
Problem Set-up¶
The UVLM is assembled in normalised time at a velocity of \(1 m/s\). The only matrices that need updating then with free stream velocity are the structural matrices, which is significantly cheaper to do than to update the UVLM.
[2]:
u_inf = 1.
alpha_deg = 0.
rho = 1.02
num_modes = 4
Note: To achieve convergence of the flutter results with the ones found in the literature, a significant discretisation may be required. If you are running this notebook for the first time, set M = 4
initially to verify that your system can perform!
[3]:
M = 16
N = 32
M_star_fact = 10
A moment-matching (Krylov subspace) model order reduction technique is employed. This ROM method offers the ability to interpolate the transfer functions at a desired point in the complex plane. See the ROM documentation pages for more info.
Note: this ROM method matches the transfer function but does not guarantee stability. Therefore the resulting system may be unstable. These unstable modes may appear far in the right hand plane but will not affect the flutter speed calculations.
[4]:
c_ref = 1.8288 # Goland wing reference chord. Used for frequency normalisation
rom_settings = dict()
rom_settings['algorithm'] = 'mimo_rational_arnoldi' # reduction algorithm
rom_settings['r'] = 6 # Krylov subspace order
frequency_continuous_k = np.array([0.]) # Interpolation point in the complex plane with reduced frequency units
frequency_continuous_w = 2 * u_inf * frequency_continuous_k / c_ref
rom_settings['frequency'] = frequency_continuous_w
[5]:
case_name = 'goland_cs'
case_nlin_info = 'M%dN%dMs%d_nmodes%d' % (M, N, M_star_fact, num_modes)
case_rom_info = 'rom_MIMORA_r%d_sig%04d_%04dj' % (rom_settings['r'], frequency_continuous_k[-1].real * 100,
frequency_continuous_k[-1].imag * 100)
case_name += case_nlin_info + case_rom_info
route_test_dir = os.path.abspath('')
print('The case to run will be: %s' % case_name)
print('Case files will be saved in ./cases/%s' %case_name)
print('Output files will be saved in ./output/%s/' %case_name)
The case to run will be: goland_csM16N32Ms10_nmodes4rom_MIMORA_r6_sig0000_0000j
Case files will be saved in ./cases/goland_csM16N32Ms10_nmodes4rom_MIMORA_r6_sig0000_0000j
Output files will be saved in ./output/goland_csM16N32Ms10_nmodes4rom_MIMORA_r6_sig0000_0000j/
Simulation Set-Up¶
ws
is an instance of a Goland wing with a control surface. Reference the template file cases.templates.flying_wings.GolandControlSurface
for more info on the geometrical, structural and aerodynamic definition of the Goland wing here used.
[6]:
ws = wings.GolandControlSurface(M=M,
N=N,
Mstar_fact=M_star_fact,
u_inf=u_inf,
alpha=alpha_deg,
cs_deflection=[0, 0],
rho=rho,
sweep=0,
physical_time=2,
n_surfaces=2,
route=route_test_dir + '/cases',
case_name=case_name)
ws.clean_test_files()
ws.update_derived_params()
ws.set_default_config_dict()
ws.generate_aero_file()
ws.generate_fem_file()
Surface0
Surface1
The settings for each of the solvers are now set. For a detailed description on them please reference their respective documentation pages
SHARPy Settings¶
The most important setting is the flow
list. It tells SHARPy which solvers to run and in which order.
[7]:
ws.config['SHARPy'] = {
'flow':
['BeamLoader', 'AerogridLoader',
'StaticCoupled',
'AerogridPlot',
'BeamPlot',
'Modal',
'LinearAssembler',
'FrequencyResponse',
'AsymptoticStability',
],
'case': ws.case_name, 'route': ws.route,
'write_screen': 'on', 'write_log': 'on',
'log_folder': route_test_dir + '/output/' + ws.case_name + '/',
'log_file': ws.case_name + '.log'}
Beam Loader Settings¶
[8]:
ws.config['BeamLoader'] = {
'unsteady': 'off',
'orientation': ws.quat}
Aerogrid Loader Settings¶
[9]:
ws.config['AerogridLoader'] = {
'unsteady': 'off',
'aligned_grid': 'on',
'mstar': ws.Mstar_fact * ws.M,
'freestream_dir': ws.u_inf_direction
}
Static Coupled Solver¶
[10]:
ws.config['StaticCoupled'] = {
'print_info': 'on',
'max_iter': 200,
'n_load_steps': 1,
'tolerance': 1e-10,
'relaxation_factor': 0.,
'aero_solver': 'StaticUvlm',
'aero_solver_settings': {
'rho': ws.rho,
'print_info': 'off',
'horseshoe': 'off',
'num_cores': 4,
'n_rollup': 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': ws.u_inf_direction}},
'structural_solver': 'NonLinearStatic',
'structural_solver_settings': {'print_info': 'off',
'max_iterations': 150,
'num_load_steps': 4,
'delta_curved': 1e-1,
'min_delta': 1e-10,
'gravity_on': 'on',
'gravity': 9.81}}
AerogridPlot Settings¶
[11]:
ws.config['AerogridPlot'] = {'folder': route_test_dir + '/output/',
'include_rbm': 'off',
'include_applied_forces': 'on',
'minus_m_star': 0}
BeamPlot Settings¶
[12]:
ws.config['BeamPlot'] = {'folder': route_test_dir + '/output/',
'include_rbm': 'off',
'include_applied_forces': 'on'}
Modal Solver Settings¶
[13]:
ws.config['Modal'] = {'folder': route_test_dir + '/output/',
'NumLambda': 20,
'rigid_body_modes': 'off',
'print_matrices': 'on',
'keep_linear_matrices': 'on',
'write_dat': 'off',
'rigid_modes_cg': 'off',
'continuous_eigenvalues': 'off',
'dt': 0,
'plot_eigenvalues': False,
'max_rotation_deg': 15.,
'max_displacement': 0.15,
'write_modes_vtk': True,
'use_undamped_modes': True}
Linear System Assembly Settings¶
[14]:
ws.config['LinearAssembler'] = {'linear_system': 'LinearAeroelastic',
'linear_system_settings': {
'beam_settings': {'modal_projection': 'on',
'inout_coords': 'modes',
'discrete_time': 'on',
'newmark_damp': 0.5e-4,
'discr_method': 'newmark',
'dt': ws.dt,
'proj_modes': 'undamped',
'use_euler': 'off',
'num_modes': num_modes,
'print_info': 'on',
'gravity': 'on',
'remove_sym_modes': 'on',
'remove_dofs': []},
'aero_settings': {'dt': ws.dt,
'ScalingDict': {'length': 0.5 * ws.c_ref,
'speed': u_inf,
'density': rho},
'integr_order': 2,
'density': ws.rho,
'remove_predictor': 'on',
'use_sparse': 'on',
'rigid_body_motion': 'off',
'use_euler': 'off',
'remove_inputs': ['u_gust'],
'rom_method': ['Krylov'],
'rom_method_settings': {'Krylov': rom_settings}},
'rigid_body_motion': False}}
Asymptotic Stability Analysis Settings¶
[15]:
ws.config['AsymptoticStability'] = {'print_info': True,
'folder': route_test_dir + '/output/',
'velocity_analysis': [100, 180, 81],
'modes_to_plot': []}
[16]:
ws.config.write()
Run SHARPy¶
[17]:
sharpy.sharpy_main.main(['', ws.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/code/sharpy/docs/source/content/example_notebooks
SHARPy being run is in /home/ng213/code/sharpy
The branch being run is dev_examples
The version and commit hash are: v0.1-1539-gd3ef7dd-d3ef7dd
The available solvers on this session are:
PreSharpy
_BaseStructural
AerogridLoader
BeamLoader
DynamicCoupled
DynamicUVLM
LinDynamicSim
LinearAssembler
Modal
NoAero
NonLinearDynamic
NonLinearDynamicCoupledStep
NonLinearDynamicMultibody
NonLinearDynamicPrescribedStep
NonLinearStatic
NonLinearStaticMultibody
PrescribedUvlm
RigidDynamicPrescribedStep
SHWUvlm
StaticCoupled
StaticCoupledRBM
StaticTrim
StaticUvlm
StepLinearUVLM
StepUvlm
Trim
Cleanup
PickleData
SaveData
CreateSnapshot
PlotFlowField
StabilityDerivatives
AeroForcesCalculator
WriteVariablesTime
AerogridPlot
LiftDistribution
StallCheck
FrequencyResponse
AsymptoticStability
BeamPlot
BeamLoads
Generating an instance of BeamLoader
Generating an instance of AerogridLoader
Variable control_surface_deflection has no assigned value in the settings file.
will default to the value: []
Variable control_surface_deflection_generator_settings has no assigned value in the settings file.
will default to the value: []
The aerodynamic grid contains 2 surfaces
Surface 0, M=16, N=16
Wake 0, M=160, N=16
Surface 1, M=16, N=16
Wake 1, M=160, N=16
In total: 512 bound panels
In total: 5120 wake panels
Total number of panels = 5632
Generating an instance of StaticCoupled
Generating an instance of NonLinearStatic
Variable newmark_damp has no assigned value in the settings file.
will default to the value: c_double(0.0001)
Variable relaxation_factor has no assigned value in the settings file.
will default to the value: c_double(0.3)
Variable dt has no assigned value in the settings file.
will default to the value: c_double(0.01)
Variable num_steps has no assigned value in the settings file.
will default to the value: c_int(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: c_bool(False)
Variable iterative_tol has no assigned value in the settings file.
will default to the value: c_double(0.0001)
Variable iterative_precond has no assigned value in the settings file.
will default to the value: c_bool(False)
|=====|=====|============|==========|==========|==========|==========|==========|==========|
|iter |step | log10(res) | Fx | Fy | Fz | Mx | My | Mz |
|=====|=====|============|==========|==========|==========|==========|==========|==========|
| 0 | 0 | 0.00000 | -0.0000 | 0.0000 |-4271.0417| 0.0000 | 781.0842 | -0.0000 |
| 1 | 0 | -11.88931 | 0.0000 | -0.0000 |-4271.0039| 0.0000 | 781.0906 | -0.0000 |
Generating an instance of AerogridPlot
Variable include_forward_motion has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable include_unsteady_applied_forces has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable name_prefix has no assigned value in the settings file.
will default to the value:
Variable u_inf has no assigned value in the settings file.
will default to the value: c_double(0.0)
Variable dt has no assigned value in the settings file.
will default to the value: c_double(0.0)
Variable include_velocities has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable num_cores has no assigned value in the settings file.
will default to the value: c_int(1)
...Finished
Generating an instance of BeamPlot
Variable include_FoR has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable include_applied_moments has no assigned value in the settings file.
will default to the value: c_bool(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: c_bool(True)
...Finished
Generating an instance of Modal
Variable print_info has no assigned value in the settings file.
will default to the value: c_bool(True)
Variable delta_curved has no assigned value in the settings file.
will default to the value: c_double(0.01)
Variable use_custom_timestep has no assigned value in the settings file.
will default to the value: c_int(-1)
Structural eigenvalues
|==============|==============|==============|==============|==============|==============|==============|
| mode | eval_real | eval_imag | freq_n (Hz) | freq_d (Hz) | damping | period (s) |
|==============|==============|==============|==============|==============|==============|==============|
| 0 | 0.000000 | 48.067396 | 7.650164 | 7.650164 | -0.000000 | 0.130716 |
| 1 | 0.000000 | 48.067398 | 7.650164 | 7.650164 | -0.000000 | 0.130716 |
| 2 | 0.000000 | 95.685736 | 15.228858 | 15.228858 | -0.000000 | 0.065665 |
| 3 | 0.000000 | 95.685754 | 15.228861 | 15.228861 | -0.000000 | 0.065665 |
| 4 | 0.000000 | 243.144471 | 38.697644 | 38.697644 | -0.000000 | 0.025841 |
| 5 | 0.000000 | 243.144477 | 38.697645 | 38.697645 | -0.000000 | 0.025841 |
| 6 | 0.000000 | 343.801136 | 54.717650 | 54.717650 | -0.000000 | 0.018276 |
| 7 | 0.000000 | 343.801137 | 54.717650 | 54.717650 | -0.000000 | 0.018276 |
| 8 | 0.000000 | 443.324608 | 70.557303 | 70.557303 | -0.000000 | 0.014173 |
| 9 | 0.000000 | 443.324619 | 70.557304 | 70.557304 | -0.000000 | 0.014173 |
| 10 | 0.000000 | 461.992869 | 73.528449 | 73.528449 | -0.000000 | 0.013600 |
| 11 | 0.000000 | 461.992869 | 73.528449 | 73.528449 | -0.000000 | 0.013600 |
| 12 | 0.000000 | 601.126871 | 95.672313 | 95.672313 | -0.000000 | 0.010452 |
| 13 | 0.000000 | 601.126873 | 95.672313 | 95.672313 | -0.000000 | 0.010452 |
| 14 | 0.000000 | 782.997645 | 124.617946 | 124.617946 | -0.000000 | 0.008025 |
| 15 | 0.000000 | 782.997649 | 124.617946 | 124.617946 | -0.000000 | 0.008025 |
| 16 | 0.000000 | 917.191257 | 145.975522 | 145.975522 | -0.000000 | 0.006850 |
| 17 | 0.000000 | 917.191259 | 145.975523 | 145.975523 | -0.000000 | 0.006850 |
| 18 | 0.000000 | 975.005694 | 155.176976 | 155.176976 | -0.000000 | 0.006444 |
| 19 | 0.000000 | 975.005699 | 155.176977 | 155.176977 | -0.000000 | 0.006444 |
Generating an instance of LinearAssembler
Variable linearisation_tstep has no assigned value in the settings file.
will default to the value: c_int(-1)
Generating an instance of LinearAeroelastic
Variable uvlm_filename has no assigned value in the settings file.
will default to the value:
Variable track_body has no assigned value in the settings file.
will default to the value: c_bool(True)
Variable use_euler has no assigned value in the settings file.
will default to the value: c_bool(False)
Generating an instance of LinearUVLM
Variable gust_assembler has no assigned value in the settings file.
will default to the value:
Initialising Static linear UVLM solver class...
/home/ng213/code/sharpy/sharpy/solvers/linearassembler.py:79: UserWarning: LinearAssembler solver under development
warnings.warn('LinearAssembler solver under development')
...done in 1.41 sec
Generating an instance of Krylov
Variable print_info has no assigned value in the settings file.
will default to the value: c_bool(True)
Variable tangent_input_file has no assigned value in the settings file.
will default to the value:
Variable restart_arnoldi has no assigned value in the settings file.
will default to the value: c_bool(False)
Initialising Krylov Model Order Reduction
State-space realisation of UVLM equations started...
/home/ng213/code/sharpy/sharpy/linear/src/assembly.py:1256: SparseEfficiencyWarning: Changing the sparsity structure of a csc_matrix is expensive. lil_matrix is more efficient.
C[iivec, N * (M - 1) + iivec] = 1.0
/home/ng213/code/sharpy/sharpy/linear/src/assembly.py:1259: SparseEfficiencyWarning: Changing the sparsity structure of a csc_matrix is expensive. lil_matrix is more efficient.
C_star[mm * N + iivec, (mm - 1) * N + iivec] = 1.0
state-space model produced in form:
h_{n+1} = A h_{n} + B u_{n}
with:
x_n = h_n + Bp u_n
...done in 19.06 sec
Scaling UVLM system with reference time 0.914400s
Non-dimensional time step set (0.125000)
System scaled in 31.559722s
Generating an instance of LinearBeam
Warning, projecting system with damping onto undamped modes
Linearising gravity terms...
M = 7.26 kg
X_CG A -> 0.00 -0.00 -0.00
Node 1 -> B -0.000 -0.116 0.000
-> A 0.116 0.381 -0.000
-> G 0.116 0.381 -0.000
Node mass:
Matrix: 14.5125
Node 2 -> B -0.000 -0.116 0.000
-> A 0.116 0.762 -0.000
-> G 0.116 0.762 -0.000
Node mass:
Matrix: 7.2563
Node 3 -> B -0.000 -0.116 0.000
-> A 0.116 1.143 -0.000
-> G 0.116 1.143 -0.000
Node mass:
Matrix: 14.5125
Node 4 -> B -0.000 -0.116 0.000
-> A 0.116 1.524 -0.001
-> G 0.116 1.524 -0.001
Node mass:
Matrix: 7.2563
Node 5 -> B -0.000 -0.116 0.000
-> A 0.116 1.905 -0.001
-> G 0.116 1.905 -0.001
Node mass:
Matrix: 14.5125
Node 6 -> B -0.000 -0.116 0.000
-> A 0.116 2.286 -0.001
-> G 0.116 2.286 -0.001
Node mass:
Matrix: 7.2563
Node 7 -> B -0.000 -0.116 0.000
-> A 0.116 2.667 -0.002
-> G 0.116 2.667 -0.002
Node mass:
Matrix: 14.5125
Node 8 -> B -0.000 -0.116 0.000
-> A 0.116 3.048 -0.002
-> G 0.116 3.048 -0.002
Node mass:
Matrix: 7.2563
Node 9 -> B -0.000 -0.116 0.000
-> A 0.116 3.429 -0.003
-> G 0.116 3.429 -0.003
Node mass:
Matrix: 14.5125
Node 10 -> B -0.000 -0.116 0.000
-> A 0.116 3.810 -0.003
-> G 0.116 3.810 -0.003
Node mass:
Matrix: 7.2563
Node 11 -> B -0.000 -0.116 0.000
-> A 0.116 4.191 -0.004
-> G 0.116 4.191 -0.004
Node mass:
Matrix: 14.5125
Node 12 -> B -0.000 -0.116 0.000
-> A 0.116 4.572 -0.004
-> G 0.116 4.572 -0.004
Node mass:
Matrix: 7.2563
Node 13 -> B -0.000 -0.116 0.000
-> A 0.116 4.953 -0.005
-> G 0.116 4.953 -0.005
Node mass:
Matrix: 14.5125
Node 14 -> B -0.000 -0.116 0.000
-> A 0.116 5.334 -0.005
-> G 0.116 5.334 -0.005
Node mass:
Matrix: 7.2563
Node 15 -> B -0.000 -0.116 0.000
-> A 0.116 5.715 -0.006
-> G 0.116 5.715 -0.006
Node mass:
Matrix: 14.5125
Node 16 -> B -0.000 -0.116 0.000
-> A 0.116 6.096 -0.006
-> G 0.116 6.096 -0.006
Node mass:
Matrix: 3.6281
Node 17 -> B -0.000 -0.116 -0.000
-> A 0.116 -6.096 -0.006
-> G 0.116 -6.096 -0.006
Node mass:
Matrix: 3.6281
Node 18 -> B -0.000 -0.116 -0.000
-> A 0.116 -5.715 -0.006
-> G 0.116 -5.715 -0.006
Node mass:
Matrix: 14.5125
Node 19 -> B -0.000 -0.116 -0.000
-> A 0.116 -5.334 -0.005
-> G 0.116 -5.334 -0.005
Node mass:
Matrix: 7.2563
Node 20 -> B -0.000 -0.116 -0.000
-> A 0.116 -4.953 -0.005
-> G 0.116 -4.953 -0.005
Node mass:
Matrix: 14.5125
Node 21 -> B -0.000 -0.116 -0.000
-> A 0.116 -4.572 -0.004
-> G 0.116 -4.572 -0.004
Node mass:
Matrix: 7.2563
Node 22 -> B -0.000 -0.116 -0.000
-> A 0.116 -4.191 -0.004
-> G 0.116 -4.191 -0.004
Node mass:
Matrix: 14.5125
Node 23 -> B -0.000 -0.116 -0.000
-> A 0.116 -3.810 -0.003
-> G 0.116 -3.810 -0.003
Node mass:
Matrix: 7.2563
Node 24 -> B -0.000 -0.116 -0.000
-> A 0.116 -3.429 -0.003
-> G 0.116 -3.429 -0.003
Node mass:
Matrix: 14.5125
Node 25 -> B -0.000 -0.116 -0.000
-> A 0.116 -3.048 -0.002
-> G 0.116 -3.048 -0.002
Node mass:
Matrix: 7.2563
Node 26 -> B -0.000 -0.116 -0.000
-> A 0.116 -2.667 -0.002
-> G 0.116 -2.667 -0.002
Node mass:
Matrix: 14.5125
Node 27 -> B -0.000 -0.116 -0.000
-> A 0.116 -2.286 -0.002
-> G 0.116 -2.286 -0.002
Node mass:
Matrix: 7.2563
Node 28 -> B -0.000 -0.116 -0.000
-> A 0.116 -1.905 -0.001
-> G 0.116 -1.905 -0.001
Node mass:
Matrix: 14.5125
Node 29 -> B -0.000 -0.116 -0.000
-> A 0.116 -1.524 -0.001
-> G 0.116 -1.524 -0.001
Node mass:
Matrix: 7.2563
Node 30 -> B -0.000 -0.116 -0.000
-> A 0.116 -1.143 -0.000
-> G 0.116 -1.143 -0.000
Node mass:
Matrix: 14.5125
Node 31 -> B -0.000 -0.116 -0.000
-> A 0.116 -0.762 -0.000
-> G 0.116 -0.762 -0.000
Node mass:
Matrix: 7.2563
Node 32 -> B -0.000 -0.116 -0.000
-> A 0.116 -0.381 -0.000
-> G 0.116 -0.381 -0.000
Node mass:
Matrix: 14.5125
Updated the beam C, modal C and K matrices with the terms from the
gravity linearisation
Scaling beam according to reduced time...
Setting the beam time step to (0.1250)
Updating C and K matrices and natural frequencies with new normalised time...
Model Order Reduction in progress...
Moment Matching Krylov Model Reduction
Construction Algorithm:
mimo_rational_arnoldi
Interpolation points:
Krylov order:
r = 6
Unstable ROM - 2 Eigenvalues with |r| > 1
mu = -3.202177 + 0.000000j
mu = 1.062204 + 0.000000j
System reduced from order 6656 to
n = 36 states
...Completed Model Order Reduction in 2.51 s
Aeroelastic system assembled:
Aerodynamic states: 36
Structural states: 4
Total states: 40
Inputs: 8
Outputs: 6
Generating an instance of FrequencyResponse
Variable load_fom has no assigned value in the settings file.
will default to the value:
Variable num_freqs has no assigned value in the settings file.
will default to the value: c_int(50)
Computing frequency response...
Full order system:
/home/ng213/anaconda3/envs/sharpy_env/lib/python3.7/site-packages/scipy/sparse/compressed.py:708: SparseEfficiencyWarning: Changing the sparsity structure of a csc_matrix is expensive. lil_matrix is more efficient.
self[i, j] = values
Computed the frequency response of the full order system in 26.673870 s
Reduced order system:
Computed the frequency response of the reduced order system in 0.002653 s
Computing error in frequency response
m = 0, p = 0
Error Magnitude -real-: log10(error) = -4.85 (-0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -4.80 (-0.00 pct) at 1.07 rad/s
m = 0, p = 1
Error Magnitude -real-: log10(error) = -4.93 (-0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -5.17 (0.00 pct) at 1.09 rad/s
m = 1, p = 0
Error Magnitude -real-: log10(error) = -3.98 (0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -3.94 (0.00 pct) at 1.07 rad/s
m = 1, p = 1
Error Magnitude -real-: log10(error) = -4.06 (0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -4.30 (-0.00 pct) at 1.09 rad/s
m = 2, p = 0
Error Magnitude -real-: log10(error) = -4.28 (-0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -4.23 (-0.00 pct) at 1.07 rad/s
m = 2, p = 1
Error Magnitude -real-: log10(error) = -4.35 (-0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -4.61 (0.00 pct) at 1.09 rad/s
m = 3, p = 0
Error Magnitude -real-: log10(error) = -4.16 (0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -4.12 (0.01 pct) at 1.07 rad/s
m = 3, p = 1
Error Magnitude -real-: log10(error) = -4.24 (-0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -4.48 (-0.00 pct) at 1.09 rad/s
m = 4, p = 0
Error Magnitude -real-: log10(error) = -3.67 (0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -3.59 (0.00 pct) at 1.07 rad/s
m = 4, p = 1
Error Magnitude -real-: log10(error) = -3.71 (0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -4.00 (-0.00 pct) at 0.98 rad/s
m = 5, p = 0
Error Magnitude -real-: log10(error) = -3.83 (0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -3.75 (0.00 pct) at 1.07 rad/s
m = 5, p = 1
Error Magnitude -real-: log10(error) = -3.87 (-0.00 pct) at 1.09 rad/s
Error Magnitude -imag-: log10(error) = -4.16 (-0.00 pct) at 0.98 rad/s
Creating Quick plots of the frequency response
Plots saved to ./output//goland_csM16N32Ms10_nmodes4rom_MIMORA_r6_sig0000_0000j/frequencyresponse/
Generating an instance of AsymptoticStability
Variable reference_velocity has no assigned value in the settings file.
will default to the value: c_double(1.0)
Variable frequency_cutoff has no assigned value in the settings file.
will default to the value: c_double(0.0)
Variable export_eigenvalues has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable display_root_locus has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable num_evals has no assigned value in the settings file.
will default to the value: c_int(200)
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
|==============|==============|==============|==============|==============|==============|==============|
| mode | eval_real | eval_imag | freq_n (Hz) | freq_d (Hz) | damping | period (s) |
|==============|==============|==============|==============|==============|==============|==============|
| 0 | 10.182550 | -27.485500 | 4.664997 | 4.374453 | -0.347396 | 0.228600 |
| 1 | 0.527963 | -0.000000 | 0.084028 | 0.000000 | 1.000000 | inf |
| 2 | -0.021585 | -24.315459 | 3.869927 | 3.869926 | 0.000888 | 0.258403 |
| 3 | -0.021585 | 24.315459 | 3.869927 | 3.869926 | 0.000888 | 0.258403 |
| 4 | -0.105973 | -21.319801 | 3.393194 | 3.393152 | 0.004971 | 0.294711 |
| 5 | -0.105973 | 21.319801 | 3.393194 | 3.393152 | 0.004971 | 0.294711 |
| 6 | -0.253786 | 0.000000 | 0.040391 | 0.000000 | 1.000000 | inf |
| 7 | -0.372465 | -0.355725 | 0.081972 | 0.056615 | 0.723172 | 17.663059 |
| 8 | -0.372465 | 0.355725 | 0.081972 | 0.056615 | 0.723172 | 17.663059 |
| 9 | -0.405420 | 0.870139 | 0.152781 | 0.138487 | 0.422334 | 7.220896 |
| 10 | -0.405420 | -0.870139 | 0.152781 | 0.138487 | 0.422334 | 7.220896 |
| 11 | -0.414445 | 0.000000 | 0.065961 | 0.000000 | 1.000000 | inf |
| 12 | -0.433769 | -0.705316 | 0.131784 | 0.112255 | 0.523860 | 8.908329 |
| 13 | -0.433769 | 0.705316 | 0.131784 | 0.112255 | 0.523860 | 8.908329 |
| 14 | -0.584818 | 0.000000 | 0.093077 | 0.000000 | 1.000000 | inf |
| 15 | -0.652779 | -0.945278 | 0.182832 | 0.150446 | 0.568242 | 6.646916 |
| 16 | -0.652779 | 0.945278 | 0.182832 | 0.150446 | 0.568242 | 6.646916 |
| 17 | -0.662253 | -0.344794 | 0.118830 | 0.054876 | 0.886985 | 18.223008 |
| 18 | -0.662253 | 0.344794 | 0.118830 | 0.054876 | 0.886985 | 18.223008 |
| 19 | -0.689479 | -0.611472 | 0.146671 | 0.097319 | 0.748162 | 10.275501 |
| 20 | -0.689479 | 0.611472 | 0.146671 | 0.097319 | 0.748162 | 10.275501 |
| 21 | -0.733120 | -0.423757 | 0.134769 | 0.067443 | 0.865775 | 14.827328 |
| 22 | -0.733120 | 0.423757 | 0.134769 | 0.067443 | 0.865775 | 14.827328 |
| 23 | -0.755676 | 0.287185 | 0.128662 | 0.045707 | 0.934772 | 21.878536 |
| 24 | -0.755676 | -0.287185 | 0.128662 | 0.045707 | 0.934772 | 21.878536 |
| 25 | -0.765019 | 0.043949 | 0.121957 | 0.006995 | 0.998354 | 142.964071 |
| 26 | -0.765019 | -0.043949 | 0.121957 | 0.006995 | 0.998354 | 142.964071 |
| 27 | -0.768680 | 0.696822 | 0.165125 | 0.110903 | 0.740889 | 9.016920 |
| 28 | -0.768680 | -0.696822 | 0.165125 | 0.110903 | 0.740889 | 9.016920 |
| 29 | -0.847888 | -0.177523 | 0.137872 | 0.028254 | 0.978777 | 35.393580 |
| 30 | -0.847888 | 0.177523 | 0.137872 | 0.028254 | 0.978777 | 35.393580 |
| 31 | -2.191875 | -0.000000 | 0.348848 | 0.000000 | 1.000000 | inf |
| 32 | -3.035678 | 1.135842 | 0.515855 | 0.180775 | 0.936586 | 5.531743 |
| 33 | -3.035678 | -1.135842 | 0.515855 | 0.180775 | 0.936586 | 5.531743 |
| 34 | -4.223460 | 0.000000 | 0.672185 | 0.000000 | 1.000000 | inf |
| 35 | -9.070692 | -0.000000 | 1.443645 | 0.000000 | 1.000000 | inf |
| 36 | -26.578730 | 27.485500 | 6.085219 | 4.374453 | 0.695149 | 0.228600 |
| 37 | -28.711479 | -0.000000 | 4.569574 | 0.000000 | 1.000000 | inf |
| 38 | -35.859976 | 27.485500 | 7.190899 | 4.374453 | 0.793683 | 0.228600 |
| 39 | -36.744614 | 0.000000 | 5.848087 | 0.000000 | 1.000000 | inf |
Velocity Asymptotic Stability Analysis
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 100.00 m/2 max. CT eig. real: 1018.304110
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 52.80 49.09
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 101.00 m/2 max. CT eig. real: 1028.487151
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 53.32 49.15
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 102.00 m/2 max. CT eig. real: 1038.670193
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 53.85 49.21
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 103.00 m/2 max. CT eig. real: 1048.853234
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 54.38 49.27
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 104.00 m/2 max. CT eig. real: 1059.036275
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 54.91 49.34
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 105.00 m/2 max. CT eig. real: 1069.219316
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 55.44 49.40
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 106.00 m/2 max. CT eig. real: 1079.402357
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 55.96 49.47
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 107.00 m/2 max. CT eig. real: 1089.585399
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 56.49 49.54
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 108.00 m/2 max. CT eig. real: 1099.768440
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 57.02 49.60
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 109.00 m/2 max. CT eig. real: 1109.951481
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 57.55 49.68
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 110.00 m/2 max. CT eig. real: 1120.134522
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 58.08 49.75
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 111.00 m/2 max. CT eig. real: 1130.317564
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 58.60 49.82
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 112.00 m/2 max. CT eig. real: 1140.500605
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 59.13 49.90
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 113.00 m/2 max. CT eig. real: 1150.683646
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 59.66 49.97
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 114.00 m/2 max. CT eig. real: 1160.866687
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 60.19 50.05
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 115.00 m/2 max. CT eig. real: 1171.049728
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 60.72 50.13
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 116.00 m/2 max. CT eig. real: 1181.232770
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 61.24 50.22
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 117.00 m/2 max. CT eig. real: 1191.415811
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 61.77 50.30
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 118.00 m/2 max. CT eig. real: 1201.598852
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 62.30 50.39
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 119.00 m/2 max. CT eig. real: 1211.781893
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 62.83 83.07
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 120.00 m/2 max. CT eig. real: 1221.964934
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 63.36 82.86
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 121.00 m/2 max. CT eig. real: 1232.147976
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 63.88 82.64
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 122.00 m/2 max. CT eig. real: 1242.331017
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 64.41 82.42
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 123.00 m/2 max. CT eig. real: 1252.514058
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 64.94 82.19
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 124.00 m/2 max. CT eig. real: 1262.697099
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 65.47 81.96
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 125.00 m/2 max. CT eig. real: 1272.880140
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 66.00 81.73
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 126.00 m/2 max. CT eig. real: 1283.063182
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 66.52 81.50
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 127.00 m/2 max. CT eig. real: 1293.246223
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 67.05 81.26
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 128.00 m/2 max. CT eig. real: 1303.429264
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 67.58 81.01
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 129.00 m/2 max. CT eig. real: 1313.612305
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 68.11 80.77
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 130.00 m/2 max. CT eig. real: 1323.795346
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 68.64 80.51
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 131.00 m/2 max. CT eig. real: 1333.978388
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 69.16 80.26
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 132.00 m/2 max. CT eig. real: 1344.161429
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 69.69 80.00
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 133.00 m/2 max. CT eig. real: 1354.344470
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 70.22 79.74
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 134.00 m/2 max. CT eig. real: 1364.527511
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 70.75 79.47
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 135.00 m/2 max. CT eig. real: 1374.710552
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 71.28 79.20
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 136.00 m/2 max. CT eig. real: 1384.893594
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 71.80 78.92
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 137.00 m/2 max. CT eig. real: 1395.076635
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 72.33 78.64
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 138.00 m/2 max. CT eig. real: 1405.259676
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 72.86 78.36
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 139.00 m/2 max. CT eig. real: 1415.442717
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 73.39 78.07
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 140.00 m/2 max. CT eig. real: 1425.625758
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 73.91 77.77
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 141.00 m/2 max. CT eig. real: 1435.808799
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 74.44 77.48
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 142.00 m/2 max. CT eig. real: 1445.991841
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 74.97 77.18
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 143.00 m/2 max. CT eig. real: 1456.174882
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 75.50 76.87
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 144.00 m/2 max. CT eig. real: 1466.357923
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 76.03 76.57
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 145.00 m/2 max. CT eig. real: 1476.540964
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 76.55 76.25
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 146.00 m/2 max. CT eig. real: 1486.724005
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 77.08 75.94
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 147.00 m/2 max. CT eig. real: 1496.907047
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 77.61 75.62
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 148.00 m/2 max. CT eig. real: 1507.090088
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 78.14 75.31
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 149.00 m/2 max. CT eig. real: 1517.273129
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 78.67 74.99
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 150.00 m/2 max. CT eig. real: 1527.456170
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 79.19 74.67
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 151.00 m/2 max. CT eig. real: 1537.639211
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 79.72 74.35
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 152.00 m/2 max. CT eig. real: 1547.822253
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 80.25 74.03
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 153.00 m/2 max. CT eig. real: 1558.005294
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 80.78 73.71
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 154.00 m/2 max. CT eig. real: 1568.188335
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 81.31 73.40
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 155.00 m/2 max. CT eig. real: 1578.371376
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 81.83 73.09
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 156.00 m/2 max. CT eig. real: 1588.554417
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 82.36 72.78
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 157.00 m/2 max. CT eig. real: 1598.737458
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 82.89 72.49
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 158.00 m/2 max. CT eig. real: 1608.920500
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 83.42 72.19
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 159.00 m/2 max. CT eig. real: 1619.103541
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 83.95 71.91
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 160.00 m/2 max. CT eig. real: 1629.286582
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 84.47 71.64
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 161.00 m/2 max. CT eig. real: 1639.469623
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 85.00 71.37
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 162.00 m/2 max. CT eig. real: 1649.652664
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 85.53 71.12
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 163.00 m/2 max. CT eig. real: 1659.835706
N unstab.: 002
Unstable aeroelastic natural frequency CT(rad/s): 86.06 70.87
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 164.00 m/2 max. CT eig. real: 1670.018747
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 86.59 70.64 70.64 56.53
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 165.00 m/2 max. CT eig. real: 1680.201788
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 87.11 70.41 70.41 56.63
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 166.00 m/2 max. CT eig. real: 1690.384829
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 87.64 70.20 70.20 56.73
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 167.00 m/2 max. CT eig. real: 1700.567870
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 88.17 69.99 69.99 56.82
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 168.00 m/2 max. CT eig. real: 1710.750911
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 88.70 69.79 69.79 56.90
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 169.00 m/2 max. CT eig. real: 1720.933953
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 89.23 69.61 69.61 56.97
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 170.00 m/2 max. CT eig. real: 1731.116994
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 89.75 69.43 69.43 57.04
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 171.00 m/2 max. CT eig. real: 1741.300035
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 90.28 69.26 69.26 57.10
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 172.00 m/2 max. CT eig. real: 1751.483076
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 90.81 69.10 69.10 57.16
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 173.00 m/2 max. CT eig. real: 1761.666117
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 91.34 68.94 68.94 57.21
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 174.00 m/2 max. CT eig. real: 1771.849159
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 91.87 68.79 68.79 57.25
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 175.00 m/2 max. CT eig. real: 1782.032200
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 92.39 68.65 68.65 57.29
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 176.00 m/2 max. CT eig. real: 1792.215241
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 92.92 68.51 68.51 57.33
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 177.00 m/2 max. CT eig. real: 1802.398282
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 93.45 68.38 68.38 57.36
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 178.00 m/2 max. CT eig. real: 1812.581323
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 93.98 68.25 68.25 57.39
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 179.00 m/2 max. CT eig. real: 1822.764364
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 94.51 68.13 68.13 57.41
Updating C and K matrices and natural frequencies with new normalised time...
LTI u: 180.00 m/2 max. CT eig. real: 1832.947406
N unstab.: 004
Unstable aeroelastic natural frequency CT(rad/s): 95.03 68.01 68.01 57.43
Saving velocity analysis results...
Successful
FINISHED - Elapsed time = 87.4548716 seconds
FINISHED - CPU process time = 158.0786466 seconds
/home/ng213/code/sharpy/sharpy/postproc/asymptoticstability.py:171: UserWarning: Plotting modes is under development
warn.warn('Plotting modes is under development')
[17]:
<sharpy.presharpy.presharpy.PreSharpy at 0x7f94ae37cf28>
Analysis¶
The nonlinear equilibrium condition can be visualised and analysed by opening, with Paraview, the files in the /output/<case_name>/aero
and /output/<case_name>/beam
folders to see the deflection and aerodynamic forces acting
The stability of the Goland wing is now analysed under changing free stream velocity. The aeroelastic system is projected onto 2 structural modes (1st bending and 1st torsion). The two modes are seen quite separated at 100 m/s. As speed is increased, the damping of the torsion mode decreases until it crosses the imaginary axis onto the right hand plane and flutter begins. This flutter mode is a bending-torsion mode, as seen from the natural frequency plot where the frequencies of each coalesce into this mode.
[18]:
file_name = './output/%s/stability/velocity_analysis_min1000_max1800_nvel0081.dat' % case_name
velocity_analysis = np.loadtxt(file_name)
u_inf = velocity_analysis[:, 0]
eigs_r = velocity_analysis[:, 1]
eigs_i = velocity_analysis[:, 2]
[19]:
fig = plt.figure()
plt.scatter(eigs_r, eigs_i, c=u_inf, cmap='Blues')
cbar = plt.colorbar()
cbar.set_label('Free Stream Velocity, $u_\infty$ [m/s]')
plt.grid()
plt.xlim(-10, 10)
plt.ylim(-150, 150)
plt.xlabel('Real Part, $\lambda$ [rad/s]')
plt.ylabel('Imag Part, $\lambda$ [rad/s]');

[20]:
fig = plt.figure()
natural_frequency = np.sqrt(eigs_r ** 2 + eigs_i ** 2)
damping_ratio = eigs_r / natural_frequency
cond = (eigs_r>-25) * (eigs_r<10) * (natural_frequency<100) # filter unwanted eigenvalues for this plot (mostly aero modes)
plt.scatter(u_inf[cond], damping_ratio[cond], color='k', marker='s', s=9)
plt.grid()
plt.ylim(-0.25, 0.25)
plt.xlabel('Free Stream Velocity, $u_\infty$ [m/s]')
plt.ylabel('Damping Ratio, $\zeta$ [-]');

[21]:
fig = plt.figure()
cond = (eigs_r>-25) * (eigs_r<10) # filter unwanted eigenvalues for this plot (mostly aero modes)
plt.scatter(u_inf[cond], natural_frequency[cond], color='k', marker='s', s=9)
plt.grid()
plt.ylim(40, 100)
plt.xlabel('Free Stream Velocity, $u_\infty$ [m/s]')
plt.ylabel('Natural Frequency, $\omega_n$ [rad/s]');

[1]:
%load_ext autoreload
%autoreload 2
%matplotlib inline
%config InlineBackend.figure_format = 'svg'
import numpy as np
import matplotlib.pyplot as plt
from IPython.display import Image
T-Tail HALE Model tutorial¶
The HALE T-Tail model intends to be a representative example of a typical HALE configuration, with high flexibility and aspect-ratio.
A geometry outline and a summary of the beam properties are given next
[2]:
url = 'https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/dev_doc/docs/source/content/example_notebooks/images/t-tail_geometry.png'
Image(url=url, width=800)
[2]:

[3]:
url = 'https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/dev_doc/docs/source/content/example_notebooks/images/t-tail_properties.png'
Image(url=url, width=500)
[3]:

This case is included in tests/coupled/simple_HALE/
. The generate_hale.py
file in that folder is the one that, if executed, generates all the required SHARPy files. This document is a step by step guide to how to process that case.
The T-Tail HALE model is subject to a 20% 1-cos spanwise constant gust.
First, let’s start with importing SHARPy in our Python environment.
[4]:
import sharpy
import sharpy.sharpy_main as sharpy_main
And now the generate_HALE.py
file needs to be executed.
[5]:
route_to_case = '../../../../cases/coupled/simple_HALE/'
%run '../../../../cases/coupled/simple_HALE/generate_hale.py'
There should be 3 new files, apart from the original generate_hale.py
:
[6]:
!ls ../../../../cases/coupled/simple_HALE/
generate_hale.py simple_HALE.aero.h5 simple_HALE.fem.h5 simple_HALE.sharpy
SHARPy can be run now. In the terminal, doing cd
to the simple_HALE
folder, the command would look like:
sharpy simple_HALE.sharpy
From a python console with import sharpy
already run, the command is:
[7]:
case_data = sharpy_main.main(['', route_to_case + 'simple_HALE.sharpy'])
/home/ad214/run/code_doc/sharpy/sharpy/aero/utils/uvlmlib.py:230: RuntimeWarning: invalid value encountered in true_divide
flightconditions.uinf_direction = np.ctypeslib.as_ctypes(ts_info.u_ext[0][:, 0, 0]/flightconditions.uinf)
/home/ad214/run/code_doc/sharpy/sharpy/aero/utils/uvlmlib.py:347: RuntimeWarning: invalid value encountered in true_divide
flightconditions.uinf_direction = np.ctypeslib.as_ctypes(ts_info.u_ext[0][:, 0, 0]/flightconditions.uinf)
The resulting data structure that is returned from the call to main
contains all the time-dependant variables for both the structural and aerodynamic solvers.
timestep_info
can be found in case_data.structure
and case_data.aero
. It is an array with custom-made structure to contain the data of each solver.
In the .sharpy
file, we can see which solvers are run:
flow = ['BeamLoader',
'AerogridLoader',
'StaticTrim',
'BeamLoads',
'AerogridPlot',
'BeamPlot',
'DynamicCoupled',
]
In order:
BeamLoader: reads the
fem.h5
file and generates the structure for the beam solver.AerogridLoader: reads the
aero.h5
file and generates the aerodynamic grid for the aerodynamic solver.StaticTrim: this solver performs a longitudinal trim (Thrust, Angle of attack and Elevator deflection) using the StaticCoupled solver.
BeamLoads: calculates the internal beam loads for the static solution
AerogridPlot: outputs the aerodynamic grid for the static solution.
BeamPlot: outputs the structural discretisation for the static solution.
DynamicCoupled: is the main driver of the dynamic simulation: executes the structural and aerodynamic solvers and couples both. Every converged time step is followed by a BeamLoads, AerogridPlot and BeamPlot execution.
Structural data organisation¶
The timestep_info
structure contains several relevant variables:
for_pos
: position of the body-attached frame of reference in inertial FoR.for_vel
: velocity (in body FoR) of the body FoR wrt inertial FoR.pos
: nodal position in A FoR.psi
: nodal rotations (from the material B FoR to A FoR) in a Cartesian Rotation Vector parametrisation.applied_steady_forces
: nodal forces from the aero solver and the applied forces.postproc_cell
: is a dictionary that contains the variables generated by a postprocessor, such as the internal beam loads.
The structural timestep_info
also contains some useful variables:
cag
andcga
return \(C^{AG}\) and \(C^{GA}\), the rotation matrices from the body-attached (A) FoR to the inertial (G).glob_pos
rotates thepos
variable to give you the inertial nodal position. Ifinclude_rbm = True
is passed,for_pos
is added to it.
Aerodynamic data organisation¶
The aerodynamic datastructure can be found in case_data.aero.timestep_info
. It contains useful variables, such as:
dimensions
anddimensions_star
: gives the dimensions of every surface and wake surface. Organised as:dimensions[i_surf, 0] = chordwise panels
,dimensions[i_surf, 1] = spanwise panels
.zeta
andzeta_star
: they are the \(G\) FoR coordinates of the surface vertices.gamma
andgamma_star
: vortex ring circulations.
Structural dynamics¶
We can now plot the rigid body dynamics:
RBM trajectory
[16]:
fig, ax = plt.subplots(1, 1, figsize=(7, 4))
# extract information
n_tsteps = len(case_data.structure.timestep_info)
xz = np.zeros((n_tsteps, 2))
for it in range(n_tsteps):
xz[it, 0] = -case_data.structure.timestep_info[it].for_pos[0] # the - is so that increasing time -> increasing x
xz[it, 1] = case_data.structure.timestep_info[it].for_pos[2]
ax.plot(xz[:, 0], xz[:, 1])
fig.suptitle('Longitudinal trajectory of the T-Tail model in a 20% 1-cos gust encounter')
ax.set_xlabel('X [m]')
ax.set_ylabel('Z [m]');
plt.show()
RBM velocities
[17]:
fig, ax = plt.subplots(3, 1, figsize=(7, 6), sharex=True)
ylabels = ['Vx [m/s]', 'Vy [m/s]', 'Vz [m/s]']
# extract information
n_tsteps = len(case_data.structure.timestep_info)
dt = case_data.settings['DynamicCoupled']['dt'].value
time_vec = np.linspace(0, n_tsteps*dt, n_tsteps)
for_vel = np.zeros((n_tsteps, 3))
for it in range(n_tsteps):
for_vel[it, 0:3] = case_data.structure.timestep_info[it].for_vel[0:3]
for idim in range(3):
ax[idim].plot(time_vec, for_vel[:, idim])
ax[idim].set_ylabel(ylabels[idim])
ax[2].set_xlabel('time [s]')
plt.subplots_adjust(hspace=0)
fig.suptitle('Linear RBM velocities. T-Tail model in a 20% 1-cos gust encounter');
# ax.set_xlabel('X [m]')
# ax.set_ylabel('Z [m]');
plt.show()
[18]:
fig, ax = plt.subplots(3, 1, figsize=(7, 6), sharex=True)
ylabels = ['Roll rate [deg/s]', 'Pitch rate [deg/s]', 'Yaw rate [deg/s]']
# extract information
n_tsteps = len(case_data.structure.timestep_info)
dt = case_data.settings['DynamicCoupled']['dt'].value
time_vec = np.linspace(0, n_tsteps*dt, n_tsteps)
for_vel = np.zeros((n_tsteps, 3))
for it in range(n_tsteps):
for_vel[it, 0:3] = case_data.structure.timestep_info[it].for_vel[3:6]*180/np.pi
for idim in range(3):
ax[idim].plot(time_vec, for_vel[:, idim])
ax[idim].set_ylabel(ylabels[idim])
ax[2].set_xlabel('time [s]')
plt.subplots_adjust(hspace=0)
fig.suptitle('Angular RBM velocities. T-Tail model in a 20% 1-cos gust encounter');
# ax.set_xlabel('X [m]')
# ax.set_ylabel('Z [m]');
plt.show()
Wing tip deformation
It is stored in timestep_info
as pos
. We need to find the correct node.
[19]:
fig, ax = plt.subplots(1, 1, figsize=(6, 6))
ax.scatter(case_data.structure.ini_info.pos[:, 0], case_data.structure.ini_info.pos[:, 1])
ax.axis('equal')
tip_node = np.argmax(case_data.structure.ini_info.pos[:, 1])
print('Wing tip node is the maximum Y one: ', tip_node)
ax.scatter(case_data.structure.ini_info.pos[tip_node, 0], case_data.structure.ini_info.pos[tip_node, 1], color='red')
plt.show()
Wing tip node is the maximum Y one: 16
We can plot now the pos[tip_node,:]
variable:
[20]:
fig, ax = plt.subplots(1, 1, figsize=(7, 3))
# extract information
n_tsteps = len(case_data.structure.timestep_info)
xz = np.zeros((n_tsteps, 2))
for it in range(n_tsteps):
xz[it, 0] = case_data.structure.timestep_info[it].pos[tip_node, 0]
xz[it, 1] = case_data.structure.timestep_info[it].pos[tip_node, 2]
ax.plot(time_vec, xz[:, 1])
# fig.suptitle('Longitudinal trajectory of the T-Tail model in a 20% 1-cos gust encounter')
ax.set_xlabel('time [s]')
ax.set_ylabel('Vertical disp. [m]');
plt.show()
[21]:
fig, ax = plt.subplots(1, 1, figsize=(7, 3))
# extract information
n_tsteps = len(case_data.structure.timestep_info)
xz = np.zeros((n_tsteps, 2))
for it in range(n_tsteps):
xz[it, 0] = case_data.structure.timestep_info[it].pos[tip_node, 0]
xz[it, 1] = case_data.structure.timestep_info[it].pos[tip_node, 2]
ax.plot(time_vec, xz[:, 0])
# fig.suptitle('Longitudinal trajectory of the T-Tail model in a 20% 1-cos gust encounter')
ax.set_xlabel('time [s]')
ax.set_ylabel('Horizontal disp. [m]\nPositive is aft');
plt.show()
Wing root loads
The wing root loads can be extracted from the postproc_cell
structure in timestep_info
.
[22]:
fig, ax = plt.subplots(3, 1, figsize=(7, 6), sharex=True)
ylabels = ['Torsion [Nm2]', 'OOP [Nm2]', 'IP [Nm2]']
# extract information
n_tsteps = len(case_data.structure.timestep_info)
dt = case_data.settings['DynamicCoupled']['dt'].value
time_vec = np.linspace(0, n_tsteps*dt, n_tsteps)
loads = np.zeros((n_tsteps, 3))
for it in range(n_tsteps):
loads[it, 0:3] = case_data.structure.timestep_info[it].postproc_cell['loads'][0, 3:6]
for idim in range(3):
ax[idim].plot(time_vec, loads[:, idim])
ax[idim].set_ylabel(ylabels[idim])
ax[2].set_xlabel('time [s]')
plt.subplots_adjust(hspace=0)
fig.suptitle('Wing root loads. T-Tail model in a 20% 1-cos gust encounter');
# ax.set_xlabel('X [m]')
# ax.set_ylabel('Z [m]');
plt.show()
Aerodynamic analysis¶
The aerodynamic analysis can be obviously conducted using python. However, the easiest way is to run the case by yourself and open the files in output/simple_HALE/beam
and output/simple_HALE/aero
with Paraview.
[23]:
url = 'https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/dev_doc/docs/source/content/example_notebooks/images/t-tail_solution.png'
Image(url=url, width=600)
[23]:

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',
'StabilityDerivatives',
]
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/' + ws.case_name + '/',
'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': ['']}
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'] = {'folder': './output/',
'include_rbm': 'off',
'include_applied_forces': 'on',
'minus_m_star': 0,
'u_inf': ws.u_inf
}
settings['AeroForcesCalculator'] = {'folder': './output/',
'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'] = {'folder': './output/',
'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',
'horseshoe': ws.horseshoe,
'num_cores': 4,
'n_rollup': 1,
'convection_scheme': ws.wake_type,
'rollup_dt': ws.dt,
'rollup_aic_refresh': 1,
'rollup_tolerance': 1e-4,
'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',
}
Modal Solver Settings¶
[12]:
settings['Modal'] = {'print_info': True,
'use_undamped_modes': True,
'NumLambda': 30,
'rigid_body_modes': True,
'write_modes_vtk': 'on',
'print_matrices': 'on',
'write_data': 'on',
'continuous_eigenvalues': 'off',
'dt': ws.dt,
'plot_eigenvalues': False,
'rigid_modes_cg': False}
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',
'rigid_body_motion': 'on',
'remove_inputs': ['u_gust']},
'rigid_body_motion': True,
'track_body': 'on',
'use_euler': 'on',
'linearisation_tstep': -1
}}
Asymptotic Stability Post-processor¶
[14]:
settings['AsymptoticStability'] = {
'print_info': 'on',
'frequency_cutoff': 0,
'export_eigenvalues': 'on',
'num_evals': 1000,
'folder': './output/'}
Stability Derivatives Post-processor¶
[15]:
settings['StabilityDerivatives'] = {'u_inf': ws.u_inf,
'S_ref': 12.809,
'b_ref': ws.span,
'c_ref': 0.719}
Write solver file¶
[16]:
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¶
[17]:
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/code/sharpy/docs/source/content/example_notebooks
SHARPy being run is in /home/ng213/code/sharpy
The branch being run is dev_examples
The version and commit hash are: v0.1-1590-g7385fe4-7385fe4
The available solvers on this session are:
PreSharpy
_BaseStructural
AerogridLoader
BeamLoader
DynamicCoupled
DynamicUVLM
LinDynamicSim
LinearAssembler
Modal
NoAero
NonLinearDynamic
NonLinearDynamicCoupledStep
NonLinearDynamicMultibody
NonLinearDynamicPrescribedStep
NonLinearStatic
NonLinearStaticMultibody
PrescribedUvlm
RigidDynamicPrescribedStep
SHWUvlm
StaticCoupled
StaticCoupledRBM
StaticTrim
StaticUvlm
StepLinearUVLM
StepUvlm
Trim
Cleanup
PickleData
SaveData
CreateSnapshot
PlotFlowField
StabilityDerivatives
AeroForcesCalculator
WriteVariablesTime
AerogridPlot
LiftDistribution
StallCheck
FrequencyResponse
AsymptoticStability
BeamPlot
BeamLoads
Generating an instance of BeamLoader
Generating an instance of AerogridLoader
Variable control_surface_deflection_generator_settings has no assigned value in the settings file.
will default to the value: []
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: c_bool(True)
Variable tail_cs_index has no assigned value in the settings file.
will default to the value: c_int(0)
Variable initial_angle_eps has no assigned value in the settings file.
will default to the value: c_double(0.05)
Variable initial_thrust_eps has no assigned value in the settings file.
will default to the value: c_double(2.0)
Variable relaxation_factor has no assigned value in the settings file.
will default to the value: c_double(0.2)
Generating an instance of StaticCoupled
Generating an instance of NonLinearStatic
Variable newmark_damp has no assigned value in the settings file.
will default to the value: c_double(0.0001)
Variable relaxation_factor has no assigned value in the settings file.
will default to the value: c_double(0.3)
Variable dt has no assigned value in the settings file.
will default to the value: c_double(0.01)
Variable num_steps has no assigned value in the settings file.
will default to the value: c_int(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: c_bool(False)
Variable iterative_tol has no assigned value in the settings file.
will default to the value: c_double(0.0001)
Variable iterative_precond has no assigned value in the settings file.
will default to the value: c_bool(False)
|=====|=====|============|==========|==========|==========|==========|==========|==========|
|iter |step | log10(res) | Fx | Fy | Fz | Mx | My | Mz |
|=====|=====|============|==========|==========|==========|==========|==========|==========|
|==========|==========|==========|==========|==========|==========|==========|==========|==========|==========|
| iter | alpha | elev | thrust | Fx | Fy | Fz | Mx | My | Mz |
|==========|==========|==========|==========|==========|==========|==========|==========|==========|==========|
| 0 | 0 | 0.00000 | -0.1051 | -0.0000 | 0.0604 | -0.0000 | 1.0816 | -0.0000 |
| 1 | 0 | -7.62661 | -0.1119 | 0.0000 | 0.1274 | -0.0000 | 0.0026 | 0.0000 |
| 2 | 0 | -8.34118 | -0.0941 | -0.0000 | 0.0393 | 0.0000 | -0.0793 | 0.0000 |
| 3 | 0 | -9.29266 | -0.0870 | 0.0000 | 0.0007 | -0.0000 | -0.0089 | 0.0000 |
| 4 | 0 | -10.67443 | -0.0876 | 0.0000 | 0.0028 | 0.0000 | -0.0119 | 0.0000 |
| 5 | 0 | -10.87008 | -0.0878 | 0.0000 | 0.0039 | -0.0000 | -0.0138 | 0.0000 |
| 6 | 0 | -11.64423 | -0.0877 | -0.0000 | 0.0037 | 0.0000 | -0.0135 | -0.0000 |
| 7 | 0 | -12.87835 | -0.0877 | 0.0000 | 0.0037 | -0.0000 | -0.0135 | 0.0000 |
| 0 | 4.5135 | 0.1814 | 5.5129 | -0.0877 | 0.0000 | 0.0037 | -0.0000 | -0.0135 | 0.0000 |
| 0 | 0 | 0.00000 |-116.9870 | -0.0000 | 994.8061 | -0.0000 |-882.4096 | 0.0000 |
| 1 | 0 | -5.81338 | -81.0252 | -0.0000 | 944.6090 | -0.0000 |-802.5942 | -0.0000 |
| 2 | 0 | -6.69380 | -74.1802 | -0.0000 | 937.6597 | -0.0000 |-792.1302 | 0.0000 |
| 3 | 0 | -7.20553 | -75.0015 | 0.0000 | 939.7800 | -0.0000 |-795.7138 | -0.0000 |
| 4 | 0 | -8.63165 | -74.9725 | 0.0000 | 939.7033 | -0.0000 |-795.5808 | 0.0000 |
| 5 | 0 | -8.79020 | -74.9511 | 0.0000 | 939.6488 | 0.0000 |-795.4881 | 0.0000 |
| 6 | 0 | -9.56992 | -74.9546 | -0.0000 | 939.6578 | 0.0000 |-795.5035 | -0.0000 |
| 7 | 0 | -10.77969 | -74.9549 | 0.0000 | 939.6584 | -0.0000 |-795.5044 | 0.0000 |
| 8 | 0 | -10.98913 | -74.9547 | -0.0000 | 939.6580 | 0.0000 |-795.5039 | -0.0000 |
| 9 | 0 | -12.12706 | -74.9547 | -0.0000 | 939.6581 | 0.0000 |-795.5039 | -0.0000 |
| 0 | 7.3783 | -2.6834 | 5.5129 | -74.9547 | -0.0000 | 939.6581 | 0.0000 |-795.5039 | -0.0000 |
| 0 | 0 | 0.00000 | -32.9132 | -0.0000 | 371.4719 | -0.0000 |-902.7965 | -0.0000 |
| 1 | 0 | -5.48782 | -11.8207 | 0.0000 | 298.8468 | -0.0000 |-777.2958 | 0.0000 |
| 2 | 0 | -6.40702 | -8.5206 | 0.0000 | 289.8069 | -0.0000 |-761.4879 | -0.0000 |
| 3 | 0 | -6.85006 | -9.2671 | -0.0000 | 293.2383 | 0.0000 |-767.3401 | -0.0000 |
| 4 | 0 | -8.25284 | -9.2365 | 0.0000 | 293.1025 | -0.0000 |-767.1091 | 0.0000 |
| 5 | 0 | -8.43408 | -9.2166 | 0.0000 | 293.0132 | 0.0000 |-766.9570 | 0.0000 |
| 6 | 0 | -9.20313 | -9.2199 | -0.0000 | 293.0284 | -0.0000 |-766.9829 | -0.0000 |
| 7 | 0 | -10.44114 | -9.2201 | 0.0000 | 293.0293 | -0.0000 |-766.9844 | 0.0000 |
| 8 | 0 | -10.62337 | -9.2200 | -0.0000 | 293.0287 | 0.0000 |-766.9834 | -0.0000 |
| 9 | 0 | -11.73764 | -9.2200 | -0.0000 | 293.0287 | 0.0000 |-766.9835 | -0.0000 |
| 10 | 0 | -12.29756 | -9.2200 | 0.0000 | 293.0287 | -0.0000 |-766.9835 | 0.0000 |
| 0 | 4.5135 | 3.0462 | 5.5129 | -9.2200 | 0.0000 | 293.0287 | -0.0000 |-766.9835 | 0.0000 |
| 0 | 0 | 0.00000 | -4.1051 | -0.0000 | 0.0604 | -0.0000 | 1.0812 | -0.0000 |
| 1 | 0 | -7.62660 | -4.1120 | -0.0000 | 0.1274 | -0.0000 | 0.0023 | -0.0000 |
| 2 | 0 | -8.34116 | -4.0942 | -0.0000 | 0.0393 | 0.0000 | -0.0796 | -0.0000 |
| 3 | 0 | -9.29268 | -4.0871 | 0.0000 | 0.0007 | -0.0000 | -0.0093 | 0.0000 |
| 4 | 0 | -10.67446 | -4.0876 | 0.0000 | 0.0028 | 0.0000 | -0.0123 | 0.0000 |
| 5 | 0 | -10.86979 | -4.0878 | 0.0000 | 0.0039 | -0.0000 | -0.0142 | 0.0000 |
| 6 | 0 | -11.64229 | -4.0878 | 0.0000 | 0.0037 | -0.0000 | -0.0138 | 0.0000 |
| 7 | 0 | -12.86703 | -4.0878 | 0.0000 | 0.0037 | -0.0000 | -0.0138 | 0.0000 |
| 0 | 4.5135 | 0.1814 | 7.5129 | -4.0878 | 0.0000 | 0.0037 | -0.0000 | -0.0138 | 0.0000 |
| 0 | 0 | 0.00000 | -0.0165 | 0.0000 | 0.0499 | 0.0000 | 1.1009 | 0.0000 |
| 1 | 0 | -7.62629 | -0.0236 | 0.0000 | 0.1184 | 0.0000 | 0.0195 | 0.0000 |
| 2 | 0 | -8.34096 | -0.0058 | -0.0000 | 0.0305 | -0.0000 | -0.0628 | -0.0000 |
| 3 | 0 | -9.29199 | 0.0012 | 0.0000 | -0.0082 | 0.0000 | 0.0077 | 0.0000 |
| 4 | 0 | -10.67407 | 0.0007 | 0.0000 | -0.0061 | -0.0000 | 0.0047 | 0.0000 |
| 5 | 0 | -10.86912 | 0.0005 | -0.0000 | -0.0050 | 0.0000 | 0.0028 | -0.0000 |
| 6 | 0 | -11.64225 | 0.0005 | 0.0000 | -0.0052 | -0.0000 | 0.0031 | 0.0000 |
| 7 | 0 | -12.83721 | 0.0005 | -0.0000 | -0.0052 | 0.0000 | 0.0032 | -0.0000 |
| 1 | 4.5135 | 0.1814 | 5.4690 | 0.0005 | -0.0000 | -0.0052 | 0.0000 | 0.0032 | -0.0000 |
Generating an instance of BeamPlot
Variable include_applied_moments has no assigned value in the settings file.
will default to the value: c_bool(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: c_bool(True)
...Finished
Generating an instance of AerogridPlot
Variable include_forward_motion has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable include_unsteady_applied_forces has no assigned value in the settings file.
will default to the value: c_bool(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: c_double(0.0)
Variable include_velocities has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable num_cores has no assigned value in the settings file.
will default to the value: c_int(1)
...Finished
Generating an instance of AeroForcesCalculator
--------------------------------------------------------------------------------
tstep | fx_g | fy_g | fz_g | Cfx_g | Cfy_g | Cfz_g
0 | 1.090e+01 | -1.250e-07 | 1.835e+03 | 2.129e-03 | -2.441e-11 | 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: c_int(0)
Variable dynamic_relaxation has no assigned value in the settings file.
will default to the value: c_bool(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: c_bool(False)
Variable steps_without_unsteady_force has no assigned value in the settings file.
will default to the value: c_int(0)
Variable pseudosteps_ramp_unsteady_force has no assigned value in the settings file.
will default to the value: c_int(0)
Generating an instance of NonLinearDynamicCoupledStep
Variable num_load_steps has no assigned value in the settings file.
will default to the value: c_int(1)
Variable relaxation_factor has no assigned value in the settings file.
will default to the value: c_double(0.3)
Variable balancing has no assigned value in the settings file.
will default to the value: c_bool(False)
Generating an instance of StepUvlm
Variable iterative_solver has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable iterative_tol has no assigned value in the settings file.
will default to the value: c_double(0.0001)
Variable iterative_precond has no assigned value in the settings file.
will default to the value: c_bool(False)
|=======|========|======|==============|==============|==============|==============|==============|
| ts | t | iter | struc ratio | iter time | residual vel | FoR_vel(x) | FoR_vel(z) |
|=======|========|======|==============|==============|==============|==============|==============|
/home/ng213/code/sharpy/sharpy/aero/utils/uvlmlib.py:230: 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.652648 | 0.921936 | -10.549271 |-2.791317e+01 |-2.203427e+00 |
...Finished
Generating an instance of Modal
Variable folder has no assigned value in the settings file.
will default to the value: ./output
Variable keep_linear_matrices has no assigned value in the settings file.
will default to the value: c_bool(True)
Variable write_dat has no assigned value in the settings file.
will default to the value: c_bool(True)
Variable delta_curved has no assigned value in the settings file.
will default to the value: c_double(0.01)
Variable max_rotation_deg has no assigned value in the settings file.
will default to the value: c_double(15.0)
Variable max_displacement has no assigned value in the settings file.
will default to the value: c_double(0.15)
Variable use_custom_timestep has no assigned value in the settings file.
will default to the value: c_int(-1)
Structural eigenvalues
|==============|==============|==============|==============|==============|==============|==============|
| mode | eval_real | eval_imag | freq_n (Hz) | freq_d (Hz) | damping | period (s) |
|==============|==============|==============|==============|==============|==============|==============|
/home/ng213/code/sharpy/sharpy/solvers/modal.py:284: UserWarning: Projecting a system with damping on undamped modal shapes
'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: c_int(-1)
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 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
Initialising Static linear UVLM solver class...
...done in 0.27 sec
State-space realisation of UVLM equations started...
state-space model produced in form:
x_{n+1} = A x_{n} + Bp u_{n+1}
...done in 2.44 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
Generating an instance of AsymptoticStability
Variable reference_velocity has no assigned value in the settings file.
will default to the value: c_double(1.0)
Variable display_root_locus has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable velocity_analysis has no assigned value in the settings file.
will default to the value: []
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
|==============|==============|==============|==============|==============|==============|==============|
| 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.321695 | 0.051200 | 0.051199 | 0.002749 | 19.531499 |
| 11 | -0.000884 | -0.321695 | 0.051200 | 0.051199 | 0.002749 | 19.531499 |
| 12 | -0.008471 | -0.391290 | 0.062290 | 0.062276 | 0.021644 | 16.057627 |
| 13 | -0.008471 | 0.391290 | 0.062290 | 0.062276 | 0.021644 | 16.057627 |
| 14 | -0.022506 | 0.000000 | 0.003582 | 0.000000 | 1.000000 | inf |
| 15 | -0.064807 | -53.732340 | 8.551774 | 8.551767 | 0.001206 | 0.116935 |
| 16 | -0.064807 | 53.732340 | 8.551774 | 8.551767 | 0.001206 | 0.116935 |
| 17 | -0.101946 | 68.319126 | 10.873339 | 10.873327 | 0.001492 | 0.091968 |
| 18 | -0.101946 | -68.319126 | 10.873339 | 10.873327 | 0.001492 | 0.091968 |
| 19 | -0.147587 | 83.265087 | 13.252071 | 13.252050 | 0.001772 | 0.075460 |
| 20 | -0.147587 | -83.265087 | 13.252071 | 13.252050 | 0.001772 | 0.075460 |
| 21 | -0.248703 | 109.925761 | 17.495273 | 17.495228 | 0.002262 | 0.057158 |
| 22 | -0.248703 | -109.925761 | 17.495273 | 17.495228 | 0.002262 | 0.057158 |
| 23 | -0.293471 | -120.387486 | 19.160320 | 19.160263 | 0.002438 | 0.052191 |
| 24 | -0.293471 | 120.387486 | 19.160320 | 19.160263 | 0.002438 | 0.052191 |
| 25 | -0.350319 | -132.903267 | 21.152285 | 21.152212 | 0.002636 | 0.047276 |
| 26 | -0.350319 | 132.903267 | 21.152285 | 21.152212 | 0.002636 | 0.047276 |
| 27 | -0.376400 | -138.516845 | 22.045722 | 22.045641 | 0.002717 | 0.045360 |
| 28 | -0.376400 | 138.516845 | 22.045722 | 22.045641 | 0.002717 | 0.045360 |
| 29 | -0.494445 | -162.714219 | 25.896892 | 25.896772 | 0.003039 | 0.038615 |
| 30 | -0.494445 | 162.714219 | 25.896892 | 25.896772 | 0.003039 | 0.038615 |
| 31 | -0.511650 | 166.238203 | 26.457757 | 26.457632 | 0.003078 | 0.037796 |
| 32 | -0.511650 | -166.238203 | 26.457757 | 26.457632 | 0.003078 | 0.037796 |
| 33 | -0.559180 | 175.709808 | 27.965226 | 27.965084 | 0.003182 | 0.035759 |
| 34 | -0.559180 | -175.709808 | 27.965226 | 27.965084 | 0.003182 | 0.035759 |
| 35 | -0.569755 | -177.873185 | 28.309542 | 28.309397 | 0.003203 | 0.035324 |
| 36 | -0.569755 | 177.873185 | 28.309542 | 28.309397 | 0.003203 | 0.035324 |
| 37 | -0.669914 | -197.999013 | 31.512702 | 31.512522 | 0.003383 | 0.031733 |
| 38 | -0.669914 | 197.999013 | 31.512702 | 31.512522 | 0.003383 | 0.031733 |
| 39 | -0.678424 | -199.782668 | 31.796582 | 31.796399 | 0.003396 | 0.031450 |
| 40 | -0.678424 | 199.782668 | 31.796582 | 31.796399 | 0.003396 | 0.031450 |
| 41 | -0.715684 | -207.440558 | 33.015387 | 33.015190 | 0.003450 | 0.030289 |
| 42 | -0.715684 | 207.440558 | 33.015387 | 33.015190 | 0.003450 | 0.030289 |
| 43 | -0.721193 | -208.622990 | 33.203578 | 33.203380 | 0.003457 | 0.030117 |
| 44 | -0.721193 | 208.622990 | 33.203578 | 33.203380 | 0.003457 | 0.030117 |
| 45 | -0.796838 | -224.809925 | 35.779836 | 35.779611 | 0.003544 | 0.027949 |
| 46 | -0.796838 | 224.809925 | 35.779836 | 35.779611 | 0.003544 | 0.027949 |
| 47 | -0.801462 | -225.851206 | 35.945562 | 35.945336 | 0.003549 | 0.027820 |
| 48 | -0.801462 | 225.851206 | 35.945562 | 35.945336 | 0.003549 | 0.027820 |
| 49 | -0.823221 | -257.880049 | 41.043094 | 41.042885 | 0.003192 | 0.024365 |
| 50 | -0.823221 | 257.880049 | 41.043094 | 41.042885 | 0.003192 | 0.024365 |
| 51 | -0.829849 | 232.223375 | 36.959734 | 36.959498 | 0.003573 | 0.027057 |
| 52 | -0.829849 | -232.223375 | 36.959734 | 36.959498 | 0.003573 | 0.027057 |
| 53 | -0.833132 | 232.986709 | 37.081224 | 37.080986 | 0.003576 | 0.026968 |
| 54 | -0.833132 | -232.986709 | 37.081224 | 37.080986 | 0.003576 | 0.026968 |
| 55 | -0.837695 | 252.830753 | 40.239485 | 40.239264 | 0.003313 | 0.024851 |
| 56 | -0.837695 | -252.830753 | 40.239485 | 40.239264 | 0.003313 | 0.024851 |
| 57 | -0.843057 | 274.636583 | 43.709976 | 43.709770 | 0.003070 | 0.022878 |
| 58 | -0.843057 | -274.636583 | 43.709976 | 43.709770 | 0.003070 | 0.022878 |
| 59 | -0.855992 | 264.468482 | 42.091687 | 42.091466 | 0.003237 | 0.023758 |
| 60 | -0.855992 | -264.468482 | 42.091687 | 42.091466 | 0.003237 | 0.023758 |
| 61 | -0.864725 | 271.184097 | 43.160509 | 43.160289 | 0.003189 | 0.023169 |
| 62 | -0.864725 | -271.184097 | 43.160509 | 43.160289 | 0.003189 | 0.023169 |
| 63 | -0.871326 | -283.421753 | 45.108186 | 45.107973 | 0.003074 | 0.022169 |
| 64 | -0.871326 | 283.421753 | 45.108186 | 45.107973 | 0.003074 | 0.022169 |
| 65 | -0.878446 | -267.336880 | 42.548216 | 42.547986 | 0.003286 | 0.023503 |
| 66 | -0.878446 | 267.336880 | 42.548216 | 42.547986 | 0.003286 | 0.023503 |
| 67 | -0.882869 | -280.833492 | 44.696259 | 44.696038 | 0.003144 | 0.022373 |
| 68 | -0.882869 | 280.833492 | 44.696259 | 44.696038 | 0.003144 | 0.022373 |
| 69 | -0.884024 | 245.027541 | 38.997598 | 38.997344 | 0.003608 | 0.025643 |
| 70 | -0.884024 | -245.027541 | 38.997598 | 38.997344 | 0.003608 | 0.025643 |
| 71 | -0.886589 | -245.661872 | 39.098556 | 39.098301 | 0.003609 | 0.025577 |
| 72 | -0.886589 | 245.661872 | 39.098556 | 39.098301 | 0.003609 | 0.025577 |
| 73 | -0.891211 | 288.915187 | 45.982499 | 45.982280 | 0.003085 | 0.021748 |
| 74 | -0.891211 | -288.915187 | 45.982499 | 45.982280 | 0.003085 | 0.021748 |
| 75 | -0.908699 | 251.206722 | 39.981053 | 39.980792 | 0.003617 | 0.025012 |
| 76 | -0.908699 | -251.206722 | 39.981053 | 39.980792 | 0.003617 | 0.025012 |
| 77 | -0.910251 | 251.606123 | 40.044620 | 40.044358 | 0.003618 | 0.024972 |
| 78 | -0.910251 | -251.606123 | 40.044620 | 40.044358 | 0.003618 | 0.024972 |
| 79 | -0.914189 | -241.156654 | 38.381549 | 38.381274 | 0.003791 | 0.026054 |
| 80 | -0.914189 | 241.156654 | 38.381549 | 38.381274 | 0.003791 | 0.026054 |
| 81 | -0.915396 | 290.517028 | 46.237451 | 46.237221 | 0.003151 | 0.021628 |
| 82 | -0.915396 | -290.517028 | 46.237451 | 46.237221 | 0.003151 | 0.021628 |
| 83 | -0.933975 | 278.955366 | 44.397374 | 44.397125 | 0.003348 | 0.022524 |
| 84 | -0.933975 | -278.955366 | 44.397374 | 44.397125 | 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.700477 | 41.492042 | 41.491770 | 0.003623 | 0.024101 |
| 88 | -0.944542 | -260.700477 | 41.492042 | 41.491770 | 0.003623 | 0.024101 |
| 89 | -0.953005 | 294.814043 | 46.921357 | 46.921112 | 0.003233 | 0.021312 |
| 90 | -0.953005 | -294.814043 | 46.921357 | 46.921112 | 0.003233 | 0.021312 |
| 91 | -0.960628 | 295.652741 | 47.054843 | 47.054595 | 0.003249 | 0.021252 |
| 92 | -0.960628 | -295.652741 | 47.054843 | 47.054595 | 0.003249 | 0.021252 |
| 93 | -0.960976 | 265.315973 | 42.226626 | 42.226349 | 0.003622 | 0.023682 |
| 94 | -0.960976 | -265.315973 | 42.226626 | 42.226349 | 0.003622 | 0.023682 |
| 95 | -0.961740 | -300.017780 | 47.749558 | 47.749313 | 0.003206 | 0.020943 |
| 96 | -0.961740 | 300.017780 | 47.749558 | 47.749313 | 0.003206 | 0.020943 |
| 97 | -0.961940 | -265.596058 | 42.271203 | 42.270926 | 0.003622 | 0.023657 |
| 98 | -0.961940 | 265.596058 | 42.271203 | 42.270926 | 0.003622 | 0.023657 |
| 99 | -0.965384 | 266.582845 | 42.428256 | 42.427978 | 0.003621 | 0.023569 |
| 100 | -0.965384 | -266.582845 | 42.428256 | 42.427978 | 0.003621 | 0.023569 |
| 101 | -0.968899 | -235.916658 | 37.547619 | 37.547302 | 0.004107 | 0.026633 |
| 102 | -0.968899 | 235.916658 | 37.547619 | 37.547302 | 0.004107 | 0.026633 |
| 103 | -0.969126 | 301.069959 | 47.917020 | 47.916772 | 0.003219 | 0.020870 |
| 104 | -0.969126 | -301.069959 | 47.917020 | 47.916772 | 0.003219 | 0.020870 |
| 105 | -0.977774 | -281.665806 | 44.828775 | 44.828505 | 0.003471 | 0.022307 |
| 106 | -0.977774 | 281.665806 | 44.828775 | 44.828505 | 0.003471 | 0.022307 |
| 107 | -0.984431 | -272.268138 | 43.333103 | 43.332820 | 0.003616 | 0.023077 |
| 108 | -0.984431 | 272.268138 | 43.333103 | 43.332820 | 0.003616 | 0.023077 |
| 109 | -0.985003 | 251.399896 | 40.011843 | 40.011536 | 0.003918 | 0.024993 |
| 110 | -0.985003 | -251.399896 | 40.011843 | 40.011536 | 0.003918 | 0.024993 |
| 111 | -0.985198 | -272.494340 | 43.369105 | 43.368821 | 0.003615 | 0.023058 |
| 112 | -0.985198 | 272.494340 | 43.369105 | 43.368821 | 0.003615 | 0.023058 |
| 113 | -0.998111 | 276.558228 | 44.015896 | 44.015609 | 0.003609 | 0.022719 |
| 114 | -0.998111 | -276.558228 | 44.015896 | 44.015609 | 0.003609 | 0.022719 |
| 115 | -0.998802 | 276.771420 | 44.049826 | 44.049540 | 0.003609 | 0.022702 |
| 116 | -0.998802 | -276.771420 | 44.049826 | 44.049540 | 0.003609 | 0.022702 |
| 117 | -1.002609 | -296.732610 | 47.226731 | 47.226462 | 0.003379 | 0.021175 |
| 118 | -1.002609 | 296.732610 | 47.226731 | 47.226462 | 0.003379 | 0.021175 |
| 119 | -1.006593 | -246.344800 | 39.207320 | 39.206993 | 0.004086 | 0.025506 |
| 120 | -1.006593 | 246.344800 | 39.207320 | 39.206993 | 0.004086 | 0.025506 |
| 121 | -1.012564 | -297.793229 | 47.395538 | 47.395264 | 0.003400 | 0.021099 |
| 122 | -1.012564 | 297.793229 | 47.395538 | 47.395264 | 0.003400 | 0.021099 |
| 123 | -1.014283 | 306.354455 | 48.758093 | 48.757826 | 0.003311 | 0.020510 |
| 124 | -1.014283 | -306.354455 | 48.758093 | 48.757826 | 0.003311 | 0.020510 |
| 125 | -1.014361 | 281.941928 | 44.872742 | 44.872451 | 0.003598 | 0.022285 |
| 126 | -1.014361 | -281.941928 | 44.872742 | 44.872451 | 0.003598 | 0.022285 |
| 127 | -1.014860 | 282.102785 | 44.898343 | 44.898053 | 0.003597 | 0.022273 |
| 128 | -1.014860 | -282.102785 | 44.898343 | 44.898053 | 0.003597 | 0.022273 |
| 129 | -1.017175 | -306.227153 | 48.737834 | 48.737565 | 0.003322 | 0.020518 |
| 130 | -1.017175 | 306.227153 | 48.737834 | 48.737565 | 0.003322 | 0.020518 |
| 131 | -1.017450 | 57.533524 | 9.158176 | 9.156745 | 0.017682 | 0.109209 |
| 132 | -1.017450 | -57.533524 | 9.158176 | 9.156745 | 0.017682 | 0.109209 |
| 133 | -1.021012 | 310.599833 | 49.433766 | 49.433499 | 0.003287 | 0.020229 |
| 134 | -1.021012 | -310.599833 | 49.433766 | 49.433499 | 0.003287 | 0.020229 |
| 135 | -1.021452 | 310.492397 | 49.416667 | 49.416400 | 0.003290 | 0.020236 |
| 136 | -1.021452 | -310.492397 | 49.416667 | 49.416400 | 0.003290 | 0.020236 |
| 137 | -1.022875 | -284.908060 | 45.344818 | 45.344526 | 0.003590 | 0.022053 |
| 138 | -1.022875 | 284.908060 | 45.344818 | 45.344526 | 0.003590 | 0.022053 |
| 139 | -1.023294 | 285.048653 | 45.367195 | 45.366902 | 0.003590 | 0.022043 |
| 140 | -1.023294 | -285.048653 | 45.367195 | 45.366902 | 0.003590 | 0.022043 |
| 141 | -1.036388 | -289.874565 | 46.135265 | 46.134970 | 0.003575 | 0.021676 |
| 142 | -1.036388 | 289.874565 | 46.135265 | 46.134970 | 0.003575 | 0.021676 |
| 143 | -1.036747 | -290.000394 | 46.155291 | 46.154996 | 0.003575 | 0.021666 |
| 144 | -1.036747 | 290.000394 | 46.155291 | 46.154996 | 0.003575 | 0.021666 |
| 145 | -1.040407 | 291.418922 | 46.381058 | 46.380762 | 0.003570 | 0.021561 |
| 146 | -1.040407 | -291.418922 | 46.381058 | 46.380762 | 0.003570 | 0.021561 |
| 147 | -1.040753 | 291.545493 | 46.401202 | 46.400906 | 0.003570 | 0.021551 |
| 148 | -1.040753 | -291.545493 | 46.401202 | 46.400906 | 0.003570 | 0.021551 |
| 149 | -1.041948 | 304.815949 | 48.513248 | 48.512965 | 0.003418 | 0.020613 |
| 150 | -1.041948 | -304.815949 | 48.513248 | 48.512965 | 0.003418 | 0.020613 |
| 151 | -1.042964 | -314.673618 | 50.082137 | 50.081862 | 0.003314 | 0.019967 |
| 152 | -1.042964 | 314.673618 | 50.082137 | 50.081862 | 0.003314 | 0.019967 |
| 153 | -1.043286 | -307.905151 | 49.004908 | 49.004627 | 0.003388 | 0.020406 |
| 154 | -1.043286 | 307.905151 | 49.004908 | 49.004627 | 0.003388 | 0.020406 |
| 155 | -1.044327 | 308.342971 | 49.074590 | 49.074308 | 0.003387 | 0.020377 |
| 156 | -1.044327 | -308.342971 | 49.074590 | 49.074308 | 0.003387 | 0.020377 |
| 157 | -1.046009 | -304.875396 | 48.522712 | 48.522426 | 0.003431 | 0.020609 |
| 158 | -1.046009 | 304.875396 | 48.522712 | 48.522426 | 0.003431 | 0.020609 |
| 159 | -1.047589 | 314.548401 | 50.062210 | 50.061933 | 0.003330 | 0.019975 |
| 160 | -1.047589 | -314.548401 | 50.062210 | 50.061933 | 0.003330 | 0.019975 |
| 161 | -1.049126 | -306.882777 | 48.842196 | 48.841911 | 0.003419 | 0.020474 |
| 162 | -1.049126 | 306.882777 | 48.842196 | 48.841911 | 0.003419 | 0.020474 |
| 163 | -1.050232 | 295.362748 | 47.008739 | 47.008441 | 0.003556 | 0.021273 |
| 164 | -1.050232 | -295.362748 | 47.008739 | 47.008441 | 0.003556 | 0.021273 |
| 165 | -1.050553 | -295.497323 | 47.030157 | 47.029860 | 0.003555 | 0.021263 |
| 166 | -1.050553 | 295.497323 | 47.030157 | 47.029860 | 0.003555 | 0.021263 |
| 167 | -1.051548 | -295.907799 | 47.095486 | 47.095189 | 0.003554 | 0.021234 |
| 168 | -1.051548 | 295.907799 | 47.095486 | 47.095189 | 0.003554 | 0.021234 |
| 169 | -1.051948 | 296.064745 | 47.120465 | 47.120168 | 0.003553 | 0.021222 |
| 170 | -1.051948 | -296.064745 | 47.120465 | 47.120168 | 0.003553 | 0.021222 |
| 171 | -1.054264 | -306.923573 | 48.848692 | 48.848404 | 0.003435 | 0.020471 |
| 172 | -1.054264 | 306.923573 | 48.848692 | 48.848404 | 0.003435 | 0.020471 |
| 173 | -1.054520 | -318.465849 | 50.685692 | 50.685414 | 0.003311 | 0.019730 |
| 174 | -1.054520 | 318.465849 | 50.685692 | 50.685414 | 0.003311 | 0.019730 |
| 175 | -1.055288 | -318.515081 | 50.693528 | 50.693250 | 0.003313 | 0.019726 |
| 176 | -1.055288 | 318.515081 | 50.693528 | 50.693250 | 0.003313 | 0.019726 |
| 177 | -1.057440 | 314.897307 | 50.117746 | 50.117463 | 0.003358 | 0.019953 |
| 178 | -1.057440 | -314.897307 | 50.117746 | 50.117463 | 0.003358 | 0.019953 |
| 179 | -1.058199 | -309.920136 | 49.325609 | 49.325322 | 0.003414 | 0.020274 |
| 180 | -1.058199 | 309.920136 | 49.325609 | 49.325322 | 0.003414 | 0.020274 |
| 181 | -1.059262 | 299.214097 | 47.621701 | 47.621403 | 0.003540 | 0.020999 |
| 182 | -1.059262 | -299.214097 | 47.621701 | 47.621403 | 0.003540 | 0.020999 |
| 183 | -1.059504 | -299.314232 | 47.637638 | 47.637340 | 0.003540 | 0.020992 |
| 184 | -1.059504 | 299.314232 | 47.637638 | 47.637340 | 0.003540 | 0.020992 |
| 185 | -1.060555 | -299.787498 | 47.712961 | 47.712662 | 0.003538 | 0.020959 |
| 186 | -1.060555 | 299.787498 | 47.712961 | 47.712662 | 0.003538 | 0.020959 |
| 187 | -1.060658 | -309.965877 | 49.332890 | 49.332602 | 0.003422 | 0.020271 |
| 188 | -1.060658 | 309.965877 | 49.332890 | 49.332602 | 0.003422 | 0.020271 |
| 189 | -1.060760 | 299.897460 | 47.730462 | 47.730163 | 0.003537 | 0.020951 |
| 190 | -1.060760 | -299.897460 | 47.730462 | 47.730163 | 0.003537 | 0.020951 |
| 191 | -1.064660 | 315.237918 | 50.171959 | 50.171673 | 0.003377 | 0.019932 |
| 192 | -1.064660 | -315.237918 | 50.171959 | 50.171673 | 0.003377 | 0.019932 |
| 193 | -1.065948 | -313.067380 | 49.826510 | 49.826221 | 0.003405 | 0.020070 |
| 194 | -1.065948 | 313.067380 | 49.826510 | 49.826221 | 0.003405 | 0.020070 |
| 195 | -1.066182 | 312.991749 | 49.814473 | 49.814184 | 0.003406 | 0.020075 |
| 196 | -1.066182 | -312.991749 | 49.814473 | 49.814184 | 0.003406 | 0.020075 |
| 197 | -1.070206 | 304.267646 | 48.425999 | 48.425700 | 0.003517 | 0.020650 |
| 198 | -1.070206 | -304.267646 | 48.425999 | 48.425700 | 0.003517 | 0.020650 |
| 199 | -1.070296 | 304.308945 | 48.432572 | 48.432273 | 0.003517 | 0.020647 |
| 200 | -1.070296 | -304.308945 | 48.432572 | 48.432273 | 0.003517 | 0.020647 |
| 201 | -1.071416 | -304.858400 | 48.520021 | 48.519721 | 0.003514 | 0.020610 |
| 202 | -1.071416 | 304.858400 | 48.520021 | 48.519721 | 0.003514 | 0.020610 |
| 203 | -1.071537 | -304.918001 | 48.529507 | 48.529207 | 0.003514 | 0.020606 |
| 204 | -1.071537 | 304.918001 | 48.529507 | 48.529207 | 0.003514 | 0.020606 |
| 205 | -1.071722 | -321.513275 | 51.170711 | 51.170427 | 0.003333 | 0.019543 |
| 206 | -1.071722 | 321.513275 | 51.170711 | 51.170427 | 0.003333 | 0.019543 |
| 207 | -1.072773 | -321.531559 | 51.173622 | 51.173337 | 0.003336 | 0.019541 |
| 208 | -1.072773 | 321.531559 | 51.173622 | 51.173337 | 0.003336 | 0.019541 |
| 209 | -1.073011 | 316.543066 | 50.379683 | 50.379394 | 0.003390 | 0.019849 |
| 210 | -1.073011 | -316.543066 | 50.379683 | 50.379394 | 0.003390 | 0.019849 |
| 211 | -1.073122 | -316.594455 | 50.387862 | 50.387573 | 0.003390 | 0.019846 |
| 212 | -1.073122 | 316.594455 | 50.387862 | 50.387573 | 0.003390 | 0.019846 |
| 213 | -1.075633 | 324.572398 | 51.657585 | 51.657302 | 0.003314 | 0.019358 |
| 214 | -1.075633 | -324.572398 | 51.657585 | 51.657302 | 0.003314 | 0.019358 |
| 215 | -1.076300 | -324.607705 | 51.663205 | 51.662921 | 0.003316 | 0.019356 |
| 216 | -1.076300 | 324.607705 | 51.663205 | 51.662921 | 0.003316 | 0.019356 |
| 217 | -1.078724 | 320.140186 | 50.952182 | 50.951893 | 0.003370 | 0.019626 |
| 218 | -1.078724 | -320.140186 | 50.952182 | 50.951893 | 0.003370 | 0.019626 |
| 219 | -1.078925 | 319.933158 | 50.919233 | 50.918944 | 0.003372 | 0.019639 |
| 220 | -1.078925 | -319.933158 | 50.919233 | 50.918944 | 0.003372 | 0.019639 |
| 221 | -1.080029 | 309.288686 | 49.225123 | 49.224823 | 0.003492 | 0.020315 |
| 222 | -1.080029 | -309.288686 | 49.225123 | 49.224823 | 0.003492 | 0.020315 |
| 223 | -1.080630 | 309.618139 | 49.277557 | 49.277257 | 0.003490 | 0.020293 |
| 224 | -1.080630 | -309.618139 | 49.277557 | 49.277257 | 0.003490 | 0.020293 |
| 225 | -1.080975 | 309.794320 | 49.305598 | 49.305297 | 0.003489 | 0.020282 |
| 226 | -1.080975 | -309.794320 | 49.305598 | 49.305297 | 0.003489 | 0.020282 |
| 227 | -1.081038 | 309.828767 | 49.311080 | 49.310780 | 0.003489 | 0.020280 |
| 228 | -1.081038 | -309.828767 | 49.311080 | 49.310780 | 0.003489 | 0.020280 |
| 229 | -1.082433 | 310.602445 | 49.434215 | 49.433914 | 0.003485 | 0.020229 |
| 230 | -1.082433 | -310.602445 | 49.434215 | 49.433914 | 0.003485 | 0.020229 |
| 231 | -1.084088 | 322.662762 | 51.353663 | 51.353373 | 0.003360 | 0.019473 |
| 232 | -1.084088 | -322.662762 | 51.353663 | 51.353373 | 0.003360 | 0.019473 |
| 233 | -1.084503 | -322.669036 | 51.354662 | 51.354372 | 0.003361 | 0.019473 |
| 234 | -1.084503 | 322.669036 | 51.354662 | 51.354372 | 0.003361 | 0.019473 |
| 235 | -1.085005 | -319.745514 | 50.889372 | 50.889079 | 0.003393 | 0.019651 |
| 236 | -1.085005 | 319.745514 | 50.889372 | 50.889079 | 0.003393 | 0.019651 |
| 237 | -1.085145 | 319.750916 | 50.890232 | 50.889939 | 0.003394 | 0.019650 |
| 238 | -1.085145 | -319.750916 | 50.890232 | 50.889939 | 0.003394 | 0.019650 |
| 239 | -1.086265 | -329.094966 | 52.377376 | 52.377091 | 0.003301 | 0.019092 |
| 240 | -1.086265 | 329.094966 | 52.377376 | 52.377091 | 0.003301 | 0.019092 |
| 241 | -1.086372 | -326.932381 | 52.033192 | 52.032904 | 0.003323 | 0.019219 |
| 242 | -1.086372 | 326.932381 | 52.033192 | 52.032904 | 0.003323 | 0.019219 |
| 243 | -1.086417 | 329.063936 | 52.372437 | 52.372152 | 0.003302 | 0.019094 |
| 244 | -1.086417 | -329.063936 | 52.372437 | 52.372152 | 0.003302 | 0.019094 |
| 245 | -1.087051 | 313.245575 | 49.854882 | 49.854582 | 0.003470 | 0.020058 |
| 246 | -1.087051 | -313.245575 | 49.854882 | 49.854582 | 0.003470 | 0.020058 |
| 247 | -1.087414 | 313.457338 | 49.888585 | 49.888285 | 0.003469 | 0.020045 |
| 248 | -1.087414 | -313.457338 | 49.888585 | 49.888285 | 0.003469 | 0.020045 |
| 249 | -1.087499 | 313.508013 | 49.896650 | 49.896350 | 0.003469 | 0.020042 |
| 250 | -1.087499 | -313.508013 | 49.896650 | 49.896350 | 0.003469 | 0.020042 |
| 251 | -1.087543 | 313.538425 | 49.901490 | 49.901190 | 0.003469 | 0.020040 |
| 252 | -1.087543 | -313.538425 | 49.901490 | 49.901190 | 0.003469 | 0.020040 |
| 253 | -1.087735 | 326.918220 | 52.030939 | 52.030651 | 0.003327 | 0.019219 |
| 254 | -1.087735 | -326.918220 | 52.030939 | 52.030651 | 0.003327 | 0.019219 |
| 255 | -1.089451 | 314.692046 | 50.085095 | 50.084795 | 0.003462 | 0.019966 |
| 256 | -1.089451 | -314.692046 | 50.085095 | 50.084795 | 0.003462 | 0.019966 |
| 257 | -1.089795 | -330.845038 | 52.655909 | 52.655623 | 0.003294 | 0.018991 |
| 258 | -1.089795 | 330.845038 | 52.655909 | 52.655623 | 0.003294 | 0.018991 |
| 259 | -1.091434 | -330.806905 | 52.649841 | 52.649554 | 0.003299 | 0.018994 |
| 260 | -1.091434 | 330.806905 | 52.649841 | 52.649554 | 0.003299 | 0.018994 |
| 261 | -1.091577 | 323.712470 | 51.520733 | 51.520440 | 0.003372 | 0.019410 |
| 262 | -1.091577 | -323.712470 | 51.520733 | 51.520440 | 0.003372 | 0.019410 |
| 263 | -1.091720 | -327.088590 | 52.058056 | 52.057766 | 0.003338 | 0.019209 |
| 264 | -1.091720 | 327.088590 | 52.058056 | 52.057766 | 0.003338 | 0.019209 |
| 265 | -1.091742 | -323.846011 | 51.541986 | 51.541693 | 0.003371 | 0.019402 |
| 266 | -1.091742 | 323.846011 | 51.541986 | 51.541693 | 0.003371 | 0.019402 |
| 267 | -1.092874 | 327.210801 | 52.077507 | 52.077216 | 0.003340 | 0.019202 |
| 268 | -1.092874 | -327.210801 | 52.077507 | 52.077216 | 0.003340 | 0.019202 |
| 269 | -1.092906 | -316.871195 | 50.431917 | 50.431617 | 0.003449 | 0.019829 |
| 270 | -1.092906 | 316.871195 | 50.431917 | 50.431617 | 0.003449 | 0.019829 |
| 271 | -1.092933 | 316.892539 | 50.435314 | 50.435014 | 0.003449 | 0.019827 |
| 272 | -1.092933 | -316.892539 | 50.435314 | 50.435014 | 0.003449 | 0.019827 |
| 273 | -1.092962 | 316.907185 | 50.437645 | 50.437345 | 0.003449 | 0.019827 |
| 274 | -1.092962 | -316.907185 | 50.437645 | 50.437345 | 0.003449 | 0.019827 |
| 275 | -1.092985 | -316.926030 | 50.440644 | 50.440344 | 0.003449 | 0.019825 |
| 276 | -1.092985 | 316.926030 | 50.440644 | 50.440344 | 0.003449 | 0.019825 |
| 277 | -1.093283 | -332.332221 | 52.892602 | 52.892316 | 0.003290 | 0.018906 |
| 278 | -1.093283 | 332.332221 | 52.892602 | 52.892316 | 0.003290 | 0.018906 |
| 279 | -1.093458 | 332.343157 | 52.894343 | 52.894056 | 0.003290 | 0.018906 |
| 280 | -1.093458 | -332.343157 | 52.894343 | 52.894056 | 0.003290 | 0.018906 |
| 281 | -1.094656 | 325.174138 | 51.753365 | 51.753071 | 0.003366 | 0.019323 |
| 282 | -1.094656 | -325.174138 | 51.753365 | 51.753071 | 0.003366 | 0.019323 |
| 283 | -1.095311 | 325.124568 | 51.745476 | 51.745182 | 0.003369 | 0.019325 |
| 284 | -1.095311 | -325.124568 | 51.745476 | 51.745182 | 0.003369 | 0.019325 |
| 285 | -1.096829 | -332.066508 | 52.850314 | 52.850026 | 0.003303 | 0.018921 |
| 286 | -1.096829 | 332.066508 | 52.850314 | 52.850026 | 0.003303 | 0.018921 |
| 287 | -1.097490 | -319.989534 | 50.928216 | 50.927916 | 0.003430 | 0.019636 |
| 288 | -1.097490 | 319.989534 | 50.928216 | 50.927916 | 0.003430 | 0.019636 |
| 289 | -1.097493 | 319.994348 | 50.928982 | 50.928682 | 0.003430 | 0.019635 |
| 290 | -1.097493 | -319.994348 | 50.928982 | 50.928682 | 0.003430 | 0.019635 |
| 291 | -1.097519 | -320.011922 | 50.931779 | 50.931479 | 0.003430 | 0.019634 |
| 292 | -1.097519 | 320.011922 | 50.931779 | 50.931479 | 0.003430 | 0.019634 |
| 293 | -1.097543 | -320.026563 | 50.934109 | 50.933809 | 0.003430 | 0.019633 |
| 294 | -1.097543 | 320.026563 | 50.934109 | 50.933809 | 0.003430 | 0.019633 |
| 295 | -1.098669 | -331.385423 | 52.741918 | 52.741628 | 0.003315 | 0.018960 |
| 296 | -1.098669 | 331.385423 | 52.741918 | 52.741628 | 0.003315 | 0.018960 |
| 297 | -1.100859 | -326.436651 | 51.954302 | 51.954007 | 0.003372 | 0.019248 |
| 298 | -1.100859 | 326.436651 | 51.954302 | 51.954007 | 0.003372 | 0.019248 |
| 299 | -1.101053 | -326.436812 | 51.954328 | 51.954032 | 0.003373 | 0.019248 |
| 300 | -1.101053 | 326.436812 | 51.954328 | 51.954032 | 0.003373 | 0.019248 |
| 301 | -1.101292 | 322.822286 | 51.379062 | 51.378763 | 0.003411 | 0.019463 |
| 302 | -1.101292 | -322.822286 | 51.379062 | 51.378763 | 0.003411 | 0.019463 |
| 303 | -1.101293 | 322.823898 | 51.379318 | 51.379019 | 0.003411 | 0.019463 |
| 304 | -1.101293 | -322.823898 | 51.379318 | 51.379019 | 0.003411 | 0.019463 |
| 305 | -1.101309 | 322.834412 | 51.380991 | 51.380692 | 0.003411 | 0.019463 |
| 306 | -1.101309 | -322.834412 | 51.380991 | 51.380692 | 0.003411 | 0.019463 |
| 307 | -1.101331 | 322.849724 | 51.383428 | 51.383129 | 0.003411 | 0.019462 |
| 308 | -1.101331 | -322.849724 | 51.383428 | 51.383129 | 0.003411 | 0.019462 |
| 309 | -1.102161 | -330.407444 | 52.586271 | 52.585978 | 0.003336 | 0.019016 |
| 310 | -1.102161 | 330.407444 | 52.586271 | 52.585978 | 0.003336 | 0.019016 |
| 311 | -1.102206 | -328.348838 | 52.258635 | 52.258341 | 0.003357 | 0.019136 |
| 312 | -1.102206 | 328.348838 | 52.258635 | 52.258341 | 0.003357 | 0.019136 |
| 313 | -1.102281 | -328.322944 | 52.254514 | 52.254220 | 0.003357 | 0.019137 |
| 314 | -1.102281 | 328.322944 | 52.254514 | 52.254220 | 0.003357 | 0.019137 |
| 315 | -1.103460 | 330.498141 | 52.600706 | 52.600413 | 0.003339 | 0.019011 |
| 316 | -1.103460 | -330.498141 | 52.600706 | 52.600413 | 0.003339 | 0.019011 |
| 317 | -1.104404 | -325.357719 | 51.782588 | 51.782289 | 0.003394 | 0.019312 |
| 318 | -1.104404 | 325.357719 | 51.782588 | 51.782289 | 0.003394 | 0.019312 |
| 319 | -1.104408 | -325.362658 | 51.783374 | 51.783075 | 0.003394 | 0.019311 |
| 320 | -1.104408 | 325.362658 | 51.783374 | 51.783075 | 0.003394 | 0.019311 |
| 321 | -1.104432 | 325.380976 | 51.786289 | 51.785991 | 0.003394 | 0.019310 |
| 322 | -1.104432 | -325.380976 | 51.786289 | 51.785991 | 0.003394 | 0.019310 |
| 323 | -1.104447 | -325.392512 | 51.788125 | 51.787827 | 0.003394 | 0.019310 |
| 324 | -1.104447 | 325.392512 | 51.788125 | 51.787827 | 0.003394 | 0.019310 |
| 325 | -1.104643 | 329.605095 | 52.458575 | 52.458280 | 0.003351 | 0.019063 |
| 326 | -1.104643 | -329.605095 | 52.458575 | 52.458280 | 0.003351 | 0.019063 |
| 327 | -1.104721 | 329.588858 | 52.455991 | 52.455696 | 0.003352 | 0.019064 |
| 328 | -1.104721 | -329.588858 | 52.455991 | 52.455696 | 0.003352 | 0.019064 |
| 329 | -1.106744 | -327.432658 | 52.112824 | 52.112526 | 0.003380 | 0.019189 |
| 330 | -1.106744 | 327.432658 | 52.112824 | 52.112526 | 0.003380 | 0.019189 |
| 331 | -1.106932 | 327.609429 | 52.140958 | 52.140660 | 0.003379 | 0.019179 |
| 332 | -1.106932 | -327.609429 | 52.140958 | 52.140660 | 0.003379 | 0.019179 |
| 333 | -1.106956 | -327.628565 | 52.144003 | 52.143706 | 0.003379 | 0.019178 |
| 334 | -1.106956 | 327.628565 | 52.144003 | 52.143706 | 0.003379 | 0.019178 |
| 335 | -1.106973 | 327.644199 | 52.146491 | 52.146194 | 0.003379 | 0.019177 |
| 336 | -1.106973 | -327.644199 | 52.146491 | 52.146194 | 0.003379 | 0.019177 |
| 337 | -1.107211 | -327.869981 | 52.182426 | 52.182128 | 0.003377 | 0.019164 |
| 338 | -1.107211 | 327.869981 | 52.182426 | 52.182128 | 0.003377 | 0.019164 |
| 339 | -1.107565 | 331.532240 | 52.765289 | 52.764995 | 0.003341 | 0.018952 |
| 340 | -1.107565 | -331.532240 | 52.765289 | 52.764995 | 0.003341 | 0.018952 |
| 341 | -1.107916 | -333.461804 | 53.072387 | 53.072094 | 0.003322 | 0.018842 |
| 342 | -1.107916 | 333.461804 | 53.072387 | 53.072094 | 0.003322 | 0.018842 |
| 343 | -1.108211 | 331.513313 | 52.762277 | 52.761983 | 0.003343 | 0.018953 |
| 344 | -1.108211 | -331.513313 | 52.762277 | 52.761983 | 0.003343 | 0.018953 |
| 345 | -1.108216 | -333.455247 | 53.071344 | 53.071051 | 0.003323 | 0.018843 |
| 346 | -1.108216 | 333.455247 | 53.071344 | 53.071051 | 0.003323 | 0.018843 |
| 347 | -1.108440 | 329.055252 | 52.371067 | 52.370770 | 0.003369 | 0.019095 |
| 348 | -1.108440 | -329.055252 | 52.371067 | 52.370770 | 0.003369 | 0.019095 |
| 349 | -1.108951 | 329.564068 | 52.452047 | 52.451750 | 0.003365 | 0.019065 |
| 350 | -1.108951 | -329.564068 | 52.452047 | 52.451750 | 0.003365 | 0.019065 |
| 351 | -1.108969 | 329.582680 | 52.455010 | 52.454713 | 0.003365 | 0.019064 |
| 352 | -1.108969 | -329.582680 | 52.455010 | 52.454713 | 0.003365 | 0.019064 |
| 353 | -1.108985 | 329.604673 | 52.458510 | 52.458213 | 0.003365 | 0.019063 |
| 354 | -1.108985 | -329.604673 | 52.458510 | 52.458213 | 0.003365 | 0.019063 |
| 355 | -1.109008 | 329.624636 | 52.461687 | 52.461390 | 0.003364 | 0.019062 |
| 356 | -1.109008 | -329.624636 | 52.461687 | 52.461390 | 0.003364 | 0.019062 |
| 357 | -1.109656 | -334.561471 | 53.247405 | 53.247112 | 0.003317 | 0.018780 |
| 358 | -1.109656 | 334.561471 | 53.247405 | 53.247112 | 0.003317 | 0.018780 |
| 359 | -1.109672 | -334.545407 | 53.244848 | 53.244555 | 0.003317 | 0.018781 |
| 360 | -1.109672 | 334.545407 | 53.244848 | 53.244555 | 0.003317 | 0.018781 |
| 361 | -1.110193 | -333.282365 | 53.043830 | 53.043536 | 0.003331 | 0.018852 |
| 362 | -1.110193 | 333.282365 | 53.043830 | 53.043536 | 0.003331 | 0.018852 |
| 363 | -1.110333 | -331.008434 | 52.681925 | 52.681628 | 0.003354 | 0.018982 |
| 364 | -1.110333 | 331.008434 | 52.681925 | 52.681628 | 0.003354 | 0.018982 |
| 365 | -1.110341 | 331.018034 | 52.683453 | 52.683156 | 0.003354 | 0.018981 |
| 366 | -1.110341 | -331.018034 | 52.683453 | 52.683156 | 0.003354 | 0.018981 |
| 367 | -1.110385 | -333.294673 | 53.045789 | 53.045495 | 0.003332 | 0.018852 |
| 368 | -1.110385 | 333.294673 | 53.045789 | 53.045495 | 0.003332 | 0.018852 |
| 369 | -1.110518 | 331.208602 | 52.713783 | 52.713486 | 0.003353 | 0.018970 |
| 370 | -1.110518 | -331.208602 | 52.713783 | 52.713486 | 0.003353 | 0.018970 |
| 371 | -1.110520 | 331.214085 | 52.714655 | 52.714359 | 0.003353 | 0.018970 |
| 372 | -1.110520 | -331.214085 | 52.714655 | 52.714359 | 0.003353 | 0.018970 |
| 373 | -1.110649 | 331.351732 | 52.736562 | 52.736266 | 0.003352 | 0.018962 |
| 374 | -1.110649 | -331.351732 | 52.736562 | 52.736266 | 0.003352 | 0.018962 |
| 375 | -1.110652 | -331.363928 | 52.738503 | 52.738207 | 0.003352 | 0.018962 |
| 376 | -1.110652 | 331.363928 | 52.738503 | 52.738207 | 0.003352 | 0.018962 |
| 377 | -1.111317 | -332.101213 | 52.855846 | 52.855550 | 0.003346 | 0.018919 |
| 378 | -1.111317 | 332.101213 | 52.855846 | 52.855550 | 0.003346 | 0.018919 |
| 379 | -1.111358 | -332.145988 | 52.862972 | 52.862676 | 0.003346 | 0.018917 |
| 380 | -1.111358 | 332.145988 | 52.862972 | 52.862676 | 0.003346 | 0.018917 |
| 381 | -1.111730 | -332.575059 | 52.931260 | 52.930965 | 0.003343 | 0.018893 |
| 382 | -1.111730 | 332.575059 | 52.931260 | 52.930965 | 0.003343 | 0.018893 |
| 383 | -1.111730 | 332.577756 | 52.931690 | 52.931394 | 0.003343 | 0.018892 |
| 384 | -1.111730 | -332.577756 | 52.931690 | 52.931394 | 0.003343 | 0.018892 |
| 385 | -1.111733 | -332.582902 | 52.932509 | 52.932213 | 0.003343 | 0.018892 |
| 386 | -1.111733 | 332.582902 | 52.932509 | 52.932213 | 0.003343 | 0.018892 |
| 387 | -1.111733 | 332.581750 | 52.932325 | 52.932029 | 0.003343 | 0.018892 |
| 388 | -1.111733 | -332.581750 | 52.932325 | 52.932029 | 0.003343 | 0.018892 |
| 389 | -1.111895 | -335.183640 | 53.346427 | 53.346133 | 0.003317 | 0.018746 |
| 390 | -1.111895 | 335.183640 | 53.346427 | 53.346133 | 0.003317 | 0.018746 |
| 391 | -1.111918 | -335.185684 | 53.346752 | 53.346459 | 0.003317 | 0.018745 |
| 392 | -1.111918 | 335.185684 | 53.346752 | 53.346459 | 0.003317 | 0.018745 |
| 393 | -1.111977 | -337.042524 | 53.642276 | 53.641984 | 0.003299 | 0.018642 |
| 394 | -1.111977 | 337.042524 | 53.642276 | 53.641984 | 0.003299 | 0.018642 |
| 395 | -1.111984 | 337.038066 | 53.641566 | 53.641274 | 0.003299 | 0.018642 |
| 396 | -1.111984 | -337.038066 | 53.641566 | 53.641274 | 0.003299 | 0.018642 |
| 397 | -1.113433 | 336.128317 | 53.496777 | 53.496483 | 0.003313 | 0.018693 |
| 398 | -1.113433 | -336.128317 | 53.496777 | 53.496483 | 0.003313 | 0.018693 |
| 399 | -1.113437 | 336.131297 | 53.497251 | 53.496957 | 0.003312 | 0.018693 |
| 400 | -1.113437 | -336.131297 | 53.497251 | 53.496957 | 0.003312 | 0.018693 |
| 401 | -1.113648 | -338.105396 | 53.811437 | 53.811145 | 0.003294 | 0.018584 |
| 402 | -1.113648 | 338.105396 | 53.811437 | 53.811145 | 0.003294 | 0.018584 |
| 403 | -1.113653 | -338.102774 | 53.811020 | 53.810728 | 0.003294 | 0.018584 |
| 404 | -1.113653 | 338.102774 | 53.811020 | 53.810728 | 0.003294 | 0.018584 |
| 405 | -1.113881 | 335.273046 | 53.360657 | 53.360363 | 0.003322 | 0.018741 |
| 406 | -1.113881 | -335.273046 | 53.360657 | 53.360363 | 0.003322 | 0.018741 |
| 407 | -1.114271 | 335.810669 | 53.446222 | 53.445928 | 0.003318 | 0.018710 |
| 408 | -1.114271 | -335.810669 | 53.446222 | 53.445928 | 0.003318 | 0.018710 |
| 409 | -1.114682 | -337.420697 | 53.702465 | 53.702172 | 0.003304 | 0.018621 |
| 410 | -1.114682 | 337.420697 | 53.702465 | 53.702172 | 0.003304 | 0.018621 |
| 411 | -1.114685 | -337.421129 | 53.702534 | 53.702241 | 0.003304 | 0.018621 |
| 412 | -1.114685 | 337.421129 | 53.702534 | 53.702241 | 0.003304 | 0.018621 |
| 413 | -1.114745 | -339.534726 | 54.038921 | 54.038630 | 0.003283 | 0.018505 |
| 414 | -1.114745 | 339.534726 | 54.038921 | 54.038630 | 0.003283 | 0.018505 |
| 415 | -1.114754 | 339.527234 | 54.037729 | 54.037438 | 0.003283 | 0.018506 |
| 416 | -1.114754 | -339.527234 | 54.037729 | 54.037438 | 0.003283 | 0.018506 |
| 417 | -1.115312 | 74.207184 | 11.811774 | 11.810440 | 0.015028 | 0.084671 |
| 418 | -1.115312 | -74.207184 | 11.811774 | 11.810440 | 0.015028 | 0.084671 |
| 419 | -1.115588 | 338.574851 | 53.886154 | 53.885861 | 0.003295 | 0.018558 |
| 420 | -1.115588 | -338.574851 | 53.886154 | 53.885861 | 0.003295 | 0.018558 |
| 421 | -1.115590 | 338.573805 | 53.885987 | 53.885695 | 0.003295 | 0.018558 |
| 422 | -1.115590 | -338.573805 | 53.885987 | 53.885695 | 0.003295 | 0.018558 |
| 423 | -1.115783 | -340.920059 | 54.259403 | 54.259113 | 0.003273 | 0.018430 |
| 424 | -1.115783 | 340.920059 | 54.259403 | 54.259113 | 0.003273 | 0.018430 |
| 425 | -1.115870 | 341.161924 | 54.297897 | 54.297607 | 0.003271 | 0.018417 |
| 426 | -1.115870 | -341.161924 | 54.297897 | 54.297607 | 0.003271 | 0.018417 |
| 427 | -1.115916 | 340.879701 | 54.252980 | 54.252689 | 0.003274 | 0.018432 |
| 428 | -1.115916 | -340.879701 | 54.252980 | 54.252689 | 0.003274 | 0.018432 |
| 429 | -1.116022 | -341.105628 | 54.288937 | 54.288647 | 0.003272 | 0.018420 |
| 430 | -1.116022 | 341.105628 | 54.288937 | 54.288647 | 0.003272 | 0.018420 |
| 431 | -1.116122 | 339.695422 | 54.064497 | 54.064206 | 0.003286 | 0.018497 |
| 432 | -1.116122 | -339.695422 | 54.064497 | 54.064206 | 0.003286 | 0.018497 |
| 433 | -1.116123 | 339.694299 | 54.064319 | 54.064027 | 0.003286 | 0.018497 |
| 434 | -1.116123 | -339.694299 | 54.064319 | 54.064027 | 0.003286 | 0.018497 |
| 435 | -1.116483 | -339.281941 | 53.998690 | 53.998398 | 0.003291 | 0.018519 |
| 436 | -1.116483 | 339.281941 | 53.998690 | 53.998398 | 0.003291 | 0.018519 |
| 437 | -1.116592 | -340.579316 | 54.205173 | 54.204882 | 0.003278 | 0.018449 |
| 438 | -1.116592 | 340.579316 | 54.205173 | 54.204882 | 0.003278 | 0.018449 |
| 439 | -1.116631 | -339.550217 | 54.041388 | 54.041095 | 0.003289 | 0.018504 |
| 440 | -1.116631 | 339.550217 | 54.041388 | 54.041095 | 0.003289 | 0.018504 |
| 441 | -1.116657 | -340.591235 | 54.207070 | 54.206779 | 0.003279 | 0.018448 |
| 442 | -1.116657 | 340.591235 | 54.207070 | 54.206779 | 0.003279 | 0.018448 |
| 443 | -1.117075 | 342.131792 | 54.452256 | 54.451966 | 0.003265 | 0.018365 |
| 444 | -1.117075 | -342.131792 | 54.452256 | 54.451966 | 0.003265 | 0.018365 |
| 445 | -1.117094 | 342.130820 | 54.452101 | 54.451811 | 0.003265 | 0.018365 |
| 446 | -1.117094 | -342.130820 | 54.452101 | 54.451811 | 0.003265 | 0.018365 |
| 447 | -1.117293 | -341.489178 | 54.349982 | 54.349691 | 0.003272 | 0.018399 |
| 448 | -1.117293 | 341.489178 | 54.349982 | 54.349691 | 0.003272 | 0.018399 |
| 449 | -1.117322 | 341.487729 | 54.349751 | 54.349460 | 0.003272 | 0.018399 |
| 450 | -1.117322 | -341.487729 | 54.349751 | 54.349460 | 0.003272 | 0.018399 |
| 451 | -1.117513 | -342.198690 | 54.462903 | 54.462613 | 0.003266 | 0.018361 |
| 452 | -1.117513 | 342.198690 | 54.462903 | 54.462613 | 0.003266 | 0.018361 |
| 453 | -1.117532 | -342.200560 | 54.463201 | 54.462911 | 0.003266 | 0.018361 |
| 454 | -1.117532 | 342.200560 | 54.463201 | 54.462911 | 0.003266 | 0.018361 |
| 455 | -1.117646 | 343.037593 | 54.596418 | 54.596129 | 0.003258 | 0.018316 |
| 456 | -1.117646 | -343.037593 | 54.596418 | 54.596129 | 0.003258 | 0.018316 |
| 457 | -1.117646 | -343.037592 | 54.596418 | 54.596128 | 0.003258 | 0.018316 |
| 458 | -1.117646 | 343.037592 | 54.596418 | 54.596128 | 0.003258 | 0.018316 |
| 459 | -1.117777 | -341.853412 | 54.407951 | 54.407660 | 0.003270 | 0.018380 |
| 460 | -1.117777 | 341.853412 | 54.407951 | 54.407660 | 0.003270 | 0.018380 |
| 461 | -1.117846 | -342.009266 | 54.432756 | 54.432465 | 0.003268 | 0.018371 |
| 462 | -1.117846 | 342.009266 | 54.432756 | 54.432465 | 0.003268 | 0.018371 |
| 463 | -1.118011 | -342.479554 | 54.507604 | 54.507314 | 0.003264 | 0.018346 |
| 464 | -1.118011 | 342.479554 | 54.507604 | 54.507314 | 0.003264 | 0.018346 |
| 465 | -1.118029 | -342.507545 | 54.512059 | 54.511769 | 0.003264 | 0.018345 |
| 466 | -1.118029 | 342.507545 | 54.512059 | 54.511769 | 0.003264 | 0.018345 |
| 467 | -1.118087 | -343.710417 | 54.703501 | 54.703212 | 0.003253 | 0.018280 |
| 468 | -1.118087 | 343.710417 | 54.703501 | 54.703212 | 0.003253 | 0.018280 |
| 469 | -1.118087 | 343.710417 | 54.703501 | 54.703212 | 0.003253 | 0.018280 |
| 470 | -1.118087 | -343.710417 | 54.703501 | 54.703212 | 0.003253 | 0.018280 |
| 471 | -1.118088 | -342.821813 | 54.562076 | 54.561786 | 0.003261 | 0.018328 |
| 472 | -1.118088 | 342.821813 | 54.562076 | 54.561786 | 0.003261 | 0.018328 |
| 473 | -1.118088 | 342.822024 | 54.562110 | 54.561820 | 0.003261 | 0.018328 |
| 474 | -1.118088 | -342.822024 | 54.562110 | 54.561820 | 0.003261 | 0.018328 |
| 475 | -1.118409 | -344.494693 | 54.828322 | 54.828033 | 0.003247 | 0.018239 |
| 476 | -1.118409 | 344.494693 | 54.828322 | 54.828033 | 0.003247 | 0.018239 |
| 477 | -1.118409 | -344.494693 | 54.828322 | 54.828033 | 0.003247 | 0.018239 |
| 478 | -1.118409 | 344.494693 | 54.828322 | 54.828033 | 0.003247 | 0.018239 |
| 479 | -1.118504 | -343.644764 | 54.693053 | 54.692763 | 0.003255 | 0.018284 |
| 480 | -1.118504 | 343.644764 | 54.693053 | 54.692763 | 0.003255 | 0.018284 |
| 481 | -1.118539 | -343.740135 | 54.708231 | 54.707942 | 0.003254 | 0.018279 |
| 482 | -1.118539 | 343.740135 | 54.708231 | 54.707942 | 0.003254 | 0.018279 |
| 483 | -1.118797 | 345.352018 | 54.964769 | 54.964481 | 0.003240 | 0.018194 |
| 484 | -1.118797 | -345.352018 | 54.964769 | 54.964481 | 0.003240 | 0.018194 |
| 485 | -1.118797 | 345.352018 | 54.964769 | 54.964481 | 0.003240 | 0.018194 |
| 486 | -1.118797 | -345.352018 | 54.964769 | 54.964481 | 0.003240 | 0.018194 |
| 487 | -1.118942 | -344.942716 | 54.899627 | 54.899338 | 0.003244 | 0.018215 |
| 488 | -1.118942 | 344.942716 | 54.899627 | 54.899338 | 0.003244 | 0.018215 |
| 489 | -1.118960 | -345.001926 | 54.909051 | 54.908762 | 0.003243 | 0.018212 |
| 490 | -1.118960 | 345.001926 | 54.909051 | 54.908762 | 0.003243 | 0.018212 |
| 491 | -1.119142 | 346.233999 | 55.105140 | 55.104852 | 0.003232 | 0.018147 |
| 492 | -1.119142 | -346.233999 | 55.105140 | 55.104852 | 0.003232 | 0.018147 |
| 493 | -1.119142 | 346.233999 | 55.105140 | 55.104852 | 0.003232 | 0.018147 |
| 494 | -1.119142 | -346.233999 | 55.105140 | 55.104852 | 0.003232 | 0.018147 |
| 495 | -1.119223 | 345.921418 | 55.055392 | 55.055104 | 0.003235 | 0.018164 |
| 496 | -1.119223 | -345.921418 | 55.055392 | 55.055104 | 0.003235 | 0.018164 |
| 497 | -1.119232 | 345.957711 | 55.061168 | 55.060880 | 0.003235 | 0.018162 |
| 498 | -1.119232 | -345.957711 | 55.061168 | 55.060880 | 0.003235 | 0.018162 |
| 499 | -1.119414 | -346.692126 | 55.178053 | 55.177766 | 0.003229 | 0.018123 |
| 500 | -1.119414 | 346.692126 | 55.178053 | 55.177766 | 0.003229 | 0.018123 |
| 501 | -1.119419 | -346.714128 | 55.181555 | 55.181267 | 0.003229 | 0.018122 |
| 502 | -1.119419 | 346.714128 | 55.181555 | 55.181267 | 0.003229 | 0.018122 |
| 503 | -1.119436 | -347.160911 | 55.252662 | 55.252375 | 0.003225 | 0.018099 |
| 504 | -1.119436 | 347.160911 | 55.252662 | 55.252375 | 0.003225 | 0.018099 |
| 505 | -1.119436 | -347.160911 | 55.252662 | 55.252375 | 0.003225 | 0.018099 |
| 506 | -1.119436 | 347.160911 | 55.252662 | 55.252375 | 0.003225 | 0.018099 |
| 507 | -1.119550 | -347.324058 | 55.278628 | 55.278341 | 0.003223 | 0.018090 |
| 508 | -1.119550 | 347.324058 | 55.278628 | 55.278341 | 0.003223 | 0.018090 |
| 509 | -1.119554 | -347.339241 | 55.281044 | 55.280757 | 0.003223 | 0.018089 |
| 510 | -1.119554 | 347.339241 | 55.281044 | 55.280757 | 0.003223 | 0.018089 |
| 511 | -1.119645 | 347.818682 | 55.357349 | 55.357063 | 0.003219 | 0.018065 |
| 512 | -1.119645 | -347.818682 | 55.357349 | 55.357063 | 0.003219 | 0.018065 |
| 513 | -1.119648 | 347.835778 | 55.360070 | 55.359783 | 0.003219 | 0.018064 |
| 514 | -1.119648 | -347.835778 | 55.360070 | 55.359783 | 0.003219 | 0.018064 |
| 515 | -1.119700 | 348.136761 | 55.407973 | 55.407686 | 0.003216 | 0.018048 |
| 516 | -1.119700 | -348.136761 | 55.407973 | 55.407686 | 0.003216 | 0.018048 |
| 517 | -1.119702 | 348.145161 | 55.409310 | 55.409023 | 0.003216 | 0.018048 |
| 518 | -1.119702 | -348.145161 | 55.409310 | 55.409023 | 0.003216 | 0.018048 |
| 519 | -1.119747 | 348.428886 | 55.454466 | 55.454180 | 0.003214 | 0.018033 |
| 520 | -1.119747 | -348.428886 | 55.454466 | 55.454180 | 0.003214 | 0.018033 |
| 521 | -1.119747 | 348.429776 | 55.454608 | 55.454321 | 0.003214 | 0.018033 |
| 522 | -1.119747 | -348.429776 | 55.454608 | 55.454321 | 0.003214 | 0.018033 |
| 523 | -1.119798 | -348.784816 | 55.511114 | 55.510828 | 0.003211 | 0.018015 |
| 524 | -1.119798 | 348.784816 | 55.511114 | 55.510828 | 0.003211 | 0.018015 |
| 525 | -1.119799 | 348.788549 | 55.511708 | 55.511422 | 0.003211 | 0.018014 |
| 526 | -1.119799 | -348.788549 | 55.511708 | 55.511422 | 0.003211 | 0.018014 |
| 527 | -1.119838 | 349.087485 | 55.559285 | 55.558999 | 0.003208 | 0.017999 |
| 528 | -1.119838 | -349.087485 | 55.559285 | 55.558999 | 0.003208 | 0.017999 |
| 529 | -1.119838 | 349.088940 | 55.559516 | 55.559230 | 0.003208 | 0.017999 |
| 530 | -1.119838 | -349.088940 | 55.559516 | 55.559230 | 0.003208 | 0.017999 |
| 531 | -1.119864 | 349.305750 | 55.594023 | 55.593737 | 0.003206 | 0.017988 |
| 532 | -1.119864 | -349.305750 | 55.594023 | 55.593737 | 0.003206 | 0.017988 |
| 533 | -1.119864 | 349.306973 | 55.594217 | 55.593931 | 0.003206 | 0.017988 |
| 534 | -1.119864 | -349.306973 | 55.594217 | 55.593931 | 0.003206 | 0.017988 |
| 535 | -1.119888 | -349.526188 | 55.629106 | 55.628821 | 0.003204 | 0.017976 |
| 536 | -1.119888 | 349.526188 | 55.629106 | 55.628821 | 0.003204 | 0.017976 |
| 537 | -1.119888 | -349.527157 | 55.629260 | 55.628975 | 0.003204 | 0.017976 |
| 538 | -1.119888 | 349.527157 | 55.629260 | 55.628975 | 0.003204 | 0.017976 |
| 539 | -1.119908 | -349.726171 | 55.660934 | 55.660649 | 0.003202 | 0.017966 |
| 540 | -1.119908 | 349.726171 | 55.660934 | 55.660649 | 0.003202 | 0.017966 |
| 541 | -1.119908 | -349.726960 | 55.661060 | 55.660774 | 0.003202 | 0.017966 |
| 542 | -1.119908 | 349.726960 | 55.661060 | 55.660774 | 0.003202 | 0.017966 |
| 543 | -1.119924 | 349.905629 | 55.689496 | 55.689211 | 0.003201 | 0.017957 |
| 544 | -1.119924 | -349.905629 | 55.689496 | 55.689211 | 0.003201 | 0.017957 |
| 545 | -1.119924 | -349.906343 | 55.689609 | 55.689324 | 0.003201 | 0.017957 |
| 546 | -1.119924 | 349.906343 | 55.689609 | 55.689324 | 0.003201 | 0.017957 |
| 547 | -1.119938 | 350.066095 | 55.715034 | 55.714749 | 0.003199 | 0.017949 |
| 548 | -1.119938 | -350.066095 | 55.715034 | 55.714749 | 0.003199 | 0.017949 |
| 549 | -1.119938 | 350.067052 | 55.715187 | 55.714902 | 0.003199 | 0.017949 |
| 550 | -1.119938 | -350.067052 | 55.715187 | 55.714902 | 0.003199 | 0.017949 |
| 551 | -1.119946 | -350.175587 | 55.732461 | 55.732176 | 0.003198 | 0.017943 |
| 552 | -1.119946 | 350.175587 | 55.732461 | 55.732176 | 0.003198 | 0.017943 |
| 553 | -1.119947 | 350.185229 | 55.733995 | 55.733710 | 0.003198 | 0.017942 |
| 554 | -1.119947 | -350.185229 | 55.733995 | 55.733710 | 0.003198 | 0.017942 |
| 555 | -1.119950 | -350.224672 | 55.740273 | 55.739988 | 0.003198 | 0.017940 |
| 556 | -1.119950 | 350.224672 | 55.740273 | 55.739988 | 0.003198 | 0.017940 |
| 557 | -1.119950 | -350.225655 | 55.740429 | 55.740144 | 0.003198 | 0.017940 |
| 558 | -1.119950 | 350.225655 | 55.740429 | 55.740144 | 0.003198 | 0.017940 |
| 559 | -1.119959 | -350.360870 | 55.761949 | 55.761664 | 0.003197 | 0.017933 |
| 560 | -1.119959 | 350.360870 | 55.761949 | 55.761664 | 0.003197 | 0.017933 |
| 561 | -1.119959 | -350.360874 | 55.761950 | 55.761665 | 0.003197 | 0.017933 |
| 562 | -1.119959 | 350.360874 | 55.761950 | 55.761665 | 0.003197 | 0.017933 |
| 563 | -1.119968 | -350.498253 | 55.783814 | 55.783530 | 0.003195 | 0.017926 |
| 564 | -1.119968 | 350.498253 | 55.783814 | 55.783530 | 0.003195 | 0.017926 |
| 565 | -1.119968 | -350.498253 | 55.783814 | 55.783530 | 0.003195 | 0.017926 |
| 566 | -1.119968 | 350.498253 | 55.783814 | 55.783530 | 0.003195 | 0.017926 |
| 567 | -1.202238 | 215.725167 | 34.334260 | 34.333727 | 0.005573 | 0.029126 |
| 568 | -1.202238 | -215.725167 | 34.334260 | 34.333727 | 0.005573 | 0.029126 |
| 569 | -1.211213 | 218.125851 | 34.716343 | 34.715807 | 0.005553 | 0.028805 |
| 570 | -1.211213 | -218.125851 | 34.716343 | 34.715807 | 0.005553 | 0.028805 |
| 571 | -1.314901 | 27.808792 | 4.430852 | 4.425907 | 0.047231 | 0.225942 |
| 572 | -1.314901 | -27.808792 | 4.430852 | 4.425907 | 0.047231 | 0.225942 |
| 573 | -1.331926 | -193.853508 | 30.853472 | 30.852744 | 0.006871 | 0.032412 |
| 574 | -1.331926 | 193.853508 | 30.853472 | 30.852744 | 0.006871 | 0.032412 |
| 575 | -1.387904 | -100.607607 | 16.013722 | 16.012198 | 0.013794 | 0.062452 |
| 576 | -1.387904 | 100.607607 | 16.013722 | 16.012198 | 0.013794 | 0.062452 |
| 577 | -1.429024 | 181.697099 | 28.918886 | 28.917992 | 0.007865 | 0.034581 |
| 578 | -1.429024 | -181.697099 | 28.918886 | 28.917992 | 0.007865 | 0.034581 |
| 579 | -1.467702 | -29.975101 | 4.776401 | 4.770685 | 0.048905 | 0.209613 |
| 580 | -1.467702 | 29.975101 | 4.776401 | 4.770685 | 0.048905 | 0.209613 |
| 581 | -1.475946 | -189.568142 | 30.171621 | 30.170707 | 0.007786 | 0.033145 |
| 582 | -1.475946 | 189.568142 | 30.171621 | 30.170707 | 0.007786 | 0.033145 |
| 583 | -1.552107 | 121.192652 | 19.289991 | 19.288410 | 0.012806 | 0.051845 |
| 584 | -1.552107 | -121.192652 | 19.289991 | 19.288410 | 0.012806 | 0.051845 |
| 585 | -1.569138 | 147.912741 | 23.542368 | 23.541044 | 0.010608 | 0.042479 |
| 586 | -1.569138 | -147.912741 | 23.542368 | 23.541044 | 0.010608 | 0.042479 |
| 587 | -1.679571 | -166.822478 | 26.551968 | 26.550622 | 0.010068 | 0.037664 |
| 588 | -1.679571 | 166.822478 | 26.551968 | 26.550622 | 0.010068 | 0.037664 |
| 589 | -1.900781 | 146.675612 | 23.346109 | 23.344149 | 0.012958 | 0.042837 |
| 590 | -1.900781 | -146.675612 | 23.346109 | 23.344149 | 0.012958 | 0.042837 |
| 591 | -3.829164 | 6.037090 | 1.137807 | 0.960833 | 0.535618 | 1.040764 |
| 592 | -3.829164 | -6.037090 | 1.137807 | 0.960833 | 0.535618 | 1.040764 |
| 593 | -10.569038 | -2.319301 | 1.722140 | 0.369128 | 0.976758 | 2.709085 |
| 594 | -10.569038 | 2.319301 | 1.722140 | 0.369128 | 0.976758 | 2.709085 |
| 595 | -15.876819 | 0.420548 | 2.527760 | 0.066932 | 0.999649 | 14.940485 |
| 596 | -15.876819 | -0.420548 | 2.527760 | 0.066932 | 0.999649 | 14.940485 |
| 597 | -22.629853 | 0.000000 | 3.601653 | 0.000000 | 1.000000 | inf |
| 598 | -26.267735 | 0.000000 | 4.180640 | 0.000000 | 1.000000 | inf |
| 599 | -29.470709 | 0.000000 | 4.690409 | 0.000000 | 1.000000 | inf |
| 600 | -30.882640 | -35.322709 | 7.467456 | 5.621784 | 0.658206 | 0.177879 |
| 601 | -30.882640 | 35.322709 | 7.467456 | 5.621784 | 0.658206 | 0.177879 |
| 602 | -32.639619 | 0.000000 | 5.194757 | 0.000000 | 1.000000 | inf |
| 603 | -34.172137 | 34.458728 | 7.723753 | 5.484277 | 0.704148 | 0.182339 |
| 604 | -34.172137 | -34.458728 | 7.723753 | 5.484277 | 0.704148 | 0.182339 |
| 605 | -35.603269 | 0.000000 | 5.666436 | 0.000000 | 1.000000 | inf |
| 606 | -36.439642 | -71.349091 | 12.750825 | 11.355561 | 0.454837 | 0.088063 |
| 607 | -36.439642 | 71.349091 | 12.750825 | 11.355561 | 0.454837 | 0.088063 |
| 608 | -37.441913 | 34.065477 | 8.056375 | 5.421689 | 0.739671 | 0.184444 |
| 609 | -37.441913 | -34.065477 | 8.056375 | 5.421689 | 0.739671 | 0.184444 |
| 610 | -38.677028 | 0.000000 | 6.155640 | 0.000000 | 1.000000 | inf |
| 611 | -39.517763 | 106.863529 | 18.133516 | 17.007859 | 0.346841 | 0.058796 |
| 612 | -39.517763 | -106.863529 | 18.133516 | 17.007859 | 0.346841 | 0.058796 |
| 613 | -40.027452 | 70.647916 | 12.923269 | 11.243965 | 0.492953 | 0.088937 |
| 614 | -40.027452 | -70.647916 | 12.923269 | 11.243965 | 0.492953 | 0.088937 |
| 615 | -40.915687 | -33.727014 | 8.439122 | 5.367821 | 0.771636 | 0.186295 |
| 616 | -40.915687 | 33.727014 | 8.439122 | 5.367821 | 0.771636 | 0.186295 |
| 617 | -41.445961 | -142.148833 | 23.565714 | 22.623689 | 0.279912 | 0.044201 |
| 618 | -41.445961 | 142.148833 | 23.565714 | 22.623689 | 0.279912 | 0.044201 |
| 619 | -41.867200 | 0.000000 | 6.663372 | 0.000000 | 1.000000 | inf |
| 620 | -42.728119 | -177.201966 | 29.010864 | 28.202569 | 0.234408 | 0.035458 |
| 621 | -42.728119 | 177.201966 | 29.010864 | 28.202569 | 0.234408 | 0.035458 |
| 622 | -43.280388 | -106.316208 | 18.269108 | 16.920750 | 0.377046 | 0.059099 |
| 623 | -43.280388 | 106.316208 | 18.269108 | 16.920750 | 0.377046 | 0.059099 |
| 624 | -43.336124 | 70.371812 | 13.153375 | 11.200022 | 0.524364 | 0.089286 |
| 625 | -43.336124 | -70.371812 | 13.153375 | 11.200022 | 0.524364 | 0.089286 |
| 626 | -43.703283 | -212.025014 | 34.454227 | 33.744829 | 0.201879 | 0.029634 |
| 627 | -43.703283 | 212.025014 | 34.454227 | 33.744829 | 0.201879 | 0.029634 |
| 628 | -44.464423 | -33.642593 | 8.874096 | 5.354385 | 0.797460 | 0.186763 |
| 629 | -44.464423 | 33.642593 | 8.874096 | 5.354385 | 0.797460 | 0.186763 |
| 630 | -44.565889 | 246.761554 | 39.908680 | 39.273321 | 0.177728 | 0.025463 |
| 631 | -44.565889 | -246.761554 | 39.908680 | 39.273321 | 0.177728 | 0.025463 |
| 632 | -45.337149 | -281.615994 | 45.397682 | 44.820577 | 0.158943 | 0.022311 |
| 633 | -45.337149 | 281.615994 | 45.397682 | 44.820577 | 0.158943 | 0.022311 |
| 634 | -45.383435 | -141.762571 | 23.690192 | 22.562214 | 0.304894 | 0.044322 |
| 635 | -45.383435 | 141.762571 | 23.690192 | 22.562214 | 0.304894 | 0.044322 |
| 636 | -45.635849 | 0.000000 | 7.263171 | 0.000000 | 1.000000 | inf |
| 637 | -45.889180 | 316.668954 | 50.925862 | 50.399429 | 0.143414 | 0.019841 |
| 638 | -45.889180 | -316.668954 | 50.925862 | 50.399429 | 0.143414 | 0.019841 |
| 639 | -46.088938 | 351.858377 | 56.478371 | 56.000000 | 0.129878 | 0.017857 |
| 640 | -46.676008 | 106.038788 | 18.439235 | 16.876597 | 0.402876 | 0.059254 |
| 641 | -46.676008 | -106.038788 | 18.439235 | 16.876597 | 0.402876 | 0.059254 |
| 642 | -46.767036 | 70.167150 | 13.420626 | 11.167449 | 0.554609 | 0.089546 |
| 643 | -46.767036 | -70.167150 | 13.420626 | 11.167449 | 0.554609 | 0.089546 |
| 644 | -46.853578 | -176.902076 | 29.125616 | 28.154840 | 0.256028 | 0.035518 |
| 645 | -46.853578 | 176.902076 | 29.125616 | 28.154840 | 0.256028 | 0.035518 |
| 646 | -47.914776 | 211.777248 | 34.557310 | 33.705396 | 0.220673 | 0.029669 |
| 647 | -47.914776 | -211.777248 | 34.557310 | 33.705396 | 0.220673 | 0.029669 |
| 648 | -48.163221 | 33.591764 | 9.345665 | 5.346295 | 0.820211 | 0.187045 |
| 649 | -48.163221 | -33.591764 | 9.345665 | 5.346295 | 0.820211 | 0.187045 |
| 650 | -48.252213 | 0.000000 | 7.679578 | 0.000000 | 1.000000 | inf |
| 651 | -48.812816 | 246.582271 | 40.006344 | 39.244787 | 0.194189 | 0.025481 |
| 652 | -48.812816 | -246.582271 | 40.006344 | 39.244787 | 0.194189 | 0.025481 |
| 653 | -48.813029 | -141.441198 | 23.813922 | 22.511066 | 0.326231 | 0.044423 |
| 654 | -48.813029 | 141.441198 | 23.813922 | 22.511066 | 0.326231 | 0.044423 |
| 655 | -49.598916 | 281.503089 | 45.492720 | 44.802608 | 0.173520 | 0.022320 |
| 656 | -49.598916 | -281.503089 | 45.492720 | 44.802608 | 0.173520 | 0.022320 |
| 657 | -50.130642 | -105.892724 | 18.646515 | 16.853351 | 0.427884 | 0.059335 |
| 658 | -50.130642 | 105.892724 | 18.646515 | 16.853351 | 0.427884 | 0.059335 |
| 659 | -50.155612 | 316.615486 | 51.019264 | 50.390920 | 0.156461 | 0.019845 |
| 660 | -50.155612 | -316.615486 | 51.019264 | 50.390920 | 0.156461 | 0.019845 |
| 661 | -50.199758 | 70.036291 | 13.714223 | 11.146622 | 0.582573 | 0.089713 |
| 662 | -50.199758 | -70.036291 | 13.714223 | 11.146622 | 0.582573 | 0.089713 |
| 663 | -50.274891 | -176.631667 | 29.228367 | 28.111803 | 0.273758 | 0.035572 |
| 664 | -50.274891 | 176.631667 | 29.228367 | 28.111803 | 0.273758 | 0.035572 |
| 665 | -50.356641 | 351.858377 | 56.570596 | 56.000000 | 0.141673 | 0.017857 |
| 666 | -50.561744 | 0.000000 | 8.047151 | 0.000000 | 1.000000 | inf |
| 667 | -51.384725 | -211.606085 | 34.656889 | 33.678154 | 0.235974 | 0.029693 |
| 668 | -51.384725 | 211.606085 | 34.656889 | 33.678154 | 0.235974 | 0.029693 |
| 669 | -52.064864 | 33.485400 | 9.852221 | 5.329367 | 0.841067 | 0.187640 |
| 670 | -52.064864 | -33.485400 | 9.852221 | 5.329367 | 0.841067 | 0.187640 |
| 671 | -52.270240 | -141.316069 | 23.980382 | 22.491151 | 0.346911 | 0.044462 |
| 672 | -52.270240 | 141.316069 | 23.980382 | 22.491151 | 0.346911 | 0.044462 |
| 673 | -52.308018 | -246.494054 | 40.104345 | 39.230747 | 0.207585 | 0.025490 |
| 674 | -52.308018 | 246.494054 | 40.104345 | 39.230747 | 0.207585 | 0.025490 |
| 675 | -53.091325 | -281.471463 | 45.587508 | 44.797575 | 0.185352 | 0.022323 |
| 676 | -53.091325 | 281.471463 | 45.587508 | 44.797575 | 0.185352 | 0.022323 |
| 677 | -53.523354 | 105.809988 | 18.872114 | 16.840183 | 0.451381 | 0.059382 |
| 678 | -53.523354 | -105.809988 | 18.872114 | 16.840183 | 0.451381 | 0.059382 |
| 679 | -53.632759 | -316.607749 | 51.107559 | 50.389688 | 0.167019 | 0.019845 |
| 680 | -53.632759 | 316.607749 | 51.107559 | 50.389688 | 0.167019 | 0.019845 |
| 681 | -53.713623 | 176.509633 | 29.364326 | 28.092381 | 0.291128 | 0.035597 |
| 682 | -53.713623 | -176.509633 | 29.364326 | 28.092381 | 0.291128 | 0.035597 |
| 683 | -53.826264 | 351.858377 | 56.651466 | 56.000000 | 0.151218 | 0.017857 |
| 684 | -53.844578 | 69.950619 | 14.049269 | 11.132987 | 0.609970 | 0.089823 |
| 685 | -53.844578 | -69.950619 | 14.049269 | 11.132987 | 0.609970 | 0.089823 |
| 686 | -53.932606 | 0.000000 | 8.583641 | 0.000000 | 1.000000 | inf |
| 687 | -54.796128 | 211.491959 | 34.771427 | 33.659991 | 0.250812 | 0.029709 |
| 688 | -54.796128 | -211.491959 | 34.771427 | 33.659991 | 0.250812 | 0.029709 |
| 689 | -55.610859 | 33.325370 | 10.318284 | 5.303897 | 0.857773 | 0.188541 |
| 690 | -55.610859 | -33.325370 | 10.318284 | 5.303897 | 0.857773 | 0.188541 |
| 691 | -55.689855 | 141.250770 | 24.164910 | 22.480758 | 0.366785 | 0.044482 |
| 692 | -55.689855 | -141.250770 | 24.164910 | 22.480758 | 0.366785 | 0.044482 |
| 693 | -55.734550 | -246.399761 | 40.206452 | 39.215740 | 0.220622 | 0.025500 |
| 694 | -55.734550 | 246.399761 | 40.206452 | 39.215740 | 0.220622 | 0.025500 |
| 695 | -56.557649 | 281.398311 | 45.681566 | 44.785932 | 0.197047 | 0.022328 |
| 696 | -56.557649 | -281.398311 | 45.681566 | 44.785932 | 0.197047 | 0.022328 |
| 697 | -57.110723 | -105.753973 | 19.128767 | 16.831268 | 0.475172 | 0.059413 |
| 698 | -57.110723 | 105.753973 | 19.128767 | 16.831268 | 0.475172 | 0.059413 |
| 699 | -57.130384 | 316.567088 | 51.197105 | 50.383217 | 0.177600 | 0.019848 |
| 700 | -57.130384 | -316.567088 | 51.197105 | 50.383217 | 0.177600 | 0.019848 |
| 701 | -57.151223 | -176.440063 | 29.517711 | 28.081308 | 0.308151 | 0.035611 |
| 702 | -57.151223 | 176.440063 | 29.517711 | 28.081308 | 0.308151 | 0.035611 |
| 703 | -57.334973 | 351.858377 | 56.738596 | 56.000000 | 0.160828 | 0.017857 |
| 704 | -57.797155 | 69.873743 | 14.432160 | 11.120752 | 0.637375 | 0.089922 |
| 705 | -57.797155 | -69.873743 | 14.432160 | 11.120752 | 0.637375 | 0.089922 |
| 706 | -58.238487 | -211.435876 | 34.904261 | 33.651065 | 0.265553 | 0.029717 |
| 707 | -58.238487 | 211.435876 | 34.904261 | 33.651065 | 0.265553 | 0.029717 |
| 708 | -58.985465 | -33.192087 | 10.772097 | 5.282685 | 0.871495 | 0.189298 |
| 709 | -58.985465 | 33.192087 | 10.772097 | 5.282685 | 0.871495 | 0.189298 |
| 710 | -59.167429 | -246.361687 | 40.324620 | 39.209680 | 0.233525 | 0.025504 |
| 711 | -59.167429 | 246.361687 | 40.324620 | 39.209680 | 0.233525 | 0.025504 |
| 712 | -59.256196 | -141.231341 | 24.375965 | 22.477666 | 0.386894 | 0.044489 |
| 713 | -59.256196 | 141.231341 | 24.375965 | 22.477666 | 0.386894 | 0.044489 |
| 714 | -59.966273 | 281.381357 | 45.788914 | 44.783234 | 0.208433 | 0.022330 |
| 715 | -59.966273 | -281.381357 | 45.788914 | 44.783234 | 0.208433 | 0.022330 |
| 716 | -60.004171 | 1.461338 | 9.552792 | 0.232579 | 0.999704 | 4.299611 |
| 717 | -60.004171 | -1.461338 | 9.552792 | 0.232579 | 0.999704 | 4.299611 |
| 718 | -60.524592 | 316.563727 | 51.295275 | 50.382682 | 0.187791 | 0.019848 |
| 719 | -60.524592 | -316.563727 | 51.295275 | 50.382682 | 0.187791 | 0.019848 |
| 720 | -60.724664 | 351.858377 | 56.827855 | 56.000000 | 0.170069 | 0.017857 |
| 721 | -60.725048 | -176.425011 | 29.695649 | 28.078913 | 0.325458 | 0.035614 |
| 722 | -60.725048 | 176.425011 | 29.695649 | 28.078913 | 0.325458 | 0.035614 |
| 723 | -61.050615 | 105.665542 | 19.422371 | 16.817193 | 0.500274 | 0.059463 |
| 724 | -61.050615 | -105.665542 | 19.422371 | 16.817193 | 0.500274 | 0.059463 |
| 725 | -61.075659 | 0.000000 | 9.720493 | 0.000000 | 1.000000 | inf |
| 726 | -61.346469 | 69.792184 | 14.788859 | 11.107771 | 0.660199 | 0.090027 |
| 727 | -61.346469 | -69.792184 | 14.788859 | 11.107771 | 0.660199 | 0.090027 |
| 728 | -61.829886 | -211.392322 | 35.053727 | 33.644133 | 0.280727 | 0.029723 |
| 729 | -61.829886 | 211.392322 | 35.053727 | 33.644133 | 0.280727 | 0.029723 |
| 730 | -62.781634 | 246.294823 | 40.452501 | 39.199039 | 0.247006 | 0.025511 |
| 731 | -62.781634 | -246.294823 | 40.452501 | 39.199039 | 0.247006 | 0.025511 |
| 732 | -62.929241 | 32.946966 | 11.305147 | 5.243673 | 0.885924 | 0.190706 |
| 733 | -62.929241 | -32.946966 | 11.305147 | 5.243673 | 0.885924 | 0.190706 |
| 734 | -63.197906 | 141.166186 | 24.616011 | 22.467296 | 0.408606 | 0.044509 |
| 735 | -63.197906 | -141.166186 | 24.616011 | 22.467296 | 0.408606 | 0.044509 |
| 736 | -63.604162 | 281.320050 | 45.903569 | 44.773477 | 0.220526 | 0.022335 |
| 737 | -63.604162 | -281.320050 | 45.903569 | 44.773477 | 0.220526 | 0.022335 |
| 738 | -64.180338 | -316.529779 | 51.402419 | 50.377279 | 0.198719 | 0.019850 |
| 739 | -64.180338 | 316.529779 | 51.402419 | 50.377279 | 0.198719 | 0.019850 |
| 740 | -64.386941 | 351.858377 | 56.929880 | 56.000000 | 0.180002 | 0.017857 |
| 741 | -64.589799 | 105.551154 | 19.694669 | 16.798988 | 0.521958 | 0.059527 |
| 742 | -64.589799 | -105.551154 | 19.694669 | 16.798988 | 0.521958 | 0.059527 |
| 743 | -64.637285 | 69.696959 | 15.128634 | 11.092615 | 0.679992 | 0.090150 |
| 744 | -64.637285 | -69.696959 | 15.128634 | 11.092615 | 0.679992 | 0.090150 |
| 745 | -64.694697 | -176.381060 | 29.900670 | 28.071918 | 0.344356 | 0.035623 |
| 746 | -64.694697 | 176.381060 | 29.900670 | 28.071918 | 0.344356 | 0.035623 |
| 747 | -64.771747 | 0.000000 | 10.308744 | 0.000000 | 1.000000 | inf |
| 748 | -65.832104 | -211.365674 | 35.233797 | 33.639892 | 0.297371 | 0.029727 |
| 749 | -65.832104 | 211.365674 | 35.233797 | 33.639892 | 0.297371 | 0.029727 |
| 750 | -66.701546 | 141.026543 | 24.828978 | 22.445071 | 0.427560 | 0.044553 |
| 751 | -66.701546 | -141.026543 | 24.828978 | 22.445071 | 0.427560 | 0.044553 |
| 752 | -66.800140 | -246.281319 | 40.613132 | 39.196889 | 0.261777 | 0.025512 |
| 753 | -66.800140 | 246.281319 | 40.613132 | 39.196889 | 0.261777 | 0.025512 |
| 754 | -67.619843 | -281.313309 | 46.047687 | 44.772404 | 0.233715 | 0.022335 |
| 755 | -67.619843 | 281.313309 | 46.047687 | 44.772404 | 0.233715 | 0.022335 |
| 756 | -67.868949 | -105.428356 | 19.955601 | 16.779444 | 0.541286 | 0.059597 |
| 757 | -67.868949 | 105.428356 | 19.955601 | 16.779444 | 0.541286 | 0.059597 |
| 758 | -68.186016 | 316.527115 | 51.532480 | 50.376855 | 0.210588 | 0.019850 |
| 759 | -68.186016 | -316.527115 | 51.532480 | 50.376855 | 0.210588 | 0.019850 |
| 760 | -68.198245 | 176.244217 | 30.076926 | 28.050138 | 0.360878 | 0.035650 |
| 761 | -68.198245 | -176.244217 | 30.076926 | 28.050138 | 0.360878 | 0.035650 |
| 762 | -68.388553 | 351.858377 | 57.047959 | 56.000000 | 0.190793 | 0.017857 |
| 763 | -68.578841 | -32.592349 | 12.084586 | 5.187233 | 0.903189 | 0.192781 |
| 764 | -68.578841 | 32.592349 | 12.084586 | 5.187233 | 0.903189 | 0.192781 |
| 765 | -68.595368 | -69.515583 | 15.543288 | 11.063749 | 0.702380 | 0.090385 |
| 766 | -68.595368 | 69.515583 | 15.543288 | 11.063749 | 0.702380 | 0.090385 |
| 767 | -69.371175 | 211.255741 | 35.388755 | 33.622396 | 0.311985 | 0.029742 |
| 768 | -69.371175 | -211.255741 | 35.388755 | 33.622396 | 0.311985 | 0.029742 |
| 769 | -69.970974 | -140.859652 | 25.032082 | 22.418510 | 0.444878 | 0.044606 |
| 770 | -69.970974 | 140.859652 | 25.032082 | 22.418510 | 0.444878 | 0.044606 |
| 771 | -70.388014 | 246.207763 | 40.755083 | 39.185182 | 0.274876 | 0.025520 |
| 772 | -70.388014 | -246.207763 | 40.755083 | 39.185182 | 0.274876 | 0.025520 |
| 773 | -71.236074 | 281.270855 | 46.179040 | 44.765647 | 0.245513 | 0.022339 |
| 774 | -71.236074 | -281.270855 | 46.179040 | 44.765647 | 0.245513 | 0.022339 |
| 775 | -71.291210 | 3.919085 | 11.363480 | 0.623742 | 0.998492 | 1.603228 |
| 776 | -71.291210 | -3.919085 | 11.363480 | 0.623742 | 0.998492 | 1.603228 |
| 777 | -71.480906 | 176.099249 | 30.248010 | 28.027066 | 0.376109 | 0.035680 |
| 778 | -71.480906 | -176.099249 | 30.248010 | 28.027066 | 0.376109 | 0.035680 |
| 779 | -71.511939 | -32.497012 | 12.501530 | 5.172060 | 0.910407 | 0.193347 |
| 780 | -71.511939 | 32.497012 | 12.501530 | 5.172060 | 0.910407 | 0.193347 |
| 781 | -71.808080 | 316.508402 | 51.654047 | 50.373877 | 0.221253 | 0.019852 |
| 782 | -71.808080 | -316.508402 | 51.654047 | 50.373877 | 0.221253 | 0.019852 |
| 783 | -71.851202 | 105.271767 | 20.285070 | 16.754522 | 0.563738 | 0.059685 |
| 784 | -71.851202 | -105.271767 | 20.285070 | 16.754522 | 0.563738 | 0.059685 |
| 785 | -72.010158 | 351.858377 | 57.160732 | 56.000000 | 0.200501 | 0.017857 |
| 786 | -72.173154 | -32.720681 | 12.612070 | 5.207658 | 0.910772 | 0.192025 |
| 787 | -72.173154 | 32.720681 | 12.612070 | 5.207658 | 0.910772 | 0.192025 |
| 788 | -72.681232 | 211.168850 | 35.543559 | 33.608566 | 0.325448 | 0.029754 |
| 789 | -72.681232 | -211.168850 | 35.543559 | 33.608566 | 0.325448 | 0.029754 |
| 790 | -73.692957 | 246.188140 | 40.899802 | 39.182059 | 0.286764 | 0.025522 |
| 791 | -73.692957 | -246.188140 | 40.899802 | 39.182059 | 0.286764 | 0.025522 |
| 792 | -73.972481 | -2.000937 | 11.777392 | 0.318459 | 0.999634 | 3.140121 |
| 793 | -73.972481 | 2.000937 | 11.777392 | 0.318459 | 0.999634 | 3.140121 |
| 794 | -73.984999 | -140.684708 | 25.298111 | 22.390667 | 0.465453 | 0.044661 |
| 795 | -73.984999 | 140.684708 | 25.298111 | 22.390667 | 0.465453 | 0.044661 |
| 796 | -74.508606 | -281.292379 | 46.312977 | 44.769073 | 0.256049 | 0.022337 |
| 797 | -74.508606 | 281.292379 | 46.312977 | 44.769073 | 0.256049 | 0.022337 |
| 798 | -74.757158 | 69.289437 | 16.222612 | 11.027756 | 0.733419 | 0.090680 |
| 799 | -74.757158 | -69.289437 | 16.222612 | 11.027756 | 0.733419 | 0.090680 |
| 800 | -75.045687 | -316.530852 | 51.773970 | 50.377450 | 0.230693 | 0.019850 |
| 801 | -75.045687 | 316.530852 | 51.773970 | 50.377450 | 0.230693 | 0.019850 |
| 802 | -75.233144 | 351.858377 | 57.265785 | 56.000000 | 0.209090 | 0.017857 |
| 803 | -75.487405 | 175.907873 | 30.465569 | 27.996608 | 0.394353 | 0.035719 |
| 804 | -75.487405 | -175.907873 | 30.465569 | 27.996608 | 0.394353 | 0.035719 |
| 805 | -76.676467 | -211.007198 | 35.731372 | 33.582839 | 0.341533 | 0.029777 |
| 806 | -76.676467 | 211.007198 | 35.731372 | 33.582839 | 0.341533 | 0.029777 |
| 807 | -77.232425 | 69.389625 | 16.524367 | 11.043702 | 0.743866 | 0.090549 |
| 808 | -77.232425 | -69.389625 | 16.524367 | 11.043702 | 0.743866 | 0.090549 |
| 809 | -77.356873 | -69.260283 | 16.525367 | 11.023116 | 0.745020 | 0.090718 |
| 810 | -77.356873 | 69.260283 | 16.525367 | 11.023116 | 0.745020 | 0.090718 |
| 811 | -77.358540 | -32.280256 | 13.340905 | 5.137562 | 0.922875 | 0.194645 |
| 812 | -77.358540 | 32.280256 | 13.340905 | 5.137562 | 0.922875 | 0.194645 |
| 813 | -77.690399 | 246.077645 | 41.069996 | 39.164474 | 0.301067 | 0.025533 |
| 814 | -77.690399 | -246.077645 | 41.069996 | 39.164474 | 0.301067 | 0.025533 |
| 815 | -78.253904 | 105.127152 | 20.858038 | 16.731506 | 0.597108 | 0.059767 |
| 816 | -78.253904 | -105.127152 | 20.858038 | 16.731506 | 0.597108 | 0.059767 |
| 817 | -78.514848 | -281.228183 | 46.470483 | 44.758856 | 0.268902 | 0.022342 |
| 818 | -78.514848 | 281.228183 | 46.470483 | 44.758856 | 0.268902 | 0.022342 |
| 819 | -79.058786 | 316.501686 | 51.920531 | 50.372808 | 0.242343 | 0.019852 |
| 820 | -79.058786 | -316.501686 | 51.920531 | 50.372808 | 0.242343 | 0.019852 |
| 821 | -79.248414 | 351.858377 | 57.402806 | 56.000000 | 0.219724 | 0.017857 |
| 822 | -80.292059 | -105.140847 | 21.055070 | 16.733686 | 0.606926 | 0.059760 |
| 823 | -80.292059 | 105.140847 | 21.055070 | 16.733686 | 0.606926 | 0.059760 |
| 824 | -80.376065 | -140.569414 | 25.771344 | 22.372317 | 0.496375 | 0.044698 |
| 825 | -80.376065 | 140.569414 | 25.771344 | 22.372317 | 0.496375 | 0.044698 |
| 826 | -80.738344 | -105.068490 | 21.089122 | 16.722169 | 0.609314 | 0.059801 |
| 827 | -80.738344 | 105.068490 | 21.089122 | 16.722169 | 0.609314 | 0.059801 |
| 828 | -81.728740 | 175.741308 | 30.846755 | 27.970098 | 0.421682 | 0.035752 |
| 829 | -81.728740 | -175.741308 | 30.846755 | 27.970098 | 0.421682 | 0.035752 |
| 830 | -82.328091 | -4.824289 | 13.125400 | 0.767809 | 0.998288 | 1.302406 |
| 831 | -82.328091 | 4.824289 | 13.125400 | 0.767809 | 0.998288 | 1.302406 |
| 832 | -82.600442 | 140.579658 | 25.950297 | 22.373948 | 0.506594 | 0.044695 |
| 833 | -82.600442 | -140.579658 | 25.950297 | 22.373948 | 0.506594 | 0.044695 |
| 834 | -82.777733 | -69.111821 | 17.162628 | 10.999488 | 0.767626 | 0.090913 |
| 835 | -82.777733 | 69.111821 | 17.162628 | 10.999488 | 0.767626 | 0.090913 |
| 836 | -82.862711 | 210.764530 | 36.043558 | 33.544217 | 0.365891 | 0.029811 |
| 837 | -82.862711 | -210.764530 | 36.043558 | 33.544217 | 0.365891 | 0.029811 |
| 838 | -82.995671 | 140.490869 | 25.970052 | 22.359816 | 0.508631 | 0.044723 |
| 839 | -82.995671 | -140.490869 | 25.970052 | 22.359816 | 0.508631 | 0.044723 |
| 840 | -84.019349 | 245.657331 | 41.321103 | 39.097579 | 0.323614 | 0.025577 |
| 841 | -84.019349 | -245.657331 | 41.321103 | 39.097579 | 0.323614 | 0.025577 |
| 842 | -84.263147 | 25.881773 | 14.029257 | 4.119212 | 0.955923 | 0.242765 |
| 843 | -84.263147 | -25.881773 | 14.029257 | 4.119212 | 0.955923 | 0.242765 |
| 844 | -84.334363 | 3.013423 | 13.430797 | 0.479601 | 0.999362 | 2.085066 |
| 845 | -84.334363 | -3.013423 | 13.430797 | 0.479601 | 0.999362 | 2.085066 |
| 846 | -84.417542 | -175.895762 | 31.051794 | 27.994680 | 0.432679 | 0.035721 |
| 847 | -84.417542 | 175.895762 | 31.051794 | 27.994680 | 0.432679 | 0.035721 |
| 848 | -84.577439 | -175.688159 | 31.033040 | 27.961639 | 0.433761 | 0.035763 |
| 849 | -84.577439 | 175.688159 | 31.033040 | 27.961639 | 0.433761 | 0.035763 |
| 850 | -85.105900 | 280.538672 | 46.658453 | 44.649116 | 0.290302 | 0.022397 |
| 851 | -85.105900 | -280.538672 | 46.658453 | 44.649116 | 0.290302 | 0.022397 |
| 852 | -85.168644 | 38.197052 | 14.855827 | 6.079250 | 0.912437 | 0.164494 |
| 853 | -85.168644 | -38.197052 | 14.855827 | 6.079250 | 0.912437 | 0.164494 |
| 854 | -85.665558 | 211.188899 | 36.271736 | 33.611757 | 0.375888 | 0.029751 |
| 855 | -85.665558 | -211.188899 | 36.271736 | 33.611757 | 0.375888 | 0.029751 |
| 856 | -85.756665 | -210.815246 | 36.222096 | 33.552289 | 0.376803 | 0.029804 |
| 857 | -85.756665 | 210.815246 | 36.222096 | 33.552289 | 0.376803 | 0.029804 |
| 858 | -85.966733 | -315.560139 | 52.053273 | 50.222956 | 0.262847 | 0.019911 |
| 859 | -85.966733 | 315.560139 | 52.053273 | 50.222956 | 0.262847 | 0.019911 |
| 860 | -85.974527 | 105.007973 | 21.599556 | 16.712538 | 0.633498 | 0.059835 |
| 861 | -85.974527 | -105.007973 | 21.599556 | 16.712538 | 0.633498 | 0.059835 |
| 862 | -86.375776 | 246.597853 | 41.585233 | 39.247267 | 0.330577 | 0.025479 |
| 863 | -86.375776 | -246.597853 | 41.585233 | 39.247267 | 0.330577 | 0.025479 |
| 864 | -86.519761 | 350.775137 | 57.500737 | 55.827597 | 0.239476 | 0.017912 |
| 865 | -86.519761 | -350.775137 | 57.500737 | 55.827597 | 0.239476 | 0.017912 |
| 866 | -86.708900 | 282.092865 | 46.969538 | 44.896474 | 0.293811 | 0.022273 |
| 867 | -86.708900 | -282.092865 | 46.969538 | 44.896474 | 0.293811 | 0.022273 |
| 868 | -86.734242 | -245.973742 | 41.510438 | 39.147937 | 0.332547 | 0.025544 |
| 869 | -86.734242 | 245.973742 | 41.510438 | 39.147937 | 0.332547 | 0.025544 |
| 870 | -86.757772 | -317.567748 | 52.394664 | 50.542477 | 0.263537 | 0.019785 |
| 871 | -86.757772 | 317.567748 | 52.394664 | 50.542477 | 0.263537 | 0.019785 |
| 872 | -87.524583 | 281.194311 | 46.871277 | 44.753465 | 0.297196 | 0.022345 |
| 873 | -87.524583 | -281.194311 | 46.871277 | 44.753465 | 0.297196 | 0.022345 |
| 874 | -88.040412 | -316.496355 | 52.284532 | 50.371959 | 0.267996 | 0.019852 |
| 875 | -88.040412 | 316.496355 | 52.284532 | 50.371959 | 0.267996 | 0.019852 |
| 876 | -88.170415 | 140.558523 | 26.407599 | 22.370584 | 0.531391 | 0.044702 |
| 877 | -88.170415 | -140.558523 | 26.407599 | 22.370584 | 0.531391 | 0.044702 |
| 878 | -88.219075 | 351.858377 | 57.733315 | 56.000000 | 0.243196 | 0.017857 |
| 879 | -88.657831 | 27.265548 | 14.762529 | 4.339447 | 0.955821 | 0.230444 |
| 880 | -88.657831 | -27.265548 | 14.762529 | 4.339447 | 0.955821 | 0.230444 |
| 881 | -89.526558 | 36.237090 | 15.371543 | 5.767312 | 0.926946 | 0.173391 |
| 882 | -89.526558 | -36.237090 | 15.371543 | 5.767312 | 0.926946 | 0.173391 |
| 883 | -89.792477 | 175.890513 | 31.430648 | 27.993845 | 0.454681 | 0.035722 |
| 884 | -89.792477 | -175.890513 | 31.430648 | 27.993845 | 0.454681 | 0.035722 |
| 885 | -90.026130 | -62.325176 | 17.426653 | 9.919360 | 0.822195 | 0.100813 |
| 886 | -90.026130 | 62.325176 | 17.426653 | 9.919360 | 0.822195 | 0.100813 |
| 887 | -90.376140 | 75.533052 | 18.745918 | 12.021459 | 0.767304 | 0.083185 |
| 888 | -90.376140 | -75.533052 | 18.745918 | 12.021459 | 0.767304 | 0.083185 |
| 889 | -90.531744 | 0.000000 | 14.408575 | 0.000000 | 1.000000 | inf |
| 890 | -91.010852 | -211.042064 | 36.578546 | 33.588388 | 0.395992 | 0.029772 |
| 891 | -91.010852 | 211.042064 | 36.578546 | 33.588388 | 0.395992 | 0.029772 |
| 892 | -91.898481 | -246.139516 | 41.815668 | 39.174321 | 0.349776 | 0.025527 |
| 893 | -91.898481 | 246.139516 | 41.815668 | 39.174321 | 0.349776 | 0.025527 |
| 894 | -92.541781 | -281.308683 | 47.132053 | 44.771668 | 0.312494 | 0.022336 |
| 895 | -92.541781 | 281.308683 | 47.132053 | 44.771668 | 0.312494 | 0.022336 |
| 896 | -92.956744 | -316.560408 | 52.509422 | 50.382154 | 0.281750 | 0.019848 |
| 897 | -92.956744 | 316.560408 | 52.509422 | 50.382154 | 0.281750 | 0.019848 |
| 898 | -93.101793 | 351.858377 | 57.927209 | 56.000000 | 0.255797 | 0.017857 |
| 899 | -93.387365 | -98.033026 | 21.548706 | 15.602441 | 0.689743 | 0.064093 |
| 900 | -93.387365 | 98.033026 | 21.548706 | 15.602441 | 0.689743 | 0.064093 |
| 901 | -93.532091 | -111.580776 | 23.172502 | 17.758632 | 0.642403 | 0.056311 |
| 902 | -93.532091 | 111.580776 | 23.172502 | 17.758632 | 0.642403 | 0.056311 |
| 903 | -93.692886 | -4.289078 | 14.927302 | 0.682628 | 0.998954 | 1.464927 |
| 904 | -93.692886 | 4.289078 | 14.927302 | 0.682628 | 0.998954 | 1.464927 |
| 905 | -94.349268 | 63.861696 | 18.132562 | 10.163905 | 0.828132 | 0.098387 |
| 906 | -94.349268 | -63.861696 | 18.132562 | 10.163905 | 0.828132 | 0.098387 |
| 907 | -94.745043 | 73.683778 | 19.102520 | 11.727138 | 0.789380 | 0.085272 |
| 908 | -94.745043 | -73.683778 | 19.102520 | 11.727138 | 0.789380 | 0.085272 |
| 909 | -95.202577 | 6.142057 | 15.183461 | 0.977539 | 0.997925 | 1.022977 |
| 910 | -95.202577 | -6.142057 | 15.183461 | 0.977539 | 0.997925 | 1.022977 |
| 911 | -95.692689 | 133.532122 | 26.145974 | 21.252297 | 0.582497 | 0.047054 |
| 912 | -95.692689 | -133.532122 | 26.145974 | 21.252297 | 0.582497 | 0.047054 |
| 913 | -95.747216 | -147.119968 | 27.936936 | 23.414870 | 0.545466 | 0.042708 |
| 914 | -95.747216 | 147.119968 | 27.936936 | 23.414870 | 0.545466 | 0.042708 |
| 915 | -97.319856 | 168.949269 | 31.031137 | 26.889111 | 0.499142 | 0.037190 |
| 916 | -97.319856 | -168.949269 | 31.031137 | 26.889111 | 0.499142 | 0.037190 |
| 917 | -97.471196 | 182.439238 | 32.920349 | 29.036107 | 0.471229 | 0.034440 |
| 918 | -97.471196 | -182.439238 | 32.920349 | 29.036107 | 0.471229 | 0.034440 |
| 919 | -97.628457 | -99.626238 | 22.200091 | 15.856008 | 0.699909 | 0.063068 |
| 920 | -97.628457 | 99.626238 | 22.200091 | 15.856008 | 0.699909 | 0.063068 |
| 921 | -97.948677 | -19.505992 | 15.895131 | 3.104475 | 0.980742 | 0.322116 |
| 922 | -97.948677 | 19.505992 | 15.895131 | 3.104475 | 0.980742 | 0.322116 |
| 923 | -97.952152 | -109.843672 | 23.423508 | 17.482163 | 0.665552 | 0.057201 |
| 924 | -97.952152 | 109.843672 | 23.423508 | 17.482163 | 0.665552 | 0.057201 |
| 925 | -98.399975 | 204.263076 | 36.085013 | 32.509478 | 0.433999 | 0.030760 |
| 926 | -98.399975 | -204.263076 | 36.085013 | 32.509478 | 0.433999 | 0.030760 |
| 927 | -98.873793 | -217.775410 | 38.065044 | 34.660033 | 0.413404 | 0.028852 |
| 928 | -98.873793 | 217.775410 | 38.065044 | 34.660033 | 0.413404 | 0.028852 |
| 929 | -99.104578 | -239.370236 | 41.233058 | 38.096956 | 0.382532 | 0.026249 |
| 930 | -99.104578 | 239.370236 | 41.233058 | 38.096956 | 0.382532 | 0.026249 |
| 931 | -99.299795 | -43.283124 | 17.240145 | 6.888723 | 0.916701 | 0.145165 |
| 932 | -99.299795 | 43.283124 | 17.240145 | 6.888723 | 0.916701 | 0.145165 |
| 933 | -99.680943 | -274.334108 | 46.454570 | 43.661629 | 0.341510 | 0.022903 |
| 934 | -99.680943 | 274.334108 | 46.454570 | 43.661629 | 0.341510 | 0.022903 |
| 935 | -99.833988 | -135.101920 | 26.735830 | 21.502138 | 0.594299 | 0.046507 |
| 936 | -99.833988 | 135.101920 | 26.735830 | 21.502138 | 0.594299 | 0.046507 |
| 937 | -99.860702 | 253.218384 | 43.321645 | 40.300958 | 0.366868 | 0.024813 |
| 938 | -99.860702 | -253.218384 | 43.321645 | 40.300958 | 0.366868 | 0.024813 |
| 939 | -100.175662 | -309.342071 | 51.750492 | 49.233320 | 0.308083 | 0.020311 |
| 940 | -100.175662 | 309.342071 | 51.750492 | 49.233320 | 0.308083 | 0.020311 |
| 941 | -100.185518 | -145.532934 | 28.120014 | 23.162286 | 0.567035 | 0.043174 |
| 942 | -100.185518 | 145.532934 | 28.120014 | 23.162286 | 0.567035 | 0.043174 |
| 943 | -100.392397 | 288.649950 | 48.639330 | 45.940066 | 0.328498 | 0.021767 |
| 944 | -100.392397 | -288.649950 | 48.639330 | 45.940066 | 0.328498 | 0.021767 |
| 945 | -100.497591 | -344.475254 | 57.110455 | 54.824939 | 0.280066 | 0.018240 |
| 946 | -100.497591 | 344.475254 | 57.110455 | 54.824939 | 0.280066 | 0.018240 |
| 947 | -100.581039 | 323.994069 | 53.992878 | 51.565258 | 0.296483 | 0.019393 |
| 948 | -100.581039 | -323.994069 | 53.992878 | 51.565258 | 0.296483 | 0.019393 |
| 949 | -101.426917 | 170.408514 | 31.561866 | 27.121357 | 0.511459 | 0.036871 |
| 950 | -101.426917 | -170.408514 | 31.561866 | 27.121357 | 0.511459 | 0.036871 |
| 951 | -101.798814 | 180.982879 | 33.048247 | 28.804320 | 0.490246 | 0.034717 |
| 952 | -101.798814 | -180.982879 | 33.048247 | 28.804320 | 0.490246 | 0.034717 |
| 953 | -101.883732 | 6.664475 | 16.249954 | 1.060684 | 0.997867 | 0.942788 |
| 954 | -101.883732 | -6.664475 | 16.249954 | 1.060684 | 0.997867 | 0.942788 |
| 955 | -102.388876 | 20.965247 | 16.633804 | 3.336723 | 0.979673 | 0.299695 |
| 956 | -102.388876 | -20.965247 | 16.633804 | 3.336723 | 0.979673 | 0.299695 |
| 957 | -102.649996 | -205.587598 | 36.572158 | 32.720283 | 0.446713 | 0.030562 |
| 958 | -102.649996 | 205.587598 | 36.572158 | 32.720283 | 0.446713 | 0.030562 |
| 959 | -102.964960 | -216.303713 | 38.127187 | 34.425805 | 0.429808 | 0.029048 |
| 960 | -102.964960 | 216.303713 | 38.127187 | 34.425805 | 0.429808 | 0.029048 |
| 961 | -103.611476 | 240.711782 | 41.708769 | 38.310470 | 0.395367 | 0.026103 |
| 962 | -103.611476 | -240.711782 | 41.708769 | 38.310470 | 0.395367 | 0.026103 |
| 963 | -103.754665 | -56.004045 | 18.765092 | 8.913321 | 0.879989 | 0.112192 |
| 964 | -103.754665 | 56.004045 | 18.765092 | 8.913321 | 0.879989 | 0.112192 |
| 965 | -103.791363 | 4.588853 | 16.535046 | 0.730339 | 0.999024 | 1.369228 |
| 966 | -103.791363 | -4.588853 | 16.535046 | 0.730339 | 0.999024 | 1.369228 |
| 967 | -103.792027 | 41.452110 | 17.787701 | 6.597308 | 0.928676 | 0.151577 |
| 968 | -103.792027 | -41.452110 | 17.787701 | 6.597308 | 0.928676 | 0.151577 |
| 969 | -103.817204 | -251.551913 | 43.311314 | 40.035730 | 0.381494 | 0.024978 |
| 970 | -103.817204 | 251.551913 | 43.311314 | 40.035730 | 0.381494 | 0.024978 |
| 971 | -103.986268 | -34.363132 | 17.430169 | 5.469062 | 0.949499 | 0.182847 |
| 972 | -103.986268 | 34.363132 | 17.430169 | 5.469062 | 0.949499 | 0.182847 |
| 973 | -104.260819 | -80.880610 | 21.001212 | 12.872549 | 0.790127 | 0.077685 |
| 974 | -104.260819 | 80.880610 | 21.001212 | 12.872549 | 0.790127 | 0.077685 |
| 975 | -104.322107 | 275.875236 | 46.941333 | 43.906907 | 0.353705 | 0.022775 |
| 976 | -104.322107 | -275.875236 | 46.941333 | 43.906907 | 0.353705 | 0.022775 |
| 977 | -104.432405 | -286.781615 | 48.574814 | 45.642712 | 0.342172 | 0.021909 |
| 978 | -104.432405 | 286.781615 | 48.574814 | 45.642712 | 0.342172 | 0.021909 |
| 979 | -104.765916 | -311.109362 | 52.246700 | 49.514593 | 0.319140 | 0.020196 |
| 980 | -104.765916 | 311.109362 | 52.246700 | 49.514593 | 0.319140 | 0.020196 |
| 981 | -104.812659 | -322.040367 | 53.900610 | 51.254316 | 0.309485 | 0.019511 |
| 982 | -104.812659 | 322.040367 | 53.900610 | 51.254316 | 0.309485 | 0.019511 |
| 983 | -104.929967 | 346.389833 | 57.603584 | 55.129654 | 0.289915 | 0.018139 |
| 984 | -104.929967 | -346.389833 | 57.603584 | 55.129654 | 0.289915 | 0.018139 |
| 985 | -105.208237 | 0.000000 | 16.744411 | 0.000000 | 1.000000 | inf |
| 986 | -106.069332 | 34.680255 | 17.760881 | 5.519534 | 0.950485 | 0.181175 |
| 987 | -106.069332 | -34.680255 | 17.760881 | 5.519534 | 0.950485 | 0.181175 |
| 988 | -106.442343 | -69.300672 | 20.214906 | 11.029544 | 0.838036 | 0.090666 |
| 989 | -106.442343 | 69.300672 | 20.214906 | 11.029544 | 0.838036 | 0.090666 |
| 990 | -107.170073 | 91.634457 | 22.441580 | 14.584077 | 0.760047 | 0.068568 |
| 991 | -107.170073 | -91.634457 | 22.441580 | 14.584077 | 0.760047 | 0.068568 |
| 992 | -107.393409 | 117.085123 | 25.286245 | 18.634676 | 0.675948 | 0.053663 |
| 993 | -107.393409 | -117.085123 | 25.286245 | 18.634676 | 0.675948 | 0.053663 |
| 994 | -108.092648 | 57.766084 | 19.506022 | 9.193758 | 0.881957 | 0.108769 |
| 995 | -108.092648 | -57.766084 | 19.506022 | 9.193758 | 0.881957 | 0.108769 |
| 996 | -108.203753 | 32.422115 | 17.977638 | 5.160140 | 0.957921 | 0.193793 |
| 997 | -108.203753 | -32.422115 | 17.977638 | 5.160140 | 0.957921 | 0.193793 |
| 998 | -108.324174 | 69.398551 | 20.474951 | 11.045122 | 0.842020 | 0.090538 |
| 999 | -108.324174 | -69.398551 | 20.474951 | 11.045122 | 0.842020 | 0.090538 |
Generating an instance of StabilityDerivatives
Variable print_info has no assigned value in the settings file.
will default to the value: c_bool(True)
Variable folder has no assigned value in the settings file.
will default to the value: ./output/
/home/ng213/code/sharpy/sharpy/postproc/asymptoticstability.py:171: UserWarning: Plotting modes is under development
warn.warn('Plotting modes is under development')
|==============|==============|==============|==============|==============|==============|==============|
| der | X | Y | Z | L | M | N |
|==============|==============|==============|==============|==============|==============|==============|
| u | -0.000000 | -0.032063 | 0.000000 | 103.702544 | -0.000000 | 0.215455 |
| v | 131.843986 | 0.000000 | -982.084813 | -0.000000 | 1279.474176 | -0.000000 |
| w | 0.000000 | -187.481605 | -0.000000 |-22078.785295 | 0.000000 | -3334.924961 |
| p | -187.422614 | 0.000000 | 1572.771760 | 0.000000 | -2857.778575 | 0.000000 |
| q | 0.000000 | -2.610892 | 0.000000 | 1127.543337 | -0.000000 | -38.871906 |
| r | 0.000000 | 0.000000 | -0.000000 | 0.000000 | 0.000000 | 0.000000 |
| flap1 | -0.000000 | 1.108474 | 0.000000 | 271.384778 | -0.000000 | 23.331888 |
|==============|==============|==============|==============|==============|==============|==============|
| der | C_D | C_Y | C_L | C_l | C_m | C_n |
|==============|==============|==============|==============|==============|==============|==============|
| u | -0.000000 | -0.000006 | 0.000000 | 0.001009 | -0.000000 | -0.000078 |
| v | 0.010573 | 0.000000 | -0.193187 | -0.000000 | 0.347457 | -0.000000 |
| w | 0.000000 | -0.036606 | -0.000000 | -0.217442 | 0.000000 | -0.015495 |
| p | -0.479599 | 0.000000 | 12.034020 | 0.000000 | -30.222290 | 0.000000 |
| q | 0.000000 | -0.019853 | 0.000000 | 0.010944 | -0.000000 | -0.001245 |
| r | 0.000000 | 0.000000 | -0.000000 | 0.000000 | 0.000000 | 0.000000 |
| alpha | 0.000000 | -1.024980 | -0.000000 | -6.088362 | 0.000000 | -0.433847 |
| beta | 0.296049 | 0.000000 | -5.409222 | -0.000000 | 9.728798 | -0.000000 |
FINISHED - Elapsed time = 29.3233356 seconds
FINISHED - CPU process time = 69.2634336 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¶
[18]:
eigenvalues_trim = np.loadtxt('./output/horten_u_inf2800_M4N11Msf5/stability/eigenvalues.dat')
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!
[19]:
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]');

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!
[20]:
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]');

Stability Derivatives¶
Stability derivatives are calculated using the steady-state frequency response of the UVLM system. The output is saved in ./output/<case_name>/stability/
. Note that stability derivatives are expressed in the SHARPy Frame of Reference, which is South East Up (not the conventional in flight dynamics literature).
This body attached frame of reference has:
\(x\) positive downstream
\(y\) positive towards the right wing
\(z\) positive up
Simulation NREL 5MW wind turbine¶
[1]:
%config InlineBackend.figure_format = 'svg'
from IPython.display import Image
url = 'https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/dev_doc/docs/source/content/example_notebooks/images/turbulence_no_legend.png'
Image(url=url, width=800)
[1]:

In this notebook the blade loads on the NREL-5MW reference wind turbine computed with SHARPy and OpenFAST will be compared. However, zero-drag airfoils have been used.
OpenFAST: https://openfast.readthedocs.io
NREL-5MW: Jonkman, J.; Butterfield, S.; Musial, W. and Scott, G.. Definition of a 5-MW Reference Wind Turbine for Offshore System Development, Technical Report, NREL 2009
Load the required packages:
[2]:
# Required packages
import numpy as np
import os
import matplotlib.pyplot as plt
# Required SHARPy modules
import sharpy.sharpy_main
import sharpy.utils.algebra as algebra
import sharpy.utils.generate_cases as gc
import cases.templates.template_wt as template_wt
These are the results from the OpenFAST simulation for comparison: out-of-plane of_cNdrR
and in-plane of_cTdrR
coefficients along the blade and thrust of_ct
and power of_cp
rotor coefficients
[3]:
of_rR = np.array([0.20158356, 0.3127131, 0.40794048, 0.5984148, 0.6936519, 0.85238045, 0.899999, 0.95555407, 0.98729974, 1.0])
of_cNdrR = np.array([0.08621394, 0.14687876, 0.19345148, 0.2942731, 0.36003628, 0.43748564, 0.44762507, 0.38839236, 0.29782477, 0.0])
of_cTdrR = np.array([0.048268348, 0.051957503, 0.05304592, 0.052862607, 0.056001827, 0.0536646, 0.050112925, 0.038993906, 0.023664437, 0.0])
of_ct = 0.69787693
of_cp = 0.48813498
Create SHARPy case¶
Definition of parameters
[4]:
# Mathematical constants
deg2rad = np.pi/180.
# Case
case = 'rotor'
# route = os.path.dirname(os.path.realpath(__file__)) + '/'
route = './'
# Geometry discretization
chord_panels = np.array([8], dtype=int)
revs_in_wake = 5
# Operation
rotation_velocity = 12.1*2*np.pi/60
pitch_deg = 0. #degrees
# Wind
WSP = 12.
air_density = 1.225
# Simulation
dphi = 4.*deg2rad
revs_to_simulate = 5
Computation of associated parameters
[5]:
dt = dphi/rotation_velocity
time_steps = int(revs_to_simulate*2.*np.pi/dphi)
mstar = int(revs_in_wake*2.*np.pi/dphi)
Generation of the rotor geometry based on the information in the excel file
[6]:
rotor = template_wt.rotor_from_excel_type02(
chord_panels,
rotation_velocity,
pitch_deg,
excel_file_name= 'source/type02_db_NREL5MW_v02.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,
wsp = WSP,
dt = dt)
rotor_from_excel_type02 is obsolete! rotor_from_excel_type03 instead!
WARNING: The poisson cofficient is assumed equal to 0.3
WARNING: Cross-section area is used as shear area
WARNING: Using perpendicular axis theorem to compute the inertia around xB
WARNING: Replacing node 49 by node 0
WARNING: Replacing node 98 by node 0
Define simulation details. The steady simulation is faster than the dynamic simulation. However, the dynamic simulation includes wake self-induction and provides more accurate results.
[7]:
steady_simulation = False
[8]:
SimInfo = gc.SimulationInformation()
SimInfo.set_default_values()
if steady_simulation:
SimInfo.solvers['SHARPy']['flow'] = ['BeamLoader',
'AerogridLoader',
'StaticCoupledRBM',
'BeamPlot',
'AerogridPlot',
'SaveData']
else:
SimInfo.solvers['SHARPy']['flow'] = ['BeamLoader',
'AerogridLoader',
'StaticCoupledRBM',
'DynamicCoupled']
SimInfo.solvers['SHARPy']['case'] = case
SimInfo.solvers['SHARPy']['route'] = route
SimInfo.solvers['SHARPy']['write_log'] = True
SimInfo.set_variable_all_dicts('dt', dt)
SimInfo.set_variable_all_dicts('rho', air_density)
SimInfo.solvers['SteadyVelocityField']['u_inf'] = WSP
SimInfo.solvers['SteadyVelocityField']['u_inf_direction'] = np.array([0., 0., 1.])
SimInfo.solvers['BeamLoader']['unsteady'] = 'on'
SimInfo.solvers['AerogridLoader']['unsteady'] = 'on'
SimInfo.solvers['AerogridLoader']['mstar'] = mstar
SimInfo.solvers['AerogridLoader']['freestream_dir'] = np.array([0.,0.,0.])
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': mstar,
'r': 1.,
'dphimax': 10*deg2rad}
SimInfo.solvers['StaticCoupledRBM']['structural_solver'] = 'RigidDynamicPrescribedStep'
SimInfo.solvers['StaticCoupledRBM']['structural_solver_settings'] = SimInfo.solvers['RigidDynamicPrescribedStep']
SimInfo.solvers['StaticCoupledRBM']['aero_solver'] = 'StaticUvlm'
SimInfo.solvers['StaticCoupledRBM']['aero_solver_settings'] = SimInfo.solvers['StaticUvlm']
SimInfo.solvers['StaticCoupledRBM']['tolerance'] = 1e-8
SimInfo.solvers['StaticCoupledRBM']['n_load_steps'] = 0
SimInfo.solvers['StaticCoupledRBM']['relaxation_factor'] = 0.
SimInfo.solvers['StaticUvlm']['num_cores'] = 8
SimInfo.solvers['StaticUvlm']['velocity_field_generator'] = 'SteadyVelocityField'
SimInfo.solvers['StaticUvlm']['velocity_field_input'] = SimInfo.solvers['SteadyVelocityField']
SimInfo.solvers['SaveData']['compress_float'] = True
# Only used for steady_simulation = False
SimInfo.solvers['StepUvlm']['convection_scheme'] = 3
SimInfo.solvers['StepUvlm']['num_cores'] = 8
SimInfo.solvers['StepUvlm']['velocity_field_generator'] = 'SteadyVelocityField'
SimInfo.solvers['StepUvlm']['velocity_field_input'] = SimInfo.solvers['SteadyVelocityField']
SimInfo.solvers['DynamicCoupled']['structural_solver'] = 'RigidDynamicPrescribedStep'
SimInfo.solvers['DynamicCoupled']['structural_solver_settings'] = SimInfo.solvers['RigidDynamicPrescribedStep']
SimInfo.solvers['DynamicCoupled']['aero_solver'] = 'StepUvlm'
SimInfo.solvers['DynamicCoupled']['aero_solver_settings'] = SimInfo.solvers['StepUvlm']
SimInfo.solvers['DynamicCoupled']['postprocessors'] = ['BeamPlot', 'AerogridPlot', 'Cleanup', 'SaveData']
SimInfo.solvers['DynamicCoupled']['postprocessors_settings'] = {'BeamPlot': SimInfo.solvers['BeamPlot'],
'AerogridPlot': SimInfo.solvers['AerogridPlot'],
'Cleanup': SimInfo.solvers['Cleanup'],
'SaveData': SimInfo.solvers['SaveData']}
SimInfo.solvers['DynamicCoupled']['minimum_steps'] = 0
SimInfo.solvers['DynamicCoupled']['include_unsteady_force_contribution'] = True
SimInfo.solvers['DynamicCoupled']['relaxation_factor'] = 0.
SimInfo.solvers['DynamicCoupled']['final_relaxation_factor'] = 0.
SimInfo.solvers['DynamicCoupled']['dynamic_relaxation'] = False
SimInfo.solvers['DynamicCoupled']['relaxation_steps'] = 0
# Define dynamic simulation (used regardless the value of "steady_simulation" variable)
SimInfo.define_num_steps(time_steps)
SimInfo.with_forced_vel = True
SimInfo.for_vel = np.zeros((time_steps,6), dtype=float)
SimInfo.for_vel[:,5] = rotation_velocity
SimInfo.for_acc = np.zeros((time_steps,6), dtype=float)
SimInfo.with_dynamic_forces = True
SimInfo.dynamic_forces = np.zeros((time_steps,rotor.StructuralInformation.num_node,6), dtype=float)
Generate simulation files
[9]:
gc.clean_test_files(SimInfo.solvers['SHARPy']['route'], SimInfo.solvers['SHARPy']['case'])
rotor.generate_h5_files(SimInfo.solvers['SHARPy']['route'], SimInfo.solvers['SHARPy']['case'])
SimInfo.generate_solver_file()
SimInfo.generate_dyn_file(time_steps)
Run SHARPy case¶
[10]:
sharpy_output = sharpy.sharpy_main.main(['', SimInfo.solvers['SHARPy']['route'] + SimInfo.solvers['SHARPy']['case'] + '.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/arturo/code/sharpy/docs/source/content/example_notebooks
SHARPy being run is in /home/arturo/code/sharpy
The branch being run is dev_minor_changes
The version and commit hash are: v1.2.1-2-g00d8d4a0-00d8d4a0
The available solvers on this session are:
_BaseStructural
AerogridLoader
BeamLoader
DynamicCoupled
DynamicUVLM
LinDynamicSim
LinearAssembler
Modal
NoAero
NonLinearDynamic
NonLinearDynamicCoupledStep
NonLinearDynamicMultibody
NonLinearDynamicPrescribedStep
NonLinearStatic
NonLinearStaticMultibody
PrescribedUvlm
RigidDynamicCoupledStep
RigidDynamicPrescribedStep
StaticCoupled
StaticCoupledRBM
StaticTrim
StaticUvlm
StepLinearUVLM
StepUvlm
Trim
FrequencyResponse
WriteVariablesTime
BeamPlot
LiftDistribution
AeroForcesCalculator
CreateSnapshot
Cleanup
AsymptoticStability
UDPout
PickleData
SaveData
SaveParametricCase
StallCheck
BeamLoads
PlotFlowField
AerogridPlot
PreSharpy
Generating an instance of BeamLoader
Generating an instance of AerogridLoader
Variable shear_direction has no assigned value in the settings file.
will default to the value: [1. 0. 0.]
Variable shear_exp has no assigned value in the settings file.
will default to the value: 0.0
Variable h_ref has no assigned value in the settings file.
will default to the value: 1.0
Variable h_corr has no assigned value in the settings file.
will default to the value: 1.0
The aerodynamic grid contains 3 surfaces
Surface 0, M=8, N=48
Wake 0, M=450, N=48
Surface 1, M=8, N=48
Wake 1, M=450, N=48
Surface 2, M=8, N=48
Wake 2, M=450, N=48
In total: 1152 bound panels
In total: 64800 wake panels
Total number of panels = 65952
Generating an instance of StaticCoupledRBM
Generating an instance of RigidDynamicPrescribedStep
Generating an instance of StaticUvlm
i_step: 0, i_iter: 0
Resultant forces and moments: (array([1.96223482e-10, 3.49416496e-10, 7.63216819e+04]), array([-3.95311872e-08, 2.75421144e-08, 6.10782165e+06]))
Generating an instance of DynamicCoupled
Generating an instance of RigidDynamicPrescribedStep
Generating an instance of StepUvlm
Generating an instance of BeamPlot
Generating an instance of AerogridPlot
Generating an instance of Cleanup
Generating an instance of SaveData
Variable save_linear has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable save_linear_uvlm has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable save_rom has no assigned value in the settings file.
will default to the value: c_bool(False)
Variable skip_attr has no assigned value in the settings file.
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']
Variable format has no assigned value in the settings file.
will default to the value: h5
|=======|========|======|==============|==============|==============|==============|==============|
| ts | t | iter | struc ratio | iter time | residual vel | FoR_vel(x) | FoR_vel(z) |
|=======|========|======|==============|==============|==============|==============|==============|
| 1 | 0.0551 | 1 | 0.000378 | 37.364391 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 2 | 0.1102 | 1 | 0.000387 | 36.473455 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 3 | 0.1653 | 1 | 0.000385 | 36.562880 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 4 | 0.2204 | 1 | 0.000399 | 36.460732 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 5 | 0.2755 | 1 | 0.000377 | 37.725125 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 6 | 0.3306 | 1 | 0.000380 | 37.602508 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 7 | 0.3857 | 1 | 0.000383 | 36.958194 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 8 | 0.4408 | 1 | 0.000380 | 36.965060 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 9 | 0.4959 | 1 | 0.000384 | 37.159469 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 10 | 0.5510 | 1 | 0.000381 | 37.406258 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 11 | 0.6061 | 1 | 0.000383 | 36.978996 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 12 | 0.6612 | 1 | 0.000386 | 36.671312 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 13 | 0.7163 | 1 | 0.000389 | 37.181938 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 14 | 0.7713 | 1 | 0.000397 | 35.888934 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 15 | 0.8264 | 1 | 0.000389 | 36.218724 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 16 | 0.8815 | 1 | 0.000395 | 35.675477 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 17 | 0.9366 | 1 | 0.000378 | 36.680665 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 18 | 0.9917 | 1 | 0.000379 | 37.099096 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 19 | 1.0468 | 1 | 0.000393 | 35.893127 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 20 | 1.1019 | 1 | 0.000395 | 35.762256 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 21 | 1.1570 | 1 | 0.000395 | 35.788830 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 22 | 1.2121 | 1 | 0.000396 | 35.774906 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 23 | 1.2672 | 1 | 0.000397 | 35.692661 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 24 | 1.3223 | 1 | 0.000391 | 35.944855 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 25 | 1.3774 | 1 | 0.000395 | 35.885424 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 26 | 1.4325 | 1 | 0.000392 | 35.985139 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 27 | 1.4876 | 1 | 0.000389 | 35.960321 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 28 | 1.5427 | 1 | 0.000398 | 35.716744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 29 | 1.5978 | 1 | 0.000380 | 37.372750 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 30 | 1.6529 | 1 | 0.000382 | 37.597201 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 31 | 1.7080 | 1 | 0.000377 | 37.396400 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 32 | 1.7631 | 1 | 0.000383 | 36.146122 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 33 | 1.8182 | 1 | 0.000387 | 36.151504 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 34 | 1.8733 | 1 | 0.000393 | 35.937259 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 35 | 1.9284 | 1 | 0.000396 | 35.525134 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 36 | 1.9835 | 1 | 0.000397 | 35.773998 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 37 | 2.0386 | 1 | 0.000390 | 35.713280 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 38 | 2.0937 | 1 | 0.000389 | 35.792318 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 39 | 2.1488 | 1 | 0.000396 | 35.624616 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 40 | 2.2039 | 1 | 0.000394 | 35.819409 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 41 | 2.2590 | 1 | 0.000388 | 35.763058 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 42 | 2.3140 | 1 | 0.000387 | 36.050468 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 43 | 2.3691 | 1 | 0.000397 | 35.570825 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 44 | 2.4242 | 1 | 0.000395 | 35.640756 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 45 | 2.4793 | 1 | 0.000398 | 35.528759 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 46 | 2.5344 | 1 | 0.000394 | 35.652283 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 47 | 2.5895 | 1 | 0.000390 | 35.690114 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 48 | 2.6446 | 1 | 0.000397 | 35.497854 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 49 | 2.6997 | 1 | 0.000397 | 35.710766 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 50 | 2.7548 | 1 | 0.000398 | 35.713774 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 51 | 2.8099 | 1 | 0.000389 | 36.070739 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 52 | 2.8650 | 1 | 0.000393 | 35.642581 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 53 | 2.9201 | 1 | 0.000391 | 35.758134 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 54 | 2.9752 | 1 | 0.000395 | 35.649252 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 55 | 3.0303 | 1 | 0.000394 | 35.559035 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 56 | 3.0854 | 1 | 0.000398 | 35.852584 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 57 | 3.1405 | 1 | 0.000401 | 35.527802 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 58 | 3.1956 | 1 | 0.000391 | 35.719537 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 59 | 3.2507 | 1 | 0.000387 | 35.936646 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 60 | 3.3058 | 1 | 0.000388 | 35.776060 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 61 | 3.3609 | 1 | 0.000394 | 35.610291 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 62 | 3.4160 | 1 | 0.000390 | 35.643159 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 63 | 3.4711 | 1 | 0.000390 | 35.848428 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 64 | 3.5262 | 1 | 0.000384 | 36.139704 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 65 | 3.5813 | 1 | 0.000391 | 35.612442 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 66 | 3.6364 | 1 | 0.000391 | 36.042403 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 67 | 3.6915 | 1 | 0.000388 | 35.737851 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 68 | 3.7466 | 1 | 0.000383 | 36.953023 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 69 | 3.8017 | 1 | 0.000392 | 35.727670 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 70 | 3.8567 | 1 | 0.000391 | 35.640554 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 71 | 3.9118 | 1 | 0.000396 | 35.544484 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 72 | 3.9669 | 1 | 0.000391 | 36.275415 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 73 | 4.0220 | 1 | 0.000389 | 36.397081 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 74 | 4.0771 | 1 | 0.000389 | 36.198883 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 75 | 4.1322 | 1 | 0.000384 | 36.418749 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 76 | 4.1873 | 1 | 0.000392 | 36.170168 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 77 | 4.2424 | 1 | 0.000384 | 36.848937 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 78 | 4.2975 | 1 | 0.000390 | 35.923681 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 79 | 4.3526 | 1 | 0.000385 | 35.671411 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 80 | 4.4077 | 1 | 0.000394 | 35.613817 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 81 | 4.4628 | 1 | 0.000390 | 35.833791 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 82 | 4.5179 | 1 | 0.000388 | 36.205167 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 83 | 4.5730 | 1 | 0.000391 | 35.997908 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 84 | 4.6281 | 1 | 0.000388 | 36.585743 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 85 | 4.6832 | 1 | 0.000392 | 36.192828 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 86 | 4.7383 | 1 | 0.000346 | 40.951242 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 87 | 4.7934 | 1 | 0.000386 | 36.011218 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 88 | 4.8485 | 1 | 0.000392 | 35.942685 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 89 | 4.9036 | 1 | 0.000390 | 35.892997 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 90 | 4.9587 | 1 | 0.000385 | 36.137191 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 91 | 5.0138 | 1 | 0.000397 | 35.610185 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 92 | 5.0689 | 1 | 0.000384 | 36.216245 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 93 | 5.1240 | 1 | 0.000387 | 36.592435 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 94 | 5.1791 | 1 | 0.000393 | 35.728209 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 95 | 5.2342 | 1 | 0.000407 | 36.512241 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 96 | 5.2893 | 1 | 0.000391 | 35.904736 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 97 | 5.3444 | 1 | 0.000384 | 36.873819 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 98 | 5.3994 | 1 | 0.000389 | 35.799599 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 99 | 5.4545 | 1 | 0.000382 | 36.435088 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 100 | 5.5096 | 1 | 0.000384 | 35.966849 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 101 | 5.5647 | 1 | 0.000388 | 35.696332 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 102 | 5.6198 | 1 | 0.000388 | 36.266396 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 103 | 5.6749 | 1 | 0.000392 | 35.656953 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 104 | 5.7300 | 1 | 0.000377 | 36.790132 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 105 | 5.7851 | 1 | 0.000385 | 36.148234 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 106 | 5.8402 | 1 | 0.000391 | 35.759438 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 107 | 5.8953 | 1 | 0.000367 | 40.339266 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 108 | 5.9504 | 1 | 0.000367 | 38.085460 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 109 | 6.0055 | 1 | 0.000396 | 35.776073 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 110 | 6.0606 | 1 | 0.000396 | 35.567834 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 111 | 6.1157 | 1 | 0.000387 | 36.363207 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 112 | 6.1708 | 1 | 0.000390 | 35.941066 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 113 | 6.2259 | 1 | 0.000394 | 35.692887 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 114 | 6.2810 | 1 | 0.000390 | 35.714435 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 115 | 6.3361 | 1 | 0.000396 | 35.707059 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 116 | 6.3912 | 1 | 0.000396 | 35.679613 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 117 | 6.4463 | 1 | 0.000396 | 35.601994 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 118 | 6.5014 | 1 | 0.000390 | 36.263561 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 119 | 6.5565 | 1 | 0.000392 | 35.978165 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 120 | 6.6116 | 1 | 0.000392 | 35.805989 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 121 | 6.6667 | 1 | 0.000392 | 35.858811 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 122 | 6.7218 | 1 | 0.000390 | 36.290327 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 123 | 6.7769 | 1 | 0.000385 | 36.347352 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 124 | 6.8320 | 1 | 0.000385 | 36.328808 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 125 | 6.8871 | 1 | 0.000393 | 35.859686 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 126 | 6.9421 | 1 | 0.000390 | 35.915782 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 127 | 6.9972 | 1 | 0.000384 | 36.489830 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 128 | 7.0523 | 1 | 0.000398 | 35.466412 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 129 | 7.1074 | 1 | 0.000391 | 35.716009 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 130 | 7.1625 | 1 | 0.000392 | 36.047863 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 131 | 7.2176 | 1 | 0.000390 | 35.988867 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 132 | 7.2727 | 1 | 0.000398 | 35.563805 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 133 | 7.3278 | 1 | 0.000392 | 35.880065 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 134 | 7.3829 | 1 | 0.000393 | 35.656543 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 135 | 7.4380 | 1 | 0.000397 | 35.563865 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 136 | 7.4931 | 1 | 0.000394 | 35.642912 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 137 | 7.5482 | 1 | 0.000393 | 35.610558 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 138 | 7.6033 | 1 | 0.000387 | 36.558092 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 139 | 7.6584 | 1 | 0.000394 | 35.680333 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 140 | 7.7135 | 1 | 0.000390 | 35.892435 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 141 | 7.7686 | 1 | 0.000393 | 35.786593 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 142 | 7.8237 | 1 | 0.000393 | 35.521731 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 143 | 7.8788 | 1 | 0.000396 | 35.604064 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 144 | 7.9339 | 1 | 0.000393 | 35.938835 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 145 | 7.9890 | 1 | 0.000393 | 35.572532 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 146 | 8.0441 | 1 | 0.000392 | 35.648562 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 147 | 8.0992 | 1 | 0.000389 | 35.732616 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 148 | 8.1543 | 1 | 0.000387 | 36.493986 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 149 | 8.2094 | 1 | 0.000398 | 35.509807 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 150 | 8.2645 | 1 | 0.000398 | 35.672373 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 151 | 8.3196 | 1 | 0.000393 | 35.693285 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 152 | 8.3747 | 1 | 0.000390 | 35.678862 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 153 | 8.4298 | 1 | 0.000394 | 35.555925 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 154 | 8.4848 | 1 | 0.000384 | 36.369391 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 155 | 8.5399 | 1 | 0.000400 | 35.569333 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 156 | 8.5950 | 1 | 0.000396 | 35.555515 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 157 | 8.6501 | 1 | 0.000394 | 35.763096 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 158 | 8.7052 | 1 | 0.000388 | 35.956055 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 159 | 8.7603 | 1 | 0.000398 | 35.501677 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 160 | 8.8154 | 1 | 0.000394 | 35.777963 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 161 | 8.8705 | 1 | 0.000392 | 35.758320 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 162 | 8.9256 | 1 | 0.000391 | 36.029128 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 163 | 8.9807 | 1 | 0.000392 | 35.606087 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 164 | 9.0358 | 1 | 0.000395 | 35.677994 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 165 | 9.0909 | 1 | 0.000394 | 35.873337 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 166 | 9.1460 | 1 | 0.000387 | 36.092424 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 167 | 9.2011 | 1 | 0.000385 | 36.515414 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 168 | 9.2562 | 1 | 0.000386 | 36.233166 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 169 | 9.3113 | 1 | 0.000385 | 36.375013 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 170 | 9.3664 | 1 | 0.000393 | 35.602600 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 171 | 9.4215 | 1 | 0.000382 | 36.973981 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 172 | 9.4766 | 1 | 0.000393 | 35.495461 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 173 | 9.5317 | 1 | 0.000389 | 36.241384 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 174 | 9.5868 | 1 | 0.000397 | 35.567244 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 175 | 9.6419 | 1 | 0.000396 | 35.656721 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 176 | 9.6970 | 1 | 0.000397 | 35.606253 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 177 | 9.7521 | 1 | 0.000390 | 36.000843 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 178 | 9.8072 | 1 | 0.000390 | 36.105044 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 179 | 9.8623 | 1 | 0.000381 | 36.698791 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 180 | 9.9174 | 1 | 0.000385 | 36.167741 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 181 | 9.9725 | 1 | 0.000379 | 36.530229 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 182 |10.0275 | 1 | 0.000390 | 35.967158 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 183 |10.0826 | 1 | 0.000387 | 36.273894 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 184 |10.1377 | 1 | 0.000337 | 41.355412 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 185 |10.1928 | 1 | 0.000303 | 46.366881 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 186 |10.2479 | 1 | 0.000388 | 36.594058 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 187 |10.3030 | 1 | 0.000394 | 35.627701 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 188 |10.3581 | 1 | 0.000389 | 36.184393 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 189 |10.4132 | 1 | 0.000391 | 35.833417 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 190 |10.4683 | 1 | 0.000388 | 35.954538 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 191 |10.5234 | 1 | 0.000388 | 35.752353 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 192 |10.5785 | 1 | 0.000390 | 36.019265 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 193 |10.6336 | 1 | 0.000393 | 35.861507 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 194 |10.6887 | 1 | 0.000392 | 36.622425 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 195 |10.7438 | 1 | 0.000396 | 35.875008 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 196 |10.7989 | 1 | 0.000389 | 35.990370 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 197 |10.8540 | 1 | 0.000387 | 36.174221 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 198 |10.9091 | 1 | 0.000390 | 36.089518 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 199 |10.9642 | 1 | 0.000388 | 36.378811 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 200 |11.0193 | 1 | 0.000389 | 35.807633 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 201 |11.0744 | 1 | 0.000392 | 35.780258 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 202 |11.1295 | 1 | 0.000394 | 35.819882 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 203 |11.1846 | 1 | 0.000396 | 35.670277 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 204 |11.2397 | 1 | 0.000393 | 35.807253 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 205 |11.2948 | 1 | 0.000396 | 35.515537 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 206 |11.3499 | 1 | 0.000394 | 35.557916 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 207 |11.4050 | 1 | 0.000392 | 35.601348 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 208 |11.4601 | 1 | 0.000401 | 35.770085 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 209 |11.5152 | 1 | 0.000398 | 35.545138 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 210 |11.5702 | 1 | 0.000395 | 35.732442 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 211 |11.6253 | 1 | 0.000388 | 36.380011 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 212 |11.6804 | 1 | 0.000388 | 36.165676 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 213 |11.7355 | 1 | 0.000392 | 35.822361 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 214 |11.7906 | 1 | 0.000395 | 35.542615 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 215 |11.8457 | 1 | 0.000399 | 35.519006 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 216 |11.9008 | 1 | 0.000385 | 36.224836 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 217 |11.9559 | 1 | 0.000391 | 36.177737 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 218 |12.0110 | 1 | 0.000389 | 35.887532 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 219 |12.0661 | 1 | 0.000387 | 36.011053 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 220 |12.1212 | 1 | 0.000391 | 35.657542 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 221 |12.1763 | 1 | 0.000392 | 36.109175 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 222 |12.2314 | 1 | 0.000384 | 36.520806 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 223 |12.2865 | 1 | 0.000386 | 36.333786 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 224 |12.3416 | 1 | 0.000395 | 35.685654 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 225 |12.3967 | 1 | 0.000389 | 36.118867 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 226 |12.4518 | 1 | 0.000386 | 36.145351 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 227 |12.5069 | 1 | 0.000401 | 35.561999 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 228 |12.5620 | 1 | 0.000396 | 35.548940 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 229 |12.6171 | 1 | 0.000384 | 36.447215 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 230 |12.6722 | 1 | 0.000395 | 35.805838 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 231 |12.7273 | 1 | 0.000395 | 35.603913 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 232 |12.7824 | 1 | 0.000396 | 35.556070 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 233 |12.8375 | 1 | 0.000388 | 35.801061 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 234 |12.8926 | 1 | 0.000389 | 35.818351 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 235 |12.9477 | 1 | 0.000400 | 35.800171 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 236 |13.0028 | 1 | 0.000396 | 35.836769 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 237 |13.0579 | 1 | 0.000391 | 35.729282 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 238 |13.1129 | 1 | 0.000392 | 35.616691 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 239 |13.1680 | 1 | 0.000391 | 35.905740 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 240 |13.2231 | 1 | 0.000396 | 35.722809 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 241 |13.2782 | 1 | 0.000393 | 35.703984 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 242 |13.3333 | 1 | 0.000393 | 35.793563 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 243 |13.3884 | 1 | 0.000393 | 35.496018 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 244 |13.4435 | 1 | 0.000395 | 35.639655 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 245 |13.4986 | 1 | 0.000393 | 35.641957 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 246 |13.5537 | 1 | 0.000393 | 35.678482 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 247 |13.6088 | 1 | 0.000394 | 35.591033 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 248 |13.6639 | 1 | 0.000392 | 35.937133 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 249 |13.7190 | 1 | 0.000392 | 35.674983 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 250 |13.7741 | 1 | 0.000390 | 36.198653 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 251 |13.8292 | 1 | 0.000393 | 35.704642 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 252 |13.8843 | 1 | 0.000395 | 35.607832 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 253 |13.9394 | 1 | 0.000394 | 35.702099 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 254 |13.9945 | 1 | 0.000391 | 35.591507 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 255 |14.0496 | 1 | 0.000394 | 35.582630 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 256 |14.1047 | 1 | 0.000393 | 35.607026 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 257 |14.1598 | 1 | 0.000391 | 36.007063 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 258 |14.2149 | 1 | 0.000395 | 35.624351 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 259 |14.2700 | 1 | 0.000389 | 36.323911 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 260 |14.3251 | 1 | 0.000397 | 35.892860 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 261 |14.3802 | 1 | 0.000385 | 36.282579 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 262 |14.4353 | 1 | 0.000389 | 35.964746 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 263 |14.4904 | 1 | 0.000397 | 35.545329 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 264 |14.5455 | 1 | 0.000393 | 35.724248 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 265 |14.6006 | 1 | 0.000396 | 35.780267 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 266 |14.6556 | 1 | 0.000396 | 35.604427 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 267 |14.7107 | 1 | 0.000393 | 35.638583 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 268 |14.7658 | 1 | 0.000393 | 35.552521 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 269 |14.8209 | 1 | 0.000394 | 35.633876 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 270 |14.8760 | 1 | 0.000394 | 35.708091 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 271 |14.9311 | 1 | 0.000397 | 35.643214 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 272 |14.9862 | 1 | 0.000392 | 35.777009 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 273 |15.0413 | 1 | 0.000390 | 36.027864 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 274 |15.0964 | 1 | 0.000394 | 35.778701 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 275 |15.1515 | 1 | 0.000391 | 35.878998 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 276 |15.2066 | 1 | 0.000393 | 35.672212 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 277 |15.2617 | 1 | 0.000381 | 36.811921 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 278 |15.3168 | 1 | 0.000391 | 36.149166 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 279 |15.3719 | 1 | 0.000395 | 35.778894 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 280 |15.4270 | 1 | 0.000386 | 36.266254 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 281 |15.4821 | 1 | 0.000392 | 35.829436 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 282 |15.5372 | 1 | 0.000386 | 36.292004 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 283 |15.5923 | 1 | 0.000399 | 35.601531 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 284 |15.6474 | 1 | 0.000391 | 35.748703 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 285 |15.7025 | 1 | 0.000391 | 35.636053 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 286 |15.7576 | 1 | 0.000396 | 35.492744 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 287 |15.8127 | 1 | 0.000389 | 36.207556 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 288 |15.8678 | 1 | 0.000396 | 35.573562 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 289 |15.9229 | 1 | 0.000394 | 35.543748 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 290 |15.9780 | 1 | 0.000396 | 35.656457 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 291 |16.0331 | 1 | 0.000397 | 35.503874 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 292 |16.0882 | 1 | 0.000392 | 35.775469 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 293 |16.1433 | 1 | 0.000389 | 35.884078 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 294 |16.1983 | 1 | 0.000386 | 36.296058 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 295 |16.2534 | 1 | 0.000392 | 36.012925 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 296 |16.3085 | 1 | 0.000389 | 35.905120 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 297 |16.3636 | 1 | 0.000393 | 35.542047 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 298 |16.4187 | 1 | 0.000399 | 35.531727 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 299 |16.4738 | 1 | 0.000398 | 35.553169 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 300 |16.5289 | 1 | 0.000390 | 35.675163 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 301 |16.5840 | 1 | 0.000394 | 35.706228 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 302 |16.6391 | 1 | 0.000389 | 35.917667 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 303 |16.6942 | 1 | 0.000389 | 36.043961 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 304 |16.7493 | 1 | 0.000395 | 35.600581 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 305 |16.8044 | 1 | 0.000396 | 35.914386 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 306 |16.8595 | 1 | 0.000394 | 35.722379 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 307 |16.9146 | 1 | 0.000392 | 35.747440 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 308 |16.9697 | 1 | 0.000395 | 35.719188 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 309 |17.0248 | 1 | 0.000395 | 35.746033 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 310 |17.0799 | 1 | 0.000393 | 35.771650 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 311 |17.1350 | 1 | 0.000394 | 35.736120 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 312 |17.1901 | 1 | 0.000392 | 35.665667 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 313 |17.2452 | 1 | 0.000394 | 35.602781 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 314 |17.3003 | 1 | 0.000389 | 35.846612 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 315 |17.3554 | 1 | 0.000379 | 37.106719 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 316 |17.4105 | 1 | 0.000375 | 37.428269 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 317 |17.4656 | 1 | 0.000387 | 36.144657 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 318 |17.5207 | 1 | 0.000389 | 36.151643 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 319 |17.5758 | 1 | 0.000349 | 40.086706 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 320 |17.6309 | 1 | 0.000389 | 36.406672 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 321 |17.6860 | 1 | 0.000391 | 36.359650 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 322 |17.7410 | 1 | 0.000394 | 35.605319 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 323 |17.7961 | 1 | 0.000385 | 35.991464 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 324 |17.8512 | 1 | 0.000393 | 35.689519 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 325 |17.9063 | 1 | 0.000385 | 35.967418 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 326 |17.9614 | 1 | 0.000381 | 37.067224 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 327 |18.0165 | 1 | 0.000387 | 36.658201 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 328 |18.0716 | 1 | 0.000393 | 35.587548 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 329 |18.1267 | 1 | 0.000393 | 35.768131 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 330 |18.1818 | 1 | 0.000389 | 35.705713 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 331 |18.2369 | 1 | 0.000397 | 35.684391 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 332 |18.2920 | 1 | 0.000395 | 35.589856 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 333 |18.3471 | 1 | 0.000368 | 37.669089 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 334 |18.4022 | 1 | 0.000390 | 36.358752 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 335 |18.4573 | 1 | 0.000361 | 38.958856 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 336 |18.5124 | 1 | 0.000389 | 36.302505 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 337 |18.5675 | 1 | 0.000388 | 36.050366 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 338 |18.6226 | 1 | 0.000387 | 35.937336 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 339 |18.6777 | 1 | 0.000389 | 35.702712 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 340 |18.7328 | 1 | 0.000381 | 36.515599 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 341 |18.7879 | 1 | 0.000391 | 36.227948 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 342 |18.8430 | 1 | 0.000389 | 36.285506 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 343 |18.8981 | 1 | 0.000394 | 35.641176 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 344 |18.9532 | 1 | 0.000393 | 36.092584 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 345 |19.0083 | 1 | 0.000395 | 35.727306 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 346 |19.0634 | 1 | 0.000398 | 35.902258 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 347 |19.1185 | 1 | 0.000395 | 35.619187 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 348 |19.1736 | 1 | 0.000391 | 35.554168 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 349 |19.2287 | 1 | 0.000390 | 35.809281 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 350 |19.2837 | 1 | 0.000391 | 35.920939 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 351 |19.3388 | 1 | 0.000388 | 35.860928 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 352 |19.3939 | 1 | 0.000392 | 35.795326 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 353 |19.4490 | 1 | 0.000391 | 35.635647 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 354 |19.5041 | 1 | 0.000395 | 35.537646 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 355 |19.5592 | 1 | 0.000393 | 35.677006 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 356 |19.6143 | 1 | 0.000392 | 35.571644 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 357 |19.6694 | 1 | 0.000395 | 35.542003 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 358 |19.7245 | 1 | 0.000394 | 35.865523 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 359 |19.7796 | 1 | 0.000387 | 35.962683 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 360 |19.8347 | 1 | 0.000398 | 35.633097 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 361 |19.8898 | 1 | 0.000393 | 35.737916 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 362 |19.9449 | 1 | 0.000395 | 35.536712 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 363 |20.0000 | 1 | 0.000398 | 35.525021 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 364 |20.0551 | 1 | 0.000389 | 35.743157 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 365 |20.1102 | 1 | 0.000394 | 35.578530 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 366 |20.1653 | 1 | 0.000396 | 35.711395 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 367 |20.2204 | 1 | 0.000393 | 35.516417 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 368 |20.2755 | 1 | 0.000384 | 36.510390 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 369 |20.3306 | 1 | 0.000394 | 35.556449 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 370 |20.3857 | 1 | 0.000394 | 35.736968 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 371 |20.4408 | 1 | 0.000397 | 35.538835 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 372 |20.4959 | 1 | 0.000395 | 35.529125 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 373 |20.5510 | 1 | 0.000388 | 35.763696 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 374 |20.6061 | 1 | 0.000390 | 35.428926 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 375 |20.6612 | 1 | 0.000391 | 36.080275 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 376 |20.7163 | 1 | 0.000389 | 35.986586 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 377 |20.7713 | 1 | 0.000396 | 36.017025 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 378 |20.8264 | 1 | 0.000394 | 35.774556 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 379 |20.8815 | 1 | 0.000395 | 35.721105 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 380 |20.9366 | 1 | 0.000382 | 36.540941 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 381 |20.9917 | 1 | 0.000381 | 35.940374 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 382 |21.0468 | 1 | 0.000394 | 35.675575 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 383 |21.1019 | 1 | 0.000389 | 35.719862 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 384 |21.1570 | 1 | 0.000392 | 35.687715 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 385 |21.2121 | 1 | 0.000392 | 36.033308 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 386 |21.2672 | 1 | 0.000389 | 36.131401 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 387 |21.3223 | 1 | 0.000392 | 35.921725 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 388 |21.3774 | 1 | 0.000396 | 35.609875 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 389 |21.4325 | 1 | 0.000390 | 36.132750 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 390 |21.4876 | 1 | 0.000394 | 35.809710 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 391 |21.5427 | 1 | 0.000394 | 35.717738 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 392 |21.5978 | 1 | 0.000394 | 35.708750 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 393 |21.6529 | 1 | 0.000382 | 36.388770 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 394 |21.7080 | 1 | 0.000398 | 35.556891 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 395 |21.7631 | 1 | 0.000385 | 36.525191 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 396 |21.8182 | 1 | 0.000392 | 35.692881 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 397 |21.8733 | 1 | 0.000395 | 35.540603 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 398 |21.9284 | 1 | 0.000390 | 36.187185 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 399 |21.9835 | 1 | 0.000397 | 35.583832 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 400 |22.0386 | 1 | 0.000395 | 35.659805 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 401 |22.0937 | 1 | 0.000389 | 35.931636 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 402 |22.1488 | 1 | 0.000390 | 35.963405 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 403 |22.2039 | 1 | 0.000392 | 35.869598 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 404 |22.2590 | 1 | 0.000393 | 35.917591 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 405 |22.3140 | 1 | 0.000389 | 36.119830 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 406 |22.3691 | 1 | 0.000399 | 35.628094 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 407 |22.4242 | 1 | 0.000384 | 35.944324 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 408 |22.4793 | 1 | 0.000393 | 35.947835 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 409 |22.5344 | 1 | 0.000395 | 35.754569 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 410 |22.5895 | 1 | 0.000393 | 35.547927 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 411 |22.6446 | 1 | 0.000392 | 35.868056 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 412 |22.6997 | 1 | 0.000392 | 35.616375 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 413 |22.7548 | 1 | 0.000391 | 36.188527 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 414 |22.8099 | 1 | 0.000392 | 36.074488 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 415 |22.8650 | 1 | 0.000391 | 36.059972 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 416 |22.9201 | 1 | 0.000392 | 35.733070 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 417 |22.9752 | 1 | 0.000400 | 35.595405 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 418 |23.0303 | 1 | 0.000396 | 35.626185 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 419 |23.0854 | 1 | 0.000397 | 35.657881 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 420 |23.1405 | 1 | 0.000401 | 35.578644 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 421 |23.1956 | 1 | 0.000395 | 35.599160 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 422 |23.2507 | 1 | 0.000397 | 35.541500 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 423 |23.3058 | 1 | 0.000384 | 36.371479 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 424 |23.3609 | 1 | 0.000394 | 35.768025 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 425 |23.4160 | 1 | 0.000392 | 35.845123 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 426 |23.4711 | 1 | 0.000397 | 35.656699 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 427 |23.5262 | 1 | 0.000398 | 35.498293 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 428 |23.5813 | 1 | 0.000379 | 36.483685 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 429 |23.6364 | 1 | 0.000383 | 36.687400 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 430 |23.6915 | 1 | 0.000387 | 35.578806 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 431 |23.7466 | 1 | 0.000394 | 35.627980 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 432 |23.8017 | 1 | 0.000397 | 35.648826 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 433 |23.8567 | 1 | 0.000393 | 35.661327 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 434 |23.9118 | 1 | 0.000397 | 35.547682 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 435 |23.9669 | 1 | 0.000393 | 35.566101 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 436 |24.0220 | 1 | 0.000394 | 35.548657 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 437 |24.0771 | 1 | 0.000390 | 35.525606 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 438 |24.1322 | 1 | 0.000397 | 35.570277 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 439 |24.1873 | 1 | 0.000393 | 35.508999 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 440 |24.2424 | 1 | 0.000394 | 35.661347 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 441 |24.2975 | 1 | 0.000388 | 35.822464 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 442 |24.3526 | 1 | 0.000396 | 35.529076 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 443 |24.4077 | 1 | 0.000395 | 35.757415 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 444 |24.4628 | 1 | 0.000395 | 35.586050 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 445 |24.5179 | 1 | 0.000399 | 35.536022 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 446 |24.5730 | 1 | 0.000393 | 35.571586 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 447 |24.6281 | 1 | 0.000389 | 35.593352 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 448 |24.6832 | 1 | 0.000390 | 36.020319 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 449 |24.7383 | 1 | 0.000378 | 36.827719 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
| 450 |24.7934 | 1 | 0.000364 | 38.528450 | 0.000000 | 0.000000e+00 | 0.000000e+00 |
...Finished
FINISHED - Elapsed time = 16624.0787736 seconds
FINISHED - CPU process time = 125186.7984386 seconds
Postprocessing¶
Read the structural and aerodynamic information of the last time step
[11]:
tstep = sharpy_output.structure.timestep_info[-1]
astep = sharpy_output.aero.timestep_info[-1]
Separate the structure into blades
[12]:
# Define beams
ielem = 0
nblades = np.max(sharpy_output.structure.beam_number) + 1
nodes_blade = []
first_node = 0
for iblade in range(nblades):
nodes_blade.append(np.zeros((sharpy_output.structure.num_node,), dtype=bool))
while sharpy_output.structure.beam_number[ielem] <= iblade:
ielem += 1
if ielem == sharpy_output.structure.num_elem:
break
nodes_blade[iblade][first_node:sharpy_output.structure.connectivities[ielem-1,1]+1] = True
first_node = sharpy_output.structure.connectivities[ielem-1,1]+1
Compute the radial position of the nodes and initialise the rest of the variables
[13]:
r = []
c = []
dr = []
forces = []
CN_drR = []
CTan_drR = []
CP_drR = []
nodes_num = []
for iblade in range(nblades):
forces.append(tstep.steady_applied_forces[nodes_blade[iblade]].copy())
nodes_num.append(np.arange(0, sharpy_output.structure.num_node, 1)[nodes_blade[iblade]])
r.append(np.linalg.norm(tstep.pos[nodes_blade[iblade], :], axis=1))
dr.append(np.zeros(np.sum(nodes_blade[iblade])))
dr[iblade][0] = 0.5*(r[iblade][1]-r[iblade][0])
dr[iblade][-1] = 0.5 * (r[iblade][-1] - r[iblade][-2])
for inode in range(1,len(r[iblade]) - 1):
dr[iblade][inode] = 0.5*(r[iblade][inode+1] - r[iblade][inode-1])
CN_drR.append(np.zeros(len(r[iblade])))
c.append(np.zeros(len(r[iblade])))
CTan_drR.append(np.zeros(len(r[iblade])))
CP_drR.append(np.zeros(len(r[iblade])))
Transform the loads computed by SHARPy into out-of-plane and in-plane components
[14]:
rho = sharpy_output.settings['StaticCoupledRBM']['aero_solver_settings']['rho'].value
uinf = sharpy_output.settings['StaticCoupledRBM']['aero_solver_settings']['velocity_field_input']['u_inf'].value
R = np.max(r[0])
Cp = 0
Ct = 0
global_force_factor = 0.5 * rho * uinf** 2 * np.pi * R**2
global_power_factor = global_force_factor*uinf
for iblade in range(nblades):
for inode in range(len(r[iblade])):
forces[iblade][inode, 0] *= 0. # Discard the spanwise component
node_global_index = nodes_num[iblade][inode]
ielem = sharpy_output.structure.node_master_elem[node_global_index, 0]
inode_in_elem = sharpy_output.structure.node_master_elem[node_global_index, 1]
CAB = algebra.crv2rotation(tstep.psi[ielem, inode_in_elem, :])
c[iblade][inode] = sharpy_output.aero.aero_dict['chord'][ielem,inode_in_elem]
forces_AFoR = np.dot(CAB, forces[iblade][inode, 0:3])
CN_drR[iblade][inode] = forces_AFoR[2]/dr[iblade][inode]*R / global_force_factor
CTan_drR[iblade][inode] = np.linalg.norm(forces_AFoR[0:2])/dr[iblade][inode]*R / global_force_factor
CP_drR[iblade][inode] = np.linalg.norm(forces_AFoR[0:2])/dr[iblade][inode]*R * r[iblade][inode]*rotation_velocity / global_power_factor
Cp += np.sum(CP_drR[iblade]*dr[iblade]/R)
Ct += np.sum(CN_drR[iblade]*dr[iblade]/R)
Results¶
Plot of the loads along the blade
[15]:
fig, list_plots = plt.subplots(1, 2, figsize=(12, 3))
list_plots[0].grid()
list_plots[0].set_xlabel("r/R [-]")
list_plots[0].set_ylabel("CN/d(r/R) [-]")
list_plots[0].plot(r[0]/R, CN_drR[0], '-', label='SHARPy')
list_plots[0].plot(of_rR, of_cNdrR, '-', label='OpenFAST')
list_plots[0].legend()
list_plots[1].grid()
list_plots[1].set_xlabel("r/R [-]")
list_plots[1].set_ylabel("CT/d(r/R) [-]")
list_plots[1].plot(r[0]/R, CTan_drR[0], '-', label='SHARPy')
list_plots[1].plot(of_rR, of_cTdrR, '-', label='OpenFAST')
list_plots[1].legend()
plt.show()
Print the rotor thrust and power coefficients
[16]:
print(" OpenFAST SHARPy")
print("Cp[-] %.2f %.2f" % (of_cp, Cp))
print("Ct[-] %.2f %.2f" % (of_ct, Ct))
OpenFAST SHARPy
Cp[-] 0.49 0.54
Ct[-] 0.70 0.75
A prismatic cantilever beam under a tip load¶
This is an example of the geometrically-exact beam structural solver in SHARPy.
Reference: Simpson R.J.S., Palacios R., “Numerical Aspects of Nonlinear Flexible Aircraft Flight Dynamics Modeling.” 54th AIAA/ASME/ASCE/AHS/ASC Structures, Structural Dynamics and Materials Conference, 8-11 April 2013, Boston, Massachusetts, USA [http://hdl.handle.net/10044/1/11077, http://dx.doi.org/10.2514/6.2013-1634]
Required Packages¶
[1]:
import numpy as np
import os
import matplotlib.pyplot as plt
import sharpy.sharpy_main # used to run SHARPy from Jupyter
import model_static_cantilever as model # model definition
from IPython.display import Image
plt.rcParams.update({'font.size': 20}) # Large fonts in all plots
Problem 1: Tip vertical dead load¶
Consider first a massless beam with a heavy tip mass, such that the deformations are due to the resulting dead load P. The static equilibrium will be obtained for multiple values of P=0, 100, …, 1000 kN
[2]:
Image('images/cantilever.png', width=500)
[2]:

[3]:
# Define temporary files to generate sharpy models.
case_name= 'temp'
route = './'
Nforces=10 # Number of force steps
DeltaForce=100e3 # Increment of forces
Nelem=20 # Number of beam elements
N=2*Nelem+1
x1=np.zeros((Nforces,N))
z1=np.zeros((Nforces,N))
#Loop through all external forces
for jForce in range(Nforces):
model.clean_test_files(route, case_name)
model.generate_fem_file(route, case_name, Nelem, float(jForce+1)*DeltaForce)
model.generate_solver_file(route,case_name)
case_data=sharpy.sharpy_main.main(['', route + case_name + '.sharpy'])
x1[jForce,0:N]=case_data.structure.timestep_info[0].pos[:, 0]
z1[jForce,0:N]=case_data.structure.timestep_info[0].pos[:, 2]
#Store initial geometry
x0=case_data.structure.ini_info.pos[:, 0]
z0=case_data.structure.ini_info.pos[:, 2]
[4]:
# Plot the deformed beam shapes
fig= plt.subplots(1, 1, figsize=(15, 6))
plt.scatter(x0,z0,c='black')
plt.plot(x0,z0,c='black')
for jForce in range(Nforces):
plt.scatter(x1[jForce,0:N],z1[jForce,0:N],c='black')
plt.plot(x1[jForce,0:N],z1[jForce,0:N],c='black')
plt.axis('equal')
plt.grid()
plt.xlabel('x (m)')
plt.ylabel('z (m)')
plt.savefig("images/ncb1-dead-displ.eps", format='eps', dpi=1000, bbox_inches='tight')

[5]:
print('{:>8s}{:>12s}'.format('Force','Tip z'))
dash=20*'-'; print(dash)
for jForce in range(Nforces):
print('{:>8.0f}{:>12.4f}'.format((jForce+1)*DeltaForce,z1[jForce,N-1]))
Force Tip z
--------------------
100000 -0.4438
200000 -0.8672
300000 -1.2551
400000 -1.5999
500000 -1.9005
600000 -2.1597
700000 -2.3824
800000 -2.5737
900000 -2.7386
1000000 -2.8813
[6]:
model.clean_test_files(route, case_name)
Problem 2: Comparing follower and dead forces¶
[7]:
#Loop through all external follower forces, again applied at the tip.
x2=np.zeros((Nforces,N))
z2=np.zeros((Nforces,N))
for jForce in range(Nforces):
model.clean_test_files(route, case_name)
model.generate_fem_file(route, case_name, Nelem, 0, -float(jForce+1)*DeltaForce)
model.generate_solver_file(route,case_name)
case_foll=sharpy.sharpy_main.main(['', route + case_name + '.sharpy'])
x2[jForce,0:N]=case_foll.structure.timestep_info[0].pos[:, 0]
z2[jForce,0:N]=case_foll.structure.timestep_info[0].pos[:, 2]
[8]:
#Plot results.
fig, axs = plt.subplots(nrows=1, ncols=2, figsize=(15, 6))
ax0 = axs[0]
ax0.plot([0,Nforces],[0, 0],linestyle=':', c='black')
ax0.plot(range(Nforces+1), np.concatenate((5, x1[0:Nforces,-1]), axis=None)-5*np.ones(Nforces+1),linestyle='-', c='black')
ax0.plot(range(Nforces+1), np.concatenate((5, x2[0:Nforces,-1]), axis=None)-5*np.ones(Nforces+1),linestyle='--', c='black')
#ax0.axis('equal')
ax0.grid()
ax0.set_xlabel('Force (N) x 10^5')
ax0.set_ylabel('Tip horizontal displacement (m)')
ax0.set(xlim=(0, Nforces), ylim=(-6, 1))
ax1 = axs[1]
ax1.plot([0,Nforces],np.concatenate((0, z1[0,-1]*Nforces), axis=None),linestyle=':', c='black')
ax1.plot(range(Nforces+1), np.concatenate((0, z1[0:Nforces,-1]), axis=None),linestyle='-', c='black')
ax1.plot(range(Nforces+1), np.concatenate((0, z2[0:Nforces,-1]), axis=None),linestyle='--', c='black')
#ax1.axis('equal')
ax1.grid()
ax1.set_xlabel('Force (N) x 10^5')
ax1.set_ylabel('Tip vertical displacement (m)')
ax1.set(xlim=(0, Nforces), ylim=(-5, 1))
ax1.legend(['Linear','Dead','Follower'])
fig.savefig("images/ncb1-foll-displ.eps", format='eps', dpi=1000, bbox_inches="tight")
The PostScript backend does not support transparency; partially transparent artists will be rendered opaque.
The PostScript backend does not support transparency; partially transparent artists will be rendered opaque.
The PostScript backend does not support transparency; partially transparent artists will be rendered opaque.
The PostScript backend does not support transparency; partially transparent artists will be rendered opaque.

[9]:
model.clean_test_files(route, case_name)
Downloadable files¶
Input data for wind turbine:
Contributing to SHARPy¶
Bug fixes and features¶
SHARPy is a collaborative effort, and this means that some coding practices need to be encouraged so that the code is kept tidy and consistent. Any user is welcome to raise issues for bug fixes and feature proposals through Github.
If you are submitting a bug report:
Make sure your SHARPy, xbeam and uvlm local copies are up to date and in the same branch.
Double check that your python distribution is updated by comparing with the
utils/environment_*.yml
file.Try to assemble a minimal working example that can be run quickly and easily.
Describe as accurately as possible your setup (OS, path, compilers…) and the problem.
Raise an issue with all this information in the Github repo and label it
potential bug
.
Please bear in mind that we do not have the resources to provide support for user modifications of the code through Github. If you have doubts about how to modify certain parts of the code, contact us through email and we will help you as much as we can.
If you are fixing a bug:
THANKS!
Please create a pull request from your modified fork, and describe in a few lines which bug you are fixing, a minimal example that triggers the bug and how you are fixing it. We will review it ASAP and hopefully it will be incorporated in the code!
If you have an idea for new functionality but do not know how to implement it:
We welcome tips and suggestions from users, as it allow us to broaden the scope of the code. The more people using it, the better!
Feel free to fill an issue in Github, and tag it as
feature proposal
. Please understand that the more complete the description of the potential feature, the more likely it is that some of the developers will give it a go.
If you have developed new functionality and you want to share it with the world:
AWESOME! Please follow the same instructions than for the bug fix submission. If you have some peer-reviewed references related to the new code, even better, as it will save us some precious time.
Code formatting¶
We try to follow the PEP8 standards
(with spaces, no tabs please!) and Google Python Style Guide.
We do not ask you to freak out over formatting, but please, try to keep it tidy and
descriptive. A good tip is to run pylint
https://www.pylint.org/
to make sure there are no obvious formatting problems.
Documentation¶
Contributing to SHARPy’s documentation benefits everyone. As a developer, writing documentation helps you better understand what you have done and whether your functions etc make logical sense. As a user, any documentation is better than digging through the code. The more we have documented, the easier the code is to use and the more users we can have.
If you want to contribute by documenting code, you have come to the right place.
SHARPy is documented using Sphinx and it extracts the documentation directly from the source code. It is then sorted into directories automatically and a human readable website generated. The amount of work you need to do is minimal. That said, the recipe for a successfully documented class, function, module is the following:
Your documentation has to be written in ReStructuredText (rst). I know, another language… hence I will leave a few tips:
Inline code is written using two backticks
``
Inline math is written as
:math:`1+\exp^{i\pi} = 0`
. Don’t forget the backticks!Math in a single or multiple lines is simple:
.. math:: 1 + \exp{i\pi} = 0
Lists in ReStructuredText are tricky, I must admit. Therefore, I will link to some examples. The key resides in not forgetting the spaces, in particular when you go onto a second line!
The definite example list can be found here.
Titles and docstrings, the bare minimum:
Start docstrings with
r
such that they are interpreted raw:r""" My docstring """
All functions, modules and classes should be given a title that goes in the first line of the docstring
If you are writing a whole package with an
__init__.py
file, even if it’s empty, give it a human readable docstring. This will then be imported into the documentationFor modules with several functions, the module docstring has to be at the very top of the file, prior to the
import
statements.
We use the Google documentation style. A very good set of examples of Google style documentation for functions, modules, classes etc. can be found here.
Function arguments and returns:
Function arguments are simple to describe:
def func(arg1, arg2): """Summary line. Extended description of function. Args: arg1 (int): Description of arg1 arg2 (str): Description of arg2 Returns: bool: Description of return value """ return True
Solver settings:
If your code has a settings dictionary, with defaults and types then make sure that:
They are defined as class variables and not instance attributes.
Define a
settings_types
,settings_default
andsettings_description
dictionaries.After all your settings, update the docstring with the automatically generated settings table. You will need to import the
sharpy.utils.settings
modulesettings_types = dict() settings_default = dict() settings_description = dict() # keep adding settings settings_table = sharpy.utils.settings.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default ,settings_description)
See how your docs looks like!
Once you are done, run the following
SHARPy
command:
sharpy any_string -d
If you are making minor updates to docstrings (i.e. you are not documenting a previously undocumented function/class/module) you can simply change directory to
sharpy/docs
and run
make html
Your documentation will compile and warnings will appear etc. You can check the result by opening
docs/build/index.html
and navigating to your recently created page.
Make sure that before committing any changes in the documentation you update the entire
docs
directory by running
sharpy any_string -d
Thank you for reading through this and contributing to make SHARPy a better documented, more user friendly code!
Git branching model¶
For the development of SHARPy, we try to follow this branching model summarised by the schematic
BranchingModel
Credit: Vincent Driessen https://nvie.com/posts/a-successful-git-branching-model/
Therefore, attending to this model our branches have the following versions of the code:
master
: latest stable release - paired with the appropriate tag.develop
: latest stable development build. Features get merged to develop.rc-**
: release candidate branch. Prior to releasing tests are performed on this branch.dev_doc
: documentation development branch. All work relating to documentation gets done here.fix_**
: hotfix branch.dev_**
: feature development branch.
If you contribute, please make sure you know what branch to work from. If in doubt please ask!
Commit names are also important since they are the backbone of the code’s change log. Please write concise commit titles and explain the main changes in the body of the commit message. An excellent guide on writing good commit messages can be found here.
The SHARPy Case files¶
SHARPy takes as input a series of .h5
files that contain the numerical data and a .sharpy
file that contains
the settings for each of the solvers. How these files are generated is at the user’s discretion, though templates are
provided, and all methods are valid as long as the required variables are provided with the appropriate format.
Modular Framework¶
SHARPy is built with a modular framework in mind. The following diagram shows the strutuctre of a nonlinear, time marching aeroelastic simulation

Each of the blocks correspond to individual solvers with specific settings. How we choose which solvers to run, in which order and with what settings is done through the solver configuration file, explained in the next section.
Solver configuration file¶
The solver configuration file is the main input to SHARPy. It is a ConfigObj
formatted file with the .sharpy
extension. It contains the settings for each of the solvers and the order in which
to run them.
A typical way to assemble the solver configuration file is to place all your desired settings
in a dictionary and then convert to and write your ConfigObj
. If a setting is not provided the default value will be used. The settings that each solver takes, its type and default value are explained in their relevant documentation pages.
import configobj
filename = '<case_route>/<case_name>.sharpy'
config = configobj.ConfigObj()
config.filename = filename
config['SHARPy'] = {'case': '<your SHARPy case name>', # an example setting
# Rest of your settings for the PreSHARPy class
}
config['BeamLoader'] = {'orientation': [1., 0., 0.], # an example setting
# Rest of settings for the BeamLoader solver
}
# Continue as above for the remainder of solvers that you would like to include
# finally, write the config file
config.write()
The resulting .sharpy
file is a plain text file with your specified settings for each of
the solvers.
Note that, therefore, if one of your settings is a np.array
, it will get transformed into
a string of plain text before being read by SHARPy. However, any setting with list(float)
specified as its setting type will get converted into a np.array
once it is read by SHARPy.
FEM file¶
The case.fem.h5
file has several components. We go one by one:
num_node_elem [int]
: number of nodes per element.Always 3 in our case (3 nodes per structural elements - quadratic beam elements).
num_elem [int]
: number of structural elements.num_node [int]
: number of nodes.For simple structures, it is
num_elem*(num_node_elem - 1) - 1
. For more complicated ones, you need to calculate it properly.coordinates [num_node, 3]
: coordinates of the nodes in body-attached FoR (A).connectivites [num_elem, num_node_elem]
: Beam element’s connectivities.Every row refers to an element, and the three integers in that row are the indices of the three nodes belonging to that elem. Now, the catch: the ordering is not as you’d think. Order them as
[0, 2, 1]
. That means, first one, last one, central one. The following image shows the node indices inside the circles representing the nodes, the element indices in blue and the resulting connectivities matrix next to it. Connectivities are tricky when considering complex configurations. Pay attention at the beginning and you’ll save yourself a lot of trouble.stiffness_db [:, 6, 6]
: database of stiffness matrices.The first dimension has as many elements as different stiffness matrices are in the model.
elem_stiffness [num_elem]
: array of indices (starting at 0).It links every element (index) to the stiffness matrix index in
stiffness_db
. For exampleelem_stiffness[0] = 0
;elem_stiffness[2] = 1
means that the element0
has a stiffness matrix equal tostiffness_db[0, :, :]
, and the second element has a stiffness matrix equal tostiffness_db[1, :, :]
.The shape of a stiffness matrix, \(\mathrm{S}\) is:
\[\begin{split}\mathrm{S} = \begin{bmatrix} EA & & & & & \\ & GA_y & & & & \\ & & GA_z & & & \\ & & & GJ & & \\ & & & & EI_y & \\ & & & & & EI_z \\ \end{bmatrix}\end{split}\]with the cross terms added if needed.
mass_db
andelem_mass
follow the same scheme than the stiffness, but the mass matrix is given by:\[\begin{split}\mathrm{M} = \begin{bmatrix} m\mathbf{I} & -\tilde{\boldsymbol{\xi}}_{cg}m \\ \tilde{\boldsymbol{\xi}}_{cg}m & \mathbf{J}\\ \end{bmatrix}\end{split}\]where \(m\) is the distributed mass per unit length \(kg/m\) , \((\tilde{\bullet})\) is the skew-symmetric matrix of a vector and \(\boldsymbol{\xi}_{cg}\) is the location of the centre of gravity with respect to the elastic axis in MATERIAL (local) FoR. And what is the Material FoR? This is an important point, because all the inputs that move WITH the beam are in material FoR. For example: follower forces, stiffness, mass, lumped masses…
The material frame of reference is noted as \(B\). Essentially, the \(x\) component is tangent to the beam in the increasing node ordering, \(z\) looks up generally and \(y\) is oriented such that the FoR is right handed.
In the practice (vertical surfaces, structural twist effects…) it is more complicated than this. The only sure thing about \(B\) is that its \(x\) direction is tangent to the beam in the increasing node number direction. However, with just this, we have an infinite number of potential reference frames, with \(y\) and \(z\) being normal to \(x\) but rotating around it. The solution is to indicate a
for_delta
, or frame of reference delta vector (\(\Delta\)).Now we can define unequivocally the material frame of reference. With \(x_B\) and \(\Delta\) defining a plane, \(y_b\) is chosen such that the \(z\) component is oriented upwards with respect to the lifting surface.
From this definition comes the only constraint to \(\Delta\): it cannot be parallel to \(x_B\).
frame_of_reference_delta [num_elem, num_node_elem, 3]
: rotation vector to FoR \(B\).contains the \(\Delta\) vector in body-attached (\(A\)) frame of reference.
As a rule of thumb:
\[\begin{split}\Delta = \begin{cases} [-1, 0, 0], \quad \text{if right wing} \\ [1, 0, 0], \quad \text{if left wing} \\ [0, 1, 0], \quad \text{if fuselage} \\ [-1, 0, 0], \quad \text{if vertical fin} \\ \end{cases}\end{split}\]These rules of thumb only work if the nodes increase towards the tip of the surfaces (and the tail in the case of the fuselage).
structural_twist [num_elem, num_node_elem]
: Element twist.Technically not necessary, as the same effect can be achieved with
FoR_delta
.boundary_conditions [num_node]
: boundary conditions.An array of integers
(np.zeros((num_node, ), dtype=int))
and contains all0
except forOne node NEEDS to have a
1
, this is the reference node. Usually, the first node has 1 and is located in[0, 0, 0]
. This makes things much easier.If the node is a tip of a beam (is not attached to 2 elements, but just 1), it needs to have a
-1
.
beam_number [num_elem]
: beam index.Is another array of integers. Usually you don’t need to modify its value. Leave it at 0.
app_forces [num_elem, 6]
: applied forces and moments.Contains the applied forces
app_forces[:, 0:3]
and momentsapp_forces[:, 3:6]
in a given node.Important points: the forces are given in Material FoR (check above). That means that in a symmetrical model, a thrust force oriented upstream would have the shape
[0, T, 0, 0, 0, 0]
in the right wing, while the left would be[0, -T, 0, 0, 0, 0]
. Likewise, a torsional moment for twisting the wing leading edge up would be[0, 0, 0, M, 0, 0]
for the right, and[0, 0, 0, -M, 0, 0]
for the left. But careful, because an out-of-plane bending moment (wing tip up) has the same sign (think about it).lumped_mass [:]
: lumped masses.Is an array with as many masses as needed (in kg this time). Their order is important, as more information is required to implement them in a model.
lumped_mass_nodes [:]
: Lumped mass nodes.Is an array of integers. It contains the index of the nodes related to the masses given in lumped_mass in order.
lumped_mass_inertia [:, 3, 3]
: Lumped mass inertia.Is an array of
3x3
inertial tensors. The relationship is set by the ordering as well.lumped_mass_position [:, 3]
: Lumped mass position.Is the relative position of the lumped mass with respect to the node (given in
lumped_masss_nodes
) coordinates. ATTENTION: the lumped mass is solidly attached to the node, and thus, its position is given in Material FoR.
Aerodynamics file¶
All the aerodynamic data is contained in case.aero.h5
.
It is important to know that the input for aero is usually based on elements (and inside the elements, their nodes). This causes sometimes an overlap in information, as some nodes are shared by two adjacent elements (like in the connectivities graph in the previous section). The easier way of dealing with this is to make sure the data is consistent, so that the properties of the last node of the first element are the same than the first node of the second element.
Item by item:
airfoils
: Airfoil group.In the
aero.h5
file, there is a Group calledairfoils
. The airfoils are stored in this group (which acts as a folder) as a two-column matrix with \(x/c\) and \(y/c\) in each column. They are named'0', '1'
, and so on.chords [num_elem, num_node_elem]
: ChordIs an array with the chords of every airfoil given in an element/node basis.
twist [num_elem, num_node_elem]
: Twist.Has the twist angle in radians. It is implemented as a rotation around the local \(x\) axis.
sweep [num_elem, num_node_elem]
: Sweep.Same here, just a rotation around \(z\).
airfoil_distribution_input [num_elem, num_node_elem]
: Airfoil distribution.Contains the indices of the airfoils that you put previously in
airfoils
.surface_distribution_input [num_elem]
: Surface integer array.It contains the index of the surface the element belongs to. Surfaces need to be continuous, so please note that if your beam numbering is not continuous, you need to make a surface per continuous section.
surface_m [num_surfaces]
: Chordwise panelling.Is an integer array with the number of chordwise panels for every surface.
m_distribution [string]
: Discretisation method.Is a string with the chordwise panel distribution. In almost all cases, leave it at
uniform
.aero_node_input [num_node]
: Aerodynamic node definition.Is a boolean (
True
orFalse
) array that indicates if that node has a lifting surface attached to it.elastic_axis [num_elem, num_node_elem]
: elastic axis.Indicates the elastic axis location with respect to the leading edge as a fraction of the chord of that rib. Note that the elastic axis is already determined, as the beam is fixed now, so this settings controls the location of the lifting surface wrt the beam.
control_surface [num_elem, num_node_elem]
: Control surface.Is an integer array containing
-1
if that section has no control surface associated to it, and0, 1, 2 ...
if the section belongs to the control surface0, 1, 2 ...
respectively.control_surface_type [num_control_surface]
: Control Surface type.Contains
0
if the control surface deflection is static, and1
is it is dynamic.control_surface_chord [num_control_surface]
: Control surface chord.Is an INTEGER array with the number of panels belonging to the control surface. For example, if
M = 4
and you want your control surface to be \(0.25c\), you need to put1
.control_surface_hinge_coord [num_control_surface]
: Control surface hinge coordinate.Only necessary for lifting surfaces that are deflected as a whole, like some horizontal tails in some aircraft. Leave it at
0
if you are not modelling this.airfoil_efficiency [num_elem, num_node_elem, 2, 3]
: Airfoil efficiency.This is an optional setting that introduces a user-defined efficiency and constant terms to the mapping between the aerodynamic forces calculated at the lattice grid and the structural nodes. The formatting of the 4-dimensional array is simple. The first two dimensions correspond to the element index and the local node index. The third index is whether the term is the multiplier to the force
0
or a constant term1
. The final term refers to, in the local, body-attachedB
frame, the factors and constant terms for:fy, fz, mx
. For more information on how these factors are included in the mapping terms seesharpy.aero.utils.mapping.aero2struct_force_mapping()
.
Time-varying force input file (.dyn.h5
)¶
The .dyn.h5
file is an optional input file that may contain force and acceleration inputs that vary with time.
This is intended for use in dynamic problems. For SHARPy to look for and use this file the setting unsteady
in the
BeamLoader
must be turned to on
.
Appropriate data entries in the .dyn.h5
include:
dynamic_forces [num_t_steps, num_node, 6]
: Dynamic forces in body attachedB
frame.Forces given at each time step, for each node and then for the 6 degrees of freedom (
fx, fy, fz, mx, my, mz
) in a body-attached (local) frame of referenceB
.for_pos [num_t_steps, 6]
: Body frame of reference (A FoR) position.Position of the reference frame A in time.
for_vel [num_t_steps, 6]
: Body frame of reference (A FoR) velocity.Velocity of the reference frame A in time.
for_acc [num_t_steps, 6]
: Body frame of reference (A FoR) acceleration.Acceleration of the reference frame A in time.
If a case is restarted from a pickle file, the .dyn.h5 file should include the dynamic information for the previous simulation (that will be discarded) and the information for the new simulation.
Post-Processing¶
AeroForcesCalculator¶
AerogridPlot¶
AsymptoticStability¶
Calculates the asymptotic stability properties of the linearised aeroelastic system by computing the corresponding eigenvalues.
To use an iterative eigenvalue solver, the setting
iterative_eigvals
should be set toon
. This will be beneficial when deailing with very large systems. However, the direct method is preferred and more efficient when the system is of a relatively small size (typically around 5000 states).Warning
The setting
modes_to_plot
to plot the eigenvectors in Paraview is currently under development.The settings that this solver accepts are given by a dictionary, with the following key-value pairs:
Name
Type
Description
Default
print_info
bool
Print information and table of eigenvalues
False
reference_velocity
float
Reference velocity at which to compute eigenvalues for scaled systems
1.0
frequency_cutoff
float
Truncate higher frequency modes. If zero none are truncated
0
export_eigenvalues
bool
Save eigenvalues and eigenvectors to file.
False
display_root_locus
bool
Show plot with eigenvalues on Argand diagram
False
velocity_analysis
list(float)
List containing min, max and number of velocities to analyse the system
[]
iterative_eigvals
bool
Calculate the first
num_evals
using an iterative solver.False
num_evals
int
Number of eigenvalues to retain.
200
modes_to_plot
list(int)
List of mode numbers to simulate and plot
[]
postprocessors
list(str)
To be used with
modes_to_plot
. Under development.[]
postprocessors_settings
dict
To be used with
modes_to_plot
. Under development.{}
Displays root locus diagrams.
Returns the
fig
andax
handles for further editing.- Returns
ax:
- Return type
fig
Saves a
num_evals
number of eigenvalues and eigenvectors to file. The files are saved in the output directoy and include:eigenvectors.dat
:(num_dof, num_evals)
array of eigenvectorseigenvalues_r.dat
:(num_evals, 1)
array of the real part of the eigenvalueseigenvalues_i.dat
:(num_evals, 1)
array of the imaginary part of the eigenvalues.
The units of the eigenvalues are
rad/s
References
Loading and saving complex arrays: https://stackoverflow.com/questions/6494102/how-to-save-and-load-an-array-of-complex-numbers-using-numpy-savetxt/6522396
- Parameters
num_evals – Number of eigenvalues to save
Returns a single, scaled mode shape in time domain.
- Parameters
fact – Structural deformation scaling
fact_rbm – Rigid body motion scaling
mode_num – Number of mode to plot
cycles – Number of periods/cycles to plot
- Returns
Time domain array and scaled eigenvector in time.
- Return type
tuple
Warning
Under development
Plot the aeroelastic mode shapes for the first
n_modes_to_plot
Prints the eigenvalues to a table with the corresponding natural frequency, period and damping ratios
Computes the eigenvalues and eigenvectors
- Returns
Eigenvalues sorted and frequency truncated eigenvectors (np.ndarray): Corresponding mode shapes
- Return type
eigenvalues (np.ndarray)
Sort continuous-time eigenvalues by order of magnitude.
The conjugate of complex eigenvalues is removed, then if specified, high frequency modes are truncated. Finally, the eigenvalues are sorted by largest to smallest real part.
- Parameters
eigenvalues (np.ndarray) – Continuous-time eigenvalues
eigenvectors (np.ndarray) – Corresponding right eigenvectors
frequency_cutoff (float) – Cutoff frequency for truncation
[rad/s]
Returns:
BeamLoads¶
BeamPlot¶
Plots beam to Paraview format
The settings that this solver accepts are given by a dictionary, with the following key-value pairs:
Name
Type
Description
Default
include_rbm
bool
Include frame of reference rigid body motion
True
include_FoR
bool
Include frame of reference variables
False
include_applied_forces
bool
Write beam applied forces
True
include_applied_moments
bool
Write beam applied moments
True
name_prefix
str
Name prefix for files
output_rbm
bool
Write
csv
file with rigid body motion dataTrue
FrequencyResponse¶
PickleData¶
PlotFlowField¶
SaveData¶
SaveParametricCase¶
StallCheck¶
UDPout¶
WriteVariablesTime¶
Write variables with time
WriteVariablesTime
is a class inherited fromBaseSolver
It is a postprocessor that outputs the value of variables with time onto a text file.
Acceptable data types of the input data
- Type
dict
Default values for input data should the user not provide them
- Type
dict
-
See the list of arguments
directory to output the information
- Type
str
The settings that this solver accepts are given by a dictionary, with the following key-value pairs:
Name
Type
Description
Default
delimiter
str
Delimiter to be used in the output file
`` ``
FoR_variables
list(str)
Variables of
StructTimeStepInfo
associated to the frame of reference to be writen['']
FoR_number
list(int)
Number of the A frame of reference to output (for multibody configurations)
numpy.array
structure_variables
list(str)
Variables of
StructTimeStepInfo
associated to the frame of reference to be writen['']
structure_nodes
list(int)
Number of the nodes to be writen
numpy.array
aero_panels_variables
list(str)
Variables of
AeroTimeStepInfo
associated to panels to be writen['']
aero_panels_isurf
list(int)
Number of the panels’ surface to be output
numpy.array
aero_panels_im
list(int)
Chordwise index of the panels to be output
numpy.array
aero_panels_in
list(int)
Spanwise index of the panels to be output
numpy.array
aero_nodes_variables
list(str)
Variables of
AeroTimeStepInfo
associated to nodes to be writen['']
aero_nodes_isurf
list(int)
Number of the nodes’ surface to be output
numpy.array
aero_nodes_im
list(int)
Chordwise index of the nodes to be output
numpy.array
aero_nodes_in
list(int)
Spanwise index of the nodes to be output
numpy.array
cleanup_old_solution
bool
Remove the existing files
False
vel_field_variables
list(str)
Variables associated to the velocity field. Only
uext
implemented so far[]
vel_field_points
list(float)
List of coordinates of the control points as x1, y1, z1, x2, y2, z2 …
numpy.array
A Short Debugging Guide¶
We have put together a list of common traps you may fall into, hopefully you will find the tools here to get yourself out of them!
Did you forget conda activate sharpy_env and source bin/sharpy_vars.sh?
If you do in the terminal: which sharpy, do you get the one you want?
If you do which python, does the result point to anaconda3/envs/sharpy_env/bin (or similar)?
Wrong input (inconsistent connectivities, mass = 0…)
Sometimes not easy to detect. For the structural model, run BeamLoader and BeamPlot with no structural solver in between. Go over the structure in Paraview. Check the fem.h5 file with HDFView.
Remember that connectivities are ordered as $[0, 2, 1]$ (the central node goes last).
Make sure the num_elem and num_node variables are actually your correct number of elements and nodes.
Not running the actual case you want to.
Cleanup the folder and regenerate the case
Not running the SHARPy version you want.
Check at the beginning of the execution the path to the SHARPy folder.
Not running the correct branch of the code.
You probably want to use develop. Again, check the first few lines of SHARPy output.
Very different (I’m talking orders of magnitude) stiffnesses between nodes or directions?
Maybe the UVLM requires a smaller a smaller vortex core cutoff (only for linear UVLM simulations, as the nonlinear uses another vortex core model).
Newmark damping is not enough for this case?
Do you have an element with almost 0 mass or inertia?
Are you mass matrices consistent? Check that \(I_{xx} = I_{yy} + I_{zz}\).
Have a look at the \(\dot{\Gamma}\) filtering and numerical parameters in the settings of StepUvlm and DynamicCoupled.
Add more relaxation to the StaticCoupled or DynamicCoupled solvers.
The code has a bug (depending on where, it may be likely).
Go over the rest of the list. Plot the case in paraview. Go over the rest of the list again. Prepare the simplest example that reproduces the problem and raise an issue.
- The code diverges because it has to (physical unstable behaviour)
Then don’t complain
- Your model still doesn’t work and you don’t know why.
import pdb; pdb.set_trace() and patience
If nothing else works… get a rubber duck (or a very very patient good friend) and go over every step

If your model doesn’t do what it is supposed to do:
Check for symmetric response where the model is symmetric.
If it is not, run the beam solver first and make sure your properties are correct. Make sure the matrices for mass and stiffness are rotated if they need to be (remember the Material FoR definition and the for_delta?)
Now run the aerodynamic solver only and double check that the forces are symmetric.
Make sure your tolerances are low enough so that at least 4 FSI iterations are performed in StaticCoupled or DynamicCoupled.
Make sure your inputs are correct. For example: a dynamic case can be run with \(u_\infty = 0\) and the plane moving forwards, or \(u_\infty = x\) whatever and the plane velocity = 0. It is very easy to mix both, and end up with double the effective incoming speed (or none).
Run simple stuff before coupling it. For example, if your wing tip deflections don’t match what you’d expect, calculate the deflection under a small tip force (not too small, make sure the deflection is > 1% of the length!) by hand, and compare.
It is more difficult to do the same with the UVLM, as you need a VERY VERY high aspect ratio to get close to the 2D potential solutions. You are going to have to take my word for it: the UVLM works.
But check the aero grid geometry in Paraview, including chords lengths and angles.
Frequently Asked Questions [FAQs]¶
Over the years, we have gathered a valuable experience running SHARPy so we would like to collect here a few of the most frequently asked questions we get here to hopefully help other users.
In addition to the questions listed below, do check the issues page in our GitHub repo as you may find useful information there. Do also check our Short Debugging Guide.
[Q] I get a
ModuleNotFound Error
when trying to run SHARPy.[A] Make sure you have loaded the SHARPy variables using the command
source <path_to_sharpy>/bin_sharpy_var.sh
.[Q] When plotting the aerodynamic forces in Paraview from the UVLM, the forces at the boundary between two surfaces (for instance at the wing root) appears halved. Is my simulation incorrect?
[A] This is most likely not an issue with your simulation. We have observed over time that Paraview actually only plots the result from one of the surfaces, hence why it appears half of what it should be. If you extract the forces without using Paraview using the WriteVariablesTime postprocessor you will get the correct result.
[Q] My time-domain simulation does not converge. I get a
SolverNotConverged
error. What can I do?[A] This is quite an open question and it could be for a wide variety of reasons. Things that should be in your First Aid kit for these situations:
Is your tolerance appropriate? If you raise the tolerance to something (maybe unreasonably) high does it converge?
Is your number of iterations sufficient? Increase the number of maximum allowed iterations.
Is there anything happening at all in your simulation? We have all fallen into the trap of trying to run a time domain simulation of something that is already in steady state. I.e. you calculate its static equilibrium and then try to advance in time. Since nothing is happening the convergence criteria in the solvers may not be triggered and reach the maximum number of iterations. Solution: make sure something happens in your time domain simulation: gusts, external forces, control surface deflections…
Are you giving your simulation too much of a “kick”? Sometimes we simulate things that dramatically change the state of the problem from one time step to another (like adding very large external forces at once) which may lead to trouble. You can choose to load the forces progressively by increasing the
num_load_steps
setting in our structural solvers.
Hopefully this list will grow over time with some of the common questions previous users encounter. If you cannot solve
your problem please open an issue on Github and assign it the
label label:question
so we can keep track of it and others can benefit of the discussion.
Citing SHARPy¶
SHARPy has been published in the Journal of Open Source Software (JOSS) and the relevant paper can be found here.
If you are using SHARPy for your work, please remember to cite it using the paper in JOSS as:
del Carre et al., (2019). SHARPy: A dynamic aeroelastic simulation toolbox for very flexible aircraft and wind turbines. Journal of Open Source Software, 4(44), 1885, https://doi.org/10.21105/joss.01885
The bibtex entry for this citation is:
@Article{delCarre2019,
doi = {10.21105/joss.01885},
url = {https://doi.org/10.21105/joss.01885},
year = {2019},
month = dec,
publisher = {The Open Journal},
volume = {4},
number = {44},
pages = {1885},
author = {Alfonso del Carre and Arturo Mu{\~{n}}oz-Sim\'on and Norberto Goizueta and Rafael Palacios},
title = {{SHARPy}: A dynamic aeroelastic simulation toolbox for very flexible aircraft and wind turbines},
journal = {Journal of Open Source Software}
}
Indices and tables¶
Contact¶
SHARPy is developed at the Department of Aeronautics, Imperial College London. To get in touch, visit the Loads Control and Aeroelastics Lab website.