-
Notifications
You must be signed in to change notification settings - Fork 14
/
Copy pathElasticRod.cc
1562 lines (1340 loc) · 87.8 KB
/
ElasticRod.cc
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
#include "ElasticRod.hh"
#include <stdexcept>
#include <cmath>
#include <MeshFEM/GlobalBenchmark.hh>
#include "VectorOperations.hh"
#include "SparseMatrixOps.hh"
#include <MeshFEM/unused.hh>
#include "AutomaticDifferentiation.hh"
////////////////////////////////////////////////////////////////////////////////
// Geometric operations
////////////////////////////////////////////////////////////////////////////////
// Compute the unit tangents (normalized edge vectors) for the chain of edges
// connecting "pts"
template<typename Real_>
void unitTangents(const std::vector<Pt3_T<Real_>> &pts, std::vector<Vec3_T<Real_>> &result) {
const size_t ne = pts.size() - 1;
result.clear();
result.reserve(ne);
for (size_t j = 0; j < ne; ++j) {
result.emplace_back(pts[j + 1] - pts[j]);
result.back().normalize();
}
}
template<typename Real_>
std::vector<Vec3_T<Real_>> unitTangents(const std::vector<Pt3_T<Real_>> &pts) {
std::vector<Vec3_T<Real_>> result;
unitTangents(pts, result);
return result;
}
////////////////////////////////////////////////////////////////////////////////
// Elastic Rod Accessors
////////////////////////////////////////////////////////////////////////////////
template<typename Real_>
void ElasticRod_T<Real_>::setRestConfiguration(const std::vector<Pt3_T<Real_>> &points) {
if (points.size() < 3) throw std::runtime_error("Must have at least three points (two edges)");
m_restPoints = points;
const size_t nv = points.size();
const size_t ne = nv - 1;
auto unit_tangents = unitTangents(m_restPoints);
std::vector<Vec3> rest_d1;
rest_d1.reserve(ne);
// Choose first rest reference director arbitrarily.
rest_d1.emplace_back(getPerpendicularVector(unit_tangents[0]));
// Parallel transport this reference vector to the remaining rod edges
for (size_t i = 1; i < ne; ++i) {
rest_d1.emplace_back(
parallelTransportNormalized(unit_tangents[i - 1], unit_tangents[i],
rest_d1.back()));
}
// Compute the orthogonal reference director (d2) for each edge
m_restDirectors.clear();
m_restDirectors.reserve(ne);
for (size_t j = 0; j < ne; ++j) {
m_restDirectors.emplace_back(rest_d1[j],
unit_tangents[j].cross(rest_d1[j]));
}
m_restLen.clear();
m_restLen.reserve(ne);
for (size_t j = 0; j < ne; ++j)
m_restLen.push_back((m_restPoints[j + 1] - m_restPoints[j]).norm());
// Compute rest curvature (in material frame)
m_restKappa.assign(nv, Vec2::Zero());
for (size_t i = 1; i < nv - 1; ++i) {
auto kb = curvatureBinormal(unit_tangents[i - 1], unit_tangents[i]);
m_restKappa[i] = Vec2(0.5 * kb.dot(m_restDirectors[i - 1].d2 + m_restDirectors[i].d2),
-0.5 * kb.dot(m_restDirectors[i - 1].d1 + m_restDirectors[i].d1));
}
// For now, assume the rod is untwisted in its rest configuration
m_restTwist.assign(nv, 0);
m_initMinRestLen = minRestLength();
m_deformedStates.resize(1);
deformedConfiguration().initialize(*this);
}
template<typename Real_>
void ElasticRod_T<Real_>::setDeformedConfiguration(const std::vector<Pt3_T<Real_>> &points, const std::vector<Real_> &thetas) {
if (points.size() != numVertices()) throw std::logic_error("Invalid number of points");
if (thetas.size() != numEdges()) throw std::logic_error("Invalid number of material frame rotations");
deformedConfiguration().update(points, thetas);
}
template<typename Real_>
VecX_T<Real_> ElasticRod_T<Real_>::getDoFs() const {
VecX dofs(numDoF());
const size_t nv = numVertices(), ne = numEdges();
const auto &points = deformedConfiguration().points();
const auto &thetas = deformedConfiguration().thetas();
for (size_t i = 0; i < nv; ++i) dofs.template segment<3>(3 * i) = points[i];
for (size_t j = 0; j < ne; ++j) dofs[3 * nv + j] = thetas[j];
return dofs;
}
template<typename Real_>
void ElasticRod_T<Real_>::setDoFs(const Eigen::Ref<const VecX_T<Real_>> &dofs) {
if (size_t(dofs.size()) != numDoF()) throw std::runtime_error("DoF vector has incorrect length.");
const size_t nv = numVertices(), ne = numEdges();
std::vector<Vec3> points(nv);
std::vector<Real_> thetas(ne);
for (size_t i = 0; i < nv; ++i) points[i] = dofs.template segment<3>(3 * i);
for (size_t j = 0; j < ne; ++j) thetas[j] = dofs[3 * nv + j];
deformedConfiguration().update(points, thetas);
}
template<typename Real_>
void ElasticRod_T<Real_>::DeformedState::initialize(const ElasticRod_T &rod) {
// Initialize source reference directors and tangents since they'll be
// needed for parallel transport in the update method
sourceReferenceDirectors = rod.m_restDirectors;
unitTangents(rod.m_restPoints, sourceTangent);
sourceTheta.assign(rod.numEdges(), 0);
sourceReferenceTwist.assign(rod.numVertices(), 0);
update(rod.m_restPoints, sourceTheta);
}
// Constructor for cached deformed quantities.
template<typename Real_>
void ElasticRod_T<Real_>::DeformedState::update(const std::vector<Pt3_T<Real_>> &points, const std::vector<Real_> &thetas) {
const size_t nv = points.size(),
ne = thetas.size();
m_point = points;
m_theta = thetas;
// Compute edge lengths and new unit tangents, parallel transporting the
// material frame to the new tangent.
len.resize(ne);
tangent.resize(ne);
referenceDirectors.clear(); referenceDirectors.reserve(ne);
for (size_t j = 0; j < ne; ++j) {
tangent[j] = (points[j + 1] - points[j]);
len[j] = tangent[j].norm();
tangent[j] /= len[j];
referenceDirectors.emplace_back(parallelTransportNormalized(sourceTangent[j], tangent[j], sourceReferenceDirectors[j].d1),
parallelTransportNormalized(sourceTangent[j], tangent[j], sourceReferenceDirectors[j].d2));
}
// Compute twist of the transported reference directors from one edge to the next
referenceTwist.resize(nv);
referenceTwist.front() = referenceTwist.back() = 0;
for (size_t i = 1; i < nv - 1; ++i) {
// Finite rotation angle needed to take the parallel transported copy
// of the previous edge's reference director to the current edge's
// reference director.
Vec3 prevDirectorTransported = parallelTransportNormalized(tangent[i - 1], tangent[i], referenceDirectors[i - 1].d1);
referenceTwist[i] = angle(tangent[i], prevDirectorTransported, referenceDirectors[i].d1);
// Temporal coherence: to avoid jumps in the material frame twist of 2 pi,
// choose the 2 Pi offset to minimize change from source reference twist.
// (so the new reference twist is always in the interval [source - pi, source + pi]
Real_ diff = (sourceReferenceTwist[i] - referenceTwist[i]) / (2 * M_PI);
referenceTwist[i] += 2 * M_PI * std::round(stripAutoDiff(diff)); // TODO: strip autodiff?
}
// Compute material frame using reference directors and thetas.
// Also update the "source material frame" based on the new thetas.
materialFrame.clear(), materialFrame.reserve(ne);
sourceMaterialFrame.clear(), sourceMaterialFrame.reserve(ne);
for (size_t j = 0; j < ne; ++j) {
Real_ cosTheta = cos(thetas[j]),
sinTheta = sin(thetas[j]);
materialFrame.emplace_back(cosTheta * referenceDirectors[j].d1 + sinTheta * referenceDirectors[j].d2,
-sinTheta * referenceDirectors[j].d1 + cosTheta * referenceDirectors[j].d2);
sourceMaterialFrame.emplace_back(cosTheta * sourceReferenceDirectors[j].d1 + sinTheta * sourceReferenceDirectors[j].d2,
-sinTheta * sourceReferenceDirectors[j].d1 + cosTheta * sourceReferenceDirectors[j].d2);
}
// Compute curvature binormals
kb.resize(nv);
kb.front() = kb.back() = Vec3::Zero();
for (size_t i = 1; i < nv - 1; ++i)
kb[i] = curvatureBinormal(tangent[i - 1], tangent[i]);
// Compute curvature normal in material coordinate system.
kappa.resize(nv);
per_corner_kappa.resize(nv);
kappa.front() = kappa.back() = Vec2::Zero();
for (size_t i = 1; i < nv - 1; ++i) {
per_corner_kappa[i](0, 0) = kb[i].dot(materialFrame[i - 1].d2);
per_corner_kappa[i](0, 1) = kb[i].dot(materialFrame[i ].d2);
per_corner_kappa[i](1, 0) = -kb[i].dot(materialFrame[i - 1].d1);
per_corner_kappa[i](1, 1) = -kb[i].dot(materialFrame[i ].d1);
kappa[i] = 0.5 * per_corner_kappa[i].rowwise().sum();
}
}
template<typename Real_>
void ElasticRod_T<Real_>::DeformedState::setReferenceTwist(Real_ newTwist) {
// Compute twist of the transported reference directors from one edge to the next
const size_t nv = m_point.size();
Real_ referenceRotation = 0;
for (size_t i = 1; i < nv - 1; ++i) {
Vec3 prevD1Transported = parallelTransportNormalized(tangent[i - 1], tangent[i], referenceDirectors[i - 1].d1),
prevD2Transported = parallelTransportNormalized(tangent[i - 1], tangent[i], referenceDirectors[i - 1].d2);
referenceDirectors[i].d1 = rotatedVectorAngle(tangent[i], newTwist, prevD1Transported);
referenceDirectors[i].d2 = rotatedVectorAngle(tangent[i], newTwist, prevD2Transported);
// This modification should preserve the twisting strain, meaning:
// theta(i) - theta(i - 1) + newTwist == thetaOld(i) - thetaOld(i - 1) + referenceTwistOld
// theta(i) = thetaOld(i) - thetaOld(i - 1) + theta(i - 1) + referenceTwistOld - newTwist
// ==> thetaChange = prevThetaChange + referenceTwistOld - newTwist
// Subtract off the accumulated rotation of reference frame i to preserve the material frame.
referenceRotation += newTwist - referenceTwist[i];
m_theta[i] -= referenceRotation;
referenceTwist[i] = newTwist;
}
}
// Determine the material frame vector D2 for edge "j" that corresponds to
// angle "theta" after the edge has been transformed to have the new edge vector eNew
// (i.e., after the reference directors have been updated with parallel transport).
template<typename Real_>
Vec3_T<Real_> ElasticRod_T<Real_>::materialFrameD2ForTheta(Real_ theta, const Vec3_T<Real_> &eNew, size_t j) const {
// Determine parallel-transported directors (from source tangent vector to eNew)
const auto &dc = deformedConfiguration();
Vec3 refd1 = parallelTransportNormalized(dc.sourceTangent[j], eNew.normalized(), dc.sourceReferenceDirectors[j].d1);
Vec3 refd2 = parallelTransportNormalized(dc.sourceTangent[j], eNew.normalized(), dc.sourceReferenceDirectors[j].d2);
// std::cout << "sourceTangent: " << dc.sourceTangent[j].transpose() << std::endl;
// std::cout << "refd1: " << refd1.transpose() << std::endl;
// std::cout << "refd2: " << refd2.transpose() << std::endl;
Real_ cosTheta = cos(theta),
sinTheta = sin(theta);
return cosTheta * refd2 - sinTheta * refd1;
}
// Determine frame rotation angle "theta" for edge "j" from material frame vector "d2".
// (This is the rotation that takes the first reference director to "d2".
// We remove the integer-multiple-of-2Pi ambiguity in one of two ways:
// if spatialCoherence == true, we chose the angle that minimizes twisting energy for one of the incident vertices.
// if spatialCoherence == false, we opt for temporal coherence, minimizing the change in angle from the source configuration.
// To remove the integer-multiple-of-2Pi ambiguity, we choose the angle that minimizes twisting energy for one
// of the incident vertices).
template<typename Real_>
Real_ ElasticRod_T<Real_>::thetaForMaterialFrameD2(Vec3_T<Real_> d2, const Vec3_T<Real_> &eNew, size_t j, bool spatialCoherence) const {
const auto &dc = deformedConfiguration();
Real_ parallelComp = d2.dot(eNew);
if (std::abs(stripAutoDiff(parallelComp)) > 1e-8) {
std::cerr << "WARNING: non-perpendicular normal" << std::endl;
d2 -= (parallelComp / eNew.squaredNorm()) * eNew;
d2.normalize();
}
// Determine parallel-transported directors (from source tangent vector to eNew)
Vec3 tNew = eNew.normalized();
Vec3 refd1 = parallelTransportNormalized(dc.sourceTangent[j], tNew, dc.sourceReferenceDirectors[j].d1);
Vec3 refd2 = parallelTransportNormalized(dc.sourceTangent[j], tNew, dc.sourceReferenceDirectors[j].d2);
Real_ cosTheta = d2.dot(refd2);
Real_ sinTheta = -d2.dot(refd1);
Real_ theta = atan2(sinTheta, cosTheta);
if (spatialCoherence) {
// Choose 2 Pi offset for theta to minimize twisting energy
// Note: dc.referenceTwist[j] was computed for the old reference directors, not the new ones parallel-transported
// onto eNew. However, this shouldn't be an issue as long as eNew is not too different from the old tangent.
Real_ twistDeviation;
if (j > 0) twistDeviation = theta - dc.theta(j - 1) + dc.referenceTwist[j] - m_restTwist[j];
else twistDeviation = theta - dc.theta( 1) - dc.referenceTwist[1] + m_restTwist[1];
// This probably could be implemented with an fmod...
while (twistDeviation > M_PI) { theta -= 2 * M_PI; twistDeviation -= 2 * M_PI; }
while (twistDeviation < -M_PI) { theta += 2 * M_PI; twistDeviation += 2 * M_PI; }
}
else {
// Temporal coherence: choose 2 Pi offset to minimize change from previous theta.
Real_ diff = (dc.sourceTheta[j] - theta) / (2 * M_PI);
theta += 2 * M_PI * std::round(stripAutoDiff(diff));
}
if (std::isnan(stripAutoDiff(theta))) {
std::cerr << "NaN theta encountered" << std::endl;
std::cerr << "\td2: " << d2.transpose() << std::endl;
std::cerr << "\trefd1: " << refd1.transpose() << std::endl;
std::cerr << "\trefd2: " << refd2.transpose() << std::endl;
std::cerr << "\ttNew: " << tNew.transpose() << std::endl;
std::cerr << "\tsourceTangent: " << dc.sourceTangent[j].transpose() << std::endl;
std::cerr << "\tsourceReferenceDirectors: " << dc.sourceReferenceDirectors[j].d1.transpose() << ", " << dc.sourceReferenceDirectors[j].d1.transpose() << std::endl;
std::cerr << "\tsourceTheta: " << dc.sourceTheta[j] << std::endl;
}
return theta;
}
////////////////////////////////////////////////////////////////////////////////
// Elastic energy
////////////////////////////////////////////////////////////////////////////////
template<typename Real_>
Real_ ElasticRod_T<Real_>::energyStretch() const {
const size_t ne = numEdges();
Real_ result = 0;
for (size_t j = 0; j < ne; ++j) {
Real_ strainj = deformedConfiguration().len[j] / m_restLen[j] - 1.0;
result += density(j) * m_stretchingStiffness[j] * strainj * strainj * m_restLen[j];
}
return 0.5 * result;
}
template<typename Real_>
Real_ ElasticRod_T<Real_>::energyBend() const {
const size_t nv = numVertices();
const auto &dc = deformedConfiguration();
Real_ result = 0;
if (m_bendingEnergyType == BendingEnergyType::Bergou2010) {
for (size_t i = 1; i < nv - 1; ++i) {
Real_ libar2 = m_restLen[i - 1] + m_restLen[i];
Vec2 kappaDiff = dc.kappa[i] - m_restKappa[i];
Real_ contrib = m_bendingStiffness[i].lambda_1 * kappaDiff[0] * kappaDiff[0]
+ m_bendingStiffness[i].lambda_2 * kappaDiff[1] * kappaDiff[1];
result += contrib / libar2;
}
}
else if (m_bendingEnergyType == BendingEnergyType::Bergou2008) {
for (size_t i = 1; i < nv - 1; ++i) {
Real_ inv_libar2 = 1.0 / (m_restLen[i - 1] + m_restLen[i]);
for (size_t adj_edge = 0; adj_edge < 2; ++adj_edge) {
Vec2 kappaDiff = dc.per_corner_kappa[i].col(adj_edge) - m_restKappa[i];
Real_ contrib = m_bendingStiffness[i].lambda_1 * kappaDiff[0] * kappaDiff[0]
+ m_bendingStiffness[i].lambda_2 * kappaDiff[1] * kappaDiff[1];
result += contrib * m_restLen[(i - 1) + adj_edge] * inv_libar2 * inv_libar2;
}
}
}
else { assert(false); }
return result;
}
template<typename Real_>
Real_ ElasticRod_T<Real_>::energyTwist() const {
const size_t nv = numVertices();
const auto &dc = deformedConfiguration();
Real_ result = 0;
for (size_t i = 1; i < nv - 1; ++i) {
Real_ libar2 = m_restLen[i - 1] + m_restLen[i];
Real_ twistDeviation = dc.theta(i) - dc.theta(i - 1) + dc.referenceTwist[i] - m_restTwist[i];
result += (m_twistingStiffness[i] / libar2) * twistDeviation * twistDeviation;
}
return result;
}
template<typename Real_>
Real_ ElasticRod_T<Real_>::energy() const { return energyStretch() + energyBend() + energyTwist(); }
// Per-vertex bending energy for visualization
template<typename Real_>
VecX_T<Real_> ElasticRod_T<Real_>::energyBendPerVertex() const {
const size_t nv = numVertices();
const auto &dc = deformedConfiguration();
VecX_T<Real_> result(nv);
result[0] = result[nv - 1] = 0.0;
if (m_bendingEnergyType == BendingEnergyType::Bergou2010) {
for (size_t i = 1; i < nv - 1; ++i) {
Real_ libar2 = m_restLen[i - 1] + m_restLen[i];
Vec2 kappaDiff = dc.kappa[i] - m_restKappa[i];
Real_ contrib = m_bendingStiffness[i].lambda_1 * kappaDiff[0] * kappaDiff[0]
+ m_bendingStiffness[i].lambda_2 * kappaDiff[1] * kappaDiff[1];
result[i] = contrib / libar2;
}
}
else if (m_bendingEnergyType == BendingEnergyType::Bergou2008) {
for (size_t i = 1; i < nv - 1; ++i) {
Real_ inv_libar2 = 1.0 / (m_restLen[i - 1] + m_restLen[i]);
for (size_t adj_edge = 0; adj_edge < 2; ++adj_edge) {
Vec2 kappaDiff = dc.per_corner_kappa[i].col(adj_edge) - m_restKappa[i];
Real_ contrib = m_bendingStiffness[i].lambda_1 * kappaDiff[0] * kappaDiff[0]
+ m_bendingStiffness[i].lambda_2 * kappaDiff[1] * kappaDiff[1];
result[i] = contrib * m_restLen[(i - 1) + adj_edge] * inv_libar2 * inv_libar2;
}
}
}
else { assert(false); }
return result;
}
////////////////////////////////////////////////////////////////////////////////
// Elastic energy gradients
////////////////////////////////////////////////////////////////////////////////
template<typename Real_>
template<typename StencilMask>
typename ElasticRod_T<Real_>::Gradient ElasticRod_T<Real_>::gradEnergyStretch(bool variableRestLen, bool restlenOnly, const StencilMask &sm) const {
// d 0.5 sum_j ks^j (l^j / rl^j - 1)^2 rl^j
// = sum_j ks^j (l^j / rl^j - 1) * dl^j
// d l^j = +/- tangent if x is +/- endpoint
const size_t ne = numEdges();
Gradient result(*this, variableRestLen);
// Stretching energy independent of twist: gradTheta = 0
const auto &dc = deformedConfiguration();
for (size_t j = 0; j < ne; ++j) {
if (!sm.includeEdgeStencil(ne, j)) continue;
Real_ fracLen = dc.len[j] / m_restLen[j];
Real_ coeff = density(j) * m_stretchingStiffness[j] * (fracLen - 1.0);
if (!restlenOnly) {
result.gradPos(j ) -= coeff * dc.tangent[j];
result.gradPos(j + 1) += coeff * dc.tangent[j];
}
if (variableRestLen)
result.gradRestLen(j) = density(j) * m_stretchingStiffness[j] * 0.5 * (1.0 - fracLen * fracLen);
}
return result;
}
// grad 0.5 sum_i 1/libar_i * (B11_i * (kappa1_i - kappabar1_i)^2 + B22_i * (kappa2_i - kappabar2_i)^2)
template<typename Real_>
template<class StencilMask>
typename ElasticRod_T<Real_>::Gradient ElasticRod_T<Real_>::gradEnergyBend(bool updatedSource, bool variableRestLen, bool restlenOnly, const StencilMask &sm) const {
const size_t nv = numVertices();
Gradient result(*this, variableRestLen);
using M32d = Eigen::Matrix<Real_, 3, 2>;
const auto &dc = deformedConfiguration();
// Compute gradient of each vertex's contribution to the bending energy.
for (size_t i = 1; i < nv - 1; ++i) {
if (!sm.includeVtxStencil(nv, i)) continue;
Real_ inv_2libar = 1.0 / (m_restLen[i - 1] + m_restLen[i]);
const auto &ti = dc.tangent[i],
&tim1 = dc.tangent[i - 1],
&kb = dc.kb[i];
const Real_ inv_chi = 1.0 / (1.0 + tim1.dot(ti)); // 1 / chi in paper
Vec3 tilde_t = inv_chi * (ti + tim1);
std::array<Real_, 2> inv_len{{1.0 / dc.len[i - 1],
1.0 / dc.len[i ]}};
M32d dE_de(M32d::Zero());
for (size_t adj_edge = 0; adj_edge < 2; ++adj_edge) { // 0 ==> i - 1, 1 ==> i
const size_t j = (i - 1) + adj_edge;
// Derivative of the bending energy with respect to (kappa_k)_i^j
std::array<Real_, 2> dE_dkappa_k_j;
if (m_bendingEnergyType == BendingEnergyType::Bergou2010) {
const Vec2 kappaDiff = dc.kappa[i] - m_restKappa[i];
if (variableRestLen) {
Real_ contrib = m_bendingStiffness[i].lambda_1 * kappaDiff[0] * kappaDiff[0]
+ m_bendingStiffness[i].lambda_2 * kappaDiff[1] * kappaDiff[1];
result.gradRestLen(j) -= inv_2libar * inv_2libar * contrib;
if (restlenOnly) continue;
}
dE_dkappa_k_j = {{inv_2libar * m_bendingStiffness[i].lambda_1 * kappaDiff[0],
inv_2libar * m_bendingStiffness[i].lambda_2 * kappaDiff[1]}};
}
else if (m_bendingEnergyType == BendingEnergyType::Bergou2008) {
const Vec2 kappaDiff = dc.per_corner_kappa[i].col(adj_edge) - m_restKappa[i];
if (variableRestLen) {
Real_ contrib = m_bendingStiffness[i].lambda_1 * kappaDiff[0] * kappaDiff[0]
+ m_bendingStiffness[i].lambda_2 * kappaDiff[1] * kappaDiff[1];
const size_t jother = i - adj_edge; // 0 ==> i, 1 ==> i - 1
result.gradRestLen(j ) += (inv_2libar * inv_2libar * inv_2libar) * (m_restLen[jother] - m_restLen[j]) * contrib;
result.gradRestLen(jother) -= (inv_2libar * inv_2libar * inv_2libar) * ( 2 * m_restLen[j]) * contrib;
if (restlenOnly) continue;
}
dE_dkappa_k_j = {{2.0 * m_restLen[j] * inv_2libar * inv_2libar * m_bendingStiffness[i].lambda_1 * kappaDiff[0],
2.0 * m_restLen[j] * inv_2libar * inv_2libar * m_bendingStiffness[i].lambda_2 * kappaDiff[1]}};
}
else { assert(false); }
// Accumulate energy dependence through (kappa_k)_i^j
// Compute material frame angle (theta) dependence
result.gradTheta(j) += dE_dkappa_k_j[0] * dc.per_corner_kappa[i](1, adj_edge) - dE_dkappa_k_j[1] * dc.per_corner_kappa[i](0, adj_edge);
for (size_t k = 0; k < 2; ++k) {
// Compute centerline position dependence
// First, compute variation of kappa_k^j with respect to a perturbation of the edge tangents.
const size_t kother = (k + 1) % 2;
Real_ sign = (k == 0) ? 1 : -1; // Infinitesimal transport kappa_2^j term is just like kappa_1, except d2 is replaced with -d1.
M32d d_kappa_k_j_de;
d_kappa_k_j_de.col(0) = inv_len[0] * (( 2 * sign * inv_chi) * ti.cross(dc.materialFrame[j].get(kother)) - dc.per_corner_kappa[i].col(adj_edge)[k] * tilde_t);
d_kappa_k_j_de.col(1) = inv_len[1] * ((-2 * sign * inv_chi) * tim1.cross(dc.materialFrame[j].get(kother)) - dc.per_corner_kappa[i].col(adj_edge)[k] * tilde_t);
if (!updatedSource) {
const auto &ts = dc.sourceTangent[j],
&t = dc.tangent[j];
const auto &ds = dc.sourceMaterialFrame[j].get(k);
Vec3 kb_cross_ts = kb.cross(ts);
Real_ inv_chi_hat = 1.0 / (1.0 + ts.dot(t));
Real_ ds_dot_t = ds.dot(t), kb_cross_ts_dot_t = t.dot(kb_cross_ts);
Vec3 finite_xport_contrib =
inv_chi_hat * (ds_dot_t * kb_cross_ts + ds * kb_cross_ts_dot_t)
- (inv_chi_hat * inv_chi_hat * ds_dot_t * kb_cross_ts_dot_t) * ts
+ ds.cross(kb);
// We only have a finite transport term for the derivative with respect to edge "j"
d_kappa_k_j_de.col(adj_edge) += inv_len[adj_edge] * (finite_xport_contrib - t * t.dot(finite_xport_contrib));
}
dE_de += dE_dkappa_k_j[k] * d_kappa_k_j_de;
}
}
// Second, compute variation of bending energy with respect to the centerline positions
result.gradPos(i - 1) -= dE_de.col(0);
result.gradPos(i ) += dE_de.col(0) - dE_de.col(1);
result.gradPos(i + 1) += dE_de.col(1);
}
return result;
}
// grad 0.5 sum_i 1/libar_i * beta_i (m_i - mbar_i)^2
template<typename Real_>
template<class StencilMask>
typename ElasticRod_T<Real_>::Gradient ElasticRod_T<Real_>::gradEnergyTwist(bool updatedSource, bool variableRestLen, bool restlenOnly, const StencilMask &sm) const {
const size_t nv = numVertices();
Gradient result(*this, variableRestLen);
const auto &dc = deformedConfiguration();
// Compute gradient of each vertex's contribution to the twisting energy.
for (size_t i = 1; i < nv - 1; ++i) {
if (!sm.includeVtxStencil(nv, i)) continue;
const Real_ inv_libar = 2.0 / (m_restLen[i - 1] + m_restLen[i]);
const Real_ inv_len_i = 1.0 / dc.len[i ],
inv_len_im1 = 1.0 / dc.len[i - 1];
const Real_ deltaTwist = (dc.theta(i) - dc.theta(i - 1) + dc.referenceTwist[i] - m_restTwist[i]);
if (variableRestLen) {
Real_ dE_dljbar = -0.25 * m_twistingStiffness[i] * inv_libar * inv_libar * deltaTwist * deltaTwist;
result.gradRestLen(i - 1) += dE_dljbar;
result.gradRestLen(i ) += dE_dljbar;
if (restlenOnly) continue;
}
const Real_ dE_dm = inv_libar * m_twistingStiffness[i] * deltaTwist;
// std::cout << "referenceTwist: " << dc.referenceTwist[i] << std::endl;
// std::cout << "m_restTwist: " << m_restTwist[i] << std::endl;
// std::cout << "dE_dm: " << dE_dm << std::endl;
// Compute material frame angle (theta) dependence
result.gradTheta(i - 1) -= dE_dm;
result.gradTheta(i ) += dE_dm;
// Compute centerline position dependence
Vec3 d_m_de_i = 0.5 * inv_len_i * dc.kb[i],
d_m_de_im1 = 0.5 * inv_len_im1 * dc.kb[i];
// If the source reference frame hasn't been updated to the current
// reference frame, we need additional terms in the gradient
// (that are not mentioned in Bergou2010's appendix)
if (!updatedSource) {
const auto &ti = dc.tangent[i ],
&tim1 = dc.tangent[i - 1],
&tsi = dc.sourceTangent[i ],
&tsim1 = dc.sourceTangent[i - 1],
// &d1i = dc.materialFrame[i ].d1,
&d2i = dc.materialFrame[i ].d2,
// &d1im1 = dc.materialFrame[i - 1].d1,
&d2im1 = dc.materialFrame[i - 1].d2,
&ds1i = dc.sourceMaterialFrame[i ].d1,
&ds1im1 = dc.sourceMaterialFrame[i - 1].d1;
{
Real_ inv_chi_hat = 1.0 / (1.0 + tsim1.dot(tim1));
Real_ ds1im1_dot_tim1 = ds1im1.dot(tim1),
d2im1_dot_tsim1 = d2im1.dot(tsim1);
// Vec3 d_m_de_im1_contrib = inv_chi_hat * (ds1im1_dot_tim1 * d1im1.cross(tsim1) + d2im1_dot_tsim1 * ds1im1)
// - (inv_chi_hat * inv_chi_hat * ds1im1_dot_tim1 * d2im1_dot_tsim1) * tsim1
// + ds1im1.cross(d1im1);
Vec3 d_m_de_im1_contrib = inv_chi_hat * (ds1im1_dot_tim1 * d2im1 + d2im1_dot_tsim1 * ds1im1
- (inv_chi_hat * ds1im1_dot_tim1 * d2im1_dot_tsim1) * tsim1);
d_m_de_im1 += inv_len_im1 * (d_m_de_im1_contrib - tim1 * tim1.dot(d_m_de_im1_contrib));
}
{
Real_ inv_chi_hat = 1.0 / (1.0 + tsi.dot(ti));
Real_ ds1i_dot_ti = ds1i.dot(ti),
d2i_dot_tsi = d2i.dot(tsi);
// Vec3 d_m_de_i_contrib = inv_chi_hat * (ds1i_dot_ti * d1i.cross(tsi) + d2i_dot_tsi * ds1i)
// - (inv_chi_hat * inv_chi_hat * ds1i_dot_ti * d2i_dot_tsi) * tsi
// + ds1i.cross(d1i);
Vec3 d_m_de_i_contrib = inv_chi_hat * (ds1i_dot_ti * d2i + d2i_dot_tsi * ds1i
- (inv_chi_hat * ds1i_dot_ti * d2i_dot_tsi) * tsi);
d_m_de_i -= inv_len_i * (d_m_de_i_contrib - ti * ti.dot(d_m_de_i_contrib));
}
}
result.gradPos(i - 1) -= dE_dm * d_m_de_im1;
result.gradPos(i ) += dE_dm * (d_m_de_im1 - d_m_de_i);
result.gradPos(i + 1) += dE_dm * d_m_de_i;
}
return result;
}
template<typename Real_>
template<class StencilMask>
typename ElasticRod_T<Real_>::Gradient ElasticRod_T<Real_>::gradEnergy(bool updatedSource, bool variableRestLen, bool restlenOnly, const StencilMask &sm) const {
auto result = gradEnergyStretch( variableRestLen, restlenOnly, sm);
result += gradEnergyBend(updatedSource, variableRestLen, restlenOnly, sm);
result += gradEnergyTwist(updatedSource, variableRestLen, restlenOnly, sm);
return result;
}
////////////////////////////////////////////////////////////////////////////////
// Elastic energy Hessians
////////////////////////////////////////////////////////////////////////////////
// The number of non-zeros in the Hessian's sparsity pattern (a tight
// upper bound for the number of non-zeros in the upper triangle for any
// configuration).
template<typename Real_>
size_t ElasticRod_T<Real_>::hessianNNZ(bool variableRestLen) const {
const size_t nv = numVertices(), ne = numEdges();
if (nv < 3) throw std::runtime_error("Too few vertices");
size_t diag = 6 * nv + ne; // Size of diagonal blocks in x-x and theta-theta parts
size_t odiagxx = 9 * (2 * (nv - 2) + 1); // Size of off-diagonal blocks in the x-x part (the last vertex has no off-diag block, second-to-last has one, all the rest have 2)
size_t odiagxt = 3 * // x-theta part consists of 3x1 blocks.
(2 * 2 // The two endpoints always contribute 2 blocks each (for the two nearest edges).
+ ((nv >= 4) ? (3 * 2 + 4 * (nv - 4)) // If there are at least 3 edges (nv >= 4), then the two endpoint-adjacent vertices contribute 3 blocks each, and the rest contribute 4.
: 2)); // Otherwise, the middle vertex contributes 2 blocks (for the two edges)
size_t odiagtt = ne - 1; // theta-theta off diagonal consists of a single band.
size_t result = diag + odiagxx + odiagxt + odiagtt;
if (variableRestLen) {
result += odiagxt; // x-restlen part is identical in size to x-theta part
result += 3 * ne - 2; // theta-restlen block is tri-diagonal (and we take the whole thing)
result += 2 * ne - 1; // restlen-restlen part is tridiagonal (and we take the upper tri)
}
return result;
}
template<typename Real_>
typename ElasticRod_T<Real_>::CSCMat ElasticRod_T<Real_>::hessianSparsityPattern(bool variableRestLen, Real_ val) const {
CSCMat result;
result.symmetry_mode = CSCMat::SymmetryMode::UPPER_TRIANGLE;
const size_t nnz = hessianNNZ(variableRestLen);
const size_t ndof = variableRestLen ? numExtendedDoF() : numDoF();
const size_t nv = numVertices(),
ne = numEdges();
result.m = result.n = ndof;
result.nz = nnz;
result.Ap.reserve(ndof + 1);
result.Ai.reserve(nnz);
result.Ax.assign(nnz, val);
auto &Ap = result.Ap;
auto &Ai = result.Ai;
// Append the indices [start, end) to Ai
auto addIdxRange = [&](const size_t start, const size_t end) {
assert((start <= ndof) && (end <= ndof));
const size_t len = end - start, oldSize = Ai.size();
Ai.resize(oldSize + len);
for (size_t i = 0; i < len; ++i)
Ai[oldSize + i] = start + i;
};
// Build sparsity pattern directly in compressed column format
result.Ap.push_back(0);
// Loop over the columns of the Hessian by looping over all centerline pos, thetas, rest lengths in order
// The vertex-associated columns of the Hessian's upper triangle hold only the x-x terms.
for (size_t vi = 0; vi < nv; ++vi) {
for (size_t c = 0; c < 3; ++c) {
const size_t j = 3 * vi + c;
// Column for x_vi has contributions from x_{vi - 2}, x_{vi - 1}, x_vi
const size_t vi_m2 = vi - std::min<size_t>(2, vi);
addIdxRange(3 * vi_m2, j + 1);
Ap.push_back(Ai.size()); // End index for this column, start of next
}
}
// The columnns associated with thetas contain the x-theta and theta-theta blocks
for (size_t ei = 0; ei < ne; ++ei) {
const size_t j = 3 * nv + ei;
// Column for theta^ei has contributions from x_{ei - 1}, x_ei, x_{ei + 1}, x_{ei + 2}
const size_t ei_m1 = ei - std::min<size_t>(1, ei),
ei_p2 = std::min<size_t>(ei + 2, nv - 1);
addIdxRange(3 * ei_m1, 3 * (ei_p2 + 1));
// Column for theta^ei has contributions from th^{ei - 1}, th^ei
addIdxRange(3 * nv + ei_m1, j + 1);
Ap.push_back(Ai.size()); // End index for this column, start of next
}
if (variableRestLen) {
// The columnns associated with the rest lengths contain the x-rl and theta-rl and rl-rl blocks
for (size_t ei = 0; ei < ne; ++ei) {
const size_t j = 3 * nv + ne + ei;
// Column for rl^ei has contributions from x_{ei - 1}, x_ei, x_{ei + 1}, x_{ei + 2}
const size_t ei_m1 = ei - std::min<size_t>(1, ei),
ei_p2 = std::min<size_t>(ei + 2, nv - 1);
addIdxRange(3 * ei_m1, 3 * (ei_p2 + 1));
// Column for rl^ei has contributions from th^{ei - 1}, th^ei, th^{ei + 1}
addIdxRange(3 * nv + ei_m1, 3 * nv + std::min<size_t>(ei + 1, ne - 1) + 1);
// Column for rl^ei has contributions from rl^{ei - 1}, rl^ei
addIdxRange(3 * nv + ne + ei_m1, j + 1);
Ap.push_back(Ai.size()); // End index for this column, start of next
}
}
return result;
}
// Hessian of twisting energy with respect to material axis (theta) variables.
// This hessian is a constant tridiagonal matrix that can be interpreted as a
// non-uniform 1D Laplacian (for the dual mesh)
template<typename Real_>
TriDiagonalSystem<Real_> ElasticRod_T<Real_>::hessThetaEnergyTwist() const {
const size_t ne = numEdges(), nv = numVertices();
// Construct -1, 0, 1 diagonals in vectors a, d, c respectively
// Since the matrix is symmetric we only need to construct d and c (upper triangle)
std::vector<Real_> d(ne), c(ne - 1);
// Compute Hessian of internal vertices' contributions to the twisting energy
for (size_t i = 1; i < nv - 1; ++i) {
Real_ coeff = (2.0 * m_twistingStiffness[i]) / (m_restLen[i - 1] + m_restLen[i]);
// Recall, the gradient contributions were
// gt[i - 1] -= coeff * (theta[i] - theta[i - 1] + const);
// gt[i ] += coeff * (theta[i] - theta[i - 1] + const);
d[i - 1] += coeff; // (i - 1, i - 1)
d[i ] += coeff; // ( i, i)
c[i - 1] = -coeff; // (i - 1, gradient i)
}
auto a = c;
return TriDiagonalSystem<Real_>(std::move(a), std::move(d), std::move(c));
}
// Accumulate stretching Hessian into H.
template<typename Real_>
void ElasticRod_T<Real_>::hessEnergyStretch(ElasticRod_T<Real_>::CSCMat &H, bool variableRestLen) const {
using M3d = Mat3_T<Real_>;
assert(H.symmetry_mode == CSCMat::SymmetryMode::UPPER_TRIANGLE);
const size_t ndof = variableRestLen ? numExtendedDoF() : numDoF();
assert((size_t(H.m) == ndof) && (size_t(H.n) == ndof));
UNUSED(ndof);
const auto &dc = deformedConfiguration();
const size_t ne = numEdges(), nv = numVertices();
// Accumulate per-edge Hessian contributions
for (size_t j = 0; j < ne; ++j) {
const Real_ ks = density(j) * m_stretchingStiffness[j];
const Real_ ks_epsilon_div_lj = ks * (1.0 / m_restLen[j] - 1.0 / dc.len[j]);
const Real_ coeff = ks / m_restLen[j] - ks_epsilon_div_lj;
const auto &t = dc.tangent[j];
// Per-edge Hessian consists of four 3x3 blocks that are identical up to sign.
// The sign is negative for the mixed derivatives, and positive for the
// Hessian with respect to a single vertex.
M3d hessianBlock = ks_epsilon_div_lj * M3d::Identity()
+ (coeff * t) * t.transpose();
// Only two vertices affect edge 'j': vertex 'j' and 'j + 1'
for (size_t col = 0; col < 3; ++col) {
// prev-prev, prev-next, next-next
H.addNZ(3 * (j ), 3 * ( j) + col, hessianBlock.col(col).head(col + 1)); // d2 / (dx_{ j} dx_{ j})
size_t idx = H.addNZ(3 * (j ), 3 * (j + 1) + col, -hessianBlock.col(col) ); // d2 / (dx_{ j} dx_{j + 1})
H.addNZ(idx, hessianBlock.col(col).head(col + 1)); // d2 / (dx_{j + 1} dx_{j + 1})
}
if (variableRestLen) {
const size_t rl_offset = 3 * nv + ne + j;
Real_ fracLen = dc.len[j] / m_restLen[j];
// (x, restlen) term
// -(grad l^j) * ks * (l^j / (restLen^j)^2) := -block
Vec3 block = t * ks * fracLen / m_restLen[j];
size_t next_idx = H.addNZ(3 * j, rl_offset, block);
H.addNZ(next_idx, -block);
// (restlen, restlen) term
H.addNZ(rl_offset, rl_offset, ks * fracLen * fracLen / m_restLen[j]);
}
}
}
// Hessian ***evaluated assuming the source frame has been updated to the current frame***
template<typename Real_>
void ElasticRod_T<Real_>::hessEnergyBend(ElasticRod_T<Real_>::CSCMat &H, bool variableRestLen) const {
assert(H.symmetry_mode == CSCMat::SymmetryMode::UPPER_TRIANGLE);
const size_t ndof = variableRestLen ? numExtendedDoF() : numDoF();
UNUSED(ndof);
assert((size_t(H.m) == ndof) && (size_t(H.n) == ndof));
using M3d = Mat3_T<Real_>;
using M2d = Mat2_T<Real_>;
const size_t nv = numVertices(), ne = numEdges();
const auto &dc = deformedConfiguration();
for (size_t i = 1; i < nv - 1; ++i) {
const auto &kb = dc.kb[i];
const Real_ inv_2libar = 1.0 / (m_restLen[i - 1] + m_restLen[i]);
const std::array<Real_, 2> B_div_2libar = {{m_bendingStiffness[i].lambda_1 * inv_2libar,
m_bendingStiffness[i].lambda_2 * inv_2libar}};
// Accumulate per-interior-vertex Hessian contributions.
// The DoFs involved are the centerline positions of the vertex and its two neighbors
// and the twisting angles of the two incident edges.
Eigen::Matrix<Real_, 9, 9> perVertexHessian_x_x; // No zero-initialization needed
Eigen::Matrix<Real_, 9, 2> perVertexHessian_x_theta( Eigen::Matrix<Real_, 9, 2>::Zero());
Eigen::Matrix<Real_, 2, 2> perVertexHessian_theta_theta(Eigen::Matrix<Real_, 2, 2>::Zero());
//////////////////////////////////////////////////////
// Quantities needed by multiple parts of the Hessian.
//////////////////////////////////////////////////////
const auto &ti = dc.tangent[i],
&tim1 = dc.tangent[i - 1];
std::array<Real_, 2> inv_len{{1.0 / dc.len[i - 1],
1.0 / dc.len[i ]}};
const Real_ inv_chi = 1.0 / (1.0 + tim1.dot(ti));
const Vec3 t_tilde = (tim1 + ti ) * inv_chi;
// Precompute some matrix terms that will be re-used
M3d tilde_t_otimes_t_2 = 2 * t_tilde * t_tilde.transpose();
M3d I_minus_ti_otimes_ti = M3d::Identity() - ti * ti .transpose(),
I_minus_tim1_otimes_tim1 = M3d::Identity() - tim1 * tim1.transpose(),
I_plus_tim1_otimes_ti = M3d::Identity() + tim1 * ti .transpose();
M3d d2E_deim1_deim1(M3d::Zero()),
d2E_deim1_dei (M3d::Zero()),
d2E_dei_dei (M3d::Zero());
////////////////////////////////////////////////////////////////////////
// Gradient outer product terms
////////////////////////////////////////////////////////////////////////
std::array<Vec3, 2> oproduct_grad_kappa_term_ei, oproduct_grad_kappa_term_eim1;
// d_kappa_k_j_de_im1[k][j] = d/deim1 (kappa_k)_i^j
std::array<std::array<Vec3, 2>, 2> d_kappa_k_j_de_im1, d_kappa_k_j_de_i;
// d_kappa_k_j_dtheta_j(k, j) = d/dtheta_j (kappa_k)_i^j
M2d d_kappa_k_j_dtheta_j;
M2d oproduct_grad_kappa_k_term_theta;
for (size_t k = 0; k < 2; ++k) {
const size_t kother = (k + 1) % 2;
for (size_t adj_edge = 0; adj_edge < 2; ++adj_edge) {
const size_t j = adj_edge + (i - 1);
d_kappa_k_j_dtheta_j(k, adj_edge) = -kb.dot(dc.materialFrame[j].get(k));
const Real_ sign = (k == 0) ? 1 : -1; // Infinitesimal transport kappa_2^j term is just like kappa_1, except d2 is replaced with -d1.
d_kappa_k_j_de_im1[k][adj_edge] = inv_len[0] * (( 2 * sign * inv_chi) * ti.cross(dc.materialFrame[j].get(kother)) - dc.per_corner_kappa[i].col(adj_edge)[k] * t_tilde);
d_kappa_k_j_de_i [k][adj_edge] = inv_len[1] * ((-2 * sign * inv_chi) * tim1.cross(dc.materialFrame[j].get(kother)) - dc.per_corner_kappa[i].col(adj_edge)[k] * t_tilde);
}
}
if (m_bendingEnergyType == BendingEnergyType::Bergou2010) {
for (size_t k = 0; k < 2; ++k) {
oproduct_grad_kappa_term_ei [k] = 0.5 * (d_kappa_k_j_de_i [k][0] + d_kappa_k_j_de_i [k][1]);
oproduct_grad_kappa_term_eim1[k] = 0.5 * (d_kappa_k_j_de_im1[k][0] + d_kappa_k_j_de_im1[k][1]);
}
oproduct_grad_kappa_k_term_theta = 0.5 * d_kappa_k_j_dtheta_j;
}
for (size_t adj_edge = 0; adj_edge < 2; ++adj_edge) {
const size_t j = adj_edge + (i - 1);
for (size_t k = 0; k < 2; ++k) {
if (m_bendingEnergyType == BendingEnergyType::Bergou2008) {
oproduct_grad_kappa_term_eim1[k] = (m_restLen[j] * 2 * inv_2libar) * d_kappa_k_j_de_im1[k][adj_edge];
oproduct_grad_kappa_term_ei [k] = (m_restLen[j] * 2 * inv_2libar) * d_kappa_k_j_de_i [k][adj_edge];
oproduct_grad_kappa_k_term_theta.setZero();
oproduct_grad_kappa_k_term_theta.col(adj_edge) = m_restLen[j] * 2 * inv_2libar * d_kappa_k_j_dtheta_j.col(adj_edge);
}
// e, e outer product term
d2E_deim1_deim1 += B_div_2libar[k] * (oproduct_grad_kappa_term_eim1[k] * d_kappa_k_j_de_im1[k][adj_edge].transpose());
d2E_deim1_dei += B_div_2libar[k] * (oproduct_grad_kappa_term_eim1[k] * d_kappa_k_j_de_i [k][adj_edge].transpose());
d2E_dei_dei += B_div_2libar[k] * (oproduct_grad_kappa_term_ei [k] * d_kappa_k_j_de_i [k][adj_edge].transpose());
// x, theta outer product term: theta_j only affects kappa_k_j
perVertexHessian_x_theta.template block<3, 1>(0, adj_edge) += (B_div_2libar[k] * d_kappa_k_j_dtheta_j(k, adj_edge)) * (-oproduct_grad_kappa_term_eim1[k] ); // (x i - 1, theta j)
perVertexHessian_x_theta.template block<3, 1>(3, adj_edge) += (B_div_2libar[k] * d_kappa_k_j_dtheta_j(k, adj_edge)) * ( oproduct_grad_kappa_term_eim1[k] - oproduct_grad_kappa_term_ei[k]); // (x i , theta j)
perVertexHessian_x_theta.template block<3, 1>(6, adj_edge) += (B_div_2libar[k] * d_kappa_k_j_dtheta_j(k, adj_edge)) * ( oproduct_grad_kappa_term_ei [k] ); // (x i + 1, theta j)
// theta, theta outer product term
perVertexHessian_theta_theta.col(adj_edge) += B_div_2libar[k] * d_kappa_k_j_dtheta_j(k, adj_edge) * oproduct_grad_kappa_k_term_theta.row(k).transpose();
}
}
////////////////////////////////////////////////////////////////////////
// Kappa Hessian terms
////////////////////////////////////////////////////////////////////////
for (size_t adj_edge = 0; adj_edge < 2; ++adj_edge) { // 0 ==> i - 1, 1 ==> i
size_t j = (i + adj_edge) - 1;
const auto &t_j = dc.tangent[j];
// dE_dkappa_k_j[k] = dE/(kappa_k)_i^j
std::array<Real_, 2> dE_dkappa_k_j;
if (m_bendingEnergyType == BendingEnergyType::Bergou2010) {
const Vec2 kappaDiff = dc.kappa[i] - m_restKappa[i];
dE_dkappa_k_j = {{B_div_2libar[0] * kappaDiff[0],
B_div_2libar[1] * kappaDiff[1]}};
}
else if (m_bendingEnergyType == BendingEnergyType::Bergou2008) {
const Vec2 kappaDiff = dc.per_corner_kappa[i].col(adj_edge) - m_restKappa[i];
dE_dkappa_k_j = {{2.0 * m_restLen[j] * inv_2libar * B_div_2libar[0] * kappaDiff[0],
2.0 * m_restLen[j] * inv_2libar * B_div_2libar[1] * kappaDiff[1]}};
}
else { assert(false); }
for (size_t k = 0; k < 2; ++k) {
const size_t kother = (k + 1) % 2;
const double sign = (k == 0) ? 1.0 : -1.0; // Infinitesimal transport kappa_2^j term is just like kappa_1, except d2 is replaced with -d1.
// Contribution from H (kappa_k)_i^j
// (x, x) part (upper left block)
const Real_ kappa = dc.per_corner_kappa[i].col(adj_edge)[k];
const Real_ half_kappa = kappa * 0.5;
const Real_ sign_inv_chi_2 = sign * 2 * inv_chi;
const auto &d_kother_j = dc.materialFrame[j].get(kother);
const auto &d_k_j = dc.materialFrame[j].get(k);
Vec3 cross_prod_term_eim1 = sign_inv_chi_2 * ti .cross(d_kother_j),
cross_prod_term_ei = sign_inv_chi_2 * tim1.cross(d_kother_j);
// Use symmetry of d2_kappa_k_j_deim1_deim1 and d2_kappa_k_j_dei_dei to speed up calculation (full result will be d2_kappa_k_j_deim1_deim1 + d2_kappa_k_j_deim1_deim1.transpose())
M3d d2_kappa_k_j_deim1_deim1 = half_kappa * tilde_t_otimes_t_2 - (cross_prod_term_eim1 * t_tilde.transpose() /* + t_tilde otimes cross_prod_term_eim1 */ ) - (half_kappa * inv_chi) * I_minus_tim1_otimes_tim1;
M3d d2_kappa_k_j_dei_dei = half_kappa * tilde_t_otimes_t_2 + (cross_prod_term_ei * t_tilde.transpose() /* + t_tilde otimes cross_prod_term_e */ ) - (half_kappa * inv_chi) * I_minus_ti_otimes_ti;
M3d d2_kappa_k_j_deim1_dei = kappa * tilde_t_otimes_t_2 - (cross_prod_term_eim1 * t_tilde.transpose() - t_tilde * cross_prod_term_ei .transpose() ) - ( kappa * inv_chi) * I_plus_tim1_otimes_ti;
// Add in [d_kother_j]_x term
d2_kappa_k_j_deim1_dei(0, 1) += sign_inv_chi_2 * d_kother_j[2];
d2_kappa_k_j_deim1_dei(0, 2) -= sign_inv_chi_2 * d_kother_j[1];
d2_kappa_k_j_deim1_dei(1, 2) += sign_inv_chi_2 * d_kother_j[0];
d2_kappa_k_j_deim1_dei(1, 0) -= sign_inv_chi_2 * d_kother_j[2];
d2_kappa_k_j_deim1_dei(2, 0) += sign_inv_chi_2 * d_kother_j[1];
d2_kappa_k_j_deim1_dei(2, 1) -= sign_inv_chi_2 * d_kother_j[0];
// We have a finite transport term only for the derivative with respect to edge "j"; leverage symmetry to drop half of the terms...
M3d finiteTransportTerm = sign * (kb * d_kother_j.transpose() /* + d_kother_j * kb.transpose() */) + 0.5 * (kb.cross(t_j) * d_k_j.transpose() /* + d_k_j * kb.cross(t_j).transpose() */) /* - half_kappa * (M3d::Identity() - t_j * t_j.transpose()) <---- moved below */;
if (adj_edge == 0) d2_kappa_k_j_deim1_deim1 += finiteTransportTerm - half_kappa * I_minus_tim1_otimes_tim1;
if (adj_edge == 1) d2_kappa_k_j_dei_dei += finiteTransportTerm - half_kappa * I_minus_ti_otimes_ti;
d2E_deim1_deim1 += (dE_dkappa_k_j[k] * inv_len[0] * inv_len[0]) * (d2_kappa_k_j_deim1_deim1 + d2_kappa_k_j_deim1_deim1.transpose());
d2E_dei_dei += (dE_dkappa_k_j[k] * inv_len[1] * inv_len[1]) * (d2_kappa_k_j_dei_dei + d2_kappa_k_j_dei_dei .transpose());
d2E_deim1_dei += (dE_dkappa_k_j[k] * inv_len[0] * inv_len[1]) * (d2_kappa_k_j_deim1_dei );
// Theta, theta Hessian (Hessian of kappas with respect to thetas have no cross terms)
perVertexHessian_theta_theta(adj_edge, adj_edge) += dE_dkappa_k_j[k] * sign * d_kappa_k_j_dtheta_j(kother, adj_edge);
// x, theta Hessian
Vec3 d2_kappa_k_j_deim1_dtheta_term = (dE_dkappa_k_j[k] * inv_len[0]) * (-(2 * inv_chi) * ti .cross(d_k_j) + kb.dot(d_k_j) * t_tilde);
Vec3 d2_kappa_k_j_dei_dtheta_term = (dE_dkappa_k_j[k] * inv_len[1]) * ( (2 * inv_chi) * tim1.cross(d_k_j) + kb.dot(d_k_j) * t_tilde);
perVertexHessian_x_theta.template block<3, 1>(0, adj_edge) += -d2_kappa_k_j_deim1_dtheta_term ; // (x i - 1, theta j)
perVertexHessian_x_theta.template block<3, 1>(3, adj_edge) += d2_kappa_k_j_deim1_dtheta_term - d2_kappa_k_j_dei_dtheta_term; // (x i , theta i - 1)
perVertexHessian_x_theta.template block<3, 1>(6, adj_edge) += d2_kappa_k_j_dei_dtheta_term ; // (x i + 1, theta i - 1)
}
}
#if 0 // Incorrect versions in Bergou2010
d2k1_deim1_deim1 = inv_len_im1 * inv_len_im1 * ( (2 * k1 * t_tilde) * t_tilde.transpose() - ti .cross(d2_tilde) * t_tilde.transpose() - t_tilde * ti .cross(d2_tilde).transpose() - inv_chi * k1 * (Eigen::Matrix3d::Identity() - tim1 * tim1.transpose()) + 0.25 * (kb * d2im1.transpose() + d2im1 * kb.transpose()));
d2k1_dei_dei = inv_len_i * inv_len_i * ( (2 * k1 * t_tilde) * t_tilde.transpose() + tim1.cross(d2_tilde) * t_tilde.transpose() + t_tilde * tim1.cross(d2_tilde).transpose() - inv_chi * k1 * (Eigen::Matrix3d::Identity() - ti * ti .transpose()) + 0.25 * (kb * d2i .transpose() + d2i * kb.transpose()));
#endif
perVertexHessian_x_x.template block<3, 3>(0, 0) = d2E_deim1_deim1 ; // (x i - 1, x i - 1) ==> (-ei-1, -ei-1)
perVertexHessian_x_x.template block<3, 3>(0, 3) = d2E_deim1_dei - d2E_deim1_deim1 ; // (x i - 1, x i ) ==> (-ei-1, +ei-1), (-ei-1, -ei)
perVertexHessian_x_x.template block<3, 3>(0, 6) = -d2E_deim1_dei ; // (x i - 1, x i + 1) ==> (-ei-1, +ei)
// perVertexHessian_x_x.template block<3, 3>(3, 0) = d2E_deim1_dei.transpose() - d2E_deim1_deim1 ; // (x i , x i - 1) ==> (-ei, -ei-1), (+ei-1, -ei-1)
perVertexHessian_x_x.template block<3, 3>(3, 3) = d2E_deim1_deim1 - d2E_deim1_dei - d2E_deim1_dei.transpose() + d2E_dei_dei; // (x i , x i ) ==> (+ei-1, +ei-1), (+ei-1, -ei), (-ei, +ei-1), (-ei, -ei)
perVertexHessian_x_x.template block<3, 3>(3, 6) = d2E_deim1_dei - d2E_dei_dei ; // (x i , x i + 1) ==> (+ei-1, +ei), (-ei, +ei)
// perVertexHessian_x_x.template block<3, 3>(6, 0) = -d2E_deim1_dei.transpose() ; // (x i + 1, x i - 1) ==> (+ei, -ei-1)
// perVertexHessian_x_x.template block<3, 3>(6, 3) = d2E_deim1_dei.transpose() - d2E_dei_dei ; // (x i + 1, x i ) ==> (+ei, +ei-1), (+ei, -ei)
perVertexHessian_x_x.template block<3, 3>(6, 6) = d2E_dei_dei ; // (x i + 1, x i + 1) ==> (+ei, +ei)
// Offset into full sparse Hessian where we should accumulate contributions.
const size_t x_offset = 3 * (i - 1), // Index of the first position variable for the stencil
theta_offset = 3 * nv + (i - 1); // Index of the first theta variable
/////////////////////////////////////////////
// Assemble Hessian blocks into sparse matrix
/////////////////////////////////////////////
for (size_t c1 = 0; c1 < 9; ++c1) H.addNZ( x_offset, x_offset + c1, perVertexHessian_x_x.col(c1).head(c1 + 1));