Skip to content

Commit

Permalink
updated coupling matrices and reduction ratio
Browse files Browse the repository at this point in the history
  • Loading branch information
gabrielenava committed Sep 20, 2018
1 parent 453f765 commit ac77b99
Show file tree
Hide file tree
Showing 12 changed files with 132 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -103,8 +108,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -134,8 +139,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -103,8 +108,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -134,8 +139,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -92,8 +97,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -381,6 +381,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -391,8 +396,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -92,8 +97,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -384,6 +384,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -394,8 +399,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -92,8 +97,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -380,10 +380,14 @@
Config.frequencyOfOscillation = 0.0;

%% Parameters for motors reflected inertia

% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -394,8 +398,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -92,8 +97,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -276,6 +276,11 @@
% transmission ratio
Config.Gamma = 0.01*eye(ROBOT_DOF);

% modify the value of the transmission ratio for the hip pitch.
% TODO: avoid to hard-code the joint numbering
Config.Gamma(end-5, end-5) = 0.0067;
Config.Gamma(end-11,end-11) = 0.0067;

% motors inertia (Kg*m^2)
legsMotors_I_m = 0.0827*1e-4;
torsoPitchRollMotors_I_m = 0.0827*1e-4;
Expand All @@ -286,8 +291,12 @@
armsMotors_I_m*ones(8,1);
legsMotors_I_m*ones(12,1)]);

% parameters for coupling matrices
t = 0.625;
% parameters for coupling matrices. Updated according to the wiki:
%
% http://wiki.icub.org/wiki/ICub_coupled_joints
%
% and corrected according to https://github.com/robotology/robots-configuration/issues/39
t = 0.615;
r = 0.022;
R = 0.04;

Expand Down

0 comments on commit ac77b99

Please sign in to comment.