Skip to content

Commit 2860b1a

Browse files
committed
fix(webots): update Wolfgang joint limits in protobuf
which was not held consistent with the `robot.urdf` joint limits
1 parent d9191c6 commit 2860b1a

File tree

1 file changed

+20
-20
lines changed
  • bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang

1 file changed

+20
-20
lines changed

bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto

+20-20
Original file line numberDiff line numberDiff line change
@@ -1584,8 +1584,8 @@ PROTO Wolfgang [
15841584
RotationalMotor {
15851585
name "RHipRoll [hip]"
15861586
maxVelocity IS MX106-vel
1587-
minPosition -1.5708
1588-
maxPosition 1.5708
1587+
minPosition -1.9
1588+
maxPosition 1.6
15891589
maxTorque IS MX106-torque
15901590
controlPID IS pid
15911591
}
@@ -1652,8 +1652,8 @@ PROTO Wolfgang [
16521652
RotationalMotor {
16531653
name "RHipPitch"
16541654
maxVelocity IS MX106-vel
1655-
minPosition -2.0944
1656-
maxPosition 1.91986
1655+
minPosition -2.77
1656+
maxPosition 0.79
16571657
maxTorque IS MX106-torque
16581658
controlPID IS pid
16591659
}
@@ -1736,7 +1736,7 @@ PROTO Wolfgang [
17361736
RotationalMotor {
17371737
name "RKnee"
17381738
maxVelocity IS XH540W270-vel
1739-
minPosition -2.96706
1739+
minPosition -2.8
17401740
maxPosition 0.2
17411741
maxTorque IS XH540W270-torque
17421742
controlPID IS pid
@@ -1828,8 +1828,8 @@ PROTO Wolfgang [
18281828
RotationalMotor {
18291829
name "RAnklePitch"
18301830
maxVelocity IS MX106-vel
1831-
minPosition -1.74533
1832-
maxPosition 1.45
1831+
minPosition -0.37
1832+
maxPosition 1.42
18331833
maxTorque IS MX106-torque
18341834
controlPID IS pid
18351835
}
@@ -1895,8 +1895,8 @@ PROTO Wolfgang [
18951895
RotationalMotor {
18961896
name "RAnkleRoll"
18971897
maxVelocity IS MX106-vel
1898-
minPosition -1.0472
1899-
maxPosition 1.0472
1898+
minPosition -1.4
1899+
maxPosition 1.58
19001900
maxTorque IS MX106-torque
19011901
controlPID IS pid
19021902
}
@@ -3005,8 +3005,8 @@ PROTO Wolfgang [
30053005
RotationalMotor {
30063006
name "LHipRoll [hip]"
30073007
maxVelocity IS MX106-vel
3008-
minPosition -1.5708
3009-
maxPosition 1.5708
3008+
minPosition -1.6
3009+
maxPosition 1.9
30103010
maxTorque IS MX106-torque
30113011
controlPID IS pid
30123012
}
@@ -3073,8 +3073,8 @@ PROTO Wolfgang [
30733073
RotationalMotor {
30743074
name "LHipPitch"
30753075
maxVelocity IS MX106-vel
3076-
minPosition -1.91986
3077-
maxPosition 2.0944
3076+
minPosition -0.79
3077+
maxPosition 2.77
30783078
maxTorque IS MX106-torque
30793079
controlPID IS pid
30803080
}
@@ -3158,7 +3158,7 @@ PROTO Wolfgang [
31583158
name "LKnee"
31593159
maxVelocity IS XH540W270-vel
31603160
minPosition -0.2
3161-
maxPosition 2.96706
3161+
maxPosition 2.8
31623162
maxTorque IS XH540W270-torque
31633163
controlPID IS pid
31643164
}
@@ -3249,8 +3249,8 @@ PROTO Wolfgang [
32493249
RotationalMotor {
32503250
name "LAnklePitch"
32513251
maxVelocity IS MX106-vel
3252-
minPosition -1.45
3253-
maxPosition 1.74533
3252+
minPosition -1.42
3253+
maxPosition 0.37
32543254
maxTorque IS MX106-torque
32553255
controlPID IS pid
32563256
}
@@ -3316,8 +3316,8 @@ PROTO Wolfgang [
33163316
RotationalMotor {
33173317
name "LAnkleRoll"
33183318
maxVelocity IS MX106-vel
3319-
minPosition -1.0472
3320-
maxPosition 1.0472
3319+
minPosition -1.58
3320+
maxPosition 1.4
33213321
maxTorque IS MX106-torque
33223322
controlPID IS pid
33233323
}
@@ -4428,8 +4428,8 @@ PROTO Wolfgang [
44284428
RotationalMotor {
44294429
name "HeadTilt"
44304430
maxVelocity IS MX64-vel
4431-
minPosition -1.5708
4432-
maxPosition 1.0472
4431+
minPosition -1.923
4432+
maxPosition 1.24
44334433
maxTorque IS MX64-torque
44344434
controlPID IS pid
44354435
}

0 commit comments

Comments
 (0)