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