-
Notifications
You must be signed in to change notification settings - Fork 57
/
lingebm.py
1594 lines (1192 loc) · 66.4 KB
/
lingebm.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
"""
Linear beam model class
S. Maraniello, Aug 2018
N. Goizueta
"""
import numpy as np
import scipy as sc
import scipy.signal as scsig
import sharpy.linear.src.libss as libss
import sharpy.utils.algebra as algebra
import sharpy.utils.settings as settings
import sharpy.utils.cout_utils as cout
import sharpy.structure.utils.modalutils as modalutils
import warnings
from sharpy.linear.utils.ss_interface import LinearVector, StateVariable, OutputVariable, InputVariable
class FlexDynamic():
r"""
Define class for linear state-space realisation of GEBM flexible-body
equations from SHARPy``timestep_info`` class and with the nonlinear structural information.
The linearised beam takes the following arguments:
Args:
tsinfo (sharpy.utils.datastructures.StructImeStepInfo): Structural timestep containing the modal information
structure (sharpy.solvers.beamloader.Beam): Beam class with the structural information
custom_settings (dict): settings for the linearised beam
State-space models can be defined in continuous or discrete time (dt
required). Modal projection, either on the damped or undamped modal shapes,
is also avaiable. The rad/s array wv can be optionally passed for freq.
response analysis
To produce the state-space equations:
1. Set the settings:
a. ``modal_projection={True,False}``: determines whether to project the states
onto modal coordinates. Projection over damped or undamped modal
shapes can be obtained selecting:
- ``proj_modes={'damped','undamped'}``
while
- ``inout_coords={'modes','nodal'}``
determines whether the modal state-space inputs/outputs are modal
coords or nodal degrees-of-freedom. If ``modes`` is selected, the
``Kin`` and ``Kout`` gain matrices are generated to transform nodal to modal
dofs
b. ``dlti={True,False}``: if true, generates discrete-time system.
The continuous to discrete transformation method is determined by::
discr_method={ 'newmark', # Newmark-beta
'zoh', # Zero-order hold
'bilinear'} # Bilinear (Tustin) transformation
DLTIs can be obtained directly using the Newmark-:math:`\beta` method
``discr_method='newmark'``
``newmark_damp=xx`` with ``xx<<1.0``
for full-states descriptions (``modal_projection=False``) and modal projection
over the undamped structural modes (``modal_projection=True`` and ``proj_modes``).
The Zero-order holder and bilinear methods, instead, work in all
descriptions, but require the continuous state-space equations.
2. Generate an instance of the beam
2. Run ``self.assemble()``. The method accepts an additional parameter, ``Nmodes``,
which allows using a lower number of modes than specified in ``self.Nmodes``
Examples:
>>> beam_settings = {'modal_projection': True,
>>> 'inout_coords': 'modes',
>>> 'discrete_time': False,
>>> 'proj_modes': 'undamped',
>>> 'use_euler': True}
>>>
>>> beam = lingebm.FlexDynamic(tsstruct0, structure=data.structure, custom_settings=beam_settings)
>>>
>>> beam.assemble()
Notes:
* Modal projection will automatically select between damped/undamped modes shapes, based on the data available
from tsinfo.
* If the full system matrices are available, use the modal_sol methods to override mode-shapes and eigenvectors
"""
def __init__(self, tsinfo, structure=None, custom_settings=dict()):
# Extract settings
self.settings = custom_settings
### extract timestep_info modal results
# unavailable attrs will be None
self.freq_natural = tsinfo.modal.get('freq_natural')
self.freq_damp = tsinfo.modal.get('freq_damped')
self.damping = tsinfo.modal.get('damping')
self.eigs = tsinfo.modal.get('eigenvalues')
self.U = tsinfo.modal.get('eigenvectors')
self.V = tsinfo.modal.get('eigenvectors_left')
self.Kin_damp = tsinfo.modal.get('Kin_damp') # for 'damped' modes only
self.Ccut = tsinfo.modal.get('Ccut') # for 'undamp' modes only
self.Mstr = tsinfo.modal.get('M')
self.Cstr = tsinfo.modal.get('C')
self.Kstr = tsinfo.modal.get('K')
### set other flags
self.modal = self.settings['modal_projection']
self.inout_coords = self.settings['inout_coords']
self.dlti = self.settings['discrete_time']
if self.dlti:
self.dt = self.settings['dt']
else:
self.dt = None
self.Nmodes = self.settings['num_modes']
self._num_modes = None
self.num_modes = self.settings['num_modes']
self.num_dof = self.U.shape[0]
if self.V is not None:
self.num_dof = self.num_dof // 2
self.proj_modes = self.settings['proj_modes']
if self.V is None:
self.proj_modes = 'undamped'
self.discr_method = self.settings['discr_method']
self.newmark_damp = self.settings['newmark_damp']
self.use_euler = self.settings['use_euler']
self.use_principal_axes = self.settings.get('rigid_modes_ppal_axes', False) # this setting is inherited from the setting in Modal solver
### set state-space variables
self.SScont = None
self.SSdisc = None
self.Kin = None
self.Kout = None
# Store structure at linearisation and linearisation conditions
self.structure = structure
self.tsstruct0 = tsinfo
self.Minv = None # Not used anymore since M is factorized inside newmark_ss
self.scaled_reference_matrices = dict() # keep reference values prior to time scaling
if self.use_euler:
self.euler_propagation_equations(tsinfo)
if self.Mstr.shape[0] == 6*(self.tsstruct0.num_node - 1):
self.clamped = True
self.num_dof_rig = 0
else:
self.clamped = False
if self.use_euler:
self.num_dof_rig = 9
else:
self.num_dof_rig = 10
if self.modal:
self.update_modal()
self.num_dof_flex = np.sum(structure.vdof >= 0)*6
self.num_dof_str = self.num_dof_flex + self.num_dof_rig
q, dq = self.reshape_struct_input()
self.tsstruct0.q = q
self.tsstruct0.dq = dq
# Linearised gravity matrices
self.Crr_grav = None
self.Csr_grav = None
self.Krs_grav = None
self.Kss_grav = None
def reshape_struct_input(self):
""" Reshape structural input in a column vector """
structure = self.structure # self.data.aero.beam
tsdata = self.tsstruct0
q = np.zeros(self.num_dof_str)
dq = np.zeros(self.num_dof_str)
jj = 0 # structural dofs index
for node_glob in range(structure.num_node):
### detect bc at node (and no. of dofs)
bc_here = structure.boundary_conditions[node_glob]
if bc_here == 1: # clamp
dofs_here = 0
continue
elif bc_here == -1 or bc_here == 0:
dofs_here = 6
jj_tra = [jj, jj + 1, jj + 2]
jj_rot = [jj + 3, jj + 4, jj + 5]
# retrieve element and local index
ee, node_loc = structure.node_master_elem[node_glob, :]
# allocate
q[jj_tra] = tsdata.pos[node_glob, :]
q[jj_rot] = tsdata.psi[ee, node_loc]
# update
jj += dofs_here
# allocate FoR A quantities
if self.use_euler:
q[-9:-3] = tsdata.for_vel
q[-3:] = algebra.quat2euler(tsdata.quat)
wa = tsdata.for_vel[3:]
dq[-9:-3] = tsdata.for_acc
T = algebra.deuler_dt(q[-3:])
dq[-3:] = T.dot(wa)
else:
q[-10:-4] = tsdata.for_vel
q[-4:] = tsdata.quat
wa = tsdata.for_vel[3:]
dq[-10:-4] = tsdata.for_acc
dq[-4] = -0.5 * np.dot(wa, tsdata.quat[1:])
return q, dq
@property
def num_modes(self):
return self._num_modes
@num_modes.setter
def num_modes(self, value):
self.update_truncated_modes(value)
self._num_modes = value
@property
def num_flex_dof(self):
return np.sum(self.structure.vdof >= 0) * 6
@property
def num_rig_dof(self):
return self.Mstr.shape[0] - self.num_flex_dof
def sort_repeated_evecs(self, evecs, evals):
num_rbm = np.sum(evals.__abs__() == 0.)
num_dof = evecs.shape[0]
evecs_sorted = evecs.copy()
if num_rbm != 0:
for i in range(num_rbm):
index_mode = np.argmax(evecs[:, i].__abs__()) - num_dof + num_rbm
evecs_sorted[:, index_mode] = evecs[:, i]
return evecs_sorted
def euler_propagation_equations(self, tsstr):
"""
Introduce the linearised Euler propagation equations that relate the body fixed angular velocities to the Earth
fixed Euler angles.
This method will remove the quaternion propagation equations created by SHARPy; the resulting
system will have 9 rigid degrees of freedom.
Args:
tsstr:
Returns:
"""
# Verify the rigid body modes are used
num_node = tsstr.num_node
num_flex_dof = 6*(num_node-1)
euler = algebra.quat2euler(tsstr.quat)
tsstr.euler = euler
if self.Mstr.shape[0] == num_flex_dof + 10:
# Erase quaternion equations
self.Cstr[-4:, :] = 0
self.Mstr = self.Mstr[:-1, :-1]
self.Cstr = self.Cstr[:-1, :-1]
self.Kstr = self.Kstr[:-1, :-1]
for_rot = tsstr.for_vel[3:]
Crr = np.zeros((9, 9))
# Euler angle propagation equations
Crr[-3:, -6:-3] = -algebra.deuler_dt(tsstr.euler)
Crr[-3:, -3:] = -algebra.der_Teuler_by_w(tsstr.euler, for_rot)
self.Cstr[-9:, -9:] += Crr
else:
warnings.warn('Euler parametrisation not implemented - Either rigid body modes are not being used or this '
'method has already been called.')
@property
def num_dof(self):
self.num_dof = self.Mstr.shape[0]
# Previously beam.U.shape[0]
return self._num_dof
@num_dof.setter
def num_dof(self, value):
self._num_dof = value
def linearise_gravity_forces(self, tsstr=None):
r"""
Linearises gravity forces and includes the resulting terms in the C and K matrices. The method takes the
linearisation condition (optional argument), linearises and updates:
* Stiffness matrix
* Damping matrix
* Modal damping matrix
The method works for both the quaternion and euler angle orientation parametrisation.
Args:
tsstr (sharpy.utils.datastructures.StructTimeStepInfo): Structural timestep at the linearisation point
Notes:
The gravity forces are linearised to express them in terms of the beam formulation input variables:
* Nodal forces: :math:`\delta \mathbf{f}_A`
* Nodal moments: :math:`\delta(T^T \mathbf{m}_B)`
* Total forces (rigid body equations): :math:`\delta \mathbf{F}_A`
* Total moments (rigid body equations): :math:`\delta \mathbf{M}_A`
Gravity forces are naturally expressed in ``G`` (inertial) frame
.. math:: \mathbf{f}_{G,0} = \mathbf{M\,g}
where the :math:`\mathbf{M}` is the tangent mass matrix obtained at the linearisation reference.
To obtain the gravity forces expressed in A frame we make use of the projection matrices
.. math:: \mathbf{f}_A = C^{AG}(\boldsymbol{\chi}) \mathbf{f}_{G,0}
that projects a vector in the inertial frame ``G`` onto the body attached frame ``A``.
The projection of a vector can then be linearised as
.. math::
\delta \mathbf{f}_A = C^{AG} \delta \mathbf{f}_{G,0}
+ \frac{\partial}{\partial \boldsymbol{\chi}}(C^{AG} \mathbf{f}_{G,0}) \delta\boldsymbol{\chi}.
* Nodal forces:
The linearisation of the gravity forces acting at each node is simply
.. math::
\delta \mathbf{f}_A =
+ \frac{\partial}{\partial \boldsymbol{\chi}}(C^{AG} \mathbf{f}_{G,0}) \delta\boldsymbol{\chi}
where it is assumed that :math:`\delta\mathbf{f}_G = 0`.
* Nodal moments:
The gravity moments can be expressed in the local node frame of reference ``B`` by
.. math:: \mathbf{m}_B = \tilde{X}_{B,CG}C^{BA}(\Psi)C^{AG}(\boldsymbol{\chi})\mathbf{f}_{G,0}
The linearisation is given by:
.. math::
\delta \mathbf{m}_B = \tilde{X}_{B,CG}
\left(\frac{\partial}{\partial\Psi}(C^{BA}\mathbf{f}_{A,0})\delta\Psi +
C^{BA}\frac{\partial}{\partial\boldsymbol{\chi}}(C^{AG}\mathbf{f}_{G,0})\delta\boldsymbol{\chi}\right)
However, recall that the input moments are defined in tangential space
:math:`\delta(T^\top\mathbf{m}_B)` whose linearised expression is
.. math:: \delta(T^T(\Psi) \mathbf{m}_B) = T_0^T \delta \mathbf{m}_B +
\frac{\partial}{\partial \Psi}(T^T \mathbf{m}_{B,0})\delta\Psi
where the :math:`\delta \mathbf{m}_B` term has been defined above.
* Total forces:
The total forces include the contribution from all flexible degrees of freedom as well as the gravity
forces arising from the mass at the clamped node
.. math:: \mathbf{F}_A = \sum_n \mathbf{f}_A + \mathbf{f}_{A,clamped}
which becomes
.. math:: \delta \mathbf{F}_A = \sum_n \delta \mathbf{f}_A +
\frac{\partial}{\partial\boldsymbol{\chi}}\left(C^{AG}\mathbf{f}_{G,clamped}\right)
\delta\boldsymbol{\chi}.
* Total moments:
The total moments, as opposed to the nodal moments, are expressed in A frame and again require the
addition of the moments from the flexible structural nodes as well as the ones from the clamped node
itself.
.. math:: \mathbf{M}_A = \sum_n \tilde{X}_{A,n}^{CG} C^{AG} \mathbf{f}_{n,G}
+ \tilde{X}_{A,clamped}C^{AG}\mathbf{f}_{G, clamped}
where :math:`X_{A,n}^{CG} = R_{A,n} + C^{AB}(\Psi)X_{B,n}^{CG}`. Its linearised form is
.. math:: \delta X_{A,n}^{CG} = \delta R_{A,n}
+ \frac{\partial}{\partial \Psi}(C^{AB} X_{B,CG})\delta\Psi
Therefore, the overall linearisation of the total moment is defined as
.. math:: \delta \mathbf{M}_A =
\tilde{X}_{A,total}^{CG} \frac{\partial}{\partial \boldsymbol{\chi}}(C^{AG}\mathbf{F}_{G, total})
\delta \boldsymbol{\chi}
-\sum_n \tilde{C}^{AG}\mathbf{f}_{G,0} \delta X_{A,n}^{CG}
where :math:`X_{A, total}` is the centre of gravity of the entire system expressed in ``A`` frame and
:math:`\mathbf{F}_{G, total}` are the gravity forces of the overall system in ``G`` frame, including the
contributions from the clamped node.
The linearisation introduces damping and stiffening terms since the :math:`\delta\boldsymbol{\chi}` and
:math:`\delta\boldsymbol{\Psi}` terms are found in the damping and stiffness matrices respectively.
Therefore, the beam matrices need updating to account for these terms:
* Terms from the linearisation of the nodal moments will be assembled in the rows corresponding to
moment equations and columns corresponding to the cartesian rotation vector
.. math:: K_{ss}^{m,\Psi} \leftarrow -T_0^T \tilde{X}_{B,CG}
\frac{\partial}{\partial\Psi}(C^{BA}\mathbf{f}_{A,0})
-\frac{\partial}{\partial \Psi}(T^T \mathbf{m}_{B,0})
* Terms from the linearisation of the translation forces with respect to the orientation are assembled
in the damping matrix, the rows corresponding to translational forces and columns to orientation
degrees of freedom
.. math:: C_{sr}^{f,\boldsymbol{\chi}} \leftarrow -
\frac{\partial}{\partial \boldsymbol{\chi}}(C^{AG} \mathbf{f}_{G,0})
* Terms from the linearisation of the moments with respect to the orientation are assembled in the
damping matrix, with the rows correspondant to the moments and the columns to the orientation degrees
of freedom
.. math:: C_{sr}^{m,\boldsymbol{\chi}} \leftarrow -
T_0^T\tilde{X}_{B,CG}C^{BA}\frac{\partial}{\partial\boldsymbol{\chi}}(C^{AG}\mathbf{f}_{G,0})
* Terms from the linearisation of the total forces with respect to the orientation correspond to the
rigid body equations in the damping matrix, the rows to the translational forces and columns to the
orientation
.. math:: C_{rr}^{F,\boldsymbol{\chi}} \leftarrow
- \sum_n \frac{\partial}{\partial \boldsymbol{\chi}}(C^{AG} \mathbf{f}_{G,0})
* Terms from the linearisation of the total moments with respect to the orientation correspond to the
rigid body equations in the damping matrix, the rows to the moments and the columns to the orientation
.. math:: C_{rr}^{M,\boldsymbol{\chi}} \leftarrow
- \sum_n\tilde{X}_{A,n}^{CG} \frac{\partial}{\partial \boldsymbol{\chi}}(C^{AG}\mathbf{f}_{G,0})
* Terms from the linearisation of the total moments with respect to the nodal position :math:`R_A` are
included in the stiffness matrix, the rows corresponding to the moments in the rigid body
equations and the columns to the nodal position
.. math:: K_{rs}^{M,R} \leftarrow + \sum_n \tilde{\mathbf{f}_{A,0}}
* Terms from the linearisation of the total moments with respect to the cartesian rotation vector are
included in the stiffness matrix, the rows corresponding to the moments in the rigid body equations
and the columns to the cartesian rotation vector
.. math:: K_{rs}^{M, \Psi} \leftarrow
+ \sum_n \tilde{\mathbf{f}_{A,0}}\frac{\partial}{\partial \Psi}(C^{AB} X_{B,CG})
"""
if tsstr is None:
tsstr = self.tsstruct0
if self.settings['print_info']:
try:
cout.cout_wrap('\nLinearising gravity terms...')
except ValueError:
pass
num_node = tsstr.num_node
flex_dof = 6 * sum(self.structure.vdof >= 0)
if self.use_euler:
rig_dof = 9
# This is a rotation matrix that rotates a vector from G to A
Cag = algebra.euler2rot(tsstr.euler)
Cga = Cag.T
# Projection matrices - this projects the vector in G t to A
Pag = Cga
Pga = Cag
else:
rig_dof = 10
# get projection matrix A->G
# Cga = algebra.quat2rotation(tsstr.quat)
# Pga = Cga.T
# Pag = Pga.T
Cag = algebra.quat2rotation(tsstr.quat) # Rotation matrix FoR G rotated by quat
Pag = Cag.T
Pga = Pag.T
# Mass matrix partitions for CG calculations
Mss = self.Mstr[:flex_dof, :flex_dof]
Mrr = self.Mstr[-rig_dof:, -rig_dof:]
# Initialise damping and stiffness gravity terms
Crr_grav = np.zeros((rig_dof, rig_dof))
Csr_grav = np.zeros((flex_dof, rig_dof))
Crr_debug = np.zeros((rig_dof, rig_dof))
Krs_grav = np.zeros((rig_dof, flex_dof))
Kss_grav = np.zeros((flex_dof, flex_dof))
# Overall CG in A frame
Xcg_A = -np.array([Mrr[2, 4], Mrr[0, 5], Mrr[1, 3]]) / Mrr[0, 0]
Xcg_Askew = algebra.skew(Xcg_A)
if self.settings['print_info']:
cout.cout_wrap('\tM = %.2f kg' % Mrr[0, 0], 1)
cout.cout_wrap('\tX_CG A -> %.2f %.2f %.2f' %(Xcg_A[0], Xcg_A[1], Xcg_A[2]), 1)
FgravA = np.zeros(3)
FgravG = np.zeros(3)
for i_node in range(num_node):
# Gravity forces at the linearisation condition (from NL SHARPy in A frame)
fgravA = tsstr.gravity_forces[i_node, :3]
fgravG = Pga.dot(fgravA)
# fgravG = tsstr.gravity_forces[i_node, :3]
mgravA = tsstr.gravity_forces[i_node, 3:]
fgravA = Pag.dot(fgravG)
mgravG = Pag.dot(mgravA)
# Get nodal position - A frame
Ra = tsstr.pos[i_node, :]
# retrieve element and local index
ee, node_loc = self.structure.node_master_elem[i_node, :]
psi = tsstr.psi[ee, node_loc, :]
Cab = algebra.crv2rotation(psi)
Cba = Cab.T
Cbg = Cba.dot(Pag)
# Tangential operator for moments calculation
Tan = algebra.crv2tan(psi)
jj = 0 # nodal dof index
bc_at_node = self.structure.boundary_conditions[i_node] # Boundary conditions at the node
if bc_at_node == 1: # clamp (only rigid-body)
dofs_at_node = 0
jj_tra, jj_rot = [], []
elif bc_at_node == -1 or bc_at_node == 0: # (rigid+flex body)
dofs_at_node = 6
jj_tra = 6 * self.structure.vdof[i_node] + np.array([0, 1, 2], dtype=int) # Translations
jj_rot = 6 * self.structure.vdof[i_node] + np.array([3, 4, 5], dtype=int) # Rotations
else:
raise NameError('Invalid boundary condition (%d) at node %d!' \
% (bc_at_node, i_node))
jj += dofs_at_node
if bc_at_node != 1:
# Nodal centre of gravity (in the case of additional lumped masses, else should be zero)
Mss_indices = np.concatenate((jj_tra, jj_rot))
Mss_node = Mss[Mss_indices,:]
Mss_node = Mss_node[:, Mss_indices]
Xcg_B = Cba.dot(-np.array([Mss_node[2, 4], Mss_node[0, 5], Mss_node[1, 3]]) / Mss_node[0, 0])
Xcg_Bskew = algebra.skew(Xcg_B)
# Nodal CG in A frame
Xcg_A_n = Ra + Cab.dot(Xcg_B)
Xcg_A_n_skew = algebra.skew(Xcg_A_n)
# Nodal CG in G frame - debug
Xcg_G_n = Pga.dot(Xcg_A_n)
if self.settings['print_info']:
cout.cout_wrap("Node %2d \t-> B %.3f %.3f %.3f" %(i_node, Xcg_B[0], Xcg_B[1], Xcg_B[2]), 2)
cout.cout_wrap("\t\t\t-> A %.3f %.3f %.3f" %(Xcg_A_n[0], Xcg_A_n[1], Xcg_A_n[2]), 2)
cout.cout_wrap("\t\t\t-> G %.3f %.3f %.3f" %(Xcg_G_n[0], Xcg_G_n[1], Xcg_G_n[2]), 2)
cout.cout_wrap("\tNode mass:", 2)
cout.cout_wrap("\t\tMatrix: %.4f" % Mss_node[0, 0], 2)
# cout.cout_wrap("\t\tGrav: %.4f" % (np.linalg.norm(fgravG)/9.81), 2)
if self.use_euler:
if bc_at_node != 1:
# Nodal moments due to gravity -> linearisation terms wrt to delta_psi
Kss_grav[np.ix_(jj_rot, jj_rot)] -= Tan.dot(Xcg_Bskew.dot(algebra.der_Ccrv_by_v(psi, fgravA)))
Kss_grav[np.ix_(jj_rot, jj_rot)] -= algebra.der_TanT_by_xv(psi, Xcg_Bskew.dot(Cbg.dot(fgravG)))
# Nodal forces due to gravity -> linearisation terms wrt to delta_euler
Csr_grav[jj_tra, -3:] -= algebra.der_Peuler_by_v(tsstr.euler, fgravG)
# Nodal moments due to gravity -> linearisation terms wrt to delta_euler
Csr_grav[jj_rot, -3:] -= Tan.dot(Xcg_Bskew.dot(Cba.dot(algebra.der_Peuler_by_v(tsstr.euler, fgravG))))
# Total moments -> linearisation terms wrt to delta_Ra
# These terms are not affected by the Euler matrix. Sign is correct (+)
Krs_grav[3:6, jj_tra] += algebra.skew(fgravA)
# Total moments -> linearisation terms wrt to delta_Psi
Krs_grav[3:6, jj_rot] += np.dot(algebra.skew(fgravA), algebra.der_Ccrv_by_v(psi, Xcg_B))
else:
if bc_at_node != 1:
# Nodal moments due to gravity -> linearisation terms wrt to delta_psi
Kss_grav[np.ix_(jj_rot, jj_rot)] -= Tan.dot(Xcg_Bskew.dot(algebra.der_Ccrv_by_v(psi, fgravA)))
Kss_grav[np.ix_(jj_rot, jj_rot)] -= algebra.der_TanT_by_xv(psi, Xcg_Bskew.dot(Cbg.dot(fgravG)))
# Total moments -> linearisation terms wrt to delta_Ra
# Check sign (in theory it should be +=)
Krs_grav[3:6, jj_tra] += algebra.skew(fgravA)
# Total moments -> linearisation terms wrt to delta_Psi
Krs_grav[3:6, jj_rot] += np.dot(algebra.skew(fgravA), algebra.der_Ccrv_by_v(psi, Xcg_B))
# Nodal forces due to gravity -> linearisation terms wrt to delta_euler
Csr_grav[jj_tra, -4:] -= algebra.der_CquatT_by_v(tsstr.quat, fgravG) # ok
# Crr_grav[:3, -4:] -= algebra.der_CquatT_by_v(tsstr.quat, fgravG) # not ok - see below
# Nodal moments due to gravity -> linearisation terms wrt to delta_euler
Csr_grav[jj_rot, -4:] -= Tan.dot(Xcg_Bskew.dot(Cba.dot(algebra.der_CquatT_by_v(tsstr.quat, fgravG))))
# Debugging:
FgravA += fgravA
FgravG += fgravG
if self.use_euler:
# Total gravity forces acting at the A frame
Crr_grav[:3, -3:] -= algebra.der_Peuler_by_v(tsstr.euler, FgravG)
# Total moments due to gravity in A frame
Crr_grav[3:6, -3:] -= algebra.skew(Xcg_A).dot(algebra.der_Peuler_by_v(tsstr.euler, FgravG))
else:
# Total gravity forces acting at the A frame
Crr_grav[:3, -4:] -= algebra.der_CquatT_by_v(tsstr.quat, FgravG)
# Total moments due to gravity in A frame
Crr_grav[3:6, -4:] -= algebra.skew(Xcg_A).dot(algebra.der_CquatT_by_v(tsstr.quat, FgravG))
# Update matrices
self.Kstr[:flex_dof, :flex_dof] += Kss_grav
if self.Kstr[:flex_dof, :flex_dof].shape != self.Kstr.shape: # If the beam is free, update rigid terms as well
self.Cstr[-rig_dof:, -rig_dof:] += Crr_grav
self.Cstr[:-rig_dof, -rig_dof:] += Csr_grav
self.Kstr[flex_dof:, :flex_dof] += Krs_grav
# Save gravity matrices for post-processing
self.Crr_grav = Crr_grav
self.Csr_grav = Csr_grav
self.Krs_grav = Krs_grav
self.Kss_grav = Kss_grav
if self.modal:
self.Ccut = self.U.T.dot(self.Cstr.dot(self.U))
if self.settings['print_info']:
cout.cout_wrap('\tUpdated the beam C, modal C and K matrices with the terms from the gravity linearisation\n')
def linearise_applied_forces(self, tsstr=None):
r"""
Linearise externally applied follower forces given in the local ``B`` reference frame.
Updates the stiffness matrix with terms arising from this linearisation.
The linearised beam equations are expressed in the following frames of reference:
* Nodal forces: :math:`\delta \mathbf{f}_A`
* Nodal moments: :math:`\delta(T^T \mathbf{m}_B)`
* Total forces (rigid body equations): :math:`\delta \mathbf{F}_A`
* Total moments (rigid body equations): :math:`\delta \mathbf{M}_A`
Thus, when linearising externally applied follower forces projected onto the appropriate frame
.. math:: \boldsymbol{f}_A^{ext} = C^{AB}(\boldsymbol{\psi})\boldsymbol{f}^{ext}_B
the following terms appear:
.. math::
\delta\boldsymbol{f}_A^{ext} = \frac{\partial}{\partial\boldsymbol{\psi}}
\left(C^{AB}(\boldsymbol{\psi})\boldsymbol{f}^{ext}_{0,B}\right)\delta\boldsymbol{\psi} +
C^{AB}_0\delta\boldsymbol f_B^{ext}
where the :math:`\delta\boldsymbol{\psi}` is a stiffenning term that needs to be included in the stiffness
matrix. The terms will appear in the rows relating to the translational degrees of freedom and the columns that
correspond to the cartesian rotation vector.
.. math::
K_{ss}^{f,\Psi} \leftarrow -\frac{\partial}{\partial\boldsymbol{\psi}}
\left(C^{AB}(\boldsymbol{\psi})\boldsymbol{f}^{ext}_{0,B}\right)
Externally applied moments in the material frame :math:`\boldsymbol{m}_B^{ext}` result in the following
linearised expression:
.. math::
\delta(T^\top\boldsymbol{m}_B) = \frac{\partial}{\partial\boldsymbol{\psi}}\left(
T^\top(\boldsymbol{\psi})\boldsymbol{m}^{ext}_{0,B}\right)\delta\boldsymbol{\psi} +
T_0^\top \delta\boldsymbol{m}_B^{ext}
Which results in the following stiffenning term:
.. math::
K_{ss}^{m,\Psi} \leftarrow -\frac{\partial}{\partial\boldsymbol{\psi}}\left(
T^\top(\boldsymbol{\psi})\boldsymbol{m}^{ext}_{0,B}\right)
The total contribution of moments must be summed up for the rigid body equations, and include contributions
due to externally applied forces as well as moments:
.. math::
\boldsymbol{M}_A^{ext} = \sum_n \tilde{\boldsymbol{R}}_A C^{AB}(\boldsymbol{\psi}) \boldsymbol{f}_B^{ext} +
\sum C^{AB}(\boldsymbol{\psi})\boldsymbol{m}_B^{ext}
The linearisation of this term becomes
.. math::
\delta\boldsymbol{M}_A^{ext} = \sum\left(-\widetilde{C^{AB}_0 \boldsymbol{f}_{0,B}^{ext}}\delta \boldsymbol{R}_A
+ \widetilde{\boldsymbol{R}}\frac{\partial}{\partial\boldsymbol{\psi}}\left(C^{AB}\boldsymbol{f}_B\right)
\delta \boldsymbol{\psi} +
\widetilde{\boldsymbol{R}}C^{AB}\delta\boldsymbol{f}^{ext}_B\right) +
\sum\left(\frac{\partial}{\partial\boldsymbol{\psi}}\left(C^{AB}\boldsymbol{m}_{0,B}\right)
\delta\boldsymbol{\psi} +
C^AB\delta\boldsymbol{m}_B^{ext}\right)
which gives the following stiffenning terms in the rigid-flex partition of the stiffness matrix:
.. math:: K_{ss}^{M,R} \leftarrow +\sum\widetilde{C^{AB}_0 \boldsymbol{f}_{0,B}^{ext}}
.. math:: K_{ss}^{M,\Psi} \leftarrow -\sum\widetilde{\boldsymbol{R}}\frac{\partial}{\partial\boldsymbol{\psi}}
\left(C^{AB}\boldsymbol{f}_{0,B}\right)
and
.. math:: K_{ss}^{M,\Psi} \leftarrow -\sum\frac{\partial}{\partial\boldsymbol{\psi}}
\left(C^{AB}\boldsymbol{m}_{0,B}\right).
Args:
tsstr (sharpy.utils.datastructures.StructTimeStepInfo): Linearisation time step.
"""
if tsstr is None:
tsstr = self.tsstruct0
# TODO: Future feature: gains for externally applied forces (i.e. thrust inputs)
num_node = tsstr.num_node
flex_dof = 6 * sum(self.structure.vdof >= 0)
if self.use_euler:
rig_dof = 9
# This is a rotation matrix that rotates a vector from G to A
Cag = algebra.euler2rot(tsstr.euler)
Cga = Cag.T
# Projection matrices - this projects the vector in G t to A
Pag = Cga
Pga = Cag
else:
rig_dof = 10
stiff_flex = np.zeros((flex_dof, flex_dof), dtype=float) # flex-flex partition of K
stiff_rig = np.zeros((rig_dof, flex_dof), dtype=float) # rig-flex partition of K
for i_node in range(num_node):
fext_b = self.structure.steady_app_forces[i_node, :3]
mext_b = self.structure.steady_app_forces[i_node, 3:]
# retrieve element and local index
ee, node_loc = self.structure.node_master_elem[i_node, :]
psi = tsstr.psi[ee, node_loc, :]
Cab = algebra.crv2rotation(psi)
Cba = Cab.T
# Tangential operator for moments calculation
Tan = algebra.crv2tan(psi)
# Get nodal position - in A frame
Ra = tsstr.pos[i_node, :]
jj = 0 # nodal dof index
bc_at_node = self.structure.boundary_conditions[i_node] # Boundary conditions at the node
if bc_at_node == 1: # clamp (only rigid-body)
dofs_at_node = 0
jj_tra, jj_rot = [], []
elif bc_at_node == -1 or bc_at_node == 0: # (rigid+flex body)
dofs_at_node = 6
jj_tra = 6 * self.structure.vdof[i_node] + np.array([0, 1, 2], dtype=int) # Translations
jj_rot = 6 * self.structure.vdof[i_node] + np.array([3, 4, 5], dtype=int) # Rotations
else:
raise NameError('Invalid boundary condition ({}) at node {}'.format(bc_at_node, i_node))
jj += dofs_at_node
if bc_at_node != 1:
# Externally applied follower forces
stiff_flex[np.ix_(jj_tra, jj_rot)] -= algebra.der_Ccrv_by_v(psi, fext_b)
stiff_rig[:3, jj_rot] -= algebra.der_Ccrv_by_v(psi, fext_b) # Rigid body contribution
# Externally applied moments in B frame
stiff_flex[np.ix_(jj_rot, jj_rot)] -= algebra.der_TanT_by_xv(psi, mext_b)
# Total moments
# force contribution
stiff_rig[3:6, jj_tra] += algebra.skew(Cab.dot(fext_b)) # delta Ra term
stiff_rig[3:6, jj_rot] -= algebra.skew(Ra).dot(algebra.der_Ccrv_by_v(psi, fext_b)) # delta psi term
# moment contribution
stiff_rig[3:6, jj_rot] -= algebra.der_Ccrv_by_v(psi, mext_b)
if bc_at_node == 1:
# forces applied at the A-frame (clamped node) need special attention since the
# node has an associated CRV to it's master element which may not be zero.
# forces applied at this node only appear in the rigid-body equations
try:
closest_node = self.structure.connectivities[ee, node_loc + 2]
except IndexError: # node is not in the first position
try:
closest_node = self.structure.connectivities[ee, node_loc + 1]
except IndexError: # node is the midpoint
closest_node = self.structure.connectivities[ee, node_loc - 1]
# indices of the node whos CRV applies to the clamped node
jj_rot = 6 * self.structure.vdof[closest_node] + np.array([3, 4, 5], dtype=int)
stiff_rig[:3, jj_rot] -= algebra.der_Ccrv_by_v(psi, fext_b) # Rigid body contribution
# Total moments
# force contribution
stiff_rig[3:6, jj_rot] += algebra.skew(Cab.dot(fext_b)) # delta Ra term
stiff_rig[3:6, jj_rot] -= algebra.skew(Ra).dot(algebra.der_Ccrv_by_v(psi, fext_b)) # delta psi term
# moment contribution
stiff_rig[3:6, jj_rot] -= algebra.der_Ccrv_by_v(psi, mext_b)
self.Kstr[:flex_dof, :flex_dof] += stiff_flex
if self.Kstr[:flex_dof, :flex_dof].shape != self.Kstr.shape: # free flying structure
self.Kstr[-rig_dof:, :flex_dof] += stiff_rig
def assemble(self, Nmodes=None):
r"""
Assemble state-space model
Several assembly options are available:
1. Discrete-time, Newmark-:math:`\beta`:
* Modal projection onto undamped modes. It uses the modal projection such
that the generalised coordinates :math:`\eta` are transformed into modal space by
.. math:: \mathbf{\eta} = \mathbf{\Phi\,q}
where :math:`\mathbf{\Phi}` are the first ``Nmodes`` right eigenvectors.
Therefore, the equation of motion can be re-written such that the modes normalise the mass matrix to
become the identity matrix.
.. math:: \mathbf{I_{Nmodes}}\mathbf{\ddot{q}} + \mathbf{\Lambda_{Nmodes}\,q} = 0
The system is then assembled in Newmark-:math:`\beta` form as detailed in :func:`newmark_ss`
* Full size system assembly. No modifications are made to the mass, damping or stiffness matrices and the
system is directly assembled by :func:`newmark_ss`.
2. Continuous time state-space
Args:
Nmodes (int): number of modes to retain
"""
### checks
assert self.inout_coords in ['modes', 'nodes'], \
'inout_coords=%s not implemented!' % self.inout_coords
dlti = self.dlti
modal = self.modal
num_dof = self.num_dof
if Nmodes is None or Nmodes >= self.num_modes:
Nmodes = self.num_modes
if dlti: # ---------------------------------- assemble discrete time
if self.discr_method in ['zoh', 'bilinear']:
# assemble continuous-time
self.dlti = False
self.assemble(Nmodes)
# convert into discrete
self.dlti = True
self.cont2disc()
elif self.discr_method == 'newmark':
if modal: # Modal projection
if self.proj_modes == 'undamped':
Phi = self.U[:, :Nmodes]
Ass, Bss, Css, Dss = newmark_ss(
Phi.T @ self.Mstr @ Phi,
Phi.T @ self.Cstr @ Phi,
Phi.T @ self.Kstr @ Phi,
self.dt,
self.newmark_damp)
self.Kin = libss.Gain(Phi.T)
self.Kin.input_variables = LinearVector([InputVariable('forces_n',
size=self.Mstr.shape[0],
index=0)])
self.Kin.output_variables = LinearVector([OutputVariable('Q',
size=Nmodes,
index=0)])
self.Kout = libss.Gain(sc.linalg.block_diag(*[Phi, Phi]))
self.Kout.input_variables = LinearVector([InputVariable('q', size=Nmodes, index=0),
InputVariable('q_dot', size=Nmodes, index=1)])
output_variables = LinearVector([OutputVariable('eta', size=self.num_dof_flex, index=0),
OutputVariable('eta_dot', size=self.num_dof_flex, index=1)])
if not self.clamped:
output_variables.add('beta_bar', size=self.num_dof_rig, index=0.5)
output_variables.append('beta', size=self.num_dof_rig)
self.Kout.output_variables = output_variables
else:
raise NameError(
'Newmark-beta discretisation not available ' \
'for projection on damped eigenvectors')
# build state-space model
self.SSdisc = libss.StateSpace(Ass, Bss, Css, Dss, dt=self.dt)
input_variables = LinearVector([InputVariable('Q', size=Nmodes, index=0)])
output_variables = LinearVector([OutputVariable('q', size=Nmodes, index=0),
OutputVariable('q_dot', size=Nmodes, index=1)])
state_variables = output_variables.transform(output_variables,
to_type=StateVariable)
self.SSdisc.input_variables = input_variables
self.SSdisc.output_variables = output_variables
self.SSdisc.state_variables = state_variables
if self.inout_coords == 'nodes':
self.SSdisc = libss.addGain(self.SSdisc, self.Kin, 'in')
self.SSdisc = libss.addGain(self.SSdisc, self.Kout, 'out')
self.Kin, self.Kout = None, None
else: # Full system
Ass, Bss, Css, Dss = newmark_ss(
self.Mstr, self.Cstr, self.Kstr,
self.dt, self.newmark_damp)
self.Kin = None
self.Kout = None
self.SSdisc = libss.StateSpace(Ass, Bss, Css, Dss, dt=self.dt)
input_variables = LinearVector([InputVariable('forces_n',
size=self.Mstr.shape[0],
index=0)])
output_variables = LinearVector([OutputVariable('eta', size=self.num_dof_flex, index=0),
OutputVariable('eta_dot', size=self.num_dof_flex, index=1)])
if not self.clamped:
output_variables.add('beta_bar', size=self.num_dof_rig, index=0.5)
output_variables.append('beta', size=self.num_dof_rig)
self.SSdisc.output_variables = output_variables
self.SSdisc.input_variables = input_variables
self.SSdisc.state_variables = LinearVector.transform(output_variables, to_type=StateVariable)
else: