Tables
Joint Limits
Can be found at Motores: motores
DH Parameters
Group: head
trunk for head (root to neck)
dh-root-head.csv
| Link |
θ |
D |
A |
α |
| 1 |
q13 |
l0 |
0 |
-90 |
| 2 |
q14 |
0 |
0 |
90 |
head
dh-head.csv
| Link |
θ |
D |
A |
α |
| 1 |
q27 |
l1+l2 |
0 |
-90 |
| 2 |
q28 |
0 |
0 |
90 |
dh-head-transformations.csv
| Name |
Transformation |
| H_head_rgb |
TrasZ(l3) * RotZ(-90) * RotX(-90) * TrasX(-l14) |
| H_head_depth |
TrasZ(l3) * RotZ(-90) * RotX(-90) * TrasX(-l14-l15) |
| H_head_flea |
TrasZ(l3+l4) * RotZ(-90) * RotX(-90) |
Group: rightArm
trunk for rightArm (root to rightArm)
dh-root-rightArm.csv
| Link |
θ |
D |
A |
α |
| 1 |
q13 |
l0 |
0 |
-90 |
| 2 |
-90+q14 |
-l5 |
l1 |
0 |
rightArm
dh-rightArm.csv
| Link |
θ |
D |
A |
α |
| 1 |
q15 |
0 |
0 |
-90 |
| 2 |
-90+q16 |
0 |
0 |
-90 |
| 3 |
-90+q17 |
-l6 |
0 |
-90 |
| 4 |
q18 |
0 |
0 |
90 |
| 5 |
q19 |
-l7 |
0 |
-90 |
| 6 |
-90+q20 |
0 |
-l8 |
0 |
fetch (right)
dh-fetch.csv
| Link |
θ |
D |
A |
α |
| 1 |
-90 |
0 |
0 |
90 |
| 2 |
0 |
lf |
0 |
0 |
Group: leftArm
trunk for leftArm (root to leftArm)
dh-root-leftArm.csv
| Link |
θ |
D |
A |
α |
| 1 |
q13 |
l0 |
0 |
-90 |
| 2 |
-90+q14 |
l5 |
l1 |
0 |
leftArm
dh-leftArm.csv
| Link |
θ |
D |
A |
α |
| 1 |
q21 |
0 |
0 |
-90 |
| 2 |
-90+q22 |
0 |
0 |
-90 |
| 3 |
-90+q23 |
-l6 |
0 |
-90 |
| 4 |
q24 |
0 |
0 |
90 |
| 5 |
q25 |
-l7 |
0 |
-90 |
| 6 |
-90+q26 |
0 |
-l8 |
0 |
fetch (left)
dh-fetch.csv
| Link |
θ |
D |
A |
α |
| 1 |
-90 |
0 |
0 |
90 |
| 2 |
0 |
lf |
0 |
0 |
Group: rightLeg
root to rightLeg
dh-root-rightLeg.csv
| Link |
θ |
D |
A |
α |
| 1 |
90 |
-l9 |
-l13 |
0 |
rightLeg
dh-rightLeg.csv
| Link |
θ |
D |
A |
α |
| 1 |
q6 |
0 |
0 |
90 |
| 2 |
90+q5 |
0 |
0 |
90 |
| 3 |
q4 |
0 |
-l10 |
0 |
| 4 |
q3 |
l16 |
-l11 |
0 |
| 5 |
q2 |
0 |
0 |
-90 |
| 6 |
q1 |
0 |
-l12 |
0 |
Group: leftLeg
root to leftLeg
dh-root-leftLeg.csv
| Link |
θ |
D |
A |
α |
| 1 |
90 |
-l9 |
l13 |
0 |
leftLeg
dh-leftLeg.csv
| Link |
θ |
D |
A |
α |
| 1 |
q7 |
0 |
0 |
90 |
| 2 |
90+q8 |
0 |
0 |
90 |
| 3 |
q9 |
0 |
-l10 |
0 |
| 4 |
q10 |
-l16 |
-l11 |
0 |
| 5 |
q11 |
0 |
0 |
-90 |
| 6 |
q12 |
0 |
-l12 |
0 |
The below are not required at time of writing, and may become outdated with time.
Deprecated trunk (root to hip)
This is the original trunk, but the three variants (for head, rightArm, leftArm; respectively, above) seem to be more useful.
deprecated/dh-trunk.csv
| Link |
θ |
D |
A |
α |
| 1 |
q13 |
l0 |
0 |
-90 |
| 2 |
q14 |
0 |
0 |
0 |
Some not required, redundant or may be derived from from existing dh-root-*.csv contents (above).
deprecated/dh-transformations.csv
| Name |
Transformation |
| H_hip_neck |
RotX(90) |
| H_hip_leftArm |
TrasZ(l5) * RotZ(-90) * TrasX(l1) |
| H_hip_rightArm |
TrasZ(-l5) * RotZ(-90) * TrasX(l1) |
Link Lengths
lengths.csv
| lengths |
distance [mm] |
| l0 |
193.2 |
| l1 |
305 |
| l2 |
162.5 |
| l3 |
59.742 |
| l4 |
37.508 |
| l5 |
346.92 |
| l6 |
329.01 |
| l7 |
215 |
| l8 |
90 |
| l9 |
92 |
| l10 |
330 |
| l11 |
300 |
| l12 |
123.005 |
| l13 |
146 |
| l14 |
18 |
| l15 |
26 |
| l16 |
17.5 |
| lf |
97.5 |
Bill of materials (BOM)
bom.csv
| Device |
Brand |
Model |
YARP device |
Desciption/Comments |
| EC Motor |
Maxon |
339282/339287/400108/402686/411815 |
nan |
30/50/70 W |
| Motor Driver |
Technosoft |
iPOS 3602/3604/4808 (MX) |
TechnosoftIpos |
3602 -> front wrist 3604 -> all except legs and trunk 4808 -> legs and trunk |
| Relative Encoder |
CUI Inc |
AMT 203-V |
TechnosoftIpos |
nan |
| Absolute Encoder |
CUI Inc |
AMT 203-V |
CuiAbsolute |
Uses PIC18F2580 |
| Force-Torque Sensor |
JR3 |
50M31A3-125-DH |
Jr3 |
50M31A3-125-DH -> wrist ((( unknown ))) -> ankle |
| Inertial Sensor |
XSENS |
MTi-28A53G35 |
xsensmtx |
Product ID: MTi-28A53G35 Device ID: 00305355 |
| RGBD Sensor |
ASUS |
XtionPRO Live |
OpenNI2Server |
RGB and Depth Sensor |
| RGB Camera |
Point Grey |
Flea3 FL3-U3-88S2C-C |
AravisGigE |
USB3 |
| Fetch Hand |
Lacquey |
Fetch Hand |
LacqueyFetch |
Three finger underactuated |
| CAN board |
PEAK-System |
PCAN-M.2 |
CanBusPeak |
Four channels |
Motores
Motores: motores
motores-motores.csv
| Joint |
Label |
CAN Bus |
CAN ID |
YARP Port |
YARP ID |
MOTOR |
R. total |
Hard. Limit Min (degrees) |
Hard. Limit Max (degrees) |
Soft. Limit Min (degrees) |
Soft. Limit Max (degrees) |
Human-inspired Min Limit (degrees) |
Human-inspired Max Limit (degrees) |
| SagittalRightAnkle |
SRA1 |
Locomotion /dev/can0 |
1 |
/teo/rightLeg |
5 |
402686 |
235.2 |
-24.9561 |
47.522 |
-19.9 |
42.5 |
-5 |
5 |
| FrontalRightAnkle |
FRA2 |
Locomotion /dev/can0 |
2 |
/teo/rightLeg |
4 |
411815 |
270.4 |
-28.1195 |
30.3867 |
-23.1 |
25.4 |
-20 |
25.4 |
| FrontalRightKnee |
FRK3 |
Locomotion /dev/can0 |
3 |
/teo/rightLeg |
3 |
402686 |
235.2 |
-66.3269 |
87.4341 |
-61.3 |
82.4 |
0 |
82.4 |
| FrontalRightHip |
FRH4 |
Locomotion /dev/can0 |
4 |
/teo/rightLeg |
2 |
402686 |
192 |
-36.6257 |
47.2759 |
-31.6 |
42.3 |
-31.6 |
30 |
| SagittalRightHip |
SRH5 |
Locomotion /dev/can0 |
5 |
/teo/rightLeg |
1 |
402686 |
523.2 |
-19.2443 |
17.4868 |
-14.2 |
12.5 |
-14.2 |
12.5 |
| AxialRightHip |
ARH6 |
Locomotion /dev/can0 |
6 |
/teo/rightLeg |
0 |
339287 |
400 |
-37.7856 |
32.935 |
-32.8 |
27.9 |
-32.8 |
27.9 |
| FrontalTrunk |
FT14 |
Locomotion /dev/can0 |
14 |
/teo/trunk |
1 |
339287 |
480 |
-95.413 |
15.1142 |
-90.4 |
10.1 |
-90.4 |
10.1 |
| AxialTrunk |
AT13 |
Locomotion /dev/can1 |
13 |
/teo/trunk |
0 |
411815 |
160 |
-51.3181 |
51.3181 |
-59.3 |
46.3 |
-30 |
30 |
| AxialLeftHip |
ALH7 |
Locomotion /dev/can1 |
7 |
/teo/leftLeg |
0 |
339287 |
400 |
-32.935 |
37.7856 |
-27.9 |
32.8 |
-27.9 |
32.8 |
| SagittalLeftHip |
SLH8 |
Locomotion /dev/can1 |
8 |
/teo/leftLeg |
1 |
402686 |
523.2 |
-17.4868 |
19.2443 |
-12.5 |
14.2 |
-12.5 |
14.2 |
| FrontalLeftHip |
FLH9 |
Locomotion /dev/can1 |
9 |
/teo/leftLeg |
2 |
411815 |
192 |
-36.6257 |
47.2759 |
-31.6 |
42.3 |
-31.6 |
30 |
| FrontalLeftKnee |
FLK10 |
Locomotion /dev/can1 |
10 |
/teo/leftLeg |
3 |
402686 |
235.2 |
-66.3269 |
87.4341 |
-61.3 |
82.4 |
0 |
82.4 |
| FrontalLeftAnkle |
FLA11 |
Locomotion /dev/can1 |
11 |
/teo/leftLeg |
4 |
402686 |
270.4 |
-28.1195 |
30.3867 |
-23.1 |
25.4 |
-20 |
25.4 |
| SagittalLeftAnkle |
SLA12 |
Locomotion /dev/can1 |
12 |
/teo/leftLeg |
5 |
402686 |
235.2 |
-47.522 |
24.9561 |
-42.5 |
19.9 |
-5 |
5 |
| FrontalRightShoulder |
FRS15 |
Manipulation /dev/can2 |
15 |
/teo/rightArm |
0 |
411815 |
160 |
-103.076 |
110.967 |
-98.1 |
106 |
-98.1 |
45 |
| SagittalRightShoulder |
SRS16 |
Manipulation /dev/can2 |
16 |
/teo/rightArm |
1 |
411815 |
160 |
-80.4745 |
27.4165 |
-75.5 |
22.4 |
-75.5 |
22.4 |
| AxialRightShoulder |
ARS17 |
Manipulation /dev/can2 |
17 |
/teo/rightArm |
2 |
608141 |
120 |
-85.1494 |
62.0211 |
-80.1 |
57 |
-40 |
55 |
| FrontalRightElbow |
FRE18 |
Manipulation /dev/can2 |
18 |
/teo/rightArm |
3 |
411815 |
160 |
-104.569 |
103.409 |
-99.6 |
98.4 |
-99.6 |
5 |
| AxialRightWrist |
ARW19 |
Manipulation /dev/can2 |
19 |
/teo/rightArm |
4 |
400108 |
120 |
-85.413 |
104.64 |
-80.4 |
99.6 |
-80.4 |
90 |
| FrontalRightWrist |
FRW20 |
Manipulation /dev/can2 |
20 |
/teo/rightArm |
5 |
339282 |
120 |
-120.123 |
49.7188 |
-115.1 |
44.7 |
-70 |
44.7 |
| FrontalNeck |
FN28 |
Manipulation /dev/can2 |
28 |
/teo/head |
1 |
nan |
nan |
nan |
nan |
-10 |
10 |
nan |
nan |
| AxialNeck |
AN27 |
Manipulation /dev/can3 |
27 |
/teo/head |
0 |
nan |
nan |
nan |
nan |
-60 |
60 |
nan |
nan |
| FrontalLeftShoulder |
FLS21 |
Manipulation /dev/can3 |
21 |
/teo/leftArm |
0 |
411815 |
160 |
-101.828 |
118.19 |
-96.8 |
113.2 |
-96.8 |
45 |
| SagittalLeftShoulder |
SLS22 |
Manipulation /dev/can3 |
22 |
/teo/leftArm |
1 |
411815 |
160 |
-28.8928 |
81.4587 |
-23.9 |
76.5 |
-23.9 |
76.5 |
| AxialLeftShoulder |
ALS23 |
Manipulation /dev/can3 |
23 |
/teo/leftArm |
2 |
400108 |
120 |
-56.5905 |
89.0861 |
-51.6 |
84.1 |
-51.6 |
40 |
| FrontalLeftElbow |
FLE24 |
Manipulation /dev/can3 |
24 |
/teo/leftArm |
3 |
339282 |
160 |
-106.134 |
101.845 |
-101.1 |
96.8 |
-101.1 |
5 |
| AxialLeftWrist |
ALW25 |
Manipulation /dev/can3 |
25 |
/teo/leftArm |
4 |
339282 |
120 |
-106.327 |
81.4411 |
-101.3 |
76.4 |
-90 |
76.4 |
| FrontalLeftWrist |
FLW26 |
Manipulation /dev/can3 |
26 |
/teo/leftArm |
5 |
339282 |
120 |
-118.26 |
66.3445 |
-113.3 |
61.3 |
-70 |
61.3 |
Motores: protecciones-brazos
motores-protecciones-brazos.csv
| Unnamed: 0 |
Unnamed: 1 |
Hombro Frontal |
Hombro Sagital |
Hombro Axial |
Codo Frontal |
Muñeca Axial |
Muñeca Frontal |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Ref Motor |
nan |
339282 |
339282 |
339282 |
339282 |
339282 |
339282 |
| driver |
nan |
iPOS3604 |
iPOS3604 |
iPOS3604 |
iPOS3604 |
iPOS3602 |
iPOS3604 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Corriente Nominal (A) |
Inom |
0.849 |
0.849 |
0.849 |
0.849 |
0.849 |
0.849 |
| Temperatura Max del bobinado (ºC) |
Tmax |
125 |
125 |
125 |
125 |
125 |
125 |
| Temperatura final del bobinado (ºC) |
Tw,∞ |
100 |
100 |
80 |
100 |
80 |
100 |
| Corriente Max de trabajo (A) |
Ipeak |
5.38 |
5.38 |
5.38 |
5.38 |
3.20 |
5.38 |
| Resistencia termica bobinado (K/W) |
Rth1 |
3.96 |
3.96 |
3.96 |
3.96 |
3.96 |
3.96 |
| Resistencia termica carcasa (K/W) |
Rth2 |
5.70 |
5.70 |
5.70 |
5.70 |
5.70 |
5.70 |
| Constante de tiempo termica (s) |
τw |
18.25 |
18.25 |
18.25 |
18.25 |
18.25 |
18.25 |
| Coeficiente de resistencia Cu (K-1) |
αCU |
0.0039 |
0.0039 |
0.0039 |
0.0039 |
0.0039 |
0.0039 |
| Resistencia del motor (Ω) |
Rmot |
6.69 |
6.69 |
6.69 |
6.69 |
6.69 |
6.69 |
| PROTECCION DE CORRIENTES DE PICO |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Factor de sobrecarga |
K |
8.1145 |
8.1145 |
6.0482 |
8.1145 |
3.5975 |
8.1145 |
| Tiempo de Corte de sobrecarga (s) |
ton |
0.2793 |
0.2793 |
0.5059 |
0.2793 |
1.4679 |
0.2793 |
| PROTECCION DE CORRIENTES DE i2t |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Perdidas por efecto Joule (W) |
PJ |
7.7640 |
7.7640 |
5.6936 |
7.7640 |
5.6936 |
7.7640 |
| Resistencia del bobinado a Tw,∞(Ω) |
RTW |
8.6468 |
8.6468 |
8.1250 |
8.6468 |
8.1250 |
8.6468 |
| Corriente I2t (A) |
II2t |
0.9476 |
0.9476 |
0.8371 |
0.9476 |
0.8371 |
0.9476 |
| Tiempo de Corte de I2t (s) |
t |
25.3053 |
25.3053 |
14.5759 |
25.3053 |
14.5759 |
25.3053 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Motor |
Tensión (V) |
Peso (Gr) |
Par max (Nm) |
Par RMS (Nm) |
I max (A) |
I RMS (A) |
Vel. Nom (rpm) |
| Flat Brushless EC 45 30W (339282) |
36 |
110 |
0.337 |
0.0666 |
5.38 |
0.849 |
4760 |
| Driver |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| iPOS3604MX-CAN |
36 |
,,, |
,,, |
,,, |
10 (2,5s) |
4 |
,,, |
Motores: protecciones-piernas
motores-protecciones-piernas.csv
| Unnamed: 0 |
Unnamed: 1 |
Tobillo Sagital |
Tobillo Frontal |
Rodilla |
Cadera Frontal |
Cadera Sagital |
Cadera Axial |
| Torques RMS Articulación (Nm) |
nan |
18.71 |
25.15 |
26.72 |
10.22 |
53.39 |
3.20 |
| Torques Max Articulación (Nm) |
nan |
49.70 |
59.43 |
61.86 |
25.99 |
84.41 |
7.24 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Relación de Red. Poleas |
nan |
1.47 |
1.69 |
1.47 |
1.2 |
3.27 |
2.5 |
| Torques Constant (mNm/A) |
nan |
33.5 |
53.3 |
53.3 |
53.3 |
101 |
101 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Torques RMS Motor (Nm) |
nan |
0.0796 |
0.0930 |
0.1136 |
0.0533 |
0.1020 |
0.0080 |
| Torques Max Motor (Nm) |
nan |
0.2113 |
0.2198 |
0.2630 |
0.1354 |
0.1613 |
0.0181 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Velocidad Eje Max |
nan |
24.9040 |
8.1382 |
32.9043 |
30.1766 |
4.2060 |
0.0000 |
| Velocidad Motor Max |
nan |
5857.4200 |
2200.5700 |
7739.1000 |
5793.9000 |
2200.5700 |
0.0000 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Currents RMS Motor (A) |
nan |
2.3748 |
1.7451 |
2.1317 |
0.9991 |
1.0104 |
0.0793 |
| Currents Max Motor (A) |
nan |
6.3078 |
4.1235 |
4.9344 |
2.5402 |
1.5974 |
0.1792 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Ref Motor |
nan |
251601 |
402686 |
402686 |
402686 |
339287 |
339287 |
| driver |
nan |
iPOS3604 |
iPOS3604 |
iPOS3604 |
iPOS3604 |
iPOS3602 |
iPOS3604 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Corriente Nominal (A) |
Inom |
2.360 |
1.930 |
1.930 |
1.930 |
0.861 |
0.861 |
| Temperatura Max del bobinado (ºC) |
Tmax |
125 |
125 |
125 |
125 |
125 |
125 |
| Temperatura final del bobinado (ºC) |
Tw,∞ |
100 |
100 |
100 |
100 |
100 |
100 |
| Corriente Max de trabajo (A) |
Ipeak |
20.00 |
20.00 |
20.00 |
20.00 |
4.86 |
4.86 |
| Resistencia termica bobinado (K/W) |
Rth1 |
4.50 |
4.22 |
4.22 |
4.22 |
4.50 |
4.50 |
| Resistencia termica carcasa (K/W) |
Rth2 |
4.25 |
3.25 |
3.25 |
3.25 |
4.25 |
4.25 |
| Constante de tiempo termica (s) |
τw |
26.35 |
48.25 |
48.25 |
48.25 |
26.35 |
26.35 |
| Coeficiente de resistencia Cu (K-1) |
αCU |
0.0039 |
0.0039 |
0.0039 |
0.0039 |
0.0039 |
0.0039 |
| Resistencia del motor (Ω) |
Rmot |
0.978 |
1.74 |
1.74 |
1.74 |
7.41 |
7.41 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| PROTECCION DE CORRIENTES DE PICO |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Factor de sobrecarga |
K |
12.1549 |
15.5775 |
15.5775 |
15.5775 |
8.0959 |
8.0959 |
| Tiempo de Corte de sobrecarga (s) |
ton |
0.1790 |
0.1993 |
0.1993 |
0.1993 |
0.4051 |
0.4051 |
| Corriente Max de trabajo (A) |
Ipeak |
20.00 |
20.00 |
20.00 |
20.00 |
4.86 |
4.86 |
| PROTECCION DE CORRIENTES DE i2t |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Perdidas por efecto Joule (W) |
PJ |
8.5714 |
10.0402 |
10.0402 |
10.0402 |
8.5714 |
8.5714 |
| Resistencia del bobinado a Tw,∞(Ω) |
RTW |
1.2641 |
2.2490 |
2.2490 |
2.2490 |
9.5774 |
9.5774 |
| Corriente I2t (A) |
II2t |
2.6040 |
2.1129 |
2.1129 |
2.1129 |
0.9460 |
0.9460 |
| Tiempo de Corte de I2t (s) |
t |
36.5277 |
66.8941 |
66.8941 |
66.8941 |
36.5277 |
36.5277 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Superficie de I2t (A2/s) |
SI2t |
247.6890 |
298.6405 |
298.6405 |
298.6405 |
32.6909 |
32.6909 |
| Tiempo de Corte de I2t fijado (s) |
t - nuevo |
15.0000 |
15.0000 |
15.0000 |
15.0000 |
15.0000 |
15.0000 |
| Corriente I2t (A) |
II2t- nuevo |
4.0636 |
4.4620 |
4.4620 |
4.4620 |
1.4763 |
1.4763 |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Motor |
Tensión (V) |
Peso (Gr) |
Par max (Nm) |
Par RMS (Nm) |
I max (A) |
I RMS (A) |
Vel. Nom (rpm) |
| nan |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| Flat Brushless EC 45 50W (339287) |
36 |
110 |
0.488 |
0.0943 |
4.86 |
0.861 |
3360 |
| Flat Brushless EC 45 50W (251601) |
24 |
110 |
0.822 |
0.0843 |
24.5 |
2.36 |
6700 |
| Flat Brushless EC 45 70W (402686) |
36 |
141 |
1 |
0.108 |
20.7 |
1.93 |
6330 |
| Flat Brushless EC 45 30W (339282) |
36 |
110 |
0.337 |
0.0666 |
5.38 |
0.849 |
4760 |
| Driver |
nan |
nan |
nan |
nan |
nan |
nan |
nan |
| iPOS3604MX-CAN |
36 |
,,, |
,,, |
,,, |
10 (2,5s) |
4 |
,,, |
| iPOS4808MX-CAN |
50 |
,,, |
,,, |
,,, |
20 (2,5s) |
8 |
,,, |
Motores: transmision
motores-transmision.csv
| Unnamed: 0 |
Unnamed: 1 |
Unnamed: 2 |
Unnamed: 3 |
Unnamed: 4 |
Unnamed: 5 |
Unnamed: 6 |
Unnamed: 7 |
Unnamed: 8 |
| Articulación |
Motor |
Polea Entrada |
Correa |
Polea Salida |
Dist. Entre Ejes |
reductora |
Relación |
R. total |
| Tobillo Sagital |
251601 |
Optibelt ZRS 30-3M-6 |
OMEGA 255-3M 3 |
Optibelt ZRS 44-3M-6 |
90 mm |
160 |
1.47 |
235.2 |
| Tobillo Frontal |
402686 |
Optibelt ZRS 26-3M-6 |
OMEGA 402-3M 3 |
Optibelt ZRS 44-3M-6 |
147'2 mm |
160 |
1.69 |
270.4 |
| Rodilla |
402686 |
Optibelt ZRS 30-3M-6 |
OMEGA 276-3M 3 |
Optibelt ZRS 44-3M-6 |
83'9 mm |
160 |
1.47 |
235.2 |
| Cadera Frontal |
402686 |
Optibelt ZRS 30-3M-6 |
OMEGA 357-3M 3 |
Optibelt ZRS 36-3M-6 |
127 mm |
160 |
1.2 |
192 |
| Cadera Sagital |
339287 |
Optibelt ZRS 22-3M-6 |
OMEGA 312-3M 3 |
Optibelt ZRS 72-3M-6 |
82 mm |
160 |
3.27 |
523.2 |
| Cadera Axial |
339287 |
Optibelt ZRS 24-3M-6 |
OMEGA 225-3M 6 |
Optibelt ZRS 60-3M-6 |
???? |
160 |
2.5 |
400 |
| Cintura Frontal |
251601 |
Optibelt ZRS 10-3M-9 |
OMEGA 231-3M 9 |
Optibelt ZRS 30-3M-9 |
???? |
160 |
3 |
480 |
| Cintura Axial |
251601 |
----- |
----- |
----- |
----- |
160 |
----- |
160 |
| Hombro Frontal |
339282 |
----- |
----- |
----- |
----- |
160 |
----- |
160 |
| Hombro Sagital |
339282 |
----- |
----- |
----- |
----- |
160 |
----- |
160 |
| Hombro Axial |
339282 |
----- |
----- |
----- |
----- |
120 |
----- |
120 |
| Codo Frontal |
339282 |
----- |
----- |
----- |
----- |
160 |
----- |
160 |
| Muñeca Axial |
339282 |
----- |
----- |
----- |
----- |
120 |
----- |
120 |
| Muñeca Frontal |
339282 |
----- |
----- |
----- |
----- |
120 |
----- |
120 |