Merge branch 'bugFix/ols-pc-ols' into 'master'

bugfix code can be run

See merge request robotics/dynamic-calibration!1
This commit is contained in:
Rui 2024-01-07 03:22:22 +00:00
commit 512ad8464b
2 changed files with 6 additions and 6 deletions

View File

@ -1,9 +1,9 @@
function tau_frcn = F_vctr_fcn(in1,in2) function tau_frcn = F_vctr_fcn(in1,in2)
%F_VCTR_FCN %F_vctr_fcn
% TAU_FRCN = F_VCTR_FCN(IN1,IN2) % TAU_FRCN = F_vctr_fcn(IN1,IN2)
% This function was generated by the Symbolic Math Toolbox version 8.2. % This function was generated by the Symbolic Math Toolbox version 9.1.
% 20-Oct-2021 10:57:15 % 06-Jan-2024 18:16:41
pi_frcn_11 = in2(1,:); pi_frcn_11 = in2(1,:);
pi_frcn_21 = in2(2,:); pi_frcn_21 = in2(2,:);

4
main.m
View File

@ -27,7 +27,7 @@ include_motor_dynamics = 1;
% Estimate drive gains % Estimate drive gains
drive_gains = estimate_drive_gains(baseQR, 'PC-OLS'); drive_gains = estimate_drive_gains(baseQR, 'OLS');
% Or use those found in the paper by De Luca % Or use those found in the paper by De Luca
% drive_gains = [14.87; 13.26; 11.13; 10.62; 11.03; 11.47]; % drive_gains = [14.87; 13.26; 11.13; 10.62; 11.03; 11.47];
@ -38,7 +38,7 @@ path_to_est_data = 'ur-20_02_10-30sec_12harm.csv'; idxs = [635, 3510];
% path_to_data = 'ur-20_02_05-20sec_8harm.csv'; idxs = [320, 2310]; % path_to_data = 'ur-20_02_05-20sec_8harm.csv'; idxs = [320, 2310];
% path_to_data = 'ur-20_02_12-50sec_12harm.csv'; idxs = [355, 5090]; % path_to_data = 'ur-20_02_12-50sec_12harm.csv'; idxs = [355, 5090];
sol = estimate_dynamic_params(path_to_est_data, idxs, ... sol = estimate_dynamic_params(path_to_est_data, idxs, ...
drive_gains, baseQR, 'PC-OLS'); drive_gains, baseQR, 'OLS');
% Validate estimated parameters % Validate estimated parameters