-
Notifications
You must be signed in to change notification settings - Fork 2
Expand file tree
/
Copy pathconfig.py
More file actions
76 lines (61 loc) · 2.12 KB
/
config.py
File metadata and controls
76 lines (61 loc) · 2.12 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
import numpy as np
robot = 'z1' # 'aliengo', 'go1', 'go2', 'b2', 'hyqreal2', 'z1'
# ----------------------------------------------------------------------------------------------------------------
if(robot == "aliengo"):
Kp = np.array([25., 25., 25.,
25., 25., 25.,
25., 25., 25.,
25., 25., 25.])
Kd = np.array([0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5])
elif(robot == "go2"):
# Order FL, FR, RL, RR
Kp = np.array([20., 20., 20.,
20., 20., 20.,
20., 20., 20.,
20., 20., 20.])
Kd = np.array([1.5, 1.5, 1.5,
1.5, 1.5, 1.5,
1.5, 1.5, 1.5,
1.5, 1.5, 1.5])
elif(robot == "b2"):
# Order FL, FR, RL, RR
Kp = np.array([20., 20., 20.,
20., 20., 20.,
20., 20., 20.,
20., 20., 20.])
Kd = np.array([1.5, 1.5, 1.5,
1.5, 1.5, 1.5,
1.5, 1.5, 1.5,
1.5, 1.5, 1.5])
elif(robot == "hyqreal2"):
# Order FL, FR, RL, RR
Kp = np.array([175., 175., 175.,
175., 175., 175.,
175., 175., 175.,
175., 175., 175.])
Kd = np.array([20., 20., 20.,
20., 20., 20.,
20., 20., 20.,
20., 20., 20.])
elif(robot =="z1"):
# Order joint1-joint2-joint3-joint4-joint5-joint6-gripper
Kp = np.array([80., 120., 120.,
80., 80., 80.,
80.])
Kd = np.array([2.5, 2.5, 2.5,
2.5, 2.5, 2.5,
2.5])
elif(robot =="piper_l"):
# Order joint1-joint2-joint3-joint4-joint5-joint6-gripper
Kp = np.array([50., 50., 50.,
50., 50., 50.,
50.])
Kd = np.array([2.5, 2.5, 2.5,
2.5, 2.5, 2.5,
2.5])
else:
raise ValueError(f"Robot {robot} not supported")
frequency_collection = 200#hz