add keyframe kick behavior, but still need to be improved
This commit is contained in:
213
behaviors/custom/keyframe/kick/kick_short.yaml
Normal file
213
behaviors/custom/keyframe/kick/kick_short.yaml
Normal file
@@ -0,0 +1,213 @@
|
||||
symmetry: false
|
||||
kp: 140
|
||||
kd: 1.2
|
||||
keyframes:
|
||||
- delta: 0.00
|
||||
motor_positions:
|
||||
Head_yaw: 0.000
|
||||
Head_pitch: 0.000
|
||||
Left_Shoulder_Pitch: 68.000
|
||||
Left_Shoulder_Roll: -76.000
|
||||
Left_Elbow_Pitch: -62.000
|
||||
Left_Elbow_Yaw: 0.000
|
||||
Right_Shoulder_Pitch: 72.000
|
||||
Right_Shoulder_Roll: 52.000
|
||||
Right_Elbow_Pitch: -70.000
|
||||
Right_Elbow_Yaw: 0.000
|
||||
Waist: 0.000
|
||||
Left_Hip_Pitch: -18.000
|
||||
Left_Hip_Roll: 8.000
|
||||
Left_Hip_Yaw: 0.000
|
||||
Left_Knee_Pitch: 42.000
|
||||
Left_Ankle_Pitch: 10.000
|
||||
Left_Ankle_Roll: 3.000
|
||||
Right_Hip_Pitch: 14.000
|
||||
Right_Hip_Roll: -9.000
|
||||
Right_Hip_Yaw: 0.000
|
||||
Right_Knee_Pitch: -10.000
|
||||
Right_Ankle_Pitch: 6.000
|
||||
Right_Ankle_Roll: -5.000
|
||||
|
||||
- delta: 0.16
|
||||
motor_positions:
|
||||
Head_yaw: 0.000
|
||||
Head_pitch: 0.000
|
||||
Left_Shoulder_Pitch: 70.000
|
||||
Left_Shoulder_Roll: -80.000
|
||||
Left_Elbow_Pitch: -70.000
|
||||
Left_Elbow_Yaw: 0.000
|
||||
Right_Shoulder_Pitch: 72.000
|
||||
Right_Shoulder_Roll: 50.000
|
||||
Right_Elbow_Pitch: -70.000
|
||||
Right_Elbow_Yaw: 0.000
|
||||
Waist: 0.000
|
||||
Left_Hip_Pitch: -30.000
|
||||
Left_Hip_Roll: 10.000
|
||||
Left_Hip_Yaw: 1.000
|
||||
Left_Knee_Pitch: 54.000
|
||||
Left_Ankle_Pitch: 10.000
|
||||
Left_Ankle_Roll: 4.500
|
||||
Right_Hip_Pitch: 14.000
|
||||
Right_Hip_Roll: -9.000
|
||||
Right_Hip_Yaw: -1.000
|
||||
Right_Knee_Pitch: -10.000
|
||||
Right_Ankle_Pitch: 6.000
|
||||
Right_Ankle_Roll: -5.500
|
||||
|
||||
- delta: 0.17
|
||||
motor_positions:
|
||||
Head_yaw: 0.000
|
||||
Head_pitch: 0.000
|
||||
Left_Shoulder_Pitch: 72.000
|
||||
Left_Shoulder_Roll: -82.000
|
||||
Left_Elbow_Pitch: -74.000
|
||||
Left_Elbow_Yaw: 0.000
|
||||
Right_Shoulder_Pitch: 72.000
|
||||
Right_Shoulder_Roll: 48.000
|
||||
Right_Elbow_Pitch: -68.000
|
||||
Right_Elbow_Yaw: 0.000
|
||||
Waist: 0.000
|
||||
Left_Hip_Pitch: -46.000
|
||||
Left_Hip_Roll: 12.000
|
||||
Left_Hip_Yaw: 2.000
|
||||
Left_Knee_Pitch: 28.000
|
||||
Left_Ankle_Pitch: 10.000
|
||||
Left_Ankle_Roll: 5.000
|
||||
Right_Hip_Pitch: 14.000
|
||||
Right_Hip_Roll: -8.000
|
||||
Right_Hip_Yaw: -2.000
|
||||
Right_Knee_Pitch: -8.000
|
||||
Right_Ankle_Pitch: 5.000
|
||||
Right_Ankle_Roll: -7.000
|
||||
|
||||
- delta: 0.16
|
||||
motor_positions:
|
||||
Head_yaw: 0.000
|
||||
Head_pitch: 0.000
|
||||
Left_Shoulder_Pitch: 73.500
|
||||
Left_Shoulder_Roll: -84.000
|
||||
Left_Elbow_Pitch: -76.000
|
||||
Left_Elbow_Yaw: 0.000
|
||||
Right_Shoulder_Pitch: 72.000
|
||||
Right_Shoulder_Roll: 46.000
|
||||
Right_Elbow_Pitch: -66.000
|
||||
Right_Elbow_Yaw: 0.000
|
||||
Waist: 0.000
|
||||
Left_Hip_Pitch: -58.000
|
||||
Left_Hip_Roll: 13.000
|
||||
Left_Hip_Yaw: 3.000
|
||||
Left_Knee_Pitch: -16.000
|
||||
Left_Ankle_Pitch: 8.000
|
||||
Left_Ankle_Roll: 5.000
|
||||
Right_Hip_Pitch: 12.000
|
||||
Right_Hip_Roll: -8.000
|
||||
Right_Hip_Yaw: -1.000
|
||||
Right_Knee_Pitch: -6.000
|
||||
Right_Ankle_Pitch: 4.000
|
||||
Right_Ankle_Roll: -5.000
|
||||
|
||||
- delta: 0.16
|
||||
motor_positions:
|
||||
Head_yaw: 0.000
|
||||
Head_pitch: 0.000
|
||||
Left_Shoulder_Pitch: 75.000
|
||||
Left_Shoulder_Roll: -86.000
|
||||
Left_Elbow_Pitch: -72.000
|
||||
Left_Elbow_Yaw: 0.000
|
||||
Right_Shoulder_Pitch: 70.000
|
||||
Right_Shoulder_Roll: 44.000
|
||||
Right_Elbow_Pitch: -64.000
|
||||
Right_Elbow_Yaw: 0.000
|
||||
Waist: 0.000
|
||||
Left_Hip_Pitch: -62.000
|
||||
Left_Hip_Roll: 13.000
|
||||
Left_Hip_Yaw: 3.000
|
||||
Left_Knee_Pitch: 10.000
|
||||
Left_Ankle_Pitch: 6.000
|
||||
Left_Ankle_Roll: 5.000
|
||||
Right_Hip_Pitch: 12.000
|
||||
Right_Hip_Roll: -8.000
|
||||
Right_Hip_Yaw: 0.000
|
||||
Right_Knee_Pitch: -6.000
|
||||
Right_Ankle_Pitch: 4.000
|
||||
Right_Ankle_Roll: -5.000
|
||||
kp: 170
|
||||
|
||||
- delta: 0.18
|
||||
motor_positions:
|
||||
Head_yaw: 0.000
|
||||
Head_pitch: 0.000
|
||||
Left_Shoulder_Pitch: 73.500
|
||||
Left_Shoulder_Roll: -82.000
|
||||
Left_Elbow_Pitch: -69.000
|
||||
Left_Elbow_Yaw: 0.000
|
||||
Right_Shoulder_Pitch: 72.000
|
||||
Right_Shoulder_Roll: 48.000
|
||||
Right_Elbow_Pitch: -68.000
|
||||
Right_Elbow_Yaw: 0.000
|
||||
Waist: 0.000
|
||||
Left_Hip_Pitch: -16.000
|
||||
Left_Hip_Roll: 9.000
|
||||
Left_Hip_Yaw: 1.000
|
||||
Left_Knee_Pitch: 38.000
|
||||
Left_Ankle_Pitch: 9.000
|
||||
Left_Ankle_Roll: 3.000
|
||||
Right_Hip_Pitch: 8.000
|
||||
Right_Hip_Roll: -5.000
|
||||
Right_Hip_Yaw: 0.000
|
||||
Right_Knee_Pitch: -8.000
|
||||
Right_Ankle_Pitch: 5.000
|
||||
Right_Ankle_Roll: -3.000
|
||||
|
||||
- delta: 0.18
|
||||
motor_positions:
|
||||
Head_yaw: 0.000
|
||||
Head_pitch: 0.000
|
||||
Left_Shoulder_Pitch: 72.000
|
||||
Left_Shoulder_Roll: -82.000
|
||||
Left_Elbow_Pitch: -68.000
|
||||
Left_Elbow_Yaw: 0.000
|
||||
Right_Shoulder_Pitch: 68.000
|
||||
Right_Shoulder_Roll: 48.000
|
||||
Right_Elbow_Pitch: -62.000
|
||||
Right_Elbow_Yaw: 0.000
|
||||
Waist: 0.000
|
||||
Left_Hip_Pitch: -10.000
|
||||
Left_Hip_Roll: 9.000
|
||||
Left_Hip_Yaw: 1.000
|
||||
Left_Knee_Pitch: 34.000
|
||||
Left_Ankle_Pitch: 9.000
|
||||
Left_Ankle_Roll: 3.000
|
||||
Right_Hip_Pitch: 8.000
|
||||
Right_Hip_Roll: -5.000
|
||||
Right_Hip_Yaw: 0.000
|
||||
Right_Knee_Pitch: -6.000
|
||||
Right_Ankle_Pitch: 4.000
|
||||
Right_Ankle_Roll: -3.000
|
||||
|
||||
- delta: 0.24
|
||||
motor_positions:
|
||||
Head_yaw: 0.000
|
||||
Head_pitch: 0.000
|
||||
Left_Shoulder_Pitch: 65.000
|
||||
Left_Shoulder_Roll: -75.000
|
||||
Left_Elbow_Pitch: -60.000
|
||||
Left_Elbow_Yaw: 0.000
|
||||
Right_Shoulder_Pitch: 65.000
|
||||
Right_Shoulder_Roll: 45.000
|
||||
Right_Elbow_Pitch: -60.000
|
||||
Right_Elbow_Yaw: 0.000
|
||||
Waist: 0.000
|
||||
Left_Hip_Pitch: 0.000
|
||||
Left_Hip_Roll: 0.000
|
||||
Left_Hip_Yaw: 0.000
|
||||
Left_Knee_Pitch: 0.000
|
||||
Left_Ankle_Pitch: 0.000
|
||||
Left_Ankle_Roll: 0.000
|
||||
Right_Hip_Pitch: 0.000
|
||||
Right_Hip_Roll: 0.000
|
||||
Right_Hip_Yaw: 0.000
|
||||
Right_Knee_Pitch: 0.000
|
||||
Right_Ankle_Pitch: 0.000
|
||||
Right_Ankle_Roll: 0.000
|
||||
kp: 120
|
||||
Reference in New Issue
Block a user