-
Notifications
You must be signed in to change notification settings - Fork 115
/
Copy pathcosserat_rod.py
1096 lines (989 loc) · 34 KB
/
cosserat_rod.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
__doc__ = """ Rod classes and implementation details """
import numpy as np
import functools
import numba
from elastica.rod import RodBase
from elastica._linalg import (
_batch_cross,
_batch_norm,
_batch_dot,
_batch_matvec,
)
from elastica._rotations import _inv_rotate
from elastica.rod.factory_function import allocate
from elastica.rod.knot_theory import KnotTheory
from elastica._calculus import (
quadrature_kernel_for_block_structure,
difference_kernel_for_block_structure,
_difference,
_average,
)
from typing import Optional
position_difference_kernel = _difference
position_average = _average
@functools.lru_cache(maxsize=1)
def _get_z_vector():
return np.array([0.0, 0.0, 1.0]).reshape(3, -1)
def _compute_sigma_kappa_for_blockstructure(memory_block):
"""
This function is a wrapper to call functions which computes shear stretch, strain and bending twist and strain.
Parameters
----------
memory_block : object
Returns
-------
"""
_compute_shear_stretch_strains(
memory_block.position_collection,
memory_block.volume,
memory_block.lengths,
memory_block.tangents,
memory_block.radius,
memory_block.rest_lengths,
memory_block.rest_voronoi_lengths,
memory_block.dilatation,
memory_block.voronoi_dilatation,
memory_block.director_collection,
memory_block.sigma,
)
# Compute bending twist strains for the block
_compute_bending_twist_strains(
memory_block.director_collection,
memory_block.rest_voronoi_lengths,
memory_block.kappa,
)
class CosseratRod(RodBase, KnotTheory):
"""
Cosserat Rod class. This is the preferred class for rods because it is derived from some
of the essential base classes.
Attributes
----------
n_elems: int
The number of elements of the rod.
position_collection: numpy.ndarray
2D (dim, n_nodes) array containing data with 'float' type.
Array containing node position vectors.
velocity_collection: numpy.ndarray
2D (dim, n_nodes) array containing data with 'float' type.
Array containing node velocity vectors.
acceleration_collection: numpy.ndarray
2D (dim, n_nodes) array containing data with 'float' type.
Array containing node acceleration vectors.
omega_collection: numpy.ndarray
2D (dim, n_elems) array containing data with 'float' type.
Array containing element angular velocity vectors.
alpha_collection: numpy.ndarray
2D (dim, n_elems) array containing data with 'float' type.
Array contining element angular acceleration vectors.
director_collection: numpy.ndarray
3D (dim, dim, n_elems) array containing data with 'float' type.
Array containing element director matrices.
rest_lengths: numpy.ndarray
1D (n_elems) array containing data with 'float' type.
Rod element lengths at rest configuration.
density: numpy.ndarray
1D (n_elems) array containing data with 'float' type.
Rod elements densities.
volume: numpy.ndarray
1D (n_elems) array containing data with 'float' type.
Rod element volumes.
mass: numpy.ndarray
1D (n_nodes) array containing data with 'float' type.
Rod node masses. Note that masses are stored on the nodes, not on elements.
mass_second_moment_of_inertia: numpy.ndarray
3D (dim, dim, n_elems) array containing data with 'float' type.
Rod element mass second moment of interia.
inv_mass_second_moment_of_inertia: numpy.ndarray
3D (dim, dim, n_elems) array containing data with 'float' type.
Rod element inverse mass moment of inertia.
rest_voronoi_lengths: numpy.ndarray
1D (n_voronoi) array containing data with 'float' type.
Rod lengths on the voronoi domain at the rest configuration.
internal_forces: numpy.ndarray
2D (dim, n_nodes) array containing data with 'float' type.
Rod node internal forces. Note that internal forces are stored on the node, not on elements.
internal_torques: numpy.ndarray
2D (dim, n_elems) array containing data with 'float' type.
Rod element internal torques.
external_forces: numpy.ndarray
2D (dim, n_nodes) array containing data with 'float' type.
External forces acting on rod nodes.
external_torques: numpy.ndarray
2D (dim, n_elems) array containing data with 'float' type.
External torques acting on rod elements.
lengths: numpy.ndarray
1D (n_elems) array containing data with 'float' type.
Rod element lengths.
tangents: numpy.ndarray
2D (dim, n_elems) array containing data with 'float' type.
Rod element tangent vectors.
radius: numpy.ndarray
1D (n_elems) array containing data with 'float' type.
Rod element radius.
dilatation: numpy.ndarray
1D (n_elems) array containing data with 'float' type.
Rod element dilatation.
voronoi_dilatation: numpy.ndarray
1D (n_voronoi) array containing data with 'float' type.
Rod dilatation on voronoi domain.
dilatation_rate: numpy.ndarray
1D (n_elems) array containing data with 'float' type.
Rod element dilatation rates.
"""
def __init__(
self,
n_elements,
position,
velocity,
omega,
acceleration,
angular_acceleration,
directors,
radius,
mass_second_moment_of_inertia,
inv_mass_second_moment_of_inertia,
shear_matrix,
bend_matrix,
density,
volume,
mass,
internal_forces,
internal_torques,
external_forces,
external_torques,
lengths,
rest_lengths,
tangents,
dilatation,
dilatation_rate,
voronoi_dilatation,
rest_voronoi_lengths,
sigma,
kappa,
rest_sigma,
rest_kappa,
internal_stress,
internal_couple,
ring_rod_flag,
):
self.n_elems = n_elements
self.position_collection = position
self.velocity_collection = velocity
self.omega_collection = omega
self.acceleration_collection = acceleration
self.alpha_collection = angular_acceleration
self.director_collection = directors
self.radius = radius
self.mass_second_moment_of_inertia = mass_second_moment_of_inertia
self.inv_mass_second_moment_of_inertia = inv_mass_second_moment_of_inertia
self.shear_matrix = shear_matrix
self.bend_matrix = bend_matrix
self.density = density
self.volume = volume
self.mass = mass
self.internal_forces = internal_forces
self.internal_torques = internal_torques
self.external_forces = external_forces
self.external_torques = external_torques
self.lengths = lengths
self.rest_lengths = rest_lengths
self.tangents = tangents
self.dilatation = dilatation
self.dilatation_rate = dilatation_rate
self.voronoi_dilatation = voronoi_dilatation
self.rest_voronoi_lengths = rest_voronoi_lengths
self.sigma = sigma
self.kappa = kappa
self.rest_sigma = rest_sigma
self.rest_kappa = rest_kappa
self.internal_stress = internal_stress
self.internal_couple = internal_couple
self.ring_rod_flag = ring_rod_flag
if not self.ring_rod_flag:
# For ring rod there are no periodic elements so below code won't run.
# We add periodic elements at the memory block construction.
# Compute shear stretch and strains.
_compute_shear_stretch_strains(
self.position_collection,
self.volume,
self.lengths,
self.tangents,
self.radius,
self.rest_lengths,
self.rest_voronoi_lengths,
self.dilatation,
self.voronoi_dilatation,
self.director_collection,
self.sigma,
)
# Compute bending twist strains
_compute_bending_twist_strains(
self.director_collection, self.rest_voronoi_lengths, self.kappa
)
@classmethod
def straight_rod(
cls,
n_elements: int,
start: np.ndarray,
direction: np.ndarray,
normal: np.ndarray,
base_length: float,
base_radius: float,
density: float,
*,
nu: Optional[float] = None,
youngs_modulus: float,
**kwargs,
):
"""
Cosserat rod constructor for straight-rod geometry.
Notes
-----
Since we expect the Cosserat Rod to simulate soft rod, Poisson's ratio is set to 0.5 by default.
It is possible to give additional argument "shear_modulus" or "poisson_ratio" to specify extra modulus.
Parameters
----------
n_elements : int
Number of element. Must be greater than 3.
Generally recommended to start with 40-50, and adjust the resolution.
start : NDArray[3, float]
Starting coordinate in 3D
direction : NDArray[3, float]
Direction of the rod in 3D
normal : NDArray[3, float]
Normal vector of the rod in 3D
base_length : float
Total length of the rod
base_radius : float
Uniform radius of the rod
density : float
Density of the rod
nu : float
Damping coefficient for Rayleigh damping
youngs_modulus : float
Young's modulus
**kwargs : dict, optional
The "position" and/or "directors" can be overrided by passing "position" and "directors" argument. Remember, the shape of the "position" is (3,n_elements+1) and the shape of the "directors" is (3,3,n_elements).
Returns
-------
CosseratRod
"""
if nu is not None:
raise ValueError(
# Remove the option to set internal nu inside, beyond v0.4.0
"The option to set damping coefficient (nu) for the rod during rod\n"
"initialisation is now deprecated. Instead, for adding damping to rods,\n"
"please derive your simulation class from the add-on Damping mixin class.\n"
"For reference see the class elastica.dissipation.AnalyticalLinearDamper(),\n"
"and for usage check examples/axial_stretching.py"
)
# Straight rod is not ring rod set flag to false
ring_rod_flag = False
(
n_elements,
position,
velocities,
omegas,
accelerations,
angular_accelerations,
directors,
radius,
mass_second_moment_of_inertia,
inv_mass_second_moment_of_inertia,
shear_matrix,
bend_matrix,
density,
volume,
mass,
internal_forces,
internal_torques,
external_forces,
external_torques,
lengths,
rest_lengths,
tangents,
dilatation,
dilatation_rate,
voronoi_dilatation,
rest_voronoi_lengths,
sigma,
kappa,
rest_sigma,
rest_kappa,
internal_stress,
internal_couple,
) = allocate(
n_elements,
direction,
normal,
base_length,
base_radius,
density,
youngs_modulus,
rod_origin_position=start,
ring_rod_flag=ring_rod_flag,
**kwargs,
)
return cls(
n_elements,
position,
velocities,
omegas,
accelerations,
angular_accelerations,
directors,
radius,
mass_second_moment_of_inertia,
inv_mass_second_moment_of_inertia,
shear_matrix,
bend_matrix,
density,
volume,
mass,
internal_forces,
internal_torques,
external_forces,
external_torques,
lengths,
rest_lengths,
tangents,
dilatation,
dilatation_rate,
voronoi_dilatation,
rest_voronoi_lengths,
sigma,
kappa,
rest_sigma,
rest_kappa,
internal_stress,
internal_couple,
ring_rod_flag,
)
@classmethod
def ring_rod(
cls,
n_elements: int,
ring_center_position: np.ndarray,
direction: np.ndarray,
normal: np.ndarray,
base_length: float,
base_radius: float,
density: float,
*,
nu: Optional[float] = None,
youngs_modulus: float,
**kwargs,
):
"""
Cosserat rod constructor for straight-rod geometry.
Notes
-----
Since we expect the Cosserat Rod to simulate soft rod, Poisson's ratio is set to 0.5 by default.
It is possible to give additional argument "shear_modulus" or "poisson_ratio" to specify extra modulus.
Parameters
----------
n_elements : int
Number of element. Must be greater than 3. Generarally recommended to start with 40-50, and adjust the resolution.
ring_center_position : NDArray[3, float]
Center coordinate for ring rod in 3D
direction : NDArray[3, float]
Direction of the rod in 3D
normal : NDArray[3, float]
Normal vector of the rod in 3D
base_length : float
Total length of the rod
base_radius : float
Uniform radius of the rod
density : float
Density of the rod
nu : float
Damping coefficient for Rayleigh damping
youngs_modulus : float
Young's modulus
**kwargs : dict, optional
The "position" and/or "directors" can be overrided by passing "position" and "directors" argument. Remember, the shape of the "position" is (3,n_elements+1) and the shape of the "directors" is (3,3,n_elements).
Returns
-------
CosseratRod
"""
if nu is not None:
raise ValueError(
# Remove the option to set internal nu inside, beyond v0.4.0
"The option to set damping coefficient (nu) for the rod during rod\n"
"initialisation is now deprecated. Instead, for adding damping to rods,\n"
"please derive your simulation class from the add-on Damping mixin class.\n"
"For reference see the class elastica.dissipation.AnalyticalLinearDamper(),\n"
"and for usage check examples/axial_stretching.py"
)
# Straight rod is not ring rod set flag to false
ring_rod_flag = True
(
n_elements,
position,
velocities,
omegas,
accelerations,
angular_accelerations,
directors,
radius,
mass_second_moment_of_inertia,
inv_mass_second_moment_of_inertia,
shear_matrix,
bend_matrix,
density_array,
volume,
mass,
internal_forces,
internal_torques,
external_forces,
external_torques,
lengths,
rest_lengths,
tangents,
dilatation,
dilatation_rate,
voronoi_dilatation,
rest_voronoi_lengths,
sigma,
kappa,
rest_sigma,
rest_kappa,
internal_stress,
internal_couple,
) = allocate(
n_elements,
direction,
normal,
base_length,
base_radius,
density,
youngs_modulus,
rod_origin_position=ring_center_position,
ring_rod_flag=ring_rod_flag,
**kwargs,
)
return cls(
n_elements,
position,
velocities,
omegas,
accelerations,
angular_accelerations,
directors,
radius,
mass_second_moment_of_inertia,
inv_mass_second_moment_of_inertia,
shear_matrix,
bend_matrix,
density_array,
volume,
mass,
internal_forces,
internal_torques,
external_forces,
external_torques,
lengths,
rest_lengths,
tangents,
dilatation,
dilatation_rate,
voronoi_dilatation,
rest_voronoi_lengths,
sigma,
kappa,
rest_sigma,
rest_kappa,
internal_stress,
internal_couple,
ring_rod_flag,
)
def compute_internal_forces_and_torques(self, time):
"""
Compute internal forces and torques. We need to compute internal forces and torques before the acceleration because
they are used in interaction. Thus in order to speed up simulation, we will compute internal forces and torques
one time and use them. Previously, we were computing internal forces and torques multiple times in interaction.
Saving internal forces and torques in a variable take some memory, but we will gain speed up.
Parameters
----------
time: float
current time
"""
_compute_internal_forces(
self.position_collection,
self.volume,
self.lengths,
self.tangents,
self.radius,
self.rest_lengths,
self.rest_voronoi_lengths,
self.dilatation,
self.voronoi_dilatation,
self.director_collection,
self.sigma,
self.rest_sigma,
self.shear_matrix,
self.internal_stress,
self.internal_forces,
self.ghost_elems_idx,
)
_compute_internal_torques(
self.position_collection,
self.velocity_collection,
self.tangents,
self.lengths,
self.rest_lengths,
self.director_collection,
self.rest_voronoi_lengths,
self.bend_matrix,
self.rest_kappa,
self.kappa,
self.voronoi_dilatation,
self.mass_second_moment_of_inertia,
self.omega_collection,
self.internal_stress,
self.internal_couple,
self.dilatation,
self.dilatation_rate,
self.internal_torques,
self.ghost_voronoi_idx,
)
# Interface to time-stepper mixins (Symplectic, Explicit), which calls this method
def update_accelerations(self, time):
"""
Updates the acceleration variables
Parameters
----------
time: float
current time
"""
_update_accelerations(
self.acceleration_collection,
self.internal_forces,
self.external_forces,
self.mass,
self.alpha_collection,
self.inv_mass_second_moment_of_inertia,
self.internal_torques,
self.external_torques,
self.dilatation,
)
def zeroed_out_external_forces_and_torques(self, time):
_zeroed_out_external_forces_and_torques(
self.external_forces, self.external_torques
)
def compute_translational_energy(self):
"""
Compute total translational energy of the rod at the instance.
"""
return (
0.5
* (
self.mass
* np.einsum(
"ij, ij-> j", self.velocity_collection, self.velocity_collection
)
).sum()
)
def compute_rotational_energy(self):
"""
Compute total rotational energy of the rod at the instance.
"""
J_omega_upon_e = (
_batch_matvec(self.mass_second_moment_of_inertia, self.omega_collection)
/ self.dilatation
)
return 0.5 * np.einsum("ik,ik->k", self.omega_collection, J_omega_upon_e).sum()
def compute_velocity_center_of_mass(self):
"""
Compute velocity center of mass of the rod at the instance.
"""
mass_times_velocity = np.einsum("j,ij->ij", self.mass, self.velocity_collection)
sum_mass_times_velocity = np.einsum("ij->i", mass_times_velocity)
return sum_mass_times_velocity / self.mass.sum()
def compute_position_center_of_mass(self):
"""
Compute position center of mass of the rod at the instance.
"""
mass_times_position = np.einsum("j,ij->ij", self.mass, self.position_collection)
sum_mass_times_position = np.einsum("ij->i", mass_times_position)
return sum_mass_times_position / self.mass.sum()
def compute_bending_energy(self):
"""
Compute total bending energy of the rod at the instance.
"""
kappa_diff = self.kappa - self.rest_kappa
bending_internal_torques = _batch_matvec(self.bend_matrix, kappa_diff)
return (
0.5
* (
_batch_dot(kappa_diff, bending_internal_torques)
* self.rest_voronoi_lengths
).sum()
)
def compute_shear_energy(self):
"""
Compute total shear energy of the rod at the instance.
"""
sigma_diff = self.sigma - self.rest_sigma
shear_internal_forces = _batch_matvec(self.shear_matrix, sigma_diff)
return (
0.5
* (_batch_dot(sigma_diff, shear_internal_forces) * self.rest_lengths).sum()
)
# Below is the numba-implementation of Cosserat Rod equations. They don't need to be visible by users.
@numba.njit(cache=True)
def _compute_geometry_from_state(
position_collection, volume, lengths, tangents, radius
):
"""
Update <length, tangents, and radius> given <position and volume>.
"""
# Compute eq (3.3) from 2018 RSOS paper
# Note : we can use the two-point difference kernel, but it needs unnecessary padding
# and hence will always be slower
position_diff = position_difference_kernel(position_collection)
# FIXME: Here 1E-14 is added to fix ghost lengths, which is 0, and causes division by zero error!
lengths[:] = _batch_norm(position_diff) + 1e-14
# _reset_scalar_ghost(lengths, ghost_elems_idx, 1.0)
for k in range(lengths.shape[0]):
tangents[0, k] = position_diff[0, k] / lengths[k]
tangents[1, k] = position_diff[1, k] / lengths[k]
tangents[2, k] = position_diff[2, k] / lengths[k]
# resize based on volume conservation
radius[k] = np.sqrt(volume[k] / lengths[k] / np.pi)
@numba.njit(cache=True)
def _compute_all_dilatations(
position_collection,
volume,
lengths,
tangents,
radius,
dilatation,
rest_lengths,
rest_voronoi_lengths,
voronoi_dilatation,
):
"""
Update <dilatation and voronoi_dilatation>
"""
_compute_geometry_from_state(position_collection, volume, lengths, tangents, radius)
# Caveat : Needs already set rest_lengths and rest voronoi domain lengths
# Put in initialization
for k in range(lengths.shape[0]):
dilatation[k] = lengths[k] / rest_lengths[k]
# Cmopute eq (3.4) from 2018 RSOS paper
# Note : we can use trapezoidal kernel, but it has padding and will be slower
voronoi_lengths = position_average(lengths)
# Cmopute eq (3.45 from 2018 RSOS paper
for k in range(voronoi_lengths.shape[0]):
voronoi_dilatation[k] = voronoi_lengths[k] / rest_voronoi_lengths[k]
@numba.njit(cache=True)
def _compute_dilatation_rate(
position_collection, velocity_collection, lengths, rest_lengths, dilatation_rate
):
"""
Update dilatation_rate given position, velocity, length, and rest_length
"""
# TODO Use the vector formula rather than separating it out
# self.lengths = l_i = |r^{i+1} - r^{i}|
r_dot_v = _batch_dot(position_collection, velocity_collection)
r_plus_one_dot_v = _batch_dot(
position_collection[..., 1:], velocity_collection[..., :-1]
)
r_dot_v_plus_one = _batch_dot(
position_collection[..., :-1], velocity_collection[..., 1:]
)
blocksize = lengths.shape[0]
for k in range(blocksize):
dilatation_rate[k] = (
(r_dot_v[k] + r_dot_v[k + 1] - r_dot_v_plus_one[k] - r_plus_one_dot_v[k])
/ lengths[k]
/ rest_lengths[k]
)
@numba.njit(cache=True)
def _compute_shear_stretch_strains(
position_collection,
volume,
lengths,
tangents,
radius,
rest_lengths,
rest_voronoi_lengths,
dilatation,
voronoi_dilatation,
director_collection,
sigma,
):
"""
Update <shear/stretch(sigma)> given <dilatation, director, and tangent>.
"""
# Quick trick : Instead of evaliation Q(et-d^3), use property that Q*d3 = (0,0,1), a constant
_compute_all_dilatations(
position_collection,
volume,
lengths,
tangents,
radius,
dilatation,
rest_lengths,
rest_voronoi_lengths,
voronoi_dilatation,
)
z_vector = np.array([0.0, 0.0, 1.0]).reshape(3, -1)
sigma[:] = dilatation * _batch_matvec(director_collection, tangents) - z_vector
@numba.njit(cache=True)
def _compute_internal_shear_stretch_stresses_from_model(
position_collection,
volume,
lengths,
tangents,
radius,
rest_lengths,
rest_voronoi_lengths,
dilatation,
voronoi_dilatation,
director_collection,
sigma,
rest_sigma,
shear_matrix,
internal_stress,
):
"""
Update <internal stress> given <shear matrix, sigma, and rest_sigma>.
Linear force functional
Operates on
S : (3,3,n) tensor and sigma (3,n)
"""
_compute_shear_stretch_strains(
position_collection,
volume,
lengths,
tangents,
radius,
rest_lengths,
rest_voronoi_lengths,
dilatation,
voronoi_dilatation,
director_collection,
sigma,
)
internal_stress[:] = _batch_matvec(shear_matrix, sigma - rest_sigma)
@numba.njit(cache=True)
def _compute_bending_twist_strains(director_collection, rest_voronoi_lengths, kappa):
"""
Update <curvature/twist (kappa)> given <director and rest_voronoi_length>.
"""
temp = _inv_rotate(director_collection)
blocksize = rest_voronoi_lengths.shape[0]
for k in range(blocksize):
kappa[0, k] = temp[0, k] / rest_voronoi_lengths[k]
kappa[1, k] = temp[1, k] / rest_voronoi_lengths[k]
kappa[2, k] = temp[2, k] / rest_voronoi_lengths[k]
@numba.njit(cache=True)
def _compute_internal_bending_twist_stresses_from_model(
director_collection,
rest_voronoi_lengths,
internal_couple,
bend_matrix,
kappa,
rest_kappa,
):
"""
Upate <internal couple> given <curvature(kappa) and bend_matrix>.
Linear force functional
Operates on
B : (3,3,n) tensor and curvature kappa (3,n)
"""
_compute_bending_twist_strains(
director_collection, rest_voronoi_lengths, kappa
) # concept : needs to compute kappa
blocksize = kappa.shape[1]
temp = np.empty((3, blocksize))
for i in range(3):
for k in range(blocksize):
temp[i, k] = kappa[i, k] - rest_kappa[i, k]
internal_couple[:] = _batch_matvec(bend_matrix, temp)
@numba.njit(cache=True)
def _compute_internal_forces(
position_collection,
volume,
lengths,
tangents,
radius,
rest_lengths,
rest_voronoi_lengths,
dilatation,
voronoi_dilatation,
director_collection,
sigma,
rest_sigma,
shear_matrix,
internal_stress,
internal_forces,
ghost_elems_idx,
):
"""
Update <internal force> given <director, internal_stress and velocity>.
"""
# Compute n_l and cache it using internal_stress
# Be careful about usage though
_compute_internal_shear_stretch_stresses_from_model(
position_collection,
volume,
lengths,
tangents,
radius,
rest_lengths,
rest_voronoi_lengths,
dilatation,
voronoi_dilatation,
director_collection,
sigma,
rest_sigma,
shear_matrix,
internal_stress,
)
# Signifies Q^T n_L / e
# Not using batch matvec as I don't want to take directors.T here
blocksize = internal_stress.shape[1]
cosserat_internal_stress = np.zeros((3, blocksize))
for i in range(3):
for j in range(3):
for k in range(blocksize):
cosserat_internal_stress[i, k] += (
director_collection[j, i, k] * internal_stress[j, k]
)
cosserat_internal_stress /= dilatation
internal_forces[:] = difference_kernel_for_block_structure(
cosserat_internal_stress, ghost_elems_idx
)
@numba.njit(cache=True)
def _compute_internal_torques(
position_collection,
velocity_collection,
tangents,
lengths,
rest_lengths,
director_collection,
rest_voronoi_lengths,
bend_matrix,
rest_kappa,
kappa,
voronoi_dilatation,
mass_second_moment_of_inertia,
omega_collection,
internal_stress,
internal_couple,
dilatation,
dilatation_rate,
internal_torques,
ghost_voronoi_idx,
):
"""
Update <internal torque>.
"""
# Compute \tau_l and cache it using internal_couple
# Be careful about usage though
_compute_internal_bending_twist_stresses_from_model(
director_collection,
rest_voronoi_lengths,
internal_couple,
bend_matrix,
kappa,
rest_kappa,
)
# Compute dilatation rate when needed, dilatation itself is done before
# in internal_stresses
_compute_dilatation_rate(
position_collection, velocity_collection, lengths, rest_lengths, dilatation_rate
)
# FIXME: change memory overload instead for the below calls!
voronoi_dilatation_inv_cube_cached = 1.0 / voronoi_dilatation ** 3
# Delta(\tau_L / \Epsilon^3)
bend_twist_couple_2D = difference_kernel_for_block_structure(
internal_couple * voronoi_dilatation_inv_cube_cached, ghost_voronoi_idx
)
# \mathcal{A}[ (\kappa x \tau_L ) * \hat{D} / \Epsilon^3 ]
bend_twist_couple_3D = quadrature_kernel_for_block_structure(