-
Notifications
You must be signed in to change notification settings - Fork 22
/
Copy pathrun_identification_benchmark.m
1801 lines (1336 loc) · 125 KB
/
run_identification_benchmark.m
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
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%% BIRDy: Benchmark for Identification of Robot Dynamics %%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
% Authors: Quentin Leboutet, Julien Roux, Alexandre Janot and Gordon Cheng
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Benchmark initialization:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
% Reset workspace
clear
close all
% Automatically add the Benchmark folder and its subfolders to the path:
addpath('Utils');
addpath(genpath('Utils'));
addpath('Benchmark');
addpath(genpath('Benchmark'));
% Provide the name of the robot to be identified:
robotName = 'TX40_uncoupled'; % [TX40, TX40_uncoupled, RV2SQ]
% Identify the robot using a subset of the experiment trajectory [t_i, t_f]:
t_i = 0; % Start time.
t_f = 10; % End time.
numberOfInitialEstimates = 25; % Number of different initial estimates (25).
sdOfInitialEstimates = 0.15; % Standard deviation of the initial estimates.
freq_decim = 500; % Decimation frequency used to compute the decimation rate (see the Matlab 'decimate' documentation).
samplingBorder = 50; % Number of samples to be removed from the beginning and the end of the data sequence, in order to mitigate filtering artefacts... (50)
gammaReg = 1e0; % Regularization factor (for methods where regularization is activated)
% Real or Simulated robot ?
experimentOnTrueRobot = false; % If true, indicates that the benchmark is executed on experiment data collected on a true robot.
identifyDriveGains = false; % If true, indicates that the drive gain identification process should be executed.
% Important parameters:
functionTolerance = 2.5e-2; % Function tolerance 2.5%
stepTolerance = 2.5e-2; % Step tolerance 2.5%
iterationMax = 10; % Maximumm number of iterations
% Set the noise level for which the identification has to be done: 'oldNoise', 'lowPositionNoise', 'standardNoise', 'highPositionNoise', 'highTorqueNoise' and 'highPositionTorqueNoise'
noiseLevel = 'lowPositionNoise';
% noiseLevel = 'standardNoise';
% noiseLevel = 'highPositionNoise';
% noiseLevel = 'highTorqueNoise';
% noiseLevel = 'highPositionTorqueNoise';
% noiseLevel = 'oldNoise';
initialParamType = 'RefSd'; % Initial parameter estimate for algorithms that require it: 'RefSd', 'LS', 'LS_f'
regenerateModel = false; % If true, recomputes the robot symbolic model.
regenerateTrajectory = false; % If true, launch the generation routine for new excitation trajectory.
regenerateData = false; % If true, generate new robot simulation data.
generateROSTrajectory = false; % If true, generate a .yaml file containing the joint trajectory
runPostProcessing = true; % If true, runs the post processing function to graph the results.
integrationAlgorithm = 'rk1'; % Defines the integration algorithm used during Identification : 'rk1', 'rk2', 'rk4' or 'ode45'.
interpolator.Algorithm = 'makima'; % Defines the interpolation algorithm used for trajctory data: 'linear', 'nearest', 'next', 'previous', 'pchip', 'cubic', 'v5cubic', 'makima', or 'spline'.
interpolator.expAlgorithm = 'nearest'; % Defines the interpolation algorithm used for experiment data: 'linear', 'nearest', 'next', 'previous', 'pchip', 'cubic', 'v5cubic', 'makima', or 'spline'.
interpolator.visualizeInterpolator = false; % If true, triggers visualization of interpolated trajectories with the different available methods.
% MEX files compilation:
recompileMexFiles = false; % Recompile mex files of the project if true.
buildList = [1 1 1 1 1 1 1 1 1 1 1 1 1]; % List of mex files to be regenerated [torqueVector_mex observationMatrix_mex integrateClosedLoopDynamics_mex ekf_opt_mex srekf_opt_mex ukf_opt_mex srukf_opt_mex cdkf_opt_mex srcdkf_opt_mex pf_opt_mex compute_ML_Cost_mex]
% buildList = [0 0 0 0 0 0 0 0 0 0 0 0 1];
% Filter parameters:
% Low pass filter:
filter.lowpass.d = fdesign.lowpass('Fp,Fst,Ap,Ast', 50, 110, 0.01, 60, 1000); % Design of the filter for the LS with filtered joint acceleration.
filter.lowpass.Hd = design(filter.lowpass.d, 'equiripple');
% Butterworth filter:
filter.butterworth.freq_fil = 50;
filter.butterworth.nfilt = 4;
% Cosmetic parameters:
verboseFlag = true; % If true, the solver communicates the identification error at each step.
debugFlag = false; % If true, the solver plots the robot trajectory using the computed parameters.
displayProgression = false; % If true, display progression GUI for each identification algorithm.
filter.visualizeFilter = false; % Filter tuning
displayTrajectory = false; % If true, display the robot joint trajectory.
displayControlPerformance = false; % If true, display the robot tracking performance on the generated trajectory.
getKinematicSymbolicExpressions = false; % If true, displays the robot homogeneous transforms and jacobians in symbolic form. Note that identificationMethods.isActivated should be zero for this to be working properly.
% Select the identification methods :
identificationMethods.algName = {
'OLS', 'OLS_f',...
'WLS', 'WLS_f', ...
'TLS', 'TLS_f', ...
'IRLS', 'IRLS_f', ...
'ML', 'ML_f','IV',...
'DIDIM', 'CLIE', 'CLOE', ...
'EKF', 'SREKF', ...
'UKF', 'SRUKF', ...
'CDKF', 'SRCDKF', 'PF', ...
'ANN', 'ANN_f', ...
'HTRNN', 'HTRNN_f',...
'PC_OLS', 'PC_OLS_f',...
'PC_WLS', 'PC_WLS_f',...
'PC_IRLS', 'PC_IRLS_f',...
'PC_OLS_Euclidean', 'PC_OLS_Euclidean_f',...
'PC_OLS_Entropic', 'PC_OLS_Entropic_f',...
'PC_OLS_ConstPullback', 'PC_OLS_ConstPullback_f',...
'PC_IV', 'PC_DIDIM'};
identificationMethods.isActivated = ...
[1,...% OLS
1,... % OLS_f
1,... % WLS
1,... % WLS_f
1,... % TLS
1,... % TLS_f
1,... % IRLS
1,... % IRLS_f
1,... % ML
1,... % ML_f
1,... % IV
1,... % DIDIM
1,... % CLIE
1,... % CLOE
1,... % EKF
1,... % SREKF
1,... % UKF
1,... % SRUKF
1,... % CDKF
1,... % SRCDKF
1,... % PF
1,... % ANN
1,... % ANN_f
1,... % HTRNN
1,... % HTRNN_f
1,... % PC_OLS
1,... % PC_OLS_f
1,... % PC_WLS
1,... % PC_WLS_f
1,... % PC_IRLS
1,... % PC_IRLS_f
1,... % PC_OLS_Euclidian
1,... % PC_OLS_Euclidian_f
1,... % PC_OLS_Entropic
1,... % PC_OLS_Entropic_f
1,... % PC_OLS_ConstPullback
1,... % PC_OLS_ConstPullback_f
1,... % PC_IV
1]; % PC_DIDIM
identificationMethods.showResults = ...
[1,...% OLS
1,... % OLS_f
1,... % WLS
1,... % WLS_f
1,... % TLS
1,... % TLS_f
1,... % IRLS
1,... % IRLS_f
1,... % ML
1,... % ML_f
1,... % IV
1,... % DIDIM
1,... % CLIE
1,... % CLOE
1,... % EKF
1,... % SREKF
1,... % UKF
1,... % SRUKF
1,... % CDKF
1,... % SRCDKF
1,... % PF
1,... % ANN
1,... % ANN_f
1,... % HTRNN
1,... % HTRNN_f
1,... % PC_OLS
1,... % PC_OLS_f
1,... % PC_WLS
1,... % PC_WLS_f
1,... % PC_IRLS
1,... % PC_IRLS_f
1,... % PC_OLS_Euclidian
1,... % PC_OLS_Euclidian_f
1,... % PC_OLS_Entropic
1,... % PC_OLS_Entropic_f
1,... % PC_OLS_ConstPullback
1,... % PC_OLS_ConstPullback_f
1,... % PC_IV
1]; % PC_DIDIM
% Run the initialization routine:
[robot, benchmarkSettings, experimentDataStruct, startBenchmark, progressBar] = ...
initBenchmark(robotName, identificationMethods, getKinematicSymbolicExpressions, recompileMexFiles, displayProgression, regenerateModel, ...
regenerateTrajectory, regenerateData, displayTrajectory, displayControlPerformance, t_i, t_f, integrationAlgorithm, interpolator, numberOfInitialEstimates, ...
sdOfInitialEstimates, freq_decim, samplingBorder, buildList, filter, generateROSTrajectory, experimentOnTrueRobot, identifyDriveGains, initialParamType, noiseLevel, gammaReg);
fprintf('Decimation rate: %d\n',benchmarkSettings.decimRate);
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Robot Drive Gains Identification Process (only for real robot data):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identifyDriveGains == true && experimentOnTrueRobot == true
disp("%%%%%%%% Starting Drive Gain Identification %%%%%%%%")
% Set Drive Gains Identification Options:
optionsDriveGainsId.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsDriveGainsId.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsDriveGainsId.solver = 'svd'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function
optionsDriveGainsId.alg = 'WLS'; % [LS]: classic Least Squares, [WLS]: Weighted Least Squares, [TLS]: Total Least Squares, [RR]: Ridge Regression, [WRR]: Weighted Ridge Regression
optionsDriveGainsId.filter = 'butterworth'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Run Drive Gains Identification:
results_DriveGains = run_Drive_Gains_Id(robot, benchmarkSettings, experimentDataStruct, optionsDriveGainsId, progressBar);
disp("%%%%%%%% Finished Grive Gain Identification %%%%%%%%")
benchmarkSettings.identificationMethods.isActivated = 0*identificationMethods.isActivated; % Deactivate other identification methods
identificationMethods.isActivated = 0*identificationMethods.isActivated;
benchmarkSettings.identificationMethods.showResults = 0*identificationMethods.showResults;
runPostProcessing = false;
end
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if (startBenchmark==true) || (runPostProcessing == true)
methodIndex=1;
disp("%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%")
disp("%%%%%%%%%%%% Starting Computations %%%%%%%%%%%%")
disp("%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%")
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Inverse Dynamic Identification Model and Ordinary Least Square (IDIM-OLS):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM_OLS
disp("%%%%%%%%%%%%%%% Starting IDIM-OLS %%%%%%%%%%%%%%%%")
% Set IDIM_OLS Options:
optionsIDIM_LS.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_LS.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_LS.solver ='backslash'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function, [cvx]: use the cvx solver, [mosek]: use the cvx+mosek solver
optionsIDIM_LS.alg = 'OLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsIDIM_LS.regularizerType = 'no'; % [no]: no regularizer, [Euclidean]: Euclidian regularization, [Entropic]: Entropic divergence regularization, [ConstPullback]: Constant Pullback distance regularization
optionsIDIM_LS.gammaReg = 0; % Regularization factor, to be multiplied to the regularizer.
optionsIDIM_LS.filter = 'no'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Run IDIM_OLS Identification:
results_OLS = run_IDIM_LS(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_LS, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_OLS', '-v7.3')
disp("%%%%%%%%%%%%%%% Finished IDIM-OLS %%%%%%%%%%%%%%%%")
end % end IDIM_OLS
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% IDIM and Ordinary Least Square (IDIM-OLS) with Zero-shift Butterworth filter:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM_OLS with 2-pass-Butterworth filter
disp("%%%%%%%%%%%%% Starting IDIM-OLS_f %%%%%%%%%%%%%%")
% Set IDIM_OLS_f Options:
optionsIDIM_LS_f.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_LS_f.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_LS_f.solver = 'backslash'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function, [cvx]: use the cvx solver, [mosek]: use the cvx+mosek solver
optionsIDIM_LS_f.alg = 'OLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsIDIM_LS_f.regularizerType = 'no'; % [no]: no regularizer, [Euclidean]: Euclidian regularization, [Entropic]: Entropic divergence regularization, [ConstPullback]: Constant Pullback distance regularization
optionsIDIM_LS_f.gammaReg = 0; % Regularization factor, to be multiplied to the regularizer.
optionsIDIM_LS_f.filter = 'butterworth'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Run IDIM_OLS_f Identification:
results_OLS_f = run_IDIM_LS(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_LS_f, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_OLS_f', '-v7.3')
disp("%%%%%%%%%%%%%%% Finished IDIM-OLS_f %%%%%%%%%%%%%%%%")
end % end IDIM_OLS_f
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Inverse Dynamic Identification Model and Weighted Least Square (IDIM-WLS):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM_WLS
disp("%%%%%%%%%%%%%%%% Starting IDIM-WLS %%%%%%%%%%%%%%%")
% Set IDIM_WLS Options:
optionsIDIM_WLS.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_WLS.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_WLS.solver ='backslash'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function, [cvx]: use the cvx solver, [mosek]: use the cvx+mosek solver
optionsIDIM_WLS.alg = 'WLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsIDIM_WLS.regularizerType = 'no'; % [no]: no regularizer, [Euclidean]: Euclidian regularization, [Entropic]: Entropic divergence regularization, [ConstPullback]: Constant Pullback distance regularization
optionsIDIM_WLS.gammaReg = 0; % Regularization factor, to be multiplied to the regularizer.
optionsIDIM_WLS.filter = 'no'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Run IDIM_WLS Identification:
results_WLS = run_IDIM_LS(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_WLS, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_WLS', '-v7.3')
disp("%%%%%%%%%%%%%%%% Finished IDIM-WLS %%%%%%%%%%%%%%%%")
end % end IDIM_WLS
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% IDIM and Weighted Least Square (IDIM-WLS) with Zero-shift Butterworth filter:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM_WLS with 2-pass-Butterworth filter
disp("%%%%%%%%%%%%%% Starting IDIM-WLS_f %%%%%%%%%%%%%")
% Set IDIM_WLS_f Options:
optionsIDIM_WLS_f.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_WLS_f.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_WLS_f.solver = 'backslash'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function, [cvx]: use the cvx solver, [mosek]: use the cvx+mosek solver
optionsIDIM_WLS_f.alg = 'WLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsIDIM_WLS_f.regularizerType = 'no'; % [no]: no regularizer, [Euclidean]: Euclidian regularization, [Entropic]: Entropic divergence regularization, [ConstPullback]: Constant Pullback distance regularization
optionsIDIM_WLS_f.gammaReg = 0; % Regularization factor, to be multiplied to the regularizer.
optionsIDIM_WLS_f.filter = 'butterworth'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Run IDIM_WLS_f Identification:
results_WLS_f = run_IDIM_LS(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_WLS_f, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_WLS_f', '-v7.3')
disp("%%%%%%%%%%%%%%%% Finished IDIM-WLS_f %%%%%%%%%%%%%%%%")
end % end IDIM_WLS_f
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Inverse Dynamic Identification Model and Total Least Square (IDIM-TLS):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM_TLS
disp("%%%%%%%%%%%%%%%% Starting IDIM-TLS %%%%%%%%%%%%%%%")
% Set IDIM_TLS Options:
optionsIDIM_TLS.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_TLS.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_TLS.solver = 'svd_ridge'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function, [svd]: compute TLS with svd, [recursive]: compute TLS using Gauss-Newton recursion.
optionsIDIM_TLS.alg = 'TLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsIDIM_TLS.filter = 'no'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Set IDIM_TLS Stop criteria:
optionsIDIM_TLS.stopCrit.tol_1 = functionTolerance;
optionsIDIM_TLS.stopCrit.Max_it = iterationMax;
% Run IDIM_TLS Identification:
results_TLS = run_IDIM_LS(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_TLS, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_TLS', '-v7.3')
disp("%%%%%%%%%%%%%%%% Finished IDIM-TLS %%%%%%%%%%%%%%%")
end % end IDIM_TLS
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Total Least Square (IDIM-TLS_f) with Zero-shift Butterworth filter:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM_TLS_f
disp("%%%%%%%%%%%%%%%% Starting IDIM-TLS_f %%%%%%%%%%%%%%%")
% Set IDIM_TLS Options:
optionsIDIM_TLS_f.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_TLS_f.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_TLS_f.solver = 'svd_ridge'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function, [svd]: compute TLS with svd, [recursive]: compute TLS using Gauss-Newton recursion.
optionsIDIM_TLS_f.alg = 'TLS'; % [LS]: classic Least Squares, [WLS]: Weighted Least Squares, [TLS]: Total Least Squares, [RR]: Ridge Regression, [WRR]: Weighted Ridge Regression
optionsIDIM_TLS_f.filter = 'butterworth'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Set IDIM_TLS Stop criteria:
optionsIDIM_TLS_f.stopCrit.tol_1 = functionTolerance;
optionsIDIM_TLS_f.stopCrit.Max_it = iterationMax;
% Run IDIM_TLS Identification:
results_TLS_f = run_IDIM_LS(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_TLS_f, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_TLS_f', '-v7.3')
disp("%%%%%%%%%%%%%%%% Finished IDIM-TLS_f %%%%%%%%%%%%%%%")
end % end IDIM_TLS_f
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Inverse Dynamic Identification Model and Iteratively Reweighted Least Square (IDIM-IRLS):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM_IRLS
disp("%%%%%%%%%%%%%%%% Starting IDIM-IRLS %%%%%%%%%%%%%%%")
% Set IDIM_WLS Options:
optionsIDIM_IRLS.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_IRLS.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_IRLS.solver ='backslash'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function
optionsIDIM_IRLS.alg = 'IRLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsIDIM_IRLS.regularizerType = 'no'; % [no]: no regularizer, [Euclidean]: Euclidian regularization, [Entropic]: Entropic divergence regularization, [ConstPullback]: Constant Pullback distance regularization
optionsIDIM_IRLS.gammaReg = 0; % Regularization factor, to be multiplied to the regularizer.
optionsIDIM_IRLS.filter = 'no'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Run IDIM_WLS Identification:
results_IRLS = run_IDIM_LS(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_IRLS, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_IRLS', '-v7.3')
disp("%%%%%%%%%%%%%%%% Finished IDIM-IRLS %%%%%%%%%%%%%%%%")
end % end IDIM_WLS
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% IDIM and Iteratively Reweighted Least Square (IDIM-IRLS) with Zero-shift Butterworth filter:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM_IRLS with 2-pass-Butterworth filter
disp("%%%%%%%%%%%%%% Starting IDIM-IRLS_f %%%%%%%%%%%%%")
% Set IDIM_WLS_f Options:
optionsIDIM_IRLS_f.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_IRLS_f.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_IRLS_f.solver = 'backslash'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function
optionsIDIM_IRLS_f.alg = 'IRLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsIDIM_IRLS_f.regularizerType = 'no'; % [no]: no regularizer, [Euclidean]: Euclidian regularization, [Entropic]: Entropic divergence regularization, [ConstPullback]: Constant Pullback distance regularization
optionsIDIM_IRLS_f.gammaReg = 0; % Regularization factor, to be multiplied to the regularizer.
optionsIDIM_IRLS_f.filter = 'butterworth'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Run IDIM_WLS_f Identification:
results_IRLS_f = run_IDIM_LS(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_IRLS_f, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_IRLS_f', '-v7.3')
disp("%%%%%%%%%%%%%%%% Finished IDIM-IRLS_f %%%%%%%%%%%%%%%%")
end % end IDIM_IRLS_f
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Maximum Likelihood estimator:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % ML estimator
disp("%%%%%%%%%%%%%%%%%% Starting ML %%%%%%%%%%%%%%%%%")
% Set ML Options:
optionsML.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsML.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsML.filter = 'no'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
optionsML.optimizer = 'lsqnonlin'; % [simplex], [lsqnonlin], [fmin], [pso] or [ga]
% Set ML Stop criteria:
optionsML.stopCrit.tol_1 = functionTolerance/1000;
optionsML.stopCrit.tol_2 = stepTolerance/1000;
optionsML.stopCrit.Max_it = iterationMax;
% Run ML Identification:
results_ML = run_ML(robot, benchmarkSettings, experimentDataStruct, optionsML, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_ML', '-v7.3')
disp("%%%%%%%%%%%%%%%%%%%% Finished ML %%%%%%%%%%%%%%%%%%%%")
end % end ML
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Maximum Likelihood estimator with Zero-shift Butterworth filter:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % ML_f estimator
disp("%%%%%%%%%%%%%%%%%% Starting ML_f %%%%%%%%%%%%%%%%%")
% Set ML Options:
optionsML_f.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsML_f.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsML_f.filter = 'butterworth'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
optionsML_f.optimizer = 'lsqnonlin'; % [simplex], [lsqnonlin], [fmin], [pso] or [ga]
% Set ML Stop criteria:
optionsML_f.stopCrit.tol_1 = functionTolerance/1000;
optionsML_f.stopCrit.tol_2 = stepTolerance/1000;
optionsML_f.stopCrit.Max_it = iterationMax;
% Run ML Identification:
results_ML_f = run_ML(robot, benchmarkSettings, experimentDataStruct, optionsML_f, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_ML_f', '-v7.3')
disp("%%%%%%%%%%%%%%%%%%%% Finished ML_f %%%%%%%%%%%%%%%%%%%%")
end % end ML_f
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Inverse Dynamic Identification Model and Instrumental Variables (IDIM-IV):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % IDIM-IV
disp("%%%%%%%%%%%%%% Starting IDIM-IV %%%%%%%%%%%%%%")
% Set IDIM_IV Options:
optionsIDIM_IV.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsIDIM_IV.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsIDIM_IV.solver = 'backslash'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function, [cvx]: use the cvx solver, [mosek]: use the cvx+mosek solver
optionsIDIM_IV.alg = 'WLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsIDIM_IV.regularizerType = 'no'; % [no]: no regularizer, [Euclidean]: Euclidian regularization, [Entropic]: Entropic divergence regularization, [ConstPullback]: Constant Pullback distance regularization
optionsIDIM_IV.gammaReg = 0; % Regularization factor, to be multiplied to the regularizer.
optionsIDIM_IV.filter = 'no'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Set IDIM_IV Stop criteria:
optionsIDIM_IV.stopCrit.tol_1 = functionTolerance;
optionsIDIM_IV.stopCrit.tol_2 = stepTolerance;
optionsIDIM_IV.stopCrit.Max_it = iterationMax;
% Run IDIM_IV Identification:
results_IV = run_IDIM_IV(robot, benchmarkSettings, experimentDataStruct, optionsIDIM_IV, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_IV', '-v7.3')
disp("%%%%%%%%%%%%%%%% Finished IDIM-IV %%%%%%%%%%%%%%%%")
end % end IDIM_IV
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Direct and Inverse Dynamic Identification Model (DIDIM):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % DIDIM
disp("%%%%%%%%%%%%%%%%% Starting DIDIM %%%%%%%%%%%%%%%%%")
% Set DIDIM Options:
optionsDIDIM.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsDIDIM.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsDIDIM.solver = 'backslash'; % [backslash]: use the matlab optimized function (x=A\b), [pinv]: use the matlab pseudoinverse function, [cvx]: use the cvx solver, [mosek]: use the cvx+mosek solver
optionsDIDIM.alg = 'WLS'; % [OLS]: Ordinary LS, [WLS]: Weighted LS, [TLS]: Total LS, [IRLS]: Iteratively Reweighted LS, [PC-OLS]: Physically Consistent OLS, [PC-WLS]: Physically Consistent WLS, [PC-IRLS]: Physically Consistent IRLS
optionsDIDIM.regularizerType = 'no'; % [no]: no regularizer, [Euclidean]: Euclidian regularization, [Entropic]: Entropic divergence regularization, [ConstPullback]: Constant Pullback distance regularization
optionsDIDIM.gammaReg = 0; % Regularization factor, to be multiplied to the regularizer.
optionsDIDIM.filter = 'no'; % [no]: no filter, [butterworth]: zero-shift butterworth filter
% Set DIDIM Stop criteria:
optionsDIDIM.stopCrit.tol_1 = functionTolerance;
optionsDIDIM.stopCrit.tol_2 = stepTolerance;
optionsDIDIM.stopCrit.Max_it = iterationMax;
% Run DIDIM Identification:
results_DIDIM = run_DIDIM(robot, benchmarkSettings, experimentDataStruct, optionsDIDIM, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_DIDIM', '-v7.3')
disp("%%%%%%%%%%%%%%%%% Finished DIDIM %%%%%%%%%%%%%%%%%")
end % end DIDIM
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Closed-Loop Input-Error (CLIE) with joint torque input:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % CLIE
disp("%%%%%%%%%%%%%%%% Starting CLIE %%%%%%%%%%%%%%%%%")
% Set CLIE Options:
optionsCLIE.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsCLIE.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsCLIE.isParamWise = false; % If true, run the parameterwise identification, else identify all the parameters at the same time
optionsCLIE.paramwiseOptimizer = 'lsqnonlin'; % [simplex] or [lsqnonlin]
optionsCLIE.globalOptimizer = 'lsqnonlin'; % [simplex], [lsqnonlin], [pso] or [ga]
optionsCLIE.filter = 'no'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
% Set CLIE Stop criteria:
optionsCLIE.stopCrit.tol_1 = functionTolerance/1000;
optionsCLIE.stopCrit.tol_2 = stepTolerance/1000;
optionsCLIE.stopCrit.Max_it = iterationMax;
% Run CLIE Identification:
results_CLIE = run_CLIE(robot, benchmarkSettings, experimentDataStruct, optionsCLIE, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_CLIE', '-v7.3')
disp("%%%%%%%%%%%%%%%%% Finished CLIE %%%%%%%%%%%%%%%%")
end % end CLIE
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Closed-Loop Output-Error (CLOE) with joint position input:
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % CLOE
disp("%%%%%%%%%%%%%%%% Starting CLOE %%%%%%%%%%%%%%%%%")
% Set CLOE Options:
optionsCLOE.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsCLOE.debug = debugFlag; % If true, the solver plots the robot trajectory using the computed parameters.
optionsCLOE.isParamWise = false; % If true, run the parameterwise identification, else identify all the parameters at the same time
optionsCLOE.paramwiseOptimizer = 'lsqnonlin'; % [simplex] or [lsqnonlin]
optionsCLOE.globalOptimizer = 'lsqnonlin'; % [simplex], [lsqnonlin], [pso] or [ga]
optionsCLOE.filter = 'no'; % [no]: no filter, [lowpass]: low pass filter, [butterworth]: zero-shift butterworth filter
optionsCLOE.errorFunction = 'Q'; % [Q] for joint position error function, [Qp] for joint velocity error function and [Qpp] for joint acceleration error function
% Set CLOE Stop criteria:
optionsCLOE.stopCrit.tol_1 = functionTolerance/1000;
optionsCLOE.stopCrit.tol_2 = stepTolerance/1000;
optionsCLOE.stopCrit.Max_it = iterationMax;
% Run CLOE Identification:
results_CLOE = run_CLOE(robot, benchmarkSettings, experimentDataStruct, optionsCLOE, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_CLOE', '-v7.3')
disp("%%%%%%%%%%%%%%%%% Finished CLOE %%%%%%%%%%%%%%%%")
end % end CLOE
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Extended Kalman Filter (EKF):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % EKF
disp("%%%%%%%%%%%%%%%%%% Starting EKF %%%%%%%%%%%%%%%%%%%")
% Set EKF Options:
optionsEKF.useComputedTorque = false; % If true, run the kalman filter in CLOE mode
optionsEKF.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsEKF.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsEKF.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsEKF.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsEKF.samplingFactor = 100;
optionsEKF.type = 'ekf';
% Run EKF Identification:
results_EKF = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsEKF, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_EKF', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished EKF %%%%%%%%%%%%%%%%%%")
end % end EKF
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Square Root Extended Kalman Filter (SREKF):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % SREKF
disp("%%%%%%%%%%%%%%%%%% Starting SREKF %%%%%%%%%%%%%%%%%%%")
% Set SREKF Options:
optionsSREKF.useComputedTorque = false; % If true, run the kalman filter in CLOE mode
optionsSREKF.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsSREKF.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsSREKF.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsSREKF.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsSREKF.samplingFactor = 100;
optionsSREKF.type = 'srekf';
% Run SREKF Identification:
results_SREKF = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsSREKF, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_SREKF', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished SREKF %%%%%%%%%%%%%%%%%%")
end % end SREKF
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Unscented Kalman Filter (UKF):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % UKF
disp("%%%%%%%%%%%%%%%%%% Starting UKF %%%%%%%%%%%%%%%%%%")
% Set UKF Options:
optionsUKF.useComputedTorque = false; % If true, run the kalman filter in CLOE mode
optionsUKF.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsUKF.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsUKF.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsUKF.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsUKF.samplingFactor = 100;
optionsUKF.type = 'ukf';
optionsUKF.sigmaCompute = 'svd'; % [svd]: compute matrix square root using svd, [chol]: compute matrix square root using Cholesky factorization.
% Run UKF Identification:
results_UKF = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsUKF, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_UKF', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished UKF %%%%%%%%%%%%%%%%%%")
end % end UKF
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Square Root Unscented Kalman Filter (SRUKF):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % SRUKF
disp("%%%%%%%%%%%%%%%%%% Starting SRUKF %%%%%%%%%%%%%%%%%%")
% Set SRUKF Options:
optionsSRUKF.useComputedTorque = false; % If true, run the kalman filter in CLOE mode
optionsSRUKF.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsSRUKF.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsSRUKF.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsSRUKF.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsSRUKF.samplingFactor = 100;
optionsSRUKF.type = 'srukf';
% Run SRUKF Identification:
results_SRUKF = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsSRUKF, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_SRUKF', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished SRUKF %%%%%%%%%%%%%%%%%%")
end % end SRUKF
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Central Difference Kalman Filter (CDKF):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % CDKF
disp("%%%%%%%%%%%%%%%%%% Starting CDKF %%%%%%%%%%%%%%%%%%")
% Set CDKF Options:
optionsCDKF.useComputedTorque = false; % If true, run the kalman filter in CLOE mode
optionsCDKF.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsCDKF.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsCDKF.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsCDKF.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsCDKF.samplingFactor = 100;
optionsCDKF.type = 'cdkf';
optionsCDKF.sigmaCompute = 'svd'; % [svd]: compute matrix square root using svd, [chol]: compute matrix square root using Cholesky factorization.
% Run CDKF Identification:
results_CDKF = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsCDKF, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_CDKF', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished CDKF %%%%%%%%%%%%%%%%%%")
end % end CDKF
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Square Root Central Difference Kalman Filter (SRCDKF):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % SRCDKF
disp("%%%%%%%%%%%%%%%%%% Starting SRCDKF %%%%%%%%%%%%%%%%%%")
% Set SRCDKF Options:
optionsSRCDKF.useComputedTorque = false; % If true, run the kalman filter in CLOE mode
optionsSRCDKF.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsSRCDKF.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsSRCDKF.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsSRCDKF.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsSRCDKF.samplingFactor = 100;
optionsSRCDKF.type = 'srcdkf';
% Run SRCDKF Identification:
results_SRCDKF = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsSRCDKF, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_SRCDKF', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished SRCDKF %%%%%%%%%%%%%%%%%%")
end % end SRCDKF
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Particle Filter (PF):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % PF
disp("%%%%%%%%%%%%%%%%%% Starting PF %%%%%%%%%%%%%%%%%%")
% Set PF Options:
optionsPF.useComputedTorque = false; % If true, run the paticle filter in CLOE mode
optionsPF.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsPF.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsPF.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsPF.samplingFactor = 100; % How often is the debug information displayed
optionsPF.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsPF.nbParticules = 25*robot.paramVectorSize;
optionsPF.initialBias = 5e-2;
optionsPF.type = 'pf';
optionsPF.resampleThreshold = 1e-2; % Resampling occurs each resampleThreshold iterations
% Run PF Identification:
results_PF = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsPF, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_PF', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished PF %%%%%%%%%%%%%%%%%%")
end % end PF
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Extended Kalman Filter with computed torque (EKF_ct):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % EKF_ct
disp("%%%%%%%%%%%%%%%%%% Starting EKF_ct %%%%%%%%%%%%%%%%%%%")
% Set EKF_ct Options:
optionsEKF_ct.useComputedTorque = true; % If true, run the kalman filter in CLOE mode
optionsEKF_ct.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsEKF_ct.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsEKF_ct.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsEKF_ct.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsEKF_ct.samplingFactor = 100;
optionsEKF_ct.type = 'ekf';
% Run EKF_ct Identification:
results_EKF_ct = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsEKF_ct, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_EKF_ct', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished EKF_ct %%%%%%%%%%%%%%%%%%")
end % end EKF_ct
methodIndex=methodIndex+1;
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Square Root Extended Kalman Filter with computed torque (SREKF_ct):
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
if identificationMethods.isActivated(methodIndex)==1 % SREKF_ct
disp("%%%%%%%%%%%%%%%%%% Starting SREKF_ct %%%%%%%%%%%%%%%%%%%")
% Set SREKF_ct Options:
optionsSREKF_ct.useComputedTorque = true; % If true, run the kalman filter in CLOE mode
optionsSREKF_ct.verbose = verboseFlag; % If true, the solver communicates the identification error at each step.
optionsSREKF_ct.debug = debugFlag; % If true, the solver plots the parameter evolution.
optionsSREKF_ct.getIterationData = false; % If true, saves the augmented state estimate and its covariance matrix each samplingFactor iteration. Produces MASSIVE data files !
optionsSREKF_ct.anneal = true; % If true, anneals the process noise covariance of the parameters with time.
optionsSREKF_ct.samplingFactor = 100;
optionsSREKF_ct.type = 'srekf';
% Run SREKF_ct Identification:
results_SREKF_ct = run_Kalman(robot, benchmarkSettings, experimentDataStruct, optionsSREKF_ct, progressBar);
% Save the Results:
if ~exist(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate), 'dir')
mkdir(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d', robot.name,noiseLevel,benchmarkSettings.decimRate));
end
save(sprintf('Benchmark/Robot_Identification_Results/%s_%s/decim_%d/results_%s_%s.mat',robot.name,noiseLevel,benchmarkSettings.decimRate,identificationMethods.algName{methodIndex},robot.name), 'results_SREKF_ct', '-v7.3')
disp("%%%%%%%%%%%%%%%%%% Finished SREKF_ct %%%%%%%%%%%%%%%%%%")