Skip to content

Commit bd83c2d

Browse files
committed
Changed Parameters in Wlfgang
1 parent 034b187 commit bd83c2d

File tree

6 files changed

+53
-84
lines changed

6 files changed

+53
-84
lines changed

animations/.json

Lines changed: 0 additions & 61 deletions
This file was deleted.

bitbots_motion/bitbots_dynup/config/dynup_sim.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ dynup:
2929
wait_in_squat_front: 0.032
3030

3131
rise:
32-
rise_time: 0.4
32+
rise_time: 2.0
3333

3434
stabilizer:
3535
end_pause:

bitbots_motion/bitbots_dynup/src/dynup_engine.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -595,18 +595,18 @@ double DynupEngine::calcWalkreadySplines(double time, double travel_time) {
595595
r_foot_spline_.pitch()->addPoint(time, -params_.end_pose.trunk_pitch * M_PI / 180);
596596
r_foot_spline_.yaw()->addPoint(time, 0);
597597

598-
// l_hand_spline_.x()->addPoint(time, 0);
599-
// l_hand_spline_.y()->addPoint(time, 0);
600-
// l_hand_spline_.z()->addPoint(time, params_.end_pose.hand_walkready_height);
601-
// l_hand_spline_.roll()->addPoint(time, 0);
602-
// l_hand_spline_.pitch()->addPoint(time, params_.end_pose.hand_walkready_pitch * M_PI / 180);
603-
// l_hand_spline_.yaw()->addPoint(time, 0);
604-
// r_hand_spline_.x()->addPoint(time, 0);
605-
// r_hand_spline_.y()->addPoint(time, 0);
606-
// r_hand_spline_.z()->addPoint(time, params_.end_pose.hand_walkready_height);
607-
// r_hand_spline_.roll()->addPoint(time, 0);
608-
// r_hand_spline_.pitch()->addPoint(time, params_.end_pose.hand_walkready_pitch * M_PI / 180);
609-
// r_hand_spline_.yaw()->addPoint(time, 0);
598+
l_hand_spline_.x()->addPoint(time, 0);
599+
l_hand_spline_.y()->addPoint(time, 0);
600+
l_hand_spline_.z()->addPoint(time, params_.end_pose.hand_walkready_height);
601+
l_hand_spline_.roll()->addPoint(time, 0);
602+
l_hand_spline_.pitch()->addPoint(time, params_.end_pose.hand_walkready_pitch * M_PI / 180);
603+
l_hand_spline_.yaw()->addPoint(time, 0);
604+
r_hand_spline_.x()->addPoint(time, 0);
605+
r_hand_spline_.y()->addPoint(time, 0);
606+
r_hand_spline_.z()->addPoint(time, params_.end_pose.hand_walkready_height);
607+
r_hand_spline_.roll()->addPoint(time, 0);
608+
r_hand_spline_.pitch()->addPoint(time, params_.end_pose.hand_walkready_pitch * M_PI / 180);
609+
r_hand_spline_.yaw()->addPoint(time, 0);
610610

611611
return time;
612612
}

animations/grab_ball.json renamed to bitbots_robot/wolfgang_animations/animations/throw_in/grab_ball.json

