~shadowrobot/sr-config/demo_hand_iros_demo

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
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
sh_ffj0_position_controller:
  joint: FFJ0
  pid:
    d: 0.0
    deadband: 0
    friction_deadband: 65535.0
    i: 0.0
    i_clamp: 1500.0
    max_force: 600.0
    p: 5150.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_ffj3_position_controller:
  joint: FFJ3
  pid:
    d: 500.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: 300.0
    i_clamp: 220.0
    max_force: 700.0
    p: 6500.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_ffj4_position_controller:
  joint: FFJ4
  pid:
    d: -300.0
    deadband: 0.02
    friction_deadband: 65535.0
    i: -200.0
    i_clamp: 300.0
    max_force: 600.0
    p: -5500.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_lfj0_position_controller:
  joint: LFJ0
  pid:
    d: 0.0
    friction_deadband: 65535.0
    i: 0.0
    i_clamp: 1500.0
    max_force: 600.0
    p: -4150.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_lfj3_position_controller:
  joint: LFJ3
  pid:
    d: -500.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: -300.0
    i_clamp: 220.0
    max_force: 700.0
    p: -7000.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_lfj4_position_controller:
  joint: LFJ4
  pid:
    d: 300.0
    deadband: 0
    friction_deadband: 65535.0
    i: 200.0
    i_clamp: 300.0
    max_force: 600.0
    p: 5000.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_lfj5_position_controller:
  joint: LFJ5
  pid:
    d: -300.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: -300.0
    i_clamp: 200.0
    max_force: 600.0
    p: -7400.0
    position_deadband: 0.003
  type: sr_mechanism_controllers/SrhJointPositionController
sh_mfj0_position_controller:
  joint: MFJ0
  pid:
    d: 0.0
    friction_deadband: 65535.0
    i: 0.0
    i_clamp: 1500.0
    max_force: 600.0
    p: 4150.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_mfj3_position_controller:
  joint: MFJ3
  pid:
    d: 500.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: 300.0
    i_clamp: 220.0
    max_force: 700.0
    p: 6500.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_mfj4_position_controller:
  joint: MFJ4
  pid:
    d: -300.0
    deadband: 0
    friction_deadband: 65535.0
    i: -200.0
    i_clamp: 300.0
    max_force: 600.0
    p: -5500.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_rfj0_position_controller:
  joint: RFJ0
  pid:
    d: 0.0
    friction_deadband: 65535.0
    i: 0.0
    i_clamp: 1500.0
    max_force: 600.0
    p: -4150.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_rfj3_position_controller:
  joint: RFJ3
  pid:
    d: -500.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: -300.0
    i_clamp: 220.0
    max_force: 700.0
    p: -8000.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_rfj4_position_controller:
  joint: RFJ4
  pid:
    d: -300.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: -200.0
    i_clamp: 300.0
    max_force: 600.0
    p: -6000.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_thj1_position_controller:
  joint: THJ1
  pid:
    d: 350.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: 200.0
    i_clamp: 200.0
    max_force: 600.0
    p: 5500.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_thj2_position_controller:
  joint: THJ2
  pid:
    d: 360.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: 300.0
    i_clamp: 220.0
    max_force: 600.0
    p: 8300.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_thj3_position_controller:
  joint: THJ3
  pid:
    d: 400.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: 400.0
    i_clamp: 200.0
    max_force: 600.0
    p: 7000.0
    position_deadband: 0.003
  type: sr_mechanism_controllers/SrhJointPositionController
sh_thj4_position_controller:
  joint: THJ4
  pid:
    d: -400.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: -300.0
    i_clamp: 200.0
    max_force: 800.0
    p: -6800.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_thj5_position_controller:
  joint: THJ5
  pid:
    d: 400.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: 300.0
    i_clamp: 200.0
    max_force: 800.0
    p: 6000.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_wrj1_position_controller:
  joint: WRJ1
  pid:
    d: 400.0
    deadband: 0.0
    friction_deadband: 65534.0
    i: 400.0
    i_clamp: 200.0
    max_force: 900.0
    p: 10000.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController
sh_wrj2_position_controller:
  joint: WRJ2
  pid:
    d: -400.0
    deadband: 0.0
    friction_deadband: 65535.0
    i: -400.0
    i_clamp: 200.0
    max_force: 900.0
    p: -11000.0
    position_deadband: 0.005
  type: sr_mechanism_controllers/SrhJointPositionController