/
robot_invkin_eulangresidual.m.template
1153 lines (1130 loc) · 55.3 KB
/
robot_invkin_eulangresidual.m.template
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
% Inverse Kinematik basierend auf Euler-Winkel-Residuum für
% %RN%
%
% Eingabe:
% Tr0E_soll [3x4]
% EE-Lage (Sollwert); homogene Transformationsmatrix ohne letzte Zeile
% Q0 [%NQJ% x N_init]
% Anfangs-Gelenkwinkel für Algorithmus (werden nacheinander ausprobiert)
% s
% Struktur mit Eingabedaten. Felder, siehe Quelltext und SerRob/invkin2
% Auswahl der Einstellungen:
% .wn [13x1] Gewichtungen der Zielfunktionen für Nullraumbewegung.
% Indiziert mit idx_ikpos_wn aus ik_optimcrit_index.m
% (1) Quadratischer Abstand der Gelenkkoordinaten von ihrer Mitte
% (2) Hyperbolischer Abstand der Gelenkkoordinaten von ihren Grenzen
% (3) Konditionszahl der IK-Residuums-Jacobi-Matrix
% (4) Konditionszahl der geometrischen Jacobi-Matrix
% (5) Abstand der Kollisionskörper voneinander (hyperbolisch gewertet)
% (6) Abstand von Prüfkörpern des Roboters zur Bauraumgrenze (hyperbolisch)
% (7) Abstand von phiz zur Grenze xlim (quadratisch gewertet)
% (8) Abstand von phiz zur Grenze xlim (hyperbolisch gewertet)
% (9) Abstand der Kollisionskörper voneinander (quadratisch gewertet)
% (10) Abstand zur Bauraumgrenze voneinander (quadratisch gewertet)
% (11) Abstand von phiz_trans zur Grenze xlim (quadratisch gewertet)
% (12) Abstand von phiz_trans zur Grenze xlim (hyperbolisch gewertet)
% (13) Positionsfehler am Endeffektor
%
% Ausgabe:
% q [%NQJ% x 1]
% Lösung der IK
% Phi
% Restfehler mit der IK-Lösung
% Tc_stack [(%NJ%+1+1)*3 x 4]
% Gestapelte homogene Transformationsmatrizen für q (jew. ohne 0001-Zeile)
% (enthält alle Koordinatensysteme aus direkter Kinematik; inkl. EE)
% Stats
% Struktur mit Detail-Ergebnissen für den Verlauf der Berechnung. Felder:
% .Q (n+1)x6: Gelenkkoordinaten für ersten Schritt und alle Iterationen
% .PHI (n+1)x6: Residuum
% .h (n+1)x(1+12): Leistungsmerkmale: siehe Reihenfolge in Eingabefeld "wn"
% .condJ (n+1x2): (1.) Konditionszahl der IK-Jacobi-Matrix (Ableitung
% des Euler-Winkel-Residuums mit reduzierten FG. (2.) Konditionszahl
% der geometrischen Jacobi-Matrix ohne Betrachtung von Aufgaben-Red.
% .maxcolldepth (n+1x2): Eindringtiefe der Kollisionen. Erste Spalte alle
% Prüfungen. Zweite Spalte nur mit Redundanz beeinflussbare Prüfungen.
% Negative Werte sind keine Kollision (gut)
% .instspc_mindst (n+1x2): Überschreitungsdistanz des Bauraums. Erste Spalte
% alle, zweite nur beeinflussbare Prüfungen. Negative Werte sind im Bauraum (gut)
% Quelle:
% [SchapplerTapOrt2019] Schappler, M. et al.: Resolution of Functional
% Redundancy for 3T2R Robot Tasks using Two Sets of Reciprocal Euler
% Angles, Proc. of the 15th IFToMM World Congress, 2019
% [1] Aufzeichnungen Schappler vom 3.8.2018
% [ChiaveriniSicEge1994] S. Chiaverini and B. Siciliano, O. Egeland:
% Review of the damped least-squares inverse kinematics with experiments
% on an industrial robot manipulator, 1994
% [NakamuraHan1986] Y. Nakamura, H. Hanafusa: Inverse Kinematic Solutions
% With Singularity Robustness for Robot Manipulator Control, 1986
% [CorkeIK] Peter Corke, Robotics Toolbox, ikine.m
% [SchapplerOrt2021] Schappler, M. et al.: Singularity Avoidance of Task-
% Redundant Robots in Pointing Tasks (...); ICINCO 2021
% [SchapplerBluJob2022] Schappler, M. et al.: Geometric Model for Serial-
% Chain Robot Inverse Kinematics in the Case of Two Translational DoF with
% Spatial Rotation and Task Redundancy, Submitted to ARK 2022
% %VERSIONINFO%
% Moritz Schappler, moritz.schappler@imes.uni-hannover.de, 2019-02
% (C) Institut für Mechatronische Systeme, Leibniz Universität Hannover
function [q, Phi, Tc_stack, Stats] = %RN%_invkin_eulangresidual(Tr0E_soll, Q0, s)
%% Coder Information
%#codegen
%$cgargs {zeros(3,4),coder.newtype('double',[%NQJ%,inf]),struct(
%$cgargs 'pkin', zeros(%NKP%,1),
%$cgargs 'sigmaJ', zeros(%NQJ%,1),
%$cgargs 'qlim', zeros(%NQJ%,2),
%$cgargs 'xlim', zeros(6,2),
%$cgargs 'q_poserr', ones(%NQJ%,1),
%$cgargs 'I_EE', true(1,6),
%$cgargs 'phiconv_W_E', uint8(2),
%$cgargs 'I_EElink', uint8(0),
%$cgargs 'reci', true,
%$cgargs 'T_N_E', zeros(4,4),
%$cgargs 'K', zeros(%NQJ%,1),
%$cgargs 'Kn', zeros(%NQJ%,1),
%$cgargs 'wn', zeros(13,1),
%$cgargs 'maxstep_ns', 0,
%$cgargs 'scale_lim', 0,
%$cgargs 'scale_coll', 0,
%$cgargs 'maxrelstep', 0.1,
%$cgargs'finish_in_limits', false,
%$cgargs'avoid_collision_finish', false,
%$cgargs'optimcrit_limits_hyp_deact', NaN,
%$cgargs 'cond_thresh_ikjac', 1,
%$cgargs 'cond_thresh_jac', 1,
%$cgargs 'normalize', false,
%$cgargs 'condlimDLS', 60,
%$cgargs 'lambda_min', 2e-4,
%$cgargs 'n_min', 0,
%$cgargs 'n_max', 1000,
%$cgargs 'rng_seed', NaN,
%$cgargs 'Phit_tol', 1.0000e-10,
%$cgargs 'Phir_tol', 1.0000e-10,
%$cgargs 'retry_on_limitviol', false,
%$cgargs 'retry_limit', 100,
%$cgargs 'collbodies', struct(
%$cgargs 'link', coder.newtype('uint16',[inf,2]),
%$cgargs 'type', coder.newtype('uint8',[inf,1]),
%$cgargs 'params', coder.newtype('double',[inf,10])),
%$cgargs 'collbodies_thresh', 1.5,
%$cgargs 'collision_thresh', NaN,
%$cgargs 'collchecks', coder.newtype('uint8',[inf,2]),
%$cgargs 'installspace_thresh', 0.1,
%$cgargs 'collbodies_instspc', struct(
%$cgargs 'link', coder.newtype('uint16',[inf,2]),
%$cgargs 'type', coder.newtype('uint8',[inf,1]),
%$cgargs 'params', coder.newtype('double',[inf,10])),
%$cgargs 'collchecks_instspc', coder.newtype('uint8',[inf,2]))}
%% Initialisierung
% Einstellungsvariablen aus Struktur herausholen
phiconv_W_E = s.phiconv_W_E;
K = s.K;
Kn = s.Kn;
n_min = s.n_min;
n_max = s.n_max;
Phit_tol = s.Phit_tol;
Phir_tol = s.Phir_tol;
retry_limit = s.retry_limit;
reci = s.reci;
I_EElink = s.I_EElink;
Rob_I_EE = %Rob_I_EE%; % Strukturelle FG (im Gegensatz zu Aufgaben-FG aus s.I_EE)
T_N_E = s.T_N_E;
pkin = s.pkin;
NQJ = %NQJ%;
sigmaJ = s.sigmaJ; % Marker für Dreh-/Schubgelenk (in den Minimalkoordinaten)
condlimDLS = s.condlimDLS;
lambda_min = s.lambda_min;
scale_lim = s.scale_lim;
scale_coll = s.scale_coll;
maxrelstep = s.maxrelstep;
maxstep_ns = s.maxstep_ns;
finish_in_limits = s.finish_in_limits;
break_when_in_limits = false;
avoid_collision_finish = s.avoid_collision_finish;
n_Phi_t = sum(s.I_EE(1:3)); % Anzahl der translatorischen Zwangsbedingungen
[idx_wn, idx_hn, ~, ~, ~, idx_ik_length] = ik_optimcrit_index(0);
% Definitionen für die Kollisionsprüfung
collbodies_ns = s.collbodies;
maxcolldepth = 0;
collobjdist_thresh = 0;
if isempty(collbodies_ns.type) % Keine Kollisionskörper
s.wn([idx_wn.coll_hyp,idx_wn.coll_par]) = 0; % Deaktivierung der Kollisionsvermeidung
scale_coll = 0;
avoid_collision_finish = false;
end
if isempty(s.collbodies_instspc.type) % Keine Bauraum-Prüfkörper
s.wn([idx_wn.instspc_hyp,idx_wn.instspc_par]) = 0; % Deaktivierung der Bauraumprüfung
end
if scale_coll || any(s.wn([idx_wn.coll_hyp,idx_wn.coll_par])) || avoid_collision_finish
% Kollisionskörper für die Kollisionserkennung z.B. 50% größer machen.
% Ist zusammen mit dem Schwellwert für die Kollisionsvermeidung wirksam.
collbodies_ns.params(collbodies_ns.type==6,1) = ... % Kapseln (Direktverbindung)
s.collbodies_thresh*collbodies_ns.params(collbodies_ns.type==6,1);
collbodies_ns.params(collbodies_ns.type==13,7) = ... % Kapseln (Basis-KS)
s.collbodies_thresh*collbodies_ns.params(collbodies_ns.type==13,7);
collbodies_ns.params(collbodies_ns.type==4|collbodies_ns.type==15,4) = ... % Kugeln
s.collbodies_thresh*collbodies_ns.params(collbodies_ns.type==4|collbodies_ns.type==15,4);
% Maximal mögliche Eindringtiefe der Warnungs-Ersatzkörper bestimmen um
% daraus die Grenzen der hyperbolischen Kollisionsfunktion zu bestimmen.
% Ist eine etwas größere Schätzung (abhängig von relativer Größe von
% Kugeln und Zylindern)
maxcolldepth = max([0; collbodies_ns.params(collbodies_ns.type==6,1); ... % 1. Eintrag damit nicht leer
collbodies_ns.params(collbodies_ns.type==13,7); ...
collbodies_ns.params(collbodies_ns.type==4|collbodies_ns.type==15,4)]);
% Abstand der Objekte, ab dem die Zielfunktion anfängt (bei größeren
% Abständen ist sie Null). Dies Wert muss kleiner sein als der, ab dem die
% Erkennung beginnt (sonst Sprung). Unklar, ob dieser Wert immer passt.
% Die Erkennung wird durch `collbodies_ns` bestimmt. Diese müssen also
% eher zu groß gewählt werden (über Parameter collbodies_thresh).
% je kleiner der Wert wird, desto später wird die Vermeidung wirksam
collobjdist_thresh = 0.3 * maxcolldepth;
end
if ~isnan(s.collision_thresh)
collobjdist_thresh = s.collision_thresh;
end
% Übergreifende Variable zur Speicherung aktiver Kollisionsprüfungen.
I_collcheck_nochange_all = false(1,size(s.collchecks,1));
I_instspccheck_nochange = false(1,size(s.collchecks_instspc,1));
% Indizes für kinematische Zwangsbedingungen festlegen
if reci
% Reihenfolge hergeleitet in [SchapplerTapOrt2019]; siehe z.B. Gl. (21)
I_IK2 = [1 2 3 6 5 4];
else
I_IK2 = [1 2 3 4 5 6];
end
I_IK = I_IK2(s.I_EE);
use_constr4 = false;
% Benutze eine modifizier Version der kinematischen Zwangsbedingungen für
% Beinketten von 3T1R-PKM. Damit Vermeidung von überbestimmten LGS mit
% Gradientenmatrix der Dimension 6x5.
if NQJ == 5 && all(s.I_EE(1:5) == [1 1 1 0 1])
use_constr4 = true;
end
% Damit der Roboter einen Nullraum für Nebenoptimierungen hat, muss er min.
% 7FG für 6FG-Aufgaben und 6FG für 5FG-Aufgaben haben.
nsoptim = false;
if NQJ > length(I_IK)
if any(s.wn ~= 0)
nsoptim = true;
end
else
% Keine zusätzlichen Optimierungskriterien
finish_in_limits = false; % Alle Nullraumbewegungen nicht möglich
end
qmin = s.qlim(:,1);
qmax = s.qlim(:,2);
if all(~isnan(s.qlim(:)))
limits_set = true;
else
% Grenzen sind nicht wirksam
qmin(:) = -Inf;
qmax(:) = Inf;
limits_set = false;
retry_limit = size(Q0,2)-1; % keine zufällige Neubestimmung möglich.
finish_in_limits = false;
end
% Grenzen für die Neubestimmung der Anfangswerte (falls unendl. vorkommt).
% Annahme: Betrifft nur Drehgelenke. Dort dann zwischen -pi und pi.
% Die Variable qmin/qmax wird für Nebenbedingungen benutzt.
qmin_norm = qmin; qmax_norm = qmax;
qmin_norm(isinf(qmin)) = sign(qmin_norm(isinf(qmin)))*(pi);
qmax_norm(isinf(qmax)) = sign(qmax_norm(isinf(qmax)))*(pi);
delta_qlim = qmax - qmin;
% Schwellwert in Gelenkkoordinaten für Aktivierung des Kriteriums für
% hyperbolisch gewichteten Abstand von den Grenzen.
qlim_thr_h2 = repmat(mean(s.qlim,2),1,2) + repmat(delta_qlim,1,2).*...
repmat([-0.5, +0.5]*s.optimcrit_limits_hyp_deact,NQJ,1);
% Schwellwert der Z-Rotation (3T2R) für Aktivierung des Kriteriums für
% hyperbolisch gewichteten Abstand von den Grenzen.
xlim_thr_h8 = repmat(mean(s.xlim,2),1,2) + repmat(s.xlim(:,2)-s.xlim(:,1),1,2).*...
repmat([-0.5, +0.5]*0.8,6,1); % vorläufig auf 80% der Grenzen in xlim
if any(isnan(s.xlim(6,:))) % Kriterium nicht bestimmbar
s.wn([idx_wn.xlim_par, idx_wn.xlim_hyp]) = 0;
end
if any(isnan(s.xlim(3,:))) % Kriterium nicht bestimmbar
s.wn([idx_wn.xlim_trans_par, idx_wn.xlim_trans_hyp]) = 0;
end
Jak = NaN(6,NQJ); % Belegung für Kompilierung
Jgk = NaN(6,NQJ);
Phi_voll = NaN(6,1); % Belegung für Kompilierung
T_0_E = NaN(4,4); % Belegung für Kompilierung
R_D_0 = Tr0E_soll(1:3,1:3)'; % Rotationsmatrix aus Soll-Transf.matrix
delta_phi_z = NaN(3,1);
if any(s.wn([idx_wn.xlim_par,idx_wn.xlim_hyp,idx_wn.xlim_trans_par,idx_wn.xlim_trans_hyp]) ~= 0)
% Euler-Winkel der Soll-Transformation berechnen
xr_0_E_soll = r2eul(Tr0E_soll(1:3,1:3), phiconv_W_E);
Tw_wn = euljac(xr_0_E_soll, phiconv_W_E); % Euler-Transformationsmatrix
else
xr_0_E_soll = NaN(3,1);
Tw_wn = NaN(3,3);
end
dz_2T2R = 0; % Für Kompilierbarkeit. Variable dz in [SchapplerBluJob2022]
wn = s.wn; % Lokale Variable definieren (kann verändert werden)
% Variablen für Dämpfung der Inkremente
delta_q_alt = zeros(NQJ,1); % Altwert für Tiefpassfilter
delta_q_N_alt = zeros(NQJ,1); % Altwert für Nullraum-Tiefpassfilter
Phi_alt = NaN(length(I_IK),1);
delta_Phi_alt = Phi_alt;
damping_active = false; % Standardmäßig noch nicht aktiviert
% Zuweisung notwendig für mex (rr-Schleife nicht automatisch erkannt)
q0 = Q0(:,1);
q1 = NaN(NQJ,1);
Phi = NaN(length(I_IK),1); % Vorbelegung für Ausgabe ohne Iteration
Tc_stack = NaN(3*(%NL%+1),4);
rejcount = 0; % Zähler für Zurückweisung des Iterationsschrittes, siehe [CorkeIK]
scale = 1; % Skalierung des Inkrements (kann reduziert werden durch scale_lim)
N = NaN(NQJ,NQJ); % Nullraum-Projektor
h = zeros(idx_ik_length.hnpos,1); h_alt = inf(idx_ik_length.hnpos,1); % Speicherung der Werte der Nebenbedingungen
bestcolldepth = inf; currcolldepth = inf; % Speicherung der Schwere von Kollisionen
bestinstspcdist = inf; currinstspcdist = inf; % Speicherung des Ausmaßes von Bauraum-Verletzungen
condJik = NaN; condJ = NaN;
% Ausgabe belegen
success = false;
if nargout == 4
Stats_default = struct('file', 'robot_invkin_eul', 'Q', NaN(1+n_max, NQJ), ...
'PHI', NaN(1+n_max, 6), 'iter', n_max, 'retry_number', retry_limit, ...
'condJ', NaN(1+n_max,2), 'lambda', NaN(n_max,2), 'rejcount', NaN(n_max,1), ...
'h', NaN(1+n_max,1+idx_ik_length.hnpos), 'coll', false, 'instspc_mindst', NaN(1+n_max,2), ...
'maxcolldepth', NaN(1+n_max,2), 'h_instspc_thresh', NaN, 'h_coll_thresh', NaN, 'version', 12);
Stats = Stats_default;
end
% Überprüfung für Fall 2T2R/2T3R. [SchapplerBluJob2022]
dof_2T2R = false;
dof_2T2R_xzproj = false;
if all(s.I_EE(1:5) == logical([1 1 0 1 1])) % 2T2R oder 2T3R (nicht: 2T1R/2T0R!)
dof_2T2R = true;
% Bei Winkeln zwischen Z-Achse der Zielkonfiguration und der XY-Ebene des
% KS0 kleiner 45°, soll Winkel mit XZ-Ebene berechnet werden -> XZ-Modus
% Winkelberechnung
e_z_OE = Tr0E_soll(:,3);
% Ebenengleichung in Normalenform für XY-Ebene ist z = 0 -> [0;0;1]
angle_Z_XY = asin(abs(sum(e_z_OE.*[0;0;1])));
if abs(angle_Z_XY) <= pi/4 % Grenze bei 45°
dof_2T2R_xzproj = true; % XZ-Projektion
if s.I_EE(6) == logical([1]) % FG vertauschen, damit Methode passt
I_EE_new = logical([1 0 1 1 1 1]);
else
I_EE_new = logical([1 0 1 1 1 0]);
end
I_IK = I_IK2(I_EE_new); % Reihenfolge der FHG neu aufstellen
else
dof_2T2R_xzproj = false; % XY-Projektion
end
end
Jdk_voll_kkk = NaN(6,6);
%% Iterative Berechnung der inversen Kinematik
for rr = 0:retry_limit % Schleife über Neu-Anfänge der Berechnung
% Variablen zum Speichern der Zwischenergebnisse
q1 = q0;
% Fehlermaß für Startwerte
if dof_2T2R == false
[Phi_voll,Tc_stack] = %RN%_constr2(q0, Tr0E_soll, pkin, T_N_E, phiconv_W_E, I_EElink, reci);
else % dof_2T2R == true
Phi_t = %RN%_constr3_trans(q0, Tr0E_soll, pkin, T_N_E, I_EElink, dof_2T2R_xzproj);
[Phi_voll_temp, Tc_stack] = %RN%_constr2(q0, Tr0E_soll, pkin, T_N_E, phiconv_W_E, I_EElink, reci);
Phi_r = Phi_voll_temp(4:6,:); % Für 2T2R nur der rotatorische Teil relevant
Phi_voll = [Phi_t;Phi_r]; % Residuum für 2T2R zusammenstellen
end
if ~use_constr4
Phi = Phi_voll(I_IK); % Reduktion auf betrachtete FG
else
Phi = %RN%_constr4(Phi_voll, s.I_EE, reci);
end
if nargout == 4 % Anfangswerte eintragen
% Zurücksetzen der Statistik (falls mehrere Wiederholungen gemacht werden
Stats = Stats_default;
Stats.PHI(1,:) = Phi_voll;
Stats.Q(1,:) = q1;
end
lambda_mult = lambda_min; % Zurücksetzen der Dämpfung
lambda = 0.0;
rejcount = 0; % Zurücksetzen des Zählers für Fehlversuche
bestPhi = inf; % Merker für bislang bestes Residuum
% Zurücksetzen des Modus für Abbruch in Grenzen (falls Neuversuch unter-
% nommen wurde, weil die Grenzen doch verletzt wurden).
if limits_set % Siehe unten bei Fallabfrage finish_in_limits
finish_in_limits = s.finish_in_limits;
nsoptim = false;
wn = s.wn;
if any(wn ~= 0), nsoptim = true; end
break_when_in_limits = false;
end
for jj = 1:n_max % Schleife über iteratives Annähern mit Newton-Verfahren
% Gradienten-Matrix, siehe [SchapplerTapOrt2019]/(23)
if dof_2T2R == false
[Jdk_voll, Jgk] = %RN%_constr2grad(q1, Tr0E_soll, pkin, T_N_E, phiconv_W_E, I_EElink, reci);
else % dof_2T2R == true
dxq=%RN%_constr3grad_tq(q1, pkin, T_N_E, I_EElink, dof_2T2R_xzproj);
[Jdk_voll_temp, Jgk] = %RN%_constr2grad(q1, Tr0E_soll, pkin, T_N_E, phiconv_W_E, I_EElink, reci);
dpq = Jdk_voll_temp(4:6,:); % Für 2T2R nur der rotatorische Teil relevant
Jdk_voll = [dxq;dpq]; % Gradient für 2T2R zusammenstellen
end
if ~use_constr4
Jdk = Jdk_voll(I_IK,:); % Reduktion auf betrachtete FG
else
Jdk = %RN%_constr4grad(Jdk_voll, Phi_voll, s.I_EE, reci);
end
%% Nullstellensuche für Positions- und Orientierungsfehler
% (Optimierung der Aufgabe)
% Benutze das Damped Least Squares Verfahren je nach Konditionszahl.
% Bei Redundanz immer benutzen, nicht nur, falls Nullraumprojektion erfolglos.
condJik = cond(Jdk); condJ = cond(Jgk(Rob_I_EE,:));
% manipJ = det(Jdk*Jdk'); % Manipulierbarkeit; nicht weiter verfolgt.
if condJik > condlimDLS% && (~nsoptim || nsoptim && rejcount > 0)
% Pseudo-Inverse mit Dämpfung:
% Passe die Dämpfung lambda im DLS-Verfahren an. Wähle die Kon-
% ditionszahl als Kriterium, da z.B. Grenzen für Singulärwerte
% und Manipulierbarkeit nicht bekannt sind.
% Skalierung zwischen 0 (z.B. Grenzfall cond=60) und 1 (komplett singulär).
% Nehme einen Mindestwert für die Dämpfung und einen sich bei Stagnation
% erhöhenden Aufschlag. Mit Aufschlag wird immer lambda_min benutzt.
lambda = (-1+2*2/pi*atan(condJik/condlimDLS))*(lambda_min+lambda_mult)/2;
% Alternative Berechnung nach [NakamuraHan1986] (nicht weiter verfolgt):
% manipJ0 = 1e-3;
% lambda = 0.1*(1e-3+lambda_mult)*(1-manipJ/manipJ0)^2;
% [NakamuraHan1986], Gl. 22. Kleinere Dimension bei Redundanz als andere pinv.
delta_q_T = ((Jdk')/(Jdk*Jdk' + lambda*eye(length(Phi))))*(-Phi);
else
% Normale (Pseudo-)Invertierung der Jacobi-Matrix (des Residuums):
delta_q_T = Jdk \ (-Phi);
lambda = 0.0;
lambda_mult = lambda_min; % Zurücksetzen. Alles (wieder) i.O.
end
%% Optimierung der Nebenbedingungen (Nullraum)
delta_q_N = zeros(size(delta_q_T));
if nsoptim && ... % Nullraum muss vorhanden sein und Kriterien gesetzt
... %% falls vorherige Iterationen erfolglos, keine Nullraumbewegung.
... % Annahme: Schädlich für Konvergenz. Nur, falls Stagnation
... % nicht durch Gelenkgrenzen (scale_lim) verursacht wurde.
(rejcount == 0 || rejcount~=0 && scale == 0)
% Berechne Gradienten der zusätzlichen Optimierungskriterien
v = zeros(NQJ, 1);
%% Einhaltung der Gelenkwinkel-Grenzen
if wn(idx_wn.qlim_par) ~= 0 % Anziehung zu Gelenkwinkel-Mitte (linear)
[h(idx_hn.qlim_par), h1dq] = invkin_optimcrit_limits1(q1, [qmin, qmax]);
v = v - wn(idx_wn.qlim_par)*h1dq';
end
if wn(idx_wn.qlim_hyp) ~= 0 % Abstoßung von den Grenzen (hyperbolisch)
[h(idx_hn.qlim_hyp), h2dq] = invkin_optimcrit_limits2(q1, [qmin, qmax], qlim_thr_h2);
v = v - wn(idx_wn.qlim_hyp)*h2dq';
end
%% Singularitätsvermeidung Jacobi-Matrix (Aufgaben- und Roboter-FG)
h([idx_hn.ikjac_cond, idx_hn.jac_cond]) = 0;
h(idx_hn.poserr_ee) = 0;
if wn(idx_wn.ikjac_cond) ~= 0 && condJik > s.cond_thresh_ikjac || ...
wn(idx_wn.jac_cond) ~= 0 && condJ > s.cond_thresh_jac || ...
wn(idx_wn.poserr_ee) ~= 0 % Translatorischer Positionsfehler ist ähnlich
h(idx_hn.ikjac_cond) = invkin_optimcrit_condsplineact(condJik, ... % Konditionszahl
1.5*s.cond_thresh_ikjac, s.cond_thresh_ikjac); % mit Spline-Aktivierung
h(idx_hn.jac_cond) = invkin_optimcrit_condsplineact(condJ, ... % Konditionszahl
1.5*s.cond_thresh_jac, s.cond_thresh_jac); % mit Spline-Aktivierung
h(idx_hn.poserr_ee) = norm(abs(Jgk(Rob_I_EE(1:3),:)) * s.q_poserr);
h3dq = NaN(1,NQJ); h4dq = NaN(1,NQJ); h12dq = NaN(1,NQJ);
for kkk = 1:NQJ % Differenzenquotient für jede Gelenkkoordinate
q_test = q1; % ausgehend von aktueller Konfiguration
q_test(kkk) = q_test(kkk) + 1e-6; % minimales Inkrement
[Jdk_voll_kkk, Jgk_kkk] = %RN%_constr2grad(q_test, Tr0E_soll, pkin, T_N_E, phiconv_W_E, I_EElink, reci);
if ~use_constr4
Jdk_kkk = Jdk_voll_kkk(I_IK,:); % Berechnung identisch mit oben
else
Phi_voll_kkk = %RN%_constr2(q_test, Tr0E_soll, pkin, T_N_E, phiconv_W_E, I_EElink, reci);
Jdk_kkk = %RN%_constr4grad(Jdk_voll_kkk, Phi_voll_kkk, s.I_EE, reci);
end
h3_kkk = invkin_optimcrit_condsplineact(cond(Jdk_kkk), ...
1.5*s.cond_thresh_ikjac, s.cond_thresh_ikjac);
h4_kkk = invkin_optimcrit_condsplineact(cond(Jgk_kkk(Rob_I_EE,:)), ...
1.5*s.cond_thresh_jac, s.cond_thresh_jac);
h3dq(kkk) = (h3_kkk-h(idx_hn.ikjac_cond))/1e-6;
h4dq(kkk) = (h4_kkk-h(idx_hn.jac_cond))/1e-6;
h12dq(kkk) = (norm(abs(Jgk_kkk(Rob_I_EE(1:3),:)) * s.q_poserr)-h(idx_hn.poserr_ee))/1e-6;
end
v = v - wn(idx_wn.ikjac_cond)*h3dq';
v = v - wn(idx_wn.jac_cond)*h4dq';
v = v - wn(idx_wn.poserr_ee)*h12dq';
end
%% Kollisionsvermeidung
if wn(idx_wn.coll_hyp) ~= 0 || wn(idx_wn.coll_par) ~= 0 % Kollisionsvermeidung bzw. Kollisionsabstand
% Bestimme Kollisionen in aktueller Konfiguration. Nutze etwas
% größere Kollisionskörper, damit auch eine Nullraumbewegung
% stattfindet, wenn die Kollision noch nicht erreicht wird.
colldet_warn = false;
colldet = true(1, size(s.collchecks,1)); % Für Kompilierbarkeit
if wn(idx_wn.coll_hyp) ~= 0
% Prüfe danach nur die Fälle, bei denen die vergrößerten
% Objekte bereits eine Kollision angezeigt haben.
colldet = check_collisionset_simplegeom(collbodies_ns, s.collchecks, ...
Tc_stack(:,4)', struct('collsearch', true));
if any(colldet)
colldet_warn = true;
end
end
if wn(idx_wn.coll_par) ~= 0 && ~colldet_warn
% Prüfe im Folgenden Schritt alle Kollisionen
colldet(:) = true;
end
h([idx_wn.coll_hyp, idx_wn.coll_par]) = 0;
if wn(idx_wn.coll_hyp) ~= 0 && colldet_warn || wn(idx_wn.coll_par)
% Inkremente der Gelenkwinkel bilden. Dafür die Gelenkpositionen
% bestimmen (für Kollisionsprüfung)
JP_test = NaN(1+NQJ,size(Tc_stack,1));
JP_test(1,:) = Tc_stack(:,4)';
for kkk = 1:NQJ % Differenzenquotient für jede Gelenkkoordinate
q_test = q1; % ausgehend von aktueller Konfiguration
q_test(kkk) = q_test(kkk) + 1e-6; % minimales Inkrement
% Bestimme Änderung der Gelenkpositionen mit diesem Inkrement
Tc_stack_kkk = %RN%_fkine_coll(q_test, pkin, T_N_E, I_EElink);
JP_test(1+kkk,:) = Tc_stack_kkk(:,4); % Letzte Spalte der homog. Trafo.-Matrix
end
% Kollisionsprüfung für alle Gelenkpositionen auf einmal.
[~, colldist_test] = check_collisionset_simplegeom( ...
s.collbodies, s.collchecks(colldet,:), JP_test, struct('collsearch', false));
I_collcheck_nochange = abs(diff(minmax2(colldist_test')')) < 1e-12;
% Kollisions-Kriterium berechnen: Tiefste Eindringtiefe (positiv)
% Falls keine Kollision vorliegt (mit den kleineren
% Kollisionskörpern), dann Abstände negativ angeben.
if all(I_collcheck_nochange) % Keine Kollision nennenswert geändert
% Setze alle auf exakt den gleichen Wert. Dann Gradient Null.
mincolldist_test = repmat(colldist_test(1), size(colldist_test,1),1);
else % Normale Bestimmung der Abstände möglich
mincolldist_test = min(colldist_test(:,~I_collcheck_nochange),[],2); % Schlimmste Kollision für jeden Körper bestimmen
end
I_collcheck_nochange_all( colldet) = I_collcheck_nochange;
I_collcheck_nochange_all(~colldet) = false;
if nargout == 4
Stats.maxcolldepth(jj,:) = [-min(colldist_test(1,:)),-mincolldist_test(1)];
end
if colldet_warn % (nur im Warnbereich aktiv)
h(idx_hn.coll_hyp) = invkin_optimcrit_limits3(-mincolldist_test(1), ... % zurückgegebene Distanz ist zuerst negativ
[-5*collobjdist_thresh, 0], -collobjdist_thresh);
else
h(idx_hn.coll_hyp) = 0;
end
if wn(idx_wn.coll_hyp) ~= 0 % hyperbolisches Kriterium
hdq = zeros(1,NQJ);
if h(idx_hn.coll_hyp) == 0 || ... % nichts tun. Noch im Toleranzbereich
all(I_collcheck_nochange) % Gradient nicht bestimmbar
hdq(:) = 0;
elseif ~isinf(h(idx_hn.coll_hyp))
for kkk = 1:NQJ
% Kriterium für Inkrement berechnen
h5_test = invkin_optimcrit_limits3(-mincolldist_test(1+kkk), ...
[-5*collobjdist_thresh, 0], -collobjdist_thresh);
% Differenzenquotient
hdq(kkk) = (h5_test-h(idx_hn.coll_hyp))/1e-6;
end
else % Kollision so groß, dass Wert inf ist. Dann kein Gradient aus h bestimmbar.
% Indirekte Bestimmung über die betragsmäßige Verkleinerung der (negativen) Eindringtiefe
for kkk = 1:NQJ
hdq(kkk) = 1e3*(-mincolldist_test(1+kkk)-(-mincolldist_test(1)))/1e-6;
end
currcolldepth = -mincolldist_test(1);
if all(abs(Phi) < 1e-3) % Nur bei finaler Nullraumbewegung sinnvoll
% (sonst Anfahrtbewegung und nicht aussagekräftig)
bestcolldepth = min(bestcolldepth,currcolldepth);
end
end
% Zu Nullraum-Vektor hinzufügen
v = v - wn(idx_wn.coll_hyp)*hdq';
end
h(idx_hn.coll_par) = invkin_optimcrit_limits1(-mincolldist_test(1), ...
[-10*maxcolldepth, 0]); % immer aktiv
if wn(idx_wn.coll_par) ~= 0 && ~all(I_collcheck_nochange) % quadratisches Kriterium
hdq = zeros(1,NQJ);
for kkk = 1:NQJ
% Kriterium für Inkrement berechnen
h8_test = invkin_optimcrit_limits1(-mincolldist_test(1+kkk), ...
[-10*maxcolldepth, 0]);
% Differenzenquotient
hdq(kkk) = (h8_test-h(idx_hn.coll_par))/1e-6;
end
% Zu Nullraum-Vektor hinzufügen
v = v - wn(idx_wn.coll_par)*hdq';
end
end
end
%% Einhaltung der Bauraum-Grenzen
h([idx_hn.instspc_hyp, idx_wn.instspc_par]) = 0;
if wn(idx_wn.instspc_hyp) ~= 0 || wn(idx_wn.instspc_par) ~= 0 % Bauraumeinhaltung
% Inkremente der Gelenkwinkel bilden. Dafür die Gelenkpositionen
% bestimmen (für Kollisionsprüfung)
JP_test = NaN(1+NQJ,size(Tc_stack,1));
JP_test(1,:) = Tc_stack(:,4)';
for kkk = 1:NQJ % Differenzenquotient für jede Gelenkkoordinate
q_test = q1; % ausgehend von aktueller Konfiguration
q_test(kkk) = q_test(kkk) + 1e-6; % minimales Inkrement
% Bestimme Änderung der Gelenkpositionen mit diesem Inkrement
Tc_stack_kkk = %RN%_fkine_coll(q_test, pkin, T_N_E, I_EElink);
JP_test(1+kkk,:) = Tc_stack_kkk(:,4); % Letzte Spalte der homog. Trafo.-Matrix
end
[~, absdist] = check_collisionset_simplegeom(s.collbodies_instspc, ...
s.collchecks_instspc, JP_test, struct('collsearch', false));
% Prüfe, ob alle beweglichen Kollisionsobjekte in mindestens einem
% Bauraumkörper enthalten sind (falls Prüfung gefordert)
I_instspccheck_nochange = abs(diff(minmax2(absdist')')) < 1e-12;
if all(I_instspccheck_nochange) % Keine Bauraumprüfung nennenswert geändert
% Setze alle auf exakt den gleichen Wert. Dann Gradient Null.
mindist_h_all = repmat(absdist(1), size(JP_test,1),1);
else
mindist_h_all = -inf(size(JP_test,1),1);
for i = 1:size(s.collbodies_instspc.link,1)
% Indizes aller Kollisionsprüfungen mit diesem (Roboter-)Objekt i
I = s.collchecks_instspc(:,1) == i & ... % erste Spalte für Roboter-Obj.
~I_instspccheck_nochange';
if ~any(I), continue; end % Bauraum-Objekte nicht direkt prüfen. Sonst leeres Array
% Falls mehrere Bauraum-Objekte, nehme das mit dem besten Wert
mindist_i = min(absdist(:,I),[],2);
% Nehme den schlechtesten Wert von allen Objekten
mindist_h_all = max([mindist_i,mindist_h_all],[],2);
end
end
% Bauraum-Kriterium berechnen: Negativer Wert ist im Bauraum (gut),
% positiver ist außerhalb (schlecht). Größter positiver Wert
% maßgeblich
if wn(idx_wn.instspc_hyp) ~= 0 % Hyperbolisches Kriterium
hdq = zeros(1,NQJ);
h(idx_hn.instspc_hyp) = invkin_optimcrit_limits3(mindist_h_all(1), ... % Wert bezogen auf aktuelle Pose
[-100.0, 0], ... % obere Grenze: Bei Schwelle zur Bauraumverletzung ist Wert inf
-s.installspace_thresh); % obere Grenze: z.B. ab 100mm Nähe zum Rand Kriterium aktiv
if h(idx_hn.instspc_hyp) == 0 || ... % nichts unternehmen (im Bauraum, mit Sicherheitsabstand)
all(I_instspccheck_nochange) % Kein Gradient bestimmbar
hdq(:) = 0;
elseif ~isinf(h(idx_hn.instspc_hyp))
for kkk = 1:NQJ
% Kriterium für Inkrement berechnen
h_test = invkin_optimcrit_limits3(mindist_h_all(1+kkk), ...
[-100.0, 0], -s.installspace_thresh);
% Differenzenquotient
hdq(kkk) = (h_test-h(idx_hn.instspc_hyp))/1e-6;
end
else % Verletzung so groß, dass Wert inf ist. Dann kein Gradient aus h bestimmbar.
% Indirekte Bestimmung über die Verkleinerung des (positiven) Abstands
for kkk = 1:NQJ
hdq(kkk) = 1e3*(mindist_h_all(1+kkk)-mindist_h_all(1))/1e-6;
end
currinstspcdist = mindist_h_all(1);
if all(abs(Phi) < 1e-3)
bestinstspcdist = min(bestinstspcdist,currinstspcdist);
end
end
% Zu Nullraum-Vektor hinzufügen
v = v - wn(idx_wn.instspc_hyp)*hdq';
end
if wn(idx_wn.instspc_par) ~= 0 % Quadratisches Kriterium
hdq = zeros(1,NQJ);
h(idx_hn.instspc_par) = invkin_optimcrit_limits1(mindist_h_all(1), ... % Wert bezogen auf aktuelle Pose
[-100.0, 0]); % Quadratisch bezogen auf -50m als Mitte. Dadurch immer auf rechtem Parabel-Ast
if all(I_instspccheck_nochange) % Kein Gradient bestimmbar
hdq(:) = 0;
else
for kkk = 1:NQJ
% Kriterium für Inkrement berechnen
h_test = invkin_optimcrit_limits1(mindist_h_all(1+kkk), ...
[-100.0, 0]);
% Differenzenquotient
hdq(kkk) = (h_test-h(idx_hn.instspc_par))/1e-6;
end
end
% Zu Nullraum-Vektor hinzufügen
v = v - wn(idx_wn.instspc_par)*hdq';
end
if nargout == 4
% Bestimme auch den Abstand ohne Berücksichtigung der
% beeinflussbaren Prüfungen
mindist_all = -inf; % ähnliche Rechnung wie oben
for i = 1:size(s.collbodies_instspc.link,1)
I = s.collchecks_instspc(:,1) == i;
if ~any(I), continue; end
mindist_i = min(absdist(1,I));
mindist_all = max([mindist_i,mindist_all]);
end
Stats.instspc_mindst(jj,:) = [mindist_all(1),mindist_h_all(1)];
end
end
%% Einhaltung der Grenzen der redundanten Koordinate (rotatorisch)
if any(wn([idx_wn.xlim_par,idx_wn.xlim_hyp]) ~= 0)
% Jacobi-Matrizen werden für folgende Rechnungen benötigt
Jak = [Jgk(1:3,:); Tw_wn \ Jgk(4:6,:)]; % analytische Jacobi-Matrix
T_0_N = %RN%_fkine_fixb_body_rotmat_mdh_sym_varpar(q1, I_EElink, pkin);
T_0_E = T_0_N * T_N_E;
% Bestimme die Abweichung der EE-Rotation zum Sollwert. Benutze
% nicht Phi_voll(4), da der Wert unten widerrufen werden kann.
xr_0_E_ist = r2eul(T_0_E(1:3,1:3), phiconv_W_E);
delta_phi_z = xr_0_E_soll - xr_0_E_ist;
end
if wn(idx_wn.xlim_par) ~= 0 && all(abs(Phi)<1e-3) % quadratische Limitierung der redundanten Koordinate (3T2R)
% Kriterium für aktuellen Iterationsschritt berechnen
[h(idx_hn.xlim_par), h7drz] = invkin_optimcrit_limits1(-delta_phi_z(3), s.xlim(6,1:2));
h7dq = h7drz*Jak(end,:); % Siehe [SchapplerOrt2021], Gl. 14
v = v - wn(idx_wn.xlim_par)*h7dq';
end
if wn(idx_wn.xlim_hyp) ~= 0 && all(abs(Phi)<1e-3) % hyperbolische Limitierung der redundanten Koordinate (3T2R)
% Kriterium für aktuellen Iterationsschritt berechnen
[h(idx_hn.xlim_hyp), h8drz] = invkin_optimcrit_limits2(-delta_phi_z(3), s.xlim(6,1:2), xlim_thr_h8(6,:));
if isinf(h(idx_hn.xlim_hyp))
xD_test_limred = [zeros(5,1); 1e-8];
qD_test = Jak \ xD_test_limred;
if -delta_phi_z(3) <= s.xlim(6,1) + 1e-6
h8dq = -1e6*qD_test';
elseif -delta_phi_z(3) >= s.xlim(6,2) - 1e-6
h8dq = +1e6*qD_test';
else
error('Fall sollte eigentlich nicht vorkommen');
end
% Mache h8dq stärker als die bisher aufsummierten Kriterien.
% Annahme: xlim_hyp kommt als letztes und muss dominieren
if any(v ~= 0) % nur notwendig, falls es andere Kriterien gibt
h8dq = h8dq / min(abs(h8dq'./v));
end
else
h8dq = h8drz*Jak(end,:); % Siehe [SchapplerOrt2021], Gl. 14
end
h8dq(isnan(h8dq)) = 0;
v = v - wn(idx_wn.xlim_hyp)*h8dq';
end
%% Einhaltung der Grenzen der redundanten Koordinate (translatorisch)
if any(wn([idx_wn.xlim_trans_par,idx_wn.xlim_trans_hyp]) ~= 0)
T_0_N = %RN%_fkine_fixb_body_rotmat_mdh_sym_varpar(q1, I_EElink, pkin);
T_0_E = T_0_N * T_N_E;
r_0_D_E = -Tr0E_soll(1:3,4) + T_0_E(1:3,4);
r_D_D_E = R_D_0*r_0_D_E;
dz_2T2R = r_D_D_E(3); % [SchapplerBluJob2022], Sect.3, Variable dz
end
if wn(idx_wn.xlim_trans_par) ~= 0 % Quadratische Limitierung der redundanten Koordinate bei z-Trans (2T2R)
[h(idx_hn.xlim_trans_par), h11drz] = invkin_optimcrit_limits1(dz_2T2R, s.xlim(3,1:2));
Jak_EE_t = R_D_0*Jgk(1:3,:);
h11dq = h11drz*Jak_EE_t(3,:); % Siehe [SchapplerBluJob2022], Gl. 15
v = v - wn(idx_wn.xlim_trans_par)*h11dq';
end
if wn(idx_wn.xlim_trans_hyp) ~= 0 % Hyperbolische Limitierung der redundanten Koordinate bei z-Trans (2T2R)
[h(idx_hn.xlim_trans_hyp), h12drz] = invkin_optimcrit_limits2( ...
dz_2T2R, s.xlim(3,1:2), xlim_thr_h8(3,:));
Jak_EE_t = R_D_0*Jgk(1:3,:);
h12dq = h12drz*Jak_EE_t(3,:); % Siehe [SchapplerBluJob2022], Gl. 15
v = v - wn(idx_wn.xlim_trans_hyp)*h12dq';
end
%% Nullraumbewegung abschließen
% [SchapplerTapOrt2019]/(35); [1], Gl. (24)
N = (eye(NQJ) - pinv(Jdk)* Jdk);
delta_q_N(:) = N * v; % "(:)" notwendig für mex
end
% Reduziere Schrittweite auf einen absoluten Wert. Annahme: Newton-
% Raphson-Verfahren basiert auf Linearisierung. Kleinwinkelnäherung
% wird verlassen, wenn alle Gelenkwinkel in Summe mehr als 20° drehen.
% (moderate Annahme, dass die Gelenke einigermaßen gleichgerichtet drehen)
% Führe das getrennt für delta_q_T und delta_q_N durch, damit die
% Nullraumbewegung nicht die Aufgabenbewegung dominieren kann.
delta_q_T = K.*delta_q_T;
delta_q_N = Kn.*delta_q_N;
sum_abs_delta_qTrev = sum(abs(delta_q_T(sigmaJ==0))); % nur Drehgelenke
if sum_abs_delta_qTrev > 0.35 % 0.35rad=20°
% Reduziere das Gelenk-Inkrement so, dass die Summe der Beträge
% danach 20° ist.
delta_q_T = delta_q_T .* 0.35/sum_abs_delta_qTrev;
end
sum_abs_delta_qNrev = sum(abs(delta_q_N(sigmaJ==0))); % nur Drehgelenke
if sum_abs_delta_qNrev > 0.035*(1-jj/n_max) % 0.035rad=2°
% Reduziere das Gelenk-Inkrement so, dass die Summe der Beträge
% danach 2° ist. Sehr kleine Schritte, damit nur sehr kleine
% Verschlechterung des Residuums durch die Nullraumbewegung.
% Bei 2° wird die lokale Näherung allerdings schon leicht verlassen.
% Verkleinere die Schritte mit fortlaufenden Iterationen, um even-
% tuellen Oszillationen auszugleichen.
delta_q_N = delta_q_N .* 0.035*(1-jj/n_max)/sum_abs_delta_qNrev;
end
% Dämpfung der Nullraumbewegung. Verlangsamt die Konvergenz, reduziert
% dafür Schwingungen zwischen delta_q_T und delta_q_N, die durch keine
% der anderen Stabilisierungsmaßnahmen erfasst werden. Nur machen, wenn
% auch Bewegung im Nullraum (nicht wenn q_N deaktiviert wurde)
if nsoptim && damping_active && any(delta_q_N)
% Korrigiere den Altwert, da bezogen auf andere Gelenkkonfig.
delta_q_N_alt_N = N*delta_q_N_alt;
% Benutze diskretes PT1-Filter mit T=2 (Schritte der IK) und K=1
delta_q_N = delta_q_N_alt_N + 1/(1+2)*(1*delta_q_N-delta_q_N_alt_N);
delta_q_N_alt = delta_q_N;
end
% Prüfe ob mit dem Inkrement eine Kollision erzeugt wird und reduziere
% die Bewegung darauf hin. Ist nur bezugen auf die Aufgabe, da die
% Nullraumbewegung keine Kollision erzeugt (falls das Kriterium benutzt wird)
if scale_coll
% Bestimme Abstand der Objekte vor und nach dem Schritt
Tc_stack_pre = %RN%_fkine_coll(q1, pkin, T_N_E, I_EElink);
Tc_stack_post = %RN%_fkine_coll(q1+delta_q_T, pkin, T_N_E, I_EElink);
[colldet_pp,colldist_pp] = check_collisionset_simplegeom(s.collbodies, s.collchecks, ...
[Tc_stack_pre(:,4)';Tc_stack_post(:,4)'], struct('collsearch', false));
% Prüfe, ob eine Kollision passieren würde und berechne die
% Reduktion des Schrittes, die notwendig ist, um das zu verhindern
if any(colldet_pp(2,:)) % Mit dem geplanten Schritt tritt eine Kollision auf
mindist_pre = min(colldist_pp(1,:));
mindist_post = min(colldist_pp(2,:));
if mindist_pre ~= mindist_post % Nur sinnvoll, wenn Gelenkinkrement die Kollisions-Kennzahl ändert. Sonst entweder Inkrement Null oder Kollisionskörper passen nicht hierzu.
% Mit `scale` wird genau die Grenze zur Kollision erreicht
% (Wert 0; in linearer Näherung)
scale = (0-mindist_pre)/(mindist_post-mindist_pre);
% Durch `scale_coll` wird dieses Erreichen weiter nach "innen" gezogen
delta_q_T = scale_coll * scale * delta_q_T;
end
end
end
% [SchapplerTapOrt2019]/(35); [1], Gl. (23)
% Verstärkungsfaktoren K und Kn oben bereits angewendet.
delta_q = delta_q_T + delta_q_N;
% Reduziere Schrittweite (qT+qN gemeinsam) auf einen Maximalwert
% bezogen auf Winkelgrenzen (bzw. auf die mögliche Spannweite)
if limits_set && ~isnan(maxrelstep)
% Bestimme Inkrement relativ zur Spannbreite der Grenzen
abs_delta_q_rel = abs(delta_q ./ delta_qlim);
if any(abs_delta_q_rel > maxrelstep)
% Ein Element hat ein zu großes Inkrement. Normiere den
% Inkrement-Vektor damit
delta_q = delta_q .* maxrelstep / max(abs_delta_q_rel);
end
end
% Zusätzlicher Dämpfungsterm (gegen Oszillationen insbesondere mit der
% Nullraumbewegung). Aktiviere, sobald Oszillationen erkannt werden
delta_Phi = Phi - Phi_alt;
if damping_active
% Benutze diskretes PT1-Filter mit T=2 (Schritte der IK) und K=1
% Zusätzlich zu obiger Filterung von delta_q_N.
delta_q = delta_q_alt + 1/(1+2)*(1*delta_q-delta_q_alt);
elseif all(sign(delta_q) == -sign(delta_q_alt)) || ...
all(sign(delta_Phi) == -sign(delta_Phi_alt))
damping_active = true; % ab jetzt aktiviert lassen.
end
delta_q_alt = delta_q;
Phi_alt = Phi;
delta_Phi_alt = delta_Phi;
% Gelenkwinkel-Schritt anwenden
q2 = q1 + delta_q;
% Prüfe, ob die Gelenkwinkel ihre Grenzen überschreiten und reduziere
% die Schrittweite, falls das der Fall ist
scale = 1;
if scale_lim
delta_ul_rel = (qmax - q2)./(qmax-q1); % Überschreitung der Maximalwerte: <0
delta_ll_rel = (-qmin + q2)./(q1-qmin); % Unterschreitung Minimalwerte: <0
if any([delta_ul_rel;delta_ll_rel] < 0)
% Berechne die prozentual stärkste Überschreitung
% und nutze diese als Skalierung für die Winkeländerung
% Reduziere die Winkeländerung so, dass die gröte Überschreitung auf
% das Erreichen der Grenzen reduziert wird.
if min(delta_ul_rel)<min(delta_ll_rel)
% Verletzung nach oben ist die größere
[~,I_max] = min(delta_ul_rel);
scale = (qmax(I_max)-q1(I_max))./(delta_q(I_max));
else
% Verletzung nach unten ist maßgeblich
[~,I_min] = min(delta_ll_rel);
scale = (qmin(I_min)-q1(I_min))./(delta_q(I_min));
end
% Mit `scale` werden die Grenzen direkt für ein Gelenk erreicht.
% Durch `scale_lim` wird dieses Erreichen weiter nach "innen" gezogen
delta_q = scale_lim*scale*delta_q;
q2 = q1 + delta_q;
end
end
if any(isnan(q2)) || any(isinf(q2))
if nargout == 4
Stats.iter = jj;
end
break; % ab hier kann das Ergebnis nicht mehr besser werden wegen NaN/Inf
end
% Fehlermaß für aktuelle Iteration (wird auch in nächster Iteration benutzt)
if dof_2T2R == false
[Phi_voll, Tc_stack] = %RN%_constr2(q2, Tr0E_soll, pkin, T_N_E, phiconv_W_E, I_EElink, reci);
else % dof_2T2R == true
Phi_t = %RN%_constr3_trans(q2, Tr0E_soll, pkin, T_N_E, I_EElink, dof_2T2R_xzproj);
[Phi_voll_temp, Tc_stack] = %RN%_constr2(q2, Tr0E_soll, pkin, T_N_E, phiconv_W_E, I_EElink, reci);
Phi_r = Phi_voll_temp(4:6,:); % Für 2T2R nur der rotatorische Teil relevant
Phi_voll = [Phi_t;Phi_r]; % Residuum für 2T2R zusammenstellen
end
if ~use_constr4
Phi_neu = Phi_voll(I_IK);
else
Phi_neu = %RN%_constr4(Phi_voll, s.I_EE, reci);
end
% Prüfe, ob Wert klein genug ist. Bei kleinen Zahlenwerten, ist
% numerisch teilweise keine Verbesserung möglich.
Phi_iO = all(abs(Phi_neu(1:n_Phi_t)) < Phit_tol) && ...
all(abs(Phi_neu(n_Phi_t+1:end)) < Phir_tol);
if Phi_iO && any(delta_q_N) && sum(wn.*h)>=sum(wn.*h_alt) && ~any(isinf(h))
% Prüfe, ob sich die Nebenbedingungen überhaupt noch verbessern. Wenn
% nicht, kann auch abgebrochen werden. Variable delta_q_N dient zur
% Ablaufsteuerung für folgende Abfragen (nicht für Ergebnis selbst).
% Wert von unendlich führt dazu, dass sehr große Gradienten erzeugt
% werden. Dann wird nicht abgebrochen
delta_q_N(:) = 0;
end
if scale_lim && scale == 0
% Die Bewegung wurde komplett herunterskaliert, da die Grenzen
% überschritten wurden. Erhöhe die Nullraumbewegung zur Vermeidung
% der Grenzen. Sonst wird die IK sowieso nicht konvergieren. Annahme:
% Keine Singularität, die mit DLS beseitigt wird.
wn(idx_wn.qlim_hyp) = wn(idx_wn.qlim_hyp) + 0.1;
end
% Prüfe, ob Schritt erfolgreich war (an dieser Stelle, da der
% Altwert von Phi noch verfügbar ist). Siehe [CorkeIK].
Phi_neu_norm = norm(Phi_neu);
Delta_Phi = Phi_neu_norm - norm(Phi); % "neu" - "alt";
bestPhi = min([bestPhi;Phi_neu_norm]);
if any(delta_q_N) && (Delta_Phi > 0 || Phi_neu_norm > bestPhi) && ... % zusätzlich prüfen gegen langsamere Oszillationen
(~any(isinf(h)) && sum(wn.*h)>=sum(wn.*h_alt) || ... % Verschlechterung (bzw. keine Verbesserung) der Opt.-Kriterien
isinf(h(idx_hn.coll_hyp)) && currcolldepth > bestcolldepth || ... % gegen langsame Oszillation für Kollisionsvermeidung aus Eindringtiefe
isinf(h(idx_hn.instspc_hyp)) && currinstspcdist > bestinstspcdist) % das gleiche für Bauraumverletzung
% Zusätzliches Optimierungskriterium hat sich verschlechtert und
% gleichzeitig auch die IK-Konvergenz. Das deutet auf eine
% Konvergenz mit Oszillationen hin. Reduziere den Betrag der
% Nullraumbewegung. Annahme: Bewegung so groß, dass keine
% Linearisierungsfehler (außerhalb des Nullraums).
% Nicht bei Kriterium unendlich (separate Gradientenberechnung).
% Dort ist das Kriterium "keine Verschlechterung" mit > statt >=.
% Der Wert bestcolldepth/bestinstspcdist ist kein Altwert wie h_alt.
Kn = Kn*0.8;
end
if Phi_iO || Delta_Phi < 0 ... % Verbesserung des Residuums
|| any(delta_q_N) && all(abs(Phi_neu)<1e-3) && Delta_Phi~=0 % Bei Nullraumbewegung auch Verschlechterung möglich, wenn noch im "guten" Bereich
if condJik>1e4 && Delta_Phi > -Phit_tol % Singularität mit Mini-Schritten
% Erhöhe Dämpfung um von Singularität wegzukommen. Falls das nicht
% funktioniert, führt das immerhin zu einem relativ frühen Abbruch,
% da lambda gegen unendlich geht und dann sich Phi nicht mehr mit
% Minimal-Schritten numerisch verbessert.
lambda_mult = lambda_mult*2;
else
% Erfolgreich. Verringere lambda bis auf Minimalwert.
lambda_mult = max(lambda_mult/2, lambda_min); % Singularität überwunden
end
% Behalte Ergebnis der Iteration für weitere Iterationen.
q1 = q2;
h_alt = h;
% Behalte Wert für Phi nur in diesem Fall. Dadurch wird auch die Verbesserung
% gegenüber der Iteration messbar, bei der zuletzt eine Verschlechterung eintrat.
if ~use_constr4
Phi = Phi_voll(I_IK); % Reduktion auf betrachtete FG
else
Phi = %RN%_constr4(Phi_voll, s.I_EE, reci);
end
rejcount = 0;
else
% Kein Erfolg. Erhöhe die Dämpfung. Mache den Schritt nicht.
% Setzt voraus, dass die Konditionszahl so schlecht ist, dass
% oben das DLS-Verfahren benutzt wird. Ansonsten Stillstand.
lambda_mult = lambda_mult*2;
rejcount = rejcount + 1;
if condJik <= condlimDLS && ~nsoptim || ... % Keine Verbesserung der Konvergenz trotz guter Konditionszahl.
rejcount > 50 % Stillstand zu lange trotz exponentieller Erhöhung von lambda.
% Abbruch. Keine Verbesserung mit Algorithmus möglich.
if nargout == 4
Stats.iter = jj;
end
break;
end
end
if nargout == 4
Stats.Q(1+jj,:) = q1;
Stats.PHI(1+jj,:) = Phi_voll;
Stats.h(jj,:) = [sum(wn.*h),h'];
Stats.condJ(jj,:) = [condJik, condJ];
Stats.lambda(jj,:) = [lambda, lambda_mult];
Stats.rejcount(jj) = rejcount;
end
% Prüfe Abbruchbedingung für Einhaltung der Winkelgrenzen. Ist dies bei
% "finish_in_limits" der Fall, muss die IK nur noch konvergiert sein.
if break_when_in_limits && (all(q1 >= qmin) && all(q1 <= qmax))
delta_q_N(:) = 0; % unvollständige Nullraumbewegung wird hiernach ignoriert.
% hiernach dürfen die Grenzen nicht mehr verlassen werden (falls
% noch weitere Iterationen gemacht werden)
scale_lim = 0.7;
% Reduziere die Nullraumbewegung ab hier ganz stark. Damit können die
% Grenzen noch leicht nachkorrigiert werden, es dominiert aber die
% Aufgabenbewegung.
Kn = Kn*0.8;
end
% Abbruchbedingungen prüfen
if jj >= n_min ... % Mindestzahl Iterationen erfüllt
&& Phi_iO && ... % Haupt-Bedingung ist erfüllt
( ~nsoptim || ... % und keine Nebenoptimierung läuft
nsoptim && all(abs(delta_q_N) <= maxstep_ns) ) % oder die Nullraumoptimierung läuft noch. "<=" für Fall 0.
success = true;
if finish_in_limits && (any(q1 < qmin) || any(q1 > qmax))
% Es soll eigentlich abgebrochen werden. Die Grenzen wurden aber
% nicht eingehalten. Mache noch mit dem Algorithmus weiter und
% optimiere nur noch die Grenzen (und nicht z.B. Konditionszahl)
finish_in_limits = false; % Modus ist damit aktiviert
nsoptim = true;
wn(:) = 0;
wn(idx_wn.qlim_hyp) = 1;% Nutze nur die hyperbolische Funktion des Abstands
wn(idx_wn.xlim_hyp) = s.wn(idx_wn.xlim_hyp); % ... und limred, falls vorher aktiv
wn(idx_wn.xlim_trans_hyp) = s.wn(idx_wn.xlim_trans_hyp);
% Mache diese Optimierung nicht mehr zu Ende, sondern höre auf,
% wenn die Grenzen erreicht sind.
break_when_in_limits = true;
success = false; % Bereits gesetzten Wert wieder zurücknehmen
Kn = s.Kn; % Änderungen an Standard-Werten zurücksetzen
continue
end
if avoid_collision_finish
% Eigentlich soll abgebrochen werden. Prüfe nochmal auf Kollisionen
colldet = check_collisionset_simplegeom(s.collbodies, s.collchecks, ...
Tc_stack(:,4)', struct('collsearch', false));
if any(colldet)
wn(:) = 0; % Deaktiviere alle anderen Nebenbedingungen
wn(idx_wn.coll_hyp) = 1e3; % Starke Kollisionsvermeidung
avoid_collision_finish = false; % Nur einmal versuchen
success = false; % Bereits gesetzten Wert wieder zurücknehmen
Kn = s.Kn; % Änderungen an Standard-Werten zurücksetzen
continue
end
end
if nargout == 4
Stats.iter = jj; % muss in der jj-Schleife zugewiesen werden (für mex)
end
break;