@@ -1584,8 +1584,8 @@ PROTO Wolfgang [
1584
1584
RotationalMotor {
1585
1585
name "RHipRoll [hip]"
1586
1586
maxVelocity IS MX106-vel
1587
- minPosition -1.5708
1588
- maxPosition 1.5708
1587
+ minPosition -1.9
1588
+ maxPosition 1.6
1589
1589
maxTorque IS MX106-torque
1590
1590
controlPID IS pid
1591
1591
}
@@ -1652,8 +1652,8 @@ PROTO Wolfgang [
1652
1652
RotationalMotor {
1653
1653
name "RHipPitch"
1654
1654
maxVelocity IS MX106-vel
1655
- minPosition -2.0944
1656
- maxPosition 1.91986
1655
+ minPosition -2.77
1656
+ maxPosition 0.79
1657
1657
maxTorque IS MX106-torque
1658
1658
controlPID IS pid
1659
1659
}
@@ -1736,7 +1736,7 @@ PROTO Wolfgang [
1736
1736
RotationalMotor {
1737
1737
name "RKnee"
1738
1738
maxVelocity IS XH540W270-vel
1739
- minPosition -2.96706
1739
+ minPosition -2.8
1740
1740
maxPosition 0.2
1741
1741
maxTorque IS XH540W270-torque
1742
1742
controlPID IS pid
@@ -1828,8 +1828,8 @@ PROTO Wolfgang [
1828
1828
RotationalMotor {
1829
1829
name "RAnklePitch"
1830
1830
maxVelocity IS MX106-vel
1831
- minPosition -1.74533
1832
- maxPosition 1.45
1831
+ minPosition -0.37
1832
+ maxPosition 1.42
1833
1833
maxTorque IS MX106-torque
1834
1834
controlPID IS pid
1835
1835
}
@@ -1895,8 +1895,8 @@ PROTO Wolfgang [
1895
1895
RotationalMotor {
1896
1896
name "RAnkleRoll"
1897
1897
maxVelocity IS MX106-vel
1898
- minPosition -1.0472
1899
- maxPosition 1.0472
1898
+ minPosition -1.4
1899
+ maxPosition 1.58
1900
1900
maxTorque IS MX106-torque
1901
1901
controlPID IS pid
1902
1902
}
@@ -3005,8 +3005,8 @@ PROTO Wolfgang [
3005
3005
RotationalMotor {
3006
3006
name "LHipRoll [hip]"
3007
3007
maxVelocity IS MX106-vel
3008
- minPosition -1.5708
3009
- maxPosition 1.5708
3008
+ minPosition -1.6
3009
+ maxPosition 1.9
3010
3010
maxTorque IS MX106-torque
3011
3011
controlPID IS pid
3012
3012
}
@@ -3073,8 +3073,8 @@ PROTO Wolfgang [
3073
3073
RotationalMotor {
3074
3074
name "LHipPitch"
3075
3075
maxVelocity IS MX106-vel
3076
- minPosition -1.91986
3077
- maxPosition 2.0944
3076
+ minPosition -0.79
3077
+ maxPosition 2.77
3078
3078
maxTorque IS MX106-torque
3079
3079
controlPID IS pid
3080
3080
}
@@ -3158,7 +3158,7 @@ PROTO Wolfgang [
3158
3158
name "LKnee"
3159
3159
maxVelocity IS XH540W270-vel
3160
3160
minPosition -0.2
3161
- maxPosition 2.96706
3161
+ maxPosition 2.8
3162
3162
maxTorque IS XH540W270-torque
3163
3163
controlPID IS pid
3164
3164
}
@@ -3249,8 +3249,8 @@ PROTO Wolfgang [
3249
3249
RotationalMotor {
3250
3250
name "LAnklePitch"
3251
3251
maxVelocity IS MX106-vel
3252
- minPosition -1.45
3253
- maxPosition 1.74533
3252
+ minPosition -1.42
3253
+ maxPosition 0.37
3254
3254
maxTorque IS MX106-torque
3255
3255
controlPID IS pid
3256
3256
}
@@ -3316,8 +3316,8 @@ PROTO Wolfgang [
3316
3316
RotationalMotor {
3317
3317
name "LAnkleRoll"
3318
3318
maxVelocity IS MX106-vel
3319
- minPosition -1.0472
3320
- maxPosition 1.0472
3319
+ minPosition -1.58
3320
+ maxPosition 1.4
3321
3321
maxTorque IS MX106-torque
3322
3322
controlPID IS pid
3323
3323
}
@@ -4428,8 +4428,8 @@ PROTO Wolfgang [
4428
4428
RotationalMotor {
4429
4429
name "HeadTilt"
4430
4430
maxVelocity IS MX64-vel
4431
- minPosition -1.5708
4432
- maxPosition 1.0472
4431
+ minPosition -1.923
4432
+ maxPosition 1.24
4433
4433
maxTorque IS MX64-torque
4434
4434
controlPID IS pid
4435
4435
}
0 commit comments