Merge lp:~shadowrobot/sr-config/Bug_change_control_type into lp:sr-config
- Bug_change_control_type
- Merge into trunk
Proposed by
Toni Oliver
Status: | Merged |
---|---|
Merged at revision: | 22 |
Proposed branch: | lp:~shadowrobot/sr-config/Bug_change_control_type |
Merge into: | lp:sr-config |
Diff against target: |
777 lines (+756/-0) 4 files modified
sr_ethercat_hand_config/controls/host/sr_edc_effort_controllers_PWM.yaml (+118/-0) sr_ethercat_hand_config/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml (+238/-0) sr_ethercat_hand_config/controls/host/sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml (+380/-0) sr_ethercat_hand_config/controls/sr_edc_default_controllers.launch (+20/-0) |
To merge this branch: | bzr merge lp:~shadowrobot/sr-config/Bug_change_control_type |
Related bugs: |
Reviewer | Review Type | Date Requested | Status |
---|---|---|---|
Ugo | Approve | ||
Review via email: mp+132116@code.launchpad.net |
Commit message
Description of the change
Added PWM versions of the parameters for every kind of controller. Moved sr_edc_
To post a comment you must log in.
Revision history for this message
Ugo (ugocupcic) : | # |
review:
Approve
Preview Diff
[H/L] Next/Prev Comment, [J/K] Next/Prev File, [N/P] Next/Prev Hunk
1 | === added file 'sr_ethercat_hand_config/controls/host/sr_edc_effort_controllers_PWM.yaml' | |||
2 | --- sr_ethercat_hand_config/controls/host/sr_edc_effort_controllers_PWM.yaml 1970-01-01 00:00:00 +0000 | |||
3 | +++ sr_ethercat_hand_config/controls/host/sr_edc_effort_controllers_PWM.yaml 2012-10-30 14:29:21 +0000 | |||
4 | @@ -0,0 +1,118 @@ | |||
5 | 1 | # First Finger (Index finger) | ||
6 | 2 | sh_ffj0_effort_controller: | ||
7 | 3 | type: sr_mechanism_controllers/SrhEffortJointController | ||
8 | 4 | joint: FFJ2 | ||
9 | 5 | max_force: 0 | ||
10 | 6 | friction_deadband: 5000 | ||
11 | 7 | sh_ffj3_effort_controller: | ||
12 | 8 | type: sr_mechanism_controllers/SrhEffortJointController | ||
13 | 9 | joint: FFJ3 | ||
14 | 10 | max_force: 0 | ||
15 | 11 | friction_deadband: 5000 | ||
16 | 12 | sh_ffj4_effort_controller: | ||
17 | 13 | type: sr_mechanism_controllers/SrhEffortJointController | ||
18 | 14 | joint: FFJ4 | ||
19 | 15 | max_force: 0 | ||
20 | 16 | friction_deadband: 5 | ||
21 | 17 | |||
22 | 18 | |||
23 | 19 | # Middle Finger | ||
24 | 20 | sh_mfj0_effort_controller: | ||
25 | 21 | type: sr_mechanism_controllers/SrhEffortJointController | ||
26 | 22 | joint: MFJ2 | ||
27 | 23 | max_force: 0 | ||
28 | 24 | friction_deadband: 5 | ||
29 | 25 | sh_mfj3_effort_controller: | ||
30 | 26 | type: sr_mechanism_controllers/SrhEffortJointController | ||
31 | 27 | joint: MFJ3 | ||
32 | 28 | max_force: 0 | ||
33 | 29 | friction_deadband: 5 | ||
34 | 30 | sh_mfj4_effort_controller: | ||
35 | 31 | type: sr_mechanism_controllers/SrhEffortJointController | ||
36 | 32 | joint: MFJ4 | ||
37 | 33 | max_force: 0 | ||
38 | 34 | friction_deadband: 5 | ||
39 | 35 | |||
40 | 36 | |||
41 | 37 | # Ring Finger | ||
42 | 38 | sh_rfj0_effort_controller: | ||
43 | 39 | type: sr_mechanism_controllers/SrhEffortJointController | ||
44 | 40 | joint: RFJ2 | ||
45 | 41 | max_force: 0 | ||
46 | 42 | friction_deadband: 5 | ||
47 | 43 | sh_rfj3_effort_controller: | ||
48 | 44 | type: sr_mechanism_controllers/SrhEffortJointController | ||
49 | 45 | joint: RFJ3 | ||
50 | 46 | max_force: 0 | ||
51 | 47 | friction_deadband: 5 | ||
52 | 48 | sh_rfj4_effort_controller: | ||
53 | 49 | type: sr_mechanism_controllers/SrhEffortJointController | ||
54 | 50 | joint: RFJ4 | ||
55 | 51 | max_force: 0 | ||
56 | 52 | friction_deadband: 5 | ||
57 | 53 | |||
58 | 54 | |||
59 | 55 | # Little Finger | ||
60 | 56 | sh_lfj0_effort_controller: | ||
61 | 57 | type: sr_mechanism_controllers/SrhEffortJointController | ||
62 | 58 | joint: LFJ2 | ||
63 | 59 | max_force: 0 | ||
64 | 60 | friction_deadband: 5 | ||
65 | 61 | sh_lfj3_effort_controller: | ||
66 | 62 | type: sr_mechanism_controllers/SrhEffortJointController | ||
67 | 63 | joint: LFJ3 | ||
68 | 64 | max_force: 0 | ||
69 | 65 | friction_deadband: 5 | ||
70 | 66 | sh_lfj4_effort_controller: | ||
71 | 67 | type: sr_mechanism_controllers/SrhEffortJointController | ||
72 | 68 | joint: LFJ4 | ||
73 | 69 | max_force: 0 | ||
74 | 70 | friction_deadband: 5 | ||
75 | 71 | sh_lfj5_effort_controller: | ||
76 | 72 | type: sr_mechanism_controllers/SrhEffortJointController | ||
77 | 73 | joint: LFJ5 | ||
78 | 74 | max_force: 0 | ||
79 | 75 | friction_deadband: 5 | ||
80 | 76 | |||
81 | 77 | |||
82 | 78 | # Thumb | ||
83 | 79 | sh_thj1_effort_controller: | ||
84 | 80 | type: sr_mechanism_controllers/SrhEffortJointController | ||
85 | 81 | joint: THJ1 | ||
86 | 82 | max_force: 0 | ||
87 | 83 | friction_deadband: 5 | ||
88 | 84 | sh_thj2_effort_controller: | ||
89 | 85 | type: sr_mechanism_controllers/SrhEffortJointController | ||
90 | 86 | joint: THJ2 | ||
91 | 87 | max_force: 0 | ||
92 | 88 | friction_deadband: 5 | ||
93 | 89 | sh_thj3_effort_controller: | ||
94 | 90 | type: sr_mechanism_controllers/SrhEffortJointController | ||
95 | 91 | joint: THJ3 | ||
96 | 92 | max_force: 0 | ||
97 | 93 | friction_deadband: 5 | ||
98 | 94 | sh_thj4_effort_controller: | ||
99 | 95 | type: sr_mechanism_controllers/SrhEffortJointController | ||
100 | 96 | joint: THJ4 | ||
101 | 97 | max_force: 0 | ||
102 | 98 | friction_deadband: 5 | ||
103 | 99 | sh_thj5_effort_controller: | ||
104 | 100 | type: sr_mechanism_controllers/SrhEffortJointController | ||
105 | 101 | joint: THJ5 | ||
106 | 102 | max_force: 0 | ||
107 | 103 | friction_deadband: 5 | ||
108 | 104 | |||
109 | 105 | |||
110 | 106 | # Wrist | ||
111 | 107 | sh_wrj1_effort_controller: | ||
112 | 108 | type: sr_mechanism_controllers/SrhEffortJointController | ||
113 | 109 | joint: WRJ1 | ||
114 | 110 | max_force: 0 | ||
115 | 111 | friction_deadband: 5 | ||
116 | 112 | sh_wrj2_effort_controller: | ||
117 | 113 | type: sr_mechanism_controllers/SrhEffortJointController | ||
118 | 114 | joint: WRJ2 | ||
119 | 115 | max_force: 0 | ||
120 | 116 | friction_deadband: 5 | ||
121 | 117 | |||
122 | 118 | |||
123 | 0 | 119 | ||
124 | === modified file 'sr_ethercat_hand_config/controls/host/sr_edc_joint_position_controllers.yaml' (properties changed: +x to -x) | |||
125 | === modified file 'sr_ethercat_hand_config/controls/host/sr_edc_joint_position_controllers_PWM.yaml' (properties changed: +x to -x) | |||
126 | === added file 'sr_ethercat_hand_config/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml' | |||
127 | --- sr_ethercat_hand_config/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml 1970-01-01 00:00:00 +0000 | |||
128 | +++ sr_ethercat_hand_config/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml 2012-10-30 14:29:21 +0000 | |||
129 | @@ -0,0 +1,238 @@ | |||
130 | 1 | # Shadow Hand Defines .. Need Fixing as PID values are not correct | ||
131 | 2 | |||
132 | 3 | sh_ffj0_velocity_controller: | ||
133 | 4 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
134 | 5 | joint: FFJ0 | ||
135 | 6 | pid: | ||
136 | 7 | p: 0 | ||
137 | 8 | i: 0 | ||
138 | 9 | d: 0 | ||
139 | 10 | i_clamp: 1 | ||
140 | 11 | max_force: 0 | ||
141 | 12 | velocity_deadband: 0.015 | ||
142 | 13 | friction_deadband: 5 | ||
143 | 14 | sh_ffj3_velocity_controller: | ||
144 | 15 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
145 | 16 | joint: FFJ3 | ||
146 | 17 | pid: | ||
147 | 18 | p: 0 | ||
148 | 19 | i: 0 | ||
149 | 20 | d: 0 | ||
150 | 21 | i_clamp: 0 | ||
151 | 22 | max_force: 0 | ||
152 | 23 | velocity_deadband: 0.0 | ||
153 | 24 | friction_deadband: 5 | ||
154 | 25 | sh_ffj4_velocity_controller: | ||
155 | 26 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
156 | 27 | joint: FFJ4 | ||
157 | 28 | pid: | ||
158 | 29 | p: 0 | ||
159 | 30 | i: 0 | ||
160 | 31 | d: 0 | ||
161 | 32 | i_clamp: 1 | ||
162 | 33 | max_force: 0 | ||
163 | 34 | velocity_deadband: 0.015 | ||
164 | 35 | friction_deadband: 5 | ||
165 | 36 | |||
166 | 37 | |||
167 | 38 | sh_mfj0_velocity_controller: | ||
168 | 39 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
169 | 40 | joint: MFJ0 | ||
170 | 41 | pid: | ||
171 | 42 | p: 0 | ||
172 | 43 | i: 0 | ||
173 | 44 | d: 0 | ||
174 | 45 | i_clamp: 1 | ||
175 | 46 | max_force: 0 | ||
176 | 47 | velocity_deadband: 0.015 | ||
177 | 48 | friction_deadband: 5 | ||
178 | 49 | sh_mfj3_velocity_controller: | ||
179 | 50 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
180 | 51 | joint: MFJ3 | ||
181 | 52 | pid: | ||
182 | 53 | p: 0 | ||
183 | 54 | i: 0 | ||
184 | 55 | d: 0 | ||
185 | 56 | i_clamp: 1 | ||
186 | 57 | max_force: 0 | ||
187 | 58 | velocity_deadband: 0.015 | ||
188 | 59 | friction_deadband: 5 | ||
189 | 60 | sh_mfj4_velocity_controller: | ||
190 | 61 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
191 | 62 | joint: MFJ4 | ||
192 | 63 | pid: | ||
193 | 64 | p: 0.0 | ||
194 | 65 | i: -0.5 | ||
195 | 66 | d: 0 | ||
196 | 67 | i_clamp: 1 | ||
197 | 68 | max_force: 0 | ||
198 | 69 | velocity_deadband: 0.015 | ||
199 | 70 | friction_deadband: 5 | ||
200 | 71 | |||
201 | 72 | |||
202 | 73 | |||
203 | 74 | sh_rfj0_velocity_controller: | ||
204 | 75 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
205 | 76 | joint: RFJ0 | ||
206 | 77 | pid: | ||
207 | 78 | p: 0 | ||
208 | 79 | i: 0 | ||
209 | 80 | d: 0 | ||
210 | 81 | i_clamp: 1 | ||
211 | 82 | max_force: 0 | ||
212 | 83 | velocity_deadband: 0.015 | ||
213 | 84 | friction_deadband: 5 | ||
214 | 85 | sh_rfj3_velocity_controller: | ||
215 | 86 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
216 | 87 | joint: RFJ3 | ||
217 | 88 | pid: | ||
218 | 89 | p: 0 | ||
219 | 90 | i: 0 | ||
220 | 91 | d: 0 | ||
221 | 92 | i_clamp: 1 | ||
222 | 93 | max_force: 0 | ||
223 | 94 | velocity_deadband: 0.015 | ||
224 | 95 | friction_deadband: 5 | ||
225 | 96 | sh_rfj4_velocity_controller: | ||
226 | 97 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
227 | 98 | joint: RFJ4 | ||
228 | 99 | pid: | ||
229 | 100 | p: 0 | ||
230 | 101 | i: 0 | ||
231 | 102 | d: 0 | ||
232 | 103 | i_clamp: 1 | ||
233 | 104 | max_force: 0 | ||
234 | 105 | velocity_deadband: 0.015 | ||
235 | 106 | friction_deadband: 5 | ||
236 | 107 | |||
237 | 108 | |||
238 | 109 | |||
239 | 110 | sh_lfj0_velocity_controller: | ||
240 | 111 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
241 | 112 | joint: LFJ0 | ||
242 | 113 | pid: | ||
243 | 114 | p: 0 | ||
244 | 115 | i: 0 | ||
245 | 116 | d: 0 | ||
246 | 117 | i_clamp: 1 | ||
247 | 118 | max_force: 0 | ||
248 | 119 | velocity_deadband: 0.015 | ||
249 | 120 | friction_deadband: 5 | ||
250 | 121 | sh_lfj3_velocity_controller: | ||
251 | 122 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
252 | 123 | joint: LFJ3 | ||
253 | 124 | pid: | ||
254 | 125 | p: 0 | ||
255 | 126 | i: 0 | ||
256 | 127 | d: 0 | ||
257 | 128 | i_clamp: 1 | ||
258 | 129 | max_force: 0 | ||
259 | 130 | velocity_deadband: 0.015 | ||
260 | 131 | friction_deadband: 5 | ||
261 | 132 | sh_lfj4_velocity_controller: | ||
262 | 133 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
263 | 134 | joint: LFJ4 | ||
264 | 135 | pid: | ||
265 | 136 | p: 0 | ||
266 | 137 | i: 0 | ||
267 | 138 | d: 0 | ||
268 | 139 | i_clamp: 1 | ||
269 | 140 | max_force: 0 | ||
270 | 141 | velocity_deadband: 0.015 | ||
271 | 142 | friction_deadband: 5 | ||
272 | 143 | sh_lfj5_velocity_controller: | ||
273 | 144 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
274 | 145 | joint: LFJ5 | ||
275 | 146 | pid: | ||
276 | 147 | p: 0 | ||
277 | 148 | i: 0 | ||
278 | 149 | d: 0 | ||
279 | 150 | i_clamp: 1 | ||
280 | 151 | max_force: 0 | ||
281 | 152 | velocity_deadband: 0.015 | ||
282 | 153 | friction_deadband: 5 | ||
283 | 154 | |||
284 | 155 | |||
285 | 156 | |||
286 | 157 | sh_thj1_velocity_controller: | ||
287 | 158 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
288 | 159 | joint: THJ1 | ||
289 | 160 | pid: | ||
290 | 161 | p: 0 | ||
291 | 162 | i: 0 | ||
292 | 163 | d: 0 | ||
293 | 164 | i_clamp: 1 | ||
294 | 165 | max_force: 0 | ||
295 | 166 | velocity_deadband: 0.015 | ||
296 | 167 | friction_deadband: 5 | ||
297 | 168 | sh_thj2_velocity_controller: | ||
298 | 169 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
299 | 170 | joint: THJ2 | ||
300 | 171 | pid: | ||
301 | 172 | p: 0 | ||
302 | 173 | i: 0 | ||
303 | 174 | d: 0 | ||
304 | 175 | i_clamp: 1 | ||
305 | 176 | max_force: 0 | ||
306 | 177 | velocity_deadband: 0.015 | ||
307 | 178 | friction_deadband: 5 | ||
308 | 179 | sh_thj3_velocity_controller: | ||
309 | 180 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
310 | 181 | joint: THJ3 | ||
311 | 182 | pid: | ||
312 | 183 | p: 0 | ||
313 | 184 | i: 0 | ||
314 | 185 | d: 0 | ||
315 | 186 | i_clamp: 1 | ||
316 | 187 | max_force: 0 | ||
317 | 188 | velocity_deadband: 0.015 | ||
318 | 189 | friction_deadband: 5 | ||
319 | 190 | sh_thj4_velocity_controller: | ||
320 | 191 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
321 | 192 | joint: THJ4 | ||
322 | 193 | pid: | ||
323 | 194 | p: 0 | ||
324 | 195 | i: 0 | ||
325 | 196 | d: 0 | ||
326 | 197 | i_clamp: 1 | ||
327 | 198 | max_force: 0 | ||
328 | 199 | velocity_deadband: 0.015 | ||
329 | 200 | friction_deadband: 5 | ||
330 | 201 | sh_thj5_velocity_controller: | ||
331 | 202 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
332 | 203 | joint: THJ5 | ||
333 | 204 | pid: | ||
334 | 205 | p: 0 | ||
335 | 206 | i: 0 | ||
336 | 207 | d: 0 | ||
337 | 208 | i_clamp: 1 | ||
338 | 209 | max_force: 0 | ||
339 | 210 | velocity_deadband: 0.015 | ||
340 | 211 | friction_deadband: 5 | ||
341 | 212 | |||
342 | 213 | |||
343 | 214 | |||
344 | 215 | sh_wrj1_velocity_controller: | ||
345 | 216 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
346 | 217 | joint: WRJ1 | ||
347 | 218 | pid: | ||
348 | 219 | p: 0 | ||
349 | 220 | i: 0 | ||
350 | 221 | d: 0 | ||
351 | 222 | i_clamp: 1 | ||
352 | 223 | max_force: 0 | ||
353 | 224 | velocity_deadband: 0.015 | ||
354 | 225 | friction_deadband: 5 | ||
355 | 226 | sh_wrj2_velocity_controller: | ||
356 | 227 | type: sr_mechanism_controllers/SrhJointVelocityController | ||
357 | 228 | joint: WRJ2 | ||
358 | 229 | pid: | ||
359 | 230 | p: 0 | ||
360 | 231 | i: 0 | ||
361 | 232 | d: 0 | ||
362 | 233 | i_clamp: 1 | ||
363 | 234 | max_force: 0 | ||
364 | 235 | velocity_deadband: 0.015 | ||
365 | 236 | friction_deadband: 5 | ||
366 | 237 | |||
367 | 238 | |||
368 | 0 | 239 | ||
369 | === added file 'sr_ethercat_hand_config/controls/host/sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml' | |||
370 | --- sr_ethercat_hand_config/controls/host/sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml 1970-01-01 00:00:00 +0000 | |||
371 | +++ sr_ethercat_hand_config/controls/host/sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml 2012-10-30 14:29:21 +0000 | |||
372 | @@ -0,0 +1,380 @@ | |||
373 | 1 | sh_ffj0_mixed_position_velocity_controller: | ||
374 | 2 | joint: FFJ0 | ||
375 | 3 | motor_min_force_threshold: 40 | ||
376 | 4 | position_pid: | ||
377 | 5 | d: 0.0 | ||
378 | 6 | i: -1.5 | ||
379 | 7 | i_clamp: 0.3 | ||
380 | 8 | max_velocity: 3.0 | ||
381 | 9 | min_velocity: -3.0 | ||
382 | 10 | p: -4.0 | ||
383 | 11 | position_deadband: 0.002 | ||
384 | 12 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
385 | 13 | velocity_pid: | ||
386 | 14 | d: 0.0 | ||
387 | 15 | friction_deadband: 100.0 | ||
388 | 16 | i: 210.0 | ||
389 | 17 | i_clamp: 160.0 | ||
390 | 18 | max_force: 0.0 | ||
391 | 19 | p: 150.0 | ||
392 | 20 | sh_ffj3_mixed_position_velocity_controller: | ||
393 | 21 | joint: FFJ3 | ||
394 | 22 | motor_min_force_threshold: 40 | ||
395 | 23 | position_pid: | ||
396 | 24 | d: 0.0 | ||
397 | 25 | i: -1.5 | ||
398 | 26 | i_clamp: 0.3 | ||
399 | 27 | max_velocity: 1.5 | ||
400 | 28 | min_velocity: -1.5 | ||
401 | 29 | p: -4.0 | ||
402 | 30 | position_deadband: 0.002 | ||
403 | 31 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
404 | 32 | velocity_pid: | ||
405 | 33 | d: 0.0 | ||
406 | 34 | friction_deadband: 100.0 | ||
407 | 35 | i: 210.0 | ||
408 | 36 | i_clamp: 160.0 | ||
409 | 37 | max_force: 0.0 | ||
410 | 38 | p: 150.0 | ||
411 | 39 | sh_ffj4_mixed_position_velocity_controller: | ||
412 | 40 | joint: FFJ4 | ||
413 | 41 | motor_min_force_threshold: 40 | ||
414 | 42 | position_pid: | ||
415 | 43 | d: 0.0 | ||
416 | 44 | i: -1.5 | ||
417 | 45 | i_clamp: 0.3 | ||
418 | 46 | max_velocity: 1.5 | ||
419 | 47 | min_velocity: -1.5 | ||
420 | 48 | p: -4.0 | ||
421 | 49 | position_deadband: 0.003 | ||
422 | 50 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
423 | 51 | velocity_pid: | ||
424 | 52 | d: 0.0 | ||
425 | 53 | friction_deadband: 5000.0 | ||
426 | 54 | i: -210.0 | ||
427 | 55 | i_clamp: 160.0 | ||
428 | 56 | max_force: 0.0 | ||
429 | 57 | p: -150.0 | ||
430 | 58 | sh_lfj0_mixed_position_velocity_controller: | ||
431 | 59 | joint: LFJ0 | ||
432 | 60 | motor_min_force_threshold: 40 | ||
433 | 61 | position_pid: | ||
434 | 62 | d: 0.0 | ||
435 | 63 | i: -1.5 | ||
436 | 64 | i_clamp: 0.3 | ||
437 | 65 | max_velocity: 3.0 | ||
438 | 66 | min_velocity: -3.0 | ||
439 | 67 | p: -4.0 | ||
440 | 68 | position_deadband: 0.002 | ||
441 | 69 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
442 | 70 | velocity_pid: | ||
443 | 71 | d: 0.0 | ||
444 | 72 | friction_deadband: 100.0 | ||
445 | 73 | i: -210.0 | ||
446 | 74 | i_clamp: 160.0 | ||
447 | 75 | max_force: 0.0 | ||
448 | 76 | p: -150.0 | ||
449 | 77 | sh_lfj3_mixed_position_velocity_controller: | ||
450 | 78 | joint: LFJ3 | ||
451 | 79 | motor_min_force_threshold: 40 | ||
452 | 80 | position_pid: | ||
453 | 81 | d: 0.0 | ||
454 | 82 | i: -1.5 | ||
455 | 83 | i_clamp: 0.3 | ||
456 | 84 | max_velocity: 1.5 | ||
457 | 85 | min_velocity: -1.5 | ||
458 | 86 | p: -4.0 | ||
459 | 87 | position_deadband: 0.002 | ||
460 | 88 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
461 | 89 | velocity_pid: | ||
462 | 90 | d: 0.0 | ||
463 | 91 | friction_deadband: 100.0 | ||
464 | 92 | i: -210.0 | ||
465 | 93 | i_clamp: 160.0 | ||
466 | 94 | max_force: 0.0 | ||
467 | 95 | p: -150.0 | ||
468 | 96 | sh_lfj4_mixed_position_velocity_controller: | ||
469 | 97 | joint: LFJ4 | ||
470 | 98 | motor_min_force_threshold: 40 | ||
471 | 99 | position_pid: | ||
472 | 100 | d: 0.0 | ||
473 | 101 | i: -1.5 | ||
474 | 102 | i_clamp: 0.3 | ||
475 | 103 | max_velocity: 1.5 | ||
476 | 104 | min_velocity: -1.5 | ||
477 | 105 | p: -4.0 | ||
478 | 106 | position_deadband: 0.003 | ||
479 | 107 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
480 | 108 | velocity_pid: | ||
481 | 109 | d: 0.0 | ||
482 | 110 | friction_deadband: 5000.0 | ||
483 | 111 | i: 210.0 | ||
484 | 112 | i_clamp: 160.0 | ||
485 | 113 | max_force: 0.0 | ||
486 | 114 | p: 150.0 | ||
487 | 115 | sh_lfj5_mixed_position_velocity_controller: | ||
488 | 116 | joint: LFJ5 | ||
489 | 117 | motor_min_force_threshold: 40 | ||
490 | 118 | position_pid: | ||
491 | 119 | d: 0.0 | ||
492 | 120 | i: -1.5 | ||
493 | 121 | i_clamp: 0.3 | ||
494 | 122 | max_velocity: 1.5 | ||
495 | 123 | min_velocity: -1.5 | ||
496 | 124 | p: -4.0 | ||
497 | 125 | position_deadband: 0.003 | ||
498 | 126 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
499 | 127 | velocity_pid: | ||
500 | 128 | d: 0.0 | ||
501 | 129 | friction_deadband: 5000.0 | ||
502 | 130 | i: -210.0 | ||
503 | 131 | i_clamp: 410.0 | ||
504 | 132 | max_force: 0.0 | ||
505 | 133 | p: -150.0 | ||
506 | 134 | sh_mfj0_mixed_position_velocity_controller: | ||
507 | 135 | joint: MFJ0 | ||
508 | 136 | motor_min_force_threshold: 40 | ||
509 | 137 | position_pid: | ||
510 | 138 | d: 0.0 | ||
511 | 139 | i: -1.5 | ||
512 | 140 | i_clamp: 0.3 | ||
513 | 141 | max_velocity: 3.0 | ||
514 | 142 | min_velocity: -3.0 | ||
515 | 143 | p: -4.0 | ||
516 | 144 | position_deadband: 0.002 | ||
517 | 145 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
518 | 146 | velocity_pid: | ||
519 | 147 | d: 0.0 | ||
520 | 148 | friction_deadband: 100.0 | ||
521 | 149 | i: 210.0 | ||
522 | 150 | i_clamp: 160.0 | ||
523 | 151 | max_force: 0.0 | ||
524 | 152 | p: 150.0 | ||
525 | 153 | sh_mfj3_mixed_position_velocity_controller: | ||
526 | 154 | joint: MFJ3 | ||
527 | 155 | motor_min_force_threshold: 40 | ||
528 | 156 | position_pid: | ||
529 | 157 | d: 0.0 | ||
530 | 158 | i: -1.5 | ||
531 | 159 | i_clamp: 0.3 | ||
532 | 160 | max_velocity: 1.5 | ||
533 | 161 | min_velocity: -1.5 | ||
534 | 162 | p: -4.0 | ||
535 | 163 | position_deadband: 0.002 | ||
536 | 164 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
537 | 165 | velocity_pid: | ||
538 | 166 | d: 0.0 | ||
539 | 167 | friction_deadband: 100.0 | ||
540 | 168 | i: 210.0 | ||
541 | 169 | i_clamp: 160.0 | ||
542 | 170 | max_force: 0.0 | ||
543 | 171 | p: 150.0 | ||
544 | 172 | sh_mfj4_mixed_position_velocity_controller: | ||
545 | 173 | joint: MFJ4 | ||
546 | 174 | motor_min_force_threshold: 40 | ||
547 | 175 | position_pid: | ||
548 | 176 | d: 0.0 | ||
549 | 177 | i: -1.5 | ||
550 | 178 | i_clamp: 0.3 | ||
551 | 179 | max_velocity: 1.5 | ||
552 | 180 | min_velocity: -1.5 | ||
553 | 181 | p: -4.0 | ||
554 | 182 | position_deadband: 0.003 | ||
555 | 183 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
556 | 184 | velocity_pid: | ||
557 | 185 | d: 0.0 | ||
558 | 186 | friction_deadband: 5000.0 | ||
559 | 187 | i: -210.0 | ||
560 | 188 | i_clamp: 160.0 | ||
561 | 189 | max_force: 0.0 | ||
562 | 190 | p: -150.0 | ||
563 | 191 | sh_rfj0_mixed_position_velocity_controller: | ||
564 | 192 | joint: RFJ0 | ||
565 | 193 | motor_min_force_threshold: 40 | ||
566 | 194 | position_pid: | ||
567 | 195 | d: 0.0 | ||
568 | 196 | i: -1.5 | ||
569 | 197 | i_clamp: 0.3 | ||
570 | 198 | max_velocity: 3.0 | ||
571 | 199 | min_velocity: -3.0 | ||
572 | 200 | p: -4.0 | ||
573 | 201 | position_deadband: 0.002 | ||
574 | 202 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
575 | 203 | velocity_pid: | ||
576 | 204 | d: 0.0 | ||
577 | 205 | friction_deadband: 100.0 | ||
578 | 206 | i: -210.0 | ||
579 | 207 | i_clamp: 160.0 | ||
580 | 208 | max_force: 0.0 | ||
581 | 209 | p: -150.0 | ||
582 | 210 | sh_rfj3_mixed_position_velocity_controller: | ||
583 | 211 | joint: RFJ3 | ||
584 | 212 | motor_min_force_threshold: 40 | ||
585 | 213 | position_pid: | ||
586 | 214 | d: 0.0 | ||
587 | 215 | i: -1.5 | ||
588 | 216 | i_clamp: 0.3 | ||
589 | 217 | max_velocity: 1.5 | ||
590 | 218 | min_velocity: -1.5 | ||
591 | 219 | p: -4.0 | ||
592 | 220 | position_deadband: 0.002 | ||
593 | 221 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
594 | 222 | velocity_pid: | ||
595 | 223 | d: 0.0 | ||
596 | 224 | friction_deadband: 100.0 | ||
597 | 225 | i: -210.0 | ||
598 | 226 | i_clamp: 160.0 | ||
599 | 227 | max_force: 0.0 | ||
600 | 228 | p: -150.0 | ||
601 | 229 | sh_rfj4_mixed_position_velocity_controller: | ||
602 | 230 | joint: RFJ4 | ||
603 | 231 | motor_min_force_threshold: 40 | ||
604 | 232 | position_pid: | ||
605 | 233 | d: 0.0 | ||
606 | 234 | i: -1.5 | ||
607 | 235 | i_clamp: 0.3 | ||
608 | 236 | max_velocity: 1.5 | ||
609 | 237 | min_velocity: -1.5 | ||
610 | 238 | p: -4.0 | ||
611 | 239 | position_deadband: 0.003 | ||
612 | 240 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
613 | 241 | velocity_pid: | ||
614 | 242 | d: 0.0 | ||
615 | 243 | friction_deadband: 5000.0 | ||
616 | 244 | i: -210.0 | ||
617 | 245 | i_clamp: 160.0 | ||
618 | 246 | max_force: 0.0 | ||
619 | 247 | p: -150.0 | ||
620 | 248 | sh_thj1_mixed_position_velocity_controller: | ||
621 | 249 | joint: THJ1 | ||
622 | 250 | motor_min_force_threshold: 40 | ||
623 | 251 | position_pid: | ||
624 | 252 | d: 0.0 | ||
625 | 253 | i: -1.5 | ||
626 | 254 | i_clamp: 0.3 | ||
627 | 255 | max_velocity: 3.0 | ||
628 | 256 | min_velocity: -3.0 | ||
629 | 257 | p: -4.0 | ||
630 | 258 | position_deadband: 0.002 | ||
631 | 259 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
632 | 260 | velocity_pid: | ||
633 | 261 | d: 0.0 | ||
634 | 262 | friction_deadband: 100.0 | ||
635 | 263 | i: 210.0 | ||
636 | 264 | i_clamp: 160.0 | ||
637 | 265 | max_force: 0.0 | ||
638 | 266 | p: 150.0 | ||
639 | 267 | sh_thj2_mixed_position_velocity_controller: | ||
640 | 268 | joint: THJ2 | ||
641 | 269 | motor_min_force_threshold: 40 | ||
642 | 270 | position_pid: | ||
643 | 271 | d: 0.0 | ||
644 | 272 | i: -1.5 | ||
645 | 273 | i_clamp: 0.3 | ||
646 | 274 | max_velocity: 3.0 | ||
647 | 275 | min_velocity: -3.0 | ||
648 | 276 | p: -4.0 | ||
649 | 277 | position_deadband: 0.002 | ||
650 | 278 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
651 | 279 | velocity_pid: | ||
652 | 280 | d: 0.0 | ||
653 | 281 | friction_deadband: 100.0 | ||
654 | 282 | i: 210.0 | ||
655 | 283 | i_clamp: 160.0 | ||
656 | 284 | max_force: 0.0 | ||
657 | 285 | p: 150.0 | ||
658 | 286 | sh_thj3_mixed_position_velocity_controller: | ||
659 | 287 | joint: THJ3 | ||
660 | 288 | motor_min_force_threshold: 40 | ||
661 | 289 | position_pid: | ||
662 | 290 | d: 0.0 | ||
663 | 291 | i: -1.5 | ||
664 | 292 | i_clamp: 0.3 | ||
665 | 293 | max_velocity: 1.5 | ||
666 | 294 | min_velocity: -1.5 | ||
667 | 295 | p: -4.0 | ||
668 | 296 | position_deadband: 0.002 | ||
669 | 297 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
670 | 298 | velocity_pid: | ||
671 | 299 | d: 0.0 | ||
672 | 300 | friction_deadband: 100.0 | ||
673 | 301 | i: 210.0 | ||
674 | 302 | i_clamp: 160.0 | ||
675 | 303 | max_force: 0.0 | ||
676 | 304 | p: 150.0 | ||
677 | 305 | sh_thj4_mixed_position_velocity_controller: | ||
678 | 306 | joint: THJ4 | ||
679 | 307 | motor_min_force_threshold: 40 | ||
680 | 308 | position_pid: | ||
681 | 309 | d: 0.0 | ||
682 | 310 | i: -1.5 | ||
683 | 311 | i_clamp: 0.3 | ||
684 | 312 | max_velocity: 1.5 | ||
685 | 313 | min_velocity: -1.5 | ||
686 | 314 | p: -4.0 | ||
687 | 315 | position_deadband: 0.003 | ||
688 | 316 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
689 | 317 | velocity_pid: | ||
690 | 318 | d: 0.0 | ||
691 | 319 | friction_deadband: 5000.0 | ||
692 | 320 | i: -260.0 | ||
693 | 321 | i_clamp: 180.0 | ||
694 | 322 | max_force: 0.0 | ||
695 | 323 | p: -210.0 | ||
696 | 324 | sh_thj5_mixed_position_velocity_controller: | ||
697 | 325 | joint: THJ5 | ||
698 | 326 | motor_min_force_threshold: 40 | ||
699 | 327 | position_pid: | ||
700 | 328 | d: 0.0 | ||
701 | 329 | i: -1.5 | ||
702 | 330 | i_clamp: 0.3 | ||
703 | 331 | max_velocity: 1.5 | ||
704 | 332 | min_velocity: -1.5 | ||
705 | 333 | p: -4.0 | ||
706 | 334 | position_deadband: 0.003 | ||
707 | 335 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
708 | 336 | velocity_pid: | ||
709 | 337 | d: 0.0 | ||
710 | 338 | friction_deadband: 5000.0 | ||
711 | 339 | i: 210.0 | ||
712 | 340 | i_clamp: 160.0 | ||
713 | 341 | max_force: 0.0 | ||
714 | 342 | p: 150.0 | ||
715 | 343 | sh_wrj1_mixed_position_velocity_controller: | ||
716 | 344 | joint: WRJ1 | ||
717 | 345 | motor_min_force_threshold: 40 | ||
718 | 346 | position_pid: | ||
719 | 347 | d: 0.0 | ||
720 | 348 | i: -1.5 | ||
721 | 349 | i_clamp: 0.3 | ||
722 | 350 | max_velocity: 0.5 | ||
723 | 351 | min_velocity: -0.5 | ||
724 | 352 | p: -4.0 | ||
725 | 353 | position_deadband: 0.002 | ||
726 | 354 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
727 | 355 | velocity_pid: | ||
728 | 356 | d: 0.0 | ||
729 | 357 | friction_deadband: 100.0 | ||
730 | 358 | i: 460.0 | ||
731 | 359 | i_clamp: 270.0 | ||
732 | 360 | max_force: 0.0 | ||
733 | 361 | p: 320.0 | ||
734 | 362 | sh_wrj2_mixed_position_velocity_controller: | ||
735 | 363 | joint: WRJ2 | ||
736 | 364 | motor_min_force_threshold: 40 | ||
737 | 365 | position_pid: | ||
738 | 366 | d: 0.0 | ||
739 | 367 | i: -1.5 | ||
740 | 368 | i_clamp: 0.3 | ||
741 | 369 | max_velocity: 0.5 | ||
742 | 370 | min_velocity: -0.5 | ||
743 | 371 | p: -4.0 | ||
744 | 372 | position_deadband: 0.002 | ||
745 | 373 | type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController | ||
746 | 374 | velocity_pid: | ||
747 | 375 | d: 0.0 | ||
748 | 376 | friction_deadband: 100.0 | ||
749 | 377 | i: -280.0 | ||
750 | 378 | i_clamp: 190.0 | ||
751 | 379 | max_force: 0.0 | ||
752 | 380 | p: -230.0 | ||
753 | 0 | 381 | ||
754 | === added file 'sr_ethercat_hand_config/controls/sr_edc_default_controllers.launch' | |||
755 | --- sr_ethercat_hand_config/controls/sr_edc_default_controllers.launch 1970-01-01 00:00:00 +0000 | |||
756 | +++ sr_ethercat_hand_config/controls/sr_edc_default_controllers.launch 2012-10-30 14:29:21 +0000 | |||
757 | @@ -0,0 +1,20 @@ | |||
758 | 1 | <launch> | ||
759 | 2 | <!-- <rosparam command="load" file="$(find sr_ethercat_hand_config)/controls/motors/motor_board_effort_controllers_stopped.yaml" /> --> | ||
760 | 3 | <!-- <rosparam command="load" file="$(find sr_ethercat_hand_config)/controls/motors/motor_board_effort_controllers_ff_and_th.yaml" /> --> | ||
761 | 4 | <rosparam command="load" file="$(find sr_ethercat_hand_config)/controls/motors/motor_board_effort_controllers.yaml" /> | ||
762 | 5 | <rosparam command="load" file="$(find sr_ethercat_hand_config)/controls/friction_compensation.yaml" /> | ||
763 | 6 | |||
764 | 7 | <!-- Parameters for the controllers if we're using torque control mode, i.e. sending force commands to | ||
765 | 8 | the force control loop in the motor board (that uses the data from the tendon strain gauges) --> | ||
766 | 9 | <rosparam unless="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_effort_controllers.yaml" /> | ||
767 | 10 | <rosparam unless="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_joint_position_controllers.yaml" /> | ||
768 | 11 | <rosparam unless="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_mixed_position_velocity_joint_controllers.yaml" /> | ||
769 | 12 | <rosparam unless="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_joint_velocity_controllers.yaml" /> | ||
770 | 13 | |||
771 | 14 | <!-- Parameters for the controllers if we're using PWM control mode, i.e. sending direct PWM commands from the host to the motor, | ||
772 | 15 | WITHOUT using the force control loop in the motor board (that uses the data from the tendon strain gauges) --> | ||
773 | 16 | <rosparam if="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_effort_controllers_PWM.yaml" /> | ||
774 | 17 | <rosparam if="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_joint_position_controllers_PWM.yaml" /> | ||
775 | 18 | <rosparam if="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml" /> | ||
776 | 19 | <rosparam if="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml" /> | ||
777 | 20 | </launch> |