Version: June 2019
SHARPy (Simulation of High Aspect Ratio Planes in Python is a framework for linear and nonlinear aeroelastic analysis of flexible structures.
It is developed by the Loads Control and Aeroelasticity lab at the Department of Aeronautics. All the code is open source and readily available in GitHub.
Important links:
Loads Control and Aeroelasticity lab https://imperial.ac.uk/aeroelastics
Main github repository https://github.com/imperialcollegelondon/sharpy
Documentation(!!!) https://ic-sharpy.readthedocs.io
UVLM solver (C++) https://github.com/imperialcollegelondon/uvlm
Structural solver (Fortran) https://github.com/imperialcollegelondon/xbeam
SHARPy is mainly coded in Python, but the expensive routines, such as aero and structural solvers are coded in faster languages such as C++ and Fortran.
A number of different structures and analysis methods can be run. For example:
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:
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, he 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.
PD: aft-loaded airfoils can be included through the definition of the camber line of the blades.
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.
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.
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.
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.
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.
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.
Flutter speed [m/s] | Frequency [rad/s] |
---|---|
164 | 70.27 |
Check https://ic-sharpy.readthedocs.io/en/latest/content/installation.html for an in-depth guide on how to install SHARPy.
This assumes a few things about your computer:
It is Linux or MacOS (definitely not Windows - if you only have Windows, check VirtualBox and make an Ubuntu or CentOS virtual machine).
It has an up-to-date compiler (this might not be straightforward, run g++ --version
. If lower than 5.0, you will need to update it). An up-to-date Intel Compiler for C++ and Fortran is a good option as well.
SHARPy relies on Anaconda https://www.anaconda.com/distribution/ to handle all the python packages. Install the Python 3 version.
You then need to download the code:
1) Create a folder. Here it will be called code
mkdir code
cd code
2) Clone all the necessary repos and make sure you are in the correct branch -- usually develop
git clone https://github.com/imperialcollegelondon/sharpy --branch=develop
git clone https://github.com/imperialcollegelondon/xbeam --branch=develop
git clone https://github.com/imperialcollegelondon/uvlm --branch=develop
3) Create the conda environment and activate it
conda env create -f sharpy/utils/environment_linux.yml
(or environment_macos.yml
if on MacOS.
Now activate the conda environment
conda activate sharpy_env
you are going to have to do this every time to start a new terminal and want to run SHARPy
It sometimes fails in the pip
stage when installing. If it says something about distwheel
failed in mayavi
, activate the environment and run pip install mayavi
manually.
4) Compile xbeam
and uvlm
.
Move to the xbeam
folder (cd xbeam
) and run sh run_make.sh
. Wait until it finishes. Please make sure your anaconda env is active before running this.
Now the same for uvlm
: cd ../uvlm
and sh run_make.sh
.
5) SHARPy is now hopefully ready to go!
Navigate to the sharpy
folder: cd ../sharpy
and run:
source bin/sharpy_vars.sh
This command is important, as it loads the program in the terminal variables.
We can run the tests now:
python -m unittest
If everything has been installed properly, the tests should pass.
----------------------------------------------------------------------
Ran 28 tests in 23.465s
OK
Remember to run every time you start a new terminal:
conda activate sharpy_env
source <path-to-sharpy>/bin/sharpy_vars.sh
Tip: edit your ~\.bashrc
(linux) or \.bash_profile
(MacOS) and add the following:
alias load_sharpy="conda activate sharpy_env && source <path-to-sharpy>/bin/sharpy_vars.sh"
# Remember to modify the <path-to-sharpy> gap with your path
Then you just need to run in the console load_sharpy
to load everything in one go.
This case can be found in sharpy/tests/xbeam/geradin
, it is part of the test suite.
Basically, it is a 5 metres long cantilevered beam with a mass at the tip. Stiffness properties: $\mathcal{S} = \mathrm{diag}(EI, GA_y, GA_z, GJ, EI_y, EI_z) = \mathrm{diag}(4.8e8, 3.231e8, 3.231e8, 1e6, 9.346e6, 9.346e6)$
There is no distributed mass, only one at the tip. $M = 6e5/9.81$.
The main point about the Geradin beam is that the deflections are past the linear range.
If you open sharpy/tests/xbeam/geradin/generate_geradin.py
, you are going to see a basic input file for a structural only case.
The last part is the one that is the most important (function generate_solver_file
from line 134). This is where the solver settings and the overall flow of the program is given.
flow
variable controls the solvers and postprocessors that are going to be run in this simulation (and in which order). When you run sharpy with a valid header file, you will see a complete list of available solvers:--------------------------------------------------------------------------------
###### ## ## ### ######## ######## ## ##
## ## ## ## ## ## ## ## ## ## ## ##
## ## ## ## ## ## ## ## ## ####
###### ######### ## ## ######## ######## ##
## ## ## ######### ## ## ## ##
## ## ## ## ## ## ## ## ## ##
###### ## ## ## ## ## ## ## ##
--------------------------------------------------------------------------------
Aeroelastics Lab, Aeronautics Department.
Copyright (c), Imperial College London.
All rights reserved.
Running SHARPy from /home/ad214/run/code/sharpy/tests/xbeam/geradin
SHARPy being run is in /home/ad214/run/code/sharpy
The branch being run is develop
The version and commit hash are: v0.1-731-g85eb5ab-85eb5ab
The available solvers on this session are:
PreSharpy
AerogridLoader
BeamLoader
Modal
NonLinearDynamic
NonLinearDynamicCoupledStep
NonLinearDynamicPrescribedStep
NonLinearStatic
PIDTrajectoryControl
PrescribedUvlm
StaticCoupled
StaticTrim
StaticUvlm
StepUvlm
Trim
RigidDynamicPrescribedStep
DynamicUVLM
StepLinearUVLM
StaticLinearUvlm
InitializeMultibody
LagrangeMultipliersTrajectoryControl
NonLinearDynamicMultibody
SHWUvlm
StaticCoupledRBM
SteadyHelicoidalWake
DynamicCoupled
AeroForcesCalculator
AerogridPlot
BeamLoads
BeamPlot
Cleanup
SaveData
StallCheck
WriteVariablesTime
PlotFlowField
CreateSnapshot
LiftDistribution
For our simple structural simulation, we only need a few blocks: BeamLoader
for reading the input file and generating the beam data structure, NonLinearStatic
is the structural solver for nonlinear, static beams, BeamPlot
outputs the deformed shape and other quantities to a Paraview file structure (more on this later), and WriteVariablesTime
outputs the data we want to text files.
The case
is a name for the simulation so we can identify results.
The route
is the path to the .sharpy
file, so that SHARPy can find all the other necessary files.
Then, the other parts of the .sharpy
(or .sharpy
) file are based on the following structure:
[Header_name]
variable1 = 1
variable2 = a
variable3 = [a, a, b]
It is important to note that you need a header per every solver indicated in flow
. If that solver needs no settings, you still need to indicate the header.
There is also a main [SHARPy]
header that contains the main program settings, such as the flow
and the case
. It also has a setting called write_screen
. It is equal to off
because this is a test case, and you don't want tons of output. If you modify it to 'on'
, you'll be able to see what's going on on the screen.
If we want to (for example), run a stiffer beam, we can do so easily:
Open generate_geradin.py
and move to line 50 more or less where there are a few lines looking like:
ea = ...
ga = ...
#...
ei = ...
and modify them to look like:
stiffness_multiplier = 10
ea = ... * stiffness_multiplier
ga = ... * stiffness_multiplier
#...
ei = ... * stiffness_multiplier
you can also change the name of the case so that the results are not overwritten:
In line 6
, case_name = geradin_stiff
.
Now run again the case. First, generate the files: python generate_geradin.py
, and then run the case sharpy geradin_stiff.sharpy
.
You can now have a look at the wing tip deformations for both cases in output/<case_name>/WriteVariablesTime/struct_pos_node-1.dat
.
This section will take a bit of time and is quite tough to follow, but keep this as a reference.
The case.fem.h5
file has several components. We go one by one:
num_node_elem [int]
is 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.
connectivites [num_elem, num_node_elem]
a tricky one. 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). Basically, it links every element (index) to the stiffness matrix index in stiffness_db
. For example elem_stiffness[0] = 0; elem_stiffness[2] = 1
means that the element 0
has a stiffness matrix equal to stiffness_db[0, :, :]
, and the second element has a stiffness matrix equal to stiffness_db[1, :, :]
.
The shape of a stiffness matrix, $\mathrm{S}$ is: $$\mathrm{S} = \begin{bmatrix} EA & & & & & \\ & GA_y & & & & \\ & & GA_z & & & \\ & & & GJ & & \\ & & & & EI_y & \\ & & & & & EI_z \\ \end{bmatrix} $$ with the cross terms added if needed.
mass_db
and elem_mass
follow the same scheme than the stiffness, but the mass matrix is given by:
$$\mathrm{M} = \begin{bmatrix}
m\mathbf{I} & -\tilde{\xi}_{cg}m \\
\tilde{\xi}_{cg}m & J\\
\end{bmatrix}
$$
where $m$ is the distributed mass per unit length [kg/m], $\tilde{\bullet}$ is the skew-symmetric matrix of a vector and $\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_fo_reference_delta [num_elem, num_node_elem, 3]
contains the $\Delta$ vector in body-attached ($A$) frame of reference. As a rule of thumb:
$$\Delta = \left\{
\begin{matrix}
[-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{matrix}
\right.
$$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]
is technically not necessary, as the same effect can be achieved with FoR_delta. CAUTION previous versions of SHARPy had structural twist defined differently:structural_twist = np.zeros((num_node, num_node_elem)) # this is wrong now, and will trigger and error in SHARPy, change it!
structural_twist = np.zeros((num_elem, num_node_elem)) # this is right.
boundary_conditions [num_node]
is an array of integers (np.zeros((num_node, ), dtype=int)
) and contains all 0
EXCEPT FOR:
1
, this is the reference node. Usually, the first node has 1
and is located in [0, 0, 0]
. This makes things much easier.-1
.beam_number [num_elem]
is another array of integers. Usually you don't need to modify its value. Leave it at 0.
app_forces [num_elem, 6]
contains the applied forces app_forces[:, 0:3]
and moments app_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 [:]
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 [:]
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]
is an array of 3x3 inertial tensors. The relationship is set by the ordering as well.
lumped_mass_position [:, 3]
is the relative position of the lumped mass wrt 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.
All the aero 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:
In the aero.h5
file, there is a Group called airfoils
. 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]
is an array with the chords of every airfoil given in an element/node basis.
twist [num_elem, num_node_elem]
has the twist angle in radians. It is implemented as a rotation around the local $x$ axis.
sweep [num_elem, num_node_elem]
same here, just a rotation around $z$.
airfoil_distribution_input [num_elem, num_node_elem]
contains the indices of the airfoils that you put previously in airfoils
surface_distribution_input [num_elem]
is an 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]
is an integer array with the number of chordwise panels for every surface.
m_distribution [string]
is a string with the chordwise panel distribution. In almost all cases, leave it at uniform
.
aero_node_input [num_node]
is a boolean (True/False) array that indicates if that node has a lifting surface attached to it.
elastic_axis [num_elem, num_node_elem]
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]
is an integer array containing -1
if that section has no control surface associated to it, and 0, 1, 2 ...
if the section belongs to the control surface 0, 1, 2 ...
respectively.
control_surface_type [num_control_surface]
contains 0
if the control surface deflection is static, and 1
is it is dynamic (if you need to run dynamic control surfaces, come see me).
control_surface_chord [num_control_surface]
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 put 1
.
control_surface_hinge_coord [num_control_surface]
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. If you are, come see me.
The solver settings are covered almost entirely in the documentation (again: https://ic-sharpy.readthedocs.io). I'm going to explain in more detail the important ones. The defaults settings are generally good enough for a majority of cases.
BeamLoader reads the solver.txt and the fem.h5 files and generates the beam
data structure. Its settings are simple:
unsteady
leave it onorientation
is what is used to set the attitude angles. It is given as a quaternion (CAREFUL: a null rotation in quaternions is $[1, 0, 0, 0]$). You can give it in Euler angles as: 'orientation' = algebra.euler2quat(np.array([roll, alpha, beta]))
.mstar
number of chordwise panels for the wake. A good value is $$M^* = \frac{L_{\mathrm{wake}}}{\Delta t u_\infty}$$, which means that the wake panels are the same size as the main wing ones.
freestream_dir
is a different approach to modifying the attitude angles. I'd leave alone unless you really need it.
The static beam solver settings. Important ones:
max_iterations
maximum number of iterations for the structural solver. These are not the same as the ones in DynamicCoupled
.
num_load_steps
if > 1, the applied forces and gravity are applied progressively in several steps in order to avoid numerical divergence. Leave it at 1 unless you have problems with convergence of static cases.
delta_curved
leave it at $1e-1$.
min_delta
this one is more tricky. Usually $1e-6$ works well for flexible structures. If you are running more stiff stuff, you might need to lower it even more. Don't go under $1e-11$. If you don't know, start at $1e-6$, note the wing tip deflection and lower it even more. A too low value will cause the beam solver to reach max_iterations
without convergence. When this happens, note the residual value and set something larger than that.
gravity_on
on
if gravity, off
if not.
gravity
$9.81$ if you are on Earth. Setting it to 0 is the same as gravity_on
= off
, but the latter is quicker.
horseshoe
if this is on
, mstar
(in AerogridLoader) has to be 1. It controls the wake modelling. Usual wakes with mstar > 1
are discretised and are of finite length. The horsehoe modelling is derived from the analytical expansion of an discretised wake of infinite length. ATTENTION: use only in static simulations.
n_rollup
how many steps are carried out to convect the wake with full free-wake. This usually should be 0
, but if you want a pretty picture, you can use n_rollup = int(mstar*1.5)
.
rollup_dt
if n_rollup > 0
, set rollup_dt
to
$$
\Delta t_{\mathrm{rollup}} = \frac{c/M}{u_\infty}
$$
'velocity_field_generator' a few options available here. This paragraph is applicable to every aero solver that has a velocity_field_generator
setting.
SteadyVelocityField
: quite straightforward. Give a u_inf value in u_inf
and a direction in u_inf_direction
.GustVelocityField
: this one generate gusts in several profiles. The ones you will probably use: gust_shape: '1-cos'
, or 'continuous_sin'
. u_inf
and u_inf_direction
already explainedgust_length
: equvalent to $2H$ in metres.gust_intensity
: reference (peak) velocity of the gust, in m/s.offset
x coord. of the first point of the gust with respect to the $[0, 0, 0]$ in inertial.span
: span of the aircraft (you are probably not going to use this, it is implemented for DARPA gusts).VelocityFieldGenerator
: a full unsteady 3D field of velocities is input. Ask me if you want to use it.print_info
: set it to on
in almost all cases.structural_solver
and aero_solver
: these are strings with the name of the structural and aerodynamic solvers you want to use for the coupled simulation. A solver with that name needs to exist in SHARPy (check the list of available solvers at the start of a simulation).structural_solver_settings
and aero_solver_settings
: a dictionary (each) that is basically the same you added before if you wanted to run a standalone structural or aero simulation. A code example:settings = dict()
settings['NonLinearStatic'] = {
'print_info': 'on',
'max_iterations': 150
# ...
}
settings['StaticUvlm'] = {
'print_info': 'on',
'horseshoe': 'off'
# ...
}
settings['StaticCoupled'] = {
'structural_solver': 'NonLinearStatic',
'structural_solver_settings': settings['NonLinearStatic'],
'aero_solver': 'StaticUvlm',
'aero_solver_settings': settings['StaticUvlm'],
# ...
max_iter
: max number of FSI iterationsn_load_steps
: if > 1, it ramps the aero and gravity forces slowly to improve convergence. Leave at 0 unless you really need it, then try 4 or 5.tolerance
: threshold for convergence of the FSI iteration. Make sure you are choosing a reasonable value for the case. If it converges in 1 iteration: lower it. If it takes more than 10: unless it is a very complicated case (next to flutter or overspeed conditions), lower it.relaxation_factor
a real number $\omega \in [0, 1)$. $\omega = 0$ means no relaxation, $\omega \to 1$ means every iteration affects very little to the state of the system. Usually 0.3 is a good value. If you are (again) close to overspeed, flutter... you are going to need to raise it to 0.6 or even more.This solver acts like a wrapper of StaticCoupled
, just like StaticCoupled
is a wrap for the structural and aero solver. That means that when we initialise the StaticTrim
solver, we also create a StaticCoupled
, a NonlinearStatic
and a StaticUvlm
instance.
It is important to know that StaticTrim only trims the longitudinal variables ($F_x, F_z, M_y$) by modifying the angle of attack, tail deflection and thrust. No lateral/directional variables are considered.
solver
: probably you want StaticCoupled
solver_settings
: most likely, something similar to settings['StaticCoupled
]`.initial_alpha
, initial_deflection
, initial_thrust
: initial values for the angle of attack, elevator deflection and thrust per engine.This is where things get interesting. DynamicCoupled
performs the time stepping and FSI iteration processes. Just as StaticCoupled
, it requires a structural solver (for free-flight elastic aircraft it will be NonLinearDynamicCoupledStep
, ask for others), and an aero solver, which will be StepUvlm
.
The structural_solver
and structural_solver_settings
(and the aero equivalents) are set up the same way I showed in the StaticCoupled
.
fsi_substeps
: max iterations in FSI loopfsi_tolerance
: quite descriptive. What I said for the static coupled tolerance still applies.relaxation_factor
: exactly the same. There are more settings to control the relaxation, and make it vary as the simulation progresses, but you probably won't need it.minimum_steps
: minimum FSI steps to run even if convergence is reached.n_time_steps
: quite descriptive.dt
: $\Delta t$include_unsteady_force_contribution
: this activates the added mass effects calculation. It is good to have it, but it makes the simulation a bit more challenging from a numerical point of view. Run some numbers by hand and decide if it is worth it. Removing this contribution makes the code faster.postprocessors
: the fun begins. postprocessors
are modules run every time step after convergence. For example, to calculate the beam loads, or output to paraview. This variable is an array of strings (['one_module', 'another_module']
) and the modules are run in the order they are indicated. A typical workflow would be:'postprocessors': [
'BeamLoads', # Calculate the loads at every beam element
'BeamPlot', # Output the beam data to paraview (including the beam loads - that's why beamloads goes first)
'AerogridPlot', # Output the aero grid to paraview
]
postprocessor_settings
: hopefully by this time you already get the _settings
thing. I won't explain the settings of the processors here, you can do it in the code.Almost same settings as NonLinearStatic
, so I'm going to explain only the settings that are different.
newmark_damp
: artificial damping parameter. Increasing this damps the higher frequencies while leaving the low frequency modes relatively untouched (please note the relatively). Start with $5\times 10^{-4}$ an increase it if needed. No more than $10^{-2}$.num_steps
: number of time stepsdt
: $\Delta t$initial_velocity
: if you want to aircraft to fly with a velocity, this is the place to put it. Instead, you can leave it at 0 and put the velocity as a u_inf
contribution. Results will be the same.convection_scheme
: you probably want to leave it at 2
. This convects the wake with the background flow (no influence from the aircraft). 3
is a full free-wake, which looks very good, takes very long and results don't change if compared to 2
in most of the cases.gamma_dot_filtering
: if you added the unsteady_forces_contribution
in DynamicCoupled
, you probably want to put 7
or 9
here. If not, it won't be considered.The command line is where you are going to spend quite a lot of your time. Make your life easier and learn how to use it.
When you open a terminal, the default location to land is your HOME
folder. In the terminal, your home folder is identified as ~
or $HOME
.
You can navigate to the folder of your choice using cd
(change directory) for example, if you want to go to Downloads
:
cd Downloads
Extra tip: write cd Dow
and press Tab to autocomplete.
If you haven't created the folder you want to move to, you can make dir: mkdir
. For example, to create a folder called Code
in you Home directory:
# go to your home folder if you are not there yet
cd ~ # or `cd ` or `cd $HOME`, all equivalent
# create the dir
mkdir Code
If you have a file in Downloads
called very_private_stuff.txt
, you can copy it (cp
) or move it (mv
) to your Code
folder:
cd Code
# copy it
cp ../Downloads/very_private_stuff.txt ./
# or move it
mv ../Downloads/very_private_stuff.txt ./
Things that require explanation:
..
denotes the parent folder of a location. For example: ../Downloads
means "go to the previous folder and then to Downloads".
(a single period) denotes the current location. For example: ./
means "right here"You can also use mv
to rename files:
mv very_private_stuff.txt homework.txt
If you want copy a folder, you need to add -r
(this is called a flag) after cp
. Example: we have a folder in Downloads
called justin_bieber_complete_discography
and we want to copy it to Music
and call it arctic_monkeys
instead:
cd ~
mkdir Music
# note the space between cp and -r
cp -r Downloads/justin_bieber_complete_discography Music/arctic_monkeys
You can also delete or remove (rm
) files and folders. Now you don't want your Justin Bieber tunes in your Downloads
folder, so you run:
cd ~/Downloads
# note the -r here too
rm -r justin_bieber_complete_discography
ATTENTION the rm
command IS NOT REVERTIBLE. No Rubbish Bin, Trash, helmet or parachute. Make sure you are very very sure you actually want to delete exactly that (and nothing else).
A note: some files cannot be deleted with a simple rm file
, and the computer will say it is protected. Then add the flag -f
(force), but this makes rm
even more dangerous, so try not to use it. The git
internal files are sometimes protected, so if you want to delete an old copy of SHARPy, you probably will need to use it.
These are the very basic commands for command line survival. I'm going to add a few non-essential ones, but useful nevertheless:
which
: it tells you which executable is running. For example which sharpy
returns: /home/user/code/sharpy/bin/sharpy
. It is useful for knowing which version of anything you are running and where it comes from. For example, it is useful for knowing if you are using the updated compilers (usually in /usr/local/bin
) or the default ones (/usr/bin
probably).top
: shows you the processes running and how much RAM they're using.touch
: creates and empty file with the name you tell after the command.ipython
: starts a nice Python terminal with autocomplete and some colours. Much better than python
.history
: if you forgot that nice command that did what I wanted and now I can't remember. Extra: history | grep "command"
(without the quotes) will only show you the history lines that contain command
.*
: wildcard for copying, removing, moving... Everything. Example: cp *.txt ./my_files/"
. Again: careful with rm
and *
together. Be VERY careful with rm
and -rf
and *
together.pwd
: for when you get lost and don't know where you are in the folder structure.nano
: simple text editor. Save with ctrl+o
, exit with ctrl+x
.more
: have a look at a file quicklyhead
: show the first lines of a filetail
: show the last lines of a fileWhen the program fails, there are a number of typical reasons:
conda activate sharpy_env
and source bin/sharpy_vars.sh
?which sharpy
, do you get the one you want?which python
, does the result point to anaconda3/envs/sharpy_env/bin
(or similar)?BeamLoader
and BeamPlot
with no structural solver in between. Go over the structure in Paraview. Check the fem.h5
file with HDFView.num_elem
and num_node
variables are actually your correct number of elements and nodes.develop
. Again, check the first few lines of SHARPy output.StepUvlm
and DynamicCoupled
.StaticCoupled
or DynamicCoupled
solvers.import pdb; pdb.set_trace()
and patienceIf your model doesn't do what it is supposed to do:
Check for symmetric response where the model is symmetric.
for_delta
?)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 = $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.