Lines changed: 31 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
"LHipYaw": -3.08,
4040
"LKnee": 160.21,
4141
"LShoulderPitch": -58.89,
42-
"LShoulderRoll": 19.35,
42+
"LShoulderRoll": 5.0,
4343
"RAnklePitch": 58.480000000000004,
4444
"RAnkleRoll": -20.39,
4545
"RElbow": 82.66,
@@ -48,7 +48,33 @@
4848
"RHipYaw": 17.5,
4949
"RKnee": -157.68,
5050
"RShoulderPitch": 56.54,
51-
"RShoulderRoll": -12.66
51+
"RShoulderRoll": -5.0
52+
},
53+
"name": "start frame_copy_1",
54+
"pause": 0.0,
55+
"torque": {}
56+
},
57+
{
58+
"duration": 1.2,
59+
"goals": {
60+
"LAnklePitch": -57.48,
61+
"LAnkleRoll": 11.96,
62+
"LElbow": -86.22,
63+
"LHipPitch": 121.61,
64+
"LHipRoll": 14.250000000000002,
65+
"LHipYaw": -3.08,
66+
"LKnee": 160.21,
67+
"LShoulderPitch": -58.89,
68+
"LShoulderRoll": 15.0,
69+
"RAnklePitch": 58.480000000000004,
70+
"RAnkleRoll": -20.39,
71+
"RElbow": 82.66,
72+
"RHipPitch": -118.74,
73+
"RHipRoll": -18.19,
74+
"RHipYaw": 17.5,
75+
"RKnee": -157.68,
76+
"RShoulderPitch": 56.54,
77+
"RShoulderRoll": -15.0
5278
},
5379
"name": "start frame_copy_1",
5480
"pause": 0.0,
@@ -64,8 +90,8 @@
6490
"LHipRoll": 13.37,
6591
"LHipYaw": 1.23,
6692
"LKnee": 142.19,
67-
"LShoulderPitch": -164.79,
68-
"LShoulderRoll": 19.35,
93+
"LShoulderPitch": -164.0,
94+
"LShoulderRoll": 12.66,
6995
"RAnklePitch": 59.71,
7096
"RAnkleRoll": -15.560000000000002,
7197
"RElbow": 82.66,
@@ -84,4 +110,4 @@
84110
"last_edited": "2024-10-30 19:16:16.384874",
85111
"name": "grab_ball",
86112
"version": ""
87-
}
113+
}

animations/throw.json renamed to bitbots_robot/wolfgang_animations/animations/throw_in/throw.json

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
"description": "",
44
"keyframes": [
55
{
6-
"duration": 1.0,
6+
"duration": 0.0,
77
"goals": {
88
"HeadPan": 0.0,
99
"HeadTilt": 0.0,
@@ -70,4 +70,4 @@
7070
"last_edited": "2024-10-30 19:13:18.833923",
7171
"name": "throw",
7272
"version": ""
73-
}
73+
}

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

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -483,6 +483,7 @@ PROTO Wolfgang [
483483
RotationalMotor {
484484
name "RShoulderRoll"
485485
maxVelocity IS MX64-vel
486+
minPosition -0.4
486487
maxPosition 3.14159
487488
maxTorque IS MX64-torque
488489
controlPID IS pid
@@ -1041,6 +1042,7 @@ PROTO Wolfgang [
10411042
name "LShoulderRoll"
10421043
maxVelocity IS MX64-vel
10431044
minPosition -3.14159
1045+
maxPosition 0.4
10441046
maxTorque IS MX64-torque
10451047
controlPID IS pid
10461048
}
@@ -1135,7 +1137,7 @@ PROTO Wolfgang [
11351137
RotationalMotor {
11361138
name "LElbow"
11371139
maxVelocity IS MX64-vel
1138-
minPosition -1.5708
1140+
minPosition -1.7
11391141
maxPosition 1.0472
11401142
maxTorque IS MX64-torque
11411143
controlPID IS pid
@@ -1735,6 +1737,7 @@ PROTO Wolfgang [
17351737
name "RKnee"
17361738
maxVelocity IS XH540W270-vel
17371739
minPosition -2.96706
1740+
maxPosition 0.2
17381741
maxTorque IS XH540W270-torque
17391742
controlPID IS pid
17401743
}
@@ -1826,7 +1829,7 @@ PROTO Wolfgang [
18261829
name "RAnklePitch"
18271830
maxVelocity IS MX106-vel
18281831
minPosition -1.74533
1829-
maxPosition 1.22173
1832+
maxPosition 1.45
18301833
maxTorque IS MX106-torque
18311834
controlPID IS pid
18321835
}
@@ -3154,6 +3157,7 @@ PROTO Wolfgang [
31543157
RotationalMotor {
31553158
name "LKnee"
31563159
maxVelocity IS XH540W270-vel
3160+
minPosition -0.2
31573161
maxPosition 2.96706
31583162
maxTorque IS XH540W270-torque
31593163
controlPID IS pid
@@ -3245,7 +3249,7 @@ PROTO Wolfgang [
32453249
RotationalMotor {
32463250
name "LAnklePitch"
32473251
maxVelocity IS MX106-vel
3248-
minPosition -1.22173
3252+
minPosition -1.45
32493253
maxPosition 1.74533
32503254
maxTorque IS MX106-torque
32513255
controlPID IS pid

0 commit comments

Comments
 (0)