Merge lp:~shadowrobot/sr-config/Bug_change_control_type into lp:sr-config

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
Reviewer Review Type Date Requested Status
Ugo Approve
Review via email: mp+132116@code.launchpad.net

Description of the change

Added PWM versions of the parameters for every kind of controller. Moved sr_edc_default_controllers.launch to sr_config stack. Removed unnecessary execution permission from yaml files.

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
=== added file 'sr_ethercat_hand_config/controls/host/sr_edc_effort_controllers_PWM.yaml'
--- sr_ethercat_hand_config/controls/host/sr_edc_effort_controllers_PWM.yaml 1970-01-01 00:00:00 +0000
+++ sr_ethercat_hand_config/controls/host/sr_edc_effort_controllers_PWM.yaml 2012-10-30 14:29:21 +0000
@@ -0,0 +1,118 @@
1# First Finger (Index finger)
2sh_ffj0_effort_controller:
3 type: sr_mechanism_controllers/SrhEffortJointController
4 joint: FFJ2
5 max_force: 0
6 friction_deadband: 5000
7sh_ffj3_effort_controller:
8 type: sr_mechanism_controllers/SrhEffortJointController
9 joint: FFJ3
10 max_force: 0
11 friction_deadband: 5000
12sh_ffj4_effort_controller:
13 type: sr_mechanism_controllers/SrhEffortJointController
14 joint: FFJ4
15 max_force: 0
16 friction_deadband: 5
17
18
19# Middle Finger
20sh_mfj0_effort_controller:
21 type: sr_mechanism_controllers/SrhEffortJointController
22 joint: MFJ2
23 max_force: 0
24 friction_deadband: 5
25sh_mfj3_effort_controller:
26 type: sr_mechanism_controllers/SrhEffortJointController
27 joint: MFJ3
28 max_force: 0
29 friction_deadband: 5
30sh_mfj4_effort_controller:
31 type: sr_mechanism_controllers/SrhEffortJointController
32 joint: MFJ4
33 max_force: 0
34 friction_deadband: 5
35
36
37# Ring Finger
38sh_rfj0_effort_controller:
39 type: sr_mechanism_controllers/SrhEffortJointController
40 joint: RFJ2
41 max_force: 0
42 friction_deadband: 5
43sh_rfj3_effort_controller:
44 type: sr_mechanism_controllers/SrhEffortJointController
45 joint: RFJ3
46 max_force: 0
47 friction_deadband: 5
48sh_rfj4_effort_controller:
49 type: sr_mechanism_controllers/SrhEffortJointController
50 joint: RFJ4
51 max_force: 0
52 friction_deadband: 5
53
54
55# Little Finger
56sh_lfj0_effort_controller:
57 type: sr_mechanism_controllers/SrhEffortJointController
58 joint: LFJ2
59 max_force: 0
60 friction_deadband: 5
61sh_lfj3_effort_controller:
62 type: sr_mechanism_controllers/SrhEffortJointController
63 joint: LFJ3
64 max_force: 0
65 friction_deadband: 5
66sh_lfj4_effort_controller:
67 type: sr_mechanism_controllers/SrhEffortJointController
68 joint: LFJ4
69 max_force: 0
70 friction_deadband: 5
71sh_lfj5_effort_controller:
72 type: sr_mechanism_controllers/SrhEffortJointController
73 joint: LFJ5
74 max_force: 0
75 friction_deadband: 5
76
77
78# Thumb
79sh_thj1_effort_controller:
80 type: sr_mechanism_controllers/SrhEffortJointController
81 joint: THJ1
82 max_force: 0
83 friction_deadband: 5
84sh_thj2_effort_controller:
85 type: sr_mechanism_controllers/SrhEffortJointController
86 joint: THJ2
87 max_force: 0
88 friction_deadband: 5
89sh_thj3_effort_controller:
90 type: sr_mechanism_controllers/SrhEffortJointController
91 joint: THJ3
92 max_force: 0
93 friction_deadband: 5
94sh_thj4_effort_controller:
95 type: sr_mechanism_controllers/SrhEffortJointController
96 joint: THJ4
97 max_force: 0
98 friction_deadband: 5
99sh_thj5_effort_controller:
100 type: sr_mechanism_controllers/SrhEffortJointController
101 joint: THJ5
102 max_force: 0
103 friction_deadband: 5
104
105
106# Wrist
107sh_wrj1_effort_controller:
108 type: sr_mechanism_controllers/SrhEffortJointController
109 joint: WRJ1
110 max_force: 0
111 friction_deadband: 5
112sh_wrj2_effort_controller:
113 type: sr_mechanism_controllers/SrhEffortJointController
114 joint: WRJ2
115 max_force: 0
116 friction_deadband: 5
117
118
0119
=== modified file 'sr_ethercat_hand_config/controls/host/sr_edc_joint_position_controllers.yaml' (properties changed: +x to -x)
=== modified file 'sr_ethercat_hand_config/controls/host/sr_edc_joint_position_controllers_PWM.yaml' (properties changed: +x to -x)
=== added file 'sr_ethercat_hand_config/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml'
--- sr_ethercat_hand_config/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml 1970-01-01 00:00:00 +0000
+++ sr_ethercat_hand_config/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml 2012-10-30 14:29:21 +0000
@@ -0,0 +1,238 @@
1# Shadow Hand Defines .. Need Fixing as PID values are not correct
2
3sh_ffj0_velocity_controller:
4 type: sr_mechanism_controllers/SrhJointVelocityController
5 joint: FFJ0
6 pid:
7 p: 0
8 i: 0
9 d: 0
10 i_clamp: 1
11 max_force: 0
12 velocity_deadband: 0.015
13 friction_deadband: 5
14sh_ffj3_velocity_controller:
15 type: sr_mechanism_controllers/SrhJointVelocityController
16 joint: FFJ3
17 pid:
18 p: 0
19 i: 0
20 d: 0
21 i_clamp: 0
22 max_force: 0
23 velocity_deadband: 0.0
24 friction_deadband: 5
25sh_ffj4_velocity_controller:
26 type: sr_mechanism_controllers/SrhJointVelocityController
27 joint: FFJ4
28 pid:
29 p: 0
30 i: 0
31 d: 0
32 i_clamp: 1
33 max_force: 0
34 velocity_deadband: 0.015
35 friction_deadband: 5
36
37
38sh_mfj0_velocity_controller:
39 type: sr_mechanism_controllers/SrhJointVelocityController
40 joint: MFJ0
41 pid:
42 p: 0
43 i: 0
44 d: 0
45 i_clamp: 1
46 max_force: 0
47 velocity_deadband: 0.015
48 friction_deadband: 5
49sh_mfj3_velocity_controller:
50 type: sr_mechanism_controllers/SrhJointVelocityController
51 joint: MFJ3
52 pid:
53 p: 0
54 i: 0
55 d: 0
56 i_clamp: 1
57 max_force: 0
58 velocity_deadband: 0.015
59 friction_deadband: 5
60sh_mfj4_velocity_controller:
61 type: sr_mechanism_controllers/SrhJointVelocityController
62 joint: MFJ4
63 pid:
64 p: 0.0
65 i: -0.5
66 d: 0
67 i_clamp: 1
68 max_force: 0
69 velocity_deadband: 0.015
70 friction_deadband: 5
71
72
73
74sh_rfj0_velocity_controller:
75 type: sr_mechanism_controllers/SrhJointVelocityController
76 joint: RFJ0
77 pid:
78 p: 0
79 i: 0
80 d: 0
81 i_clamp: 1
82 max_force: 0
83 velocity_deadband: 0.015
84 friction_deadband: 5
85sh_rfj3_velocity_controller:
86 type: sr_mechanism_controllers/SrhJointVelocityController
87 joint: RFJ3
88 pid:
89 p: 0
90 i: 0
91 d: 0
92 i_clamp: 1
93 max_force: 0
94 velocity_deadband: 0.015
95 friction_deadband: 5
96sh_rfj4_velocity_controller:
97 type: sr_mechanism_controllers/SrhJointVelocityController
98 joint: RFJ4
99 pid:
100 p: 0
101 i: 0
102 d: 0
103 i_clamp: 1
104 max_force: 0
105 velocity_deadband: 0.015
106 friction_deadband: 5
107
108
109
110sh_lfj0_velocity_controller:
111 type: sr_mechanism_controllers/SrhJointVelocityController
112 joint: LFJ0
113 pid:
114 p: 0
115 i: 0
116 d: 0
117 i_clamp: 1
118 max_force: 0
119 velocity_deadband: 0.015
120 friction_deadband: 5
121sh_lfj3_velocity_controller:
122 type: sr_mechanism_controllers/SrhJointVelocityController
123 joint: LFJ3
124 pid:
125 p: 0
126 i: 0
127 d: 0
128 i_clamp: 1
129 max_force: 0
130 velocity_deadband: 0.015
131 friction_deadband: 5
132sh_lfj4_velocity_controller:
133 type: sr_mechanism_controllers/SrhJointVelocityController
134 joint: LFJ4
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
143sh_lfj5_velocity_controller:
144 type: sr_mechanism_controllers/SrhJointVelocityController
145 joint: LFJ5
146 pid:
147 p: 0
148 i: 0
149 d: 0
150 i_clamp: 1
151 max_force: 0
152 velocity_deadband: 0.015
153 friction_deadband: 5
154
155
156
157sh_thj1_velocity_controller:
158 type: sr_mechanism_controllers/SrhJointVelocityController
159 joint: THJ1
160 pid:
161 p: 0
162 i: 0
163 d: 0
164 i_clamp: 1
165 max_force: 0
166 velocity_deadband: 0.015
167 friction_deadband: 5
168sh_thj2_velocity_controller:
169 type: sr_mechanism_controllers/SrhJointVelocityController
170 joint: THJ2
171 pid:
172 p: 0
173 i: 0
174 d: 0
175 i_clamp: 1
176 max_force: 0
177 velocity_deadband: 0.015
178 friction_deadband: 5
179sh_thj3_velocity_controller:
180 type: sr_mechanism_controllers/SrhJointVelocityController
181 joint: THJ3
182 pid:
183 p: 0
184 i: 0
185 d: 0
186 i_clamp: 1
187 max_force: 0
188 velocity_deadband: 0.015
189 friction_deadband: 5
190sh_thj4_velocity_controller:
191 type: sr_mechanism_controllers/SrhJointVelocityController
192 joint: THJ4
193 pid:
194 p: 0
195 i: 0
196 d: 0
197 i_clamp: 1
198 max_force: 0
199 velocity_deadband: 0.015
200 friction_deadband: 5
201sh_thj5_velocity_controller:
202 type: sr_mechanism_controllers/SrhJointVelocityController
203 joint: THJ5
204 pid:
205 p: 0
206 i: 0
207 d: 0
208 i_clamp: 1
209 max_force: 0
210 velocity_deadband: 0.015
211 friction_deadband: 5
212
213
214
215sh_wrj1_velocity_controller:
216 type: sr_mechanism_controllers/SrhJointVelocityController
217 joint: WRJ1
218 pid:
219 p: 0
220 i: 0
221 d: 0
222 i_clamp: 1
223 max_force: 0
224 velocity_deadband: 0.015
225 friction_deadband: 5
226sh_wrj2_velocity_controller:
227 type: sr_mechanism_controllers/SrhJointVelocityController
228 joint: WRJ2
229 pid:
230 p: 0
231 i: 0
232 d: 0
233 i_clamp: 1
234 max_force: 0
235 velocity_deadband: 0.015
236 friction_deadband: 5
237
238
0239
=== added file 'sr_ethercat_hand_config/controls/host/sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml'
--- sr_ethercat_hand_config/controls/host/sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml 1970-01-01 00:00:00 +0000
+++ sr_ethercat_hand_config/controls/host/sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml 2012-10-30 14:29:21 +0000
@@ -0,0 +1,380 @@
1sh_ffj0_mixed_position_velocity_controller:
2 joint: FFJ0
3 motor_min_force_threshold: 40
4 position_pid:
5 d: 0.0
6 i: -1.5
7 i_clamp: 0.3
8 max_velocity: 3.0
9 min_velocity: -3.0
10 p: -4.0
11 position_deadband: 0.002
12 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
13 velocity_pid:
14 d: 0.0
15 friction_deadband: 100.0
16 i: 210.0
17 i_clamp: 160.0
18 max_force: 0.0
19 p: 150.0
20sh_ffj3_mixed_position_velocity_controller:
21 joint: FFJ3
22 motor_min_force_threshold: 40
23 position_pid:
24 d: 0.0
25 i: -1.5
26 i_clamp: 0.3
27 max_velocity: 1.5
28 min_velocity: -1.5
29 p: -4.0
30 position_deadband: 0.002
31 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
32 velocity_pid:
33 d: 0.0
34 friction_deadband: 100.0
35 i: 210.0
36 i_clamp: 160.0
37 max_force: 0.0
38 p: 150.0
39sh_ffj4_mixed_position_velocity_controller:
40 joint: FFJ4
41 motor_min_force_threshold: 40
42 position_pid:
43 d: 0.0
44 i: -1.5
45 i_clamp: 0.3
46 max_velocity: 1.5
47 min_velocity: -1.5
48 p: -4.0
49 position_deadband: 0.003
50 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
51 velocity_pid:
52 d: 0.0
53 friction_deadband: 5000.0
54 i: -210.0
55 i_clamp: 160.0
56 max_force: 0.0
57 p: -150.0
58sh_lfj0_mixed_position_velocity_controller:
59 joint: LFJ0
60 motor_min_force_threshold: 40
61 position_pid:
62 d: 0.0
63 i: -1.5
64 i_clamp: 0.3
65 max_velocity: 3.0
66 min_velocity: -3.0
67 p: -4.0
68 position_deadband: 0.002
69 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
70 velocity_pid:
71 d: 0.0
72 friction_deadband: 100.0
73 i: -210.0
74 i_clamp: 160.0
75 max_force: 0.0
76 p: -150.0
77sh_lfj3_mixed_position_velocity_controller:
78 joint: LFJ3
79 motor_min_force_threshold: 40
80 position_pid:
81 d: 0.0
82 i: -1.5
83 i_clamp: 0.3
84 max_velocity: 1.5
85 min_velocity: -1.5
86 p: -4.0
87 position_deadband: 0.002
88 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
89 velocity_pid:
90 d: 0.0
91 friction_deadband: 100.0
92 i: -210.0
93 i_clamp: 160.0
94 max_force: 0.0
95 p: -150.0
96sh_lfj4_mixed_position_velocity_controller:
97 joint: LFJ4
98 motor_min_force_threshold: 40
99 position_pid:
100 d: 0.0
101 i: -1.5
102 i_clamp: 0.3
103 max_velocity: 1.5
104 min_velocity: -1.5
105 p: -4.0
106 position_deadband: 0.003
107 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
108 velocity_pid:
109 d: 0.0
110 friction_deadband: 5000.0
111 i: 210.0
112 i_clamp: 160.0
113 max_force: 0.0
114 p: 150.0
115sh_lfj5_mixed_position_velocity_controller:
116 joint: LFJ5
117 motor_min_force_threshold: 40
118 position_pid:
119 d: 0.0
120 i: -1.5
121 i_clamp: 0.3
122 max_velocity: 1.5
123 min_velocity: -1.5
124 p: -4.0
125 position_deadband: 0.003
126 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
127 velocity_pid:
128 d: 0.0
129 friction_deadband: 5000.0
130 i: -210.0
131 i_clamp: 410.0
132 max_force: 0.0
133 p: -150.0
134sh_mfj0_mixed_position_velocity_controller:
135 joint: MFJ0
136 motor_min_force_threshold: 40
137 position_pid:
138 d: 0.0
139 i: -1.5
140 i_clamp: 0.3
141 max_velocity: 3.0
142 min_velocity: -3.0
143 p: -4.0
144 position_deadband: 0.002
145 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
146 velocity_pid:
147 d: 0.0
148 friction_deadband: 100.0
149 i: 210.0
150 i_clamp: 160.0
151 max_force: 0.0
152 p: 150.0
153sh_mfj3_mixed_position_velocity_controller:
154 joint: MFJ3
155 motor_min_force_threshold: 40
156 position_pid:
157 d: 0.0
158 i: -1.5
159 i_clamp: 0.3
160 max_velocity: 1.5
161 min_velocity: -1.5
162 p: -4.0
163 position_deadband: 0.002
164 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
165 velocity_pid:
166 d: 0.0
167 friction_deadband: 100.0
168 i: 210.0
169 i_clamp: 160.0
170 max_force: 0.0
171 p: 150.0
172sh_mfj4_mixed_position_velocity_controller:
173 joint: MFJ4
174 motor_min_force_threshold: 40
175 position_pid:
176 d: 0.0
177 i: -1.5
178 i_clamp: 0.3
179 max_velocity: 1.5
180 min_velocity: -1.5
181 p: -4.0
182 position_deadband: 0.003
183 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
184 velocity_pid:
185 d: 0.0
186 friction_deadband: 5000.0
187 i: -210.0
188 i_clamp: 160.0
189 max_force: 0.0
190 p: -150.0
191sh_rfj0_mixed_position_velocity_controller:
192 joint: RFJ0
193 motor_min_force_threshold: 40
194 position_pid:
195 d: 0.0
196 i: -1.5
197 i_clamp: 0.3
198 max_velocity: 3.0
199 min_velocity: -3.0
200 p: -4.0
201 position_deadband: 0.002
202 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
203 velocity_pid:
204 d: 0.0
205 friction_deadband: 100.0
206 i: -210.0
207 i_clamp: 160.0
208 max_force: 0.0
209 p: -150.0
210sh_rfj3_mixed_position_velocity_controller:
211 joint: RFJ3
212 motor_min_force_threshold: 40
213 position_pid:
214 d: 0.0
215 i: -1.5
216 i_clamp: 0.3
217 max_velocity: 1.5
218 min_velocity: -1.5
219 p: -4.0
220 position_deadband: 0.002
221 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
222 velocity_pid:
223 d: 0.0
224 friction_deadband: 100.0
225 i: -210.0
226 i_clamp: 160.0
227 max_force: 0.0
228 p: -150.0
229sh_rfj4_mixed_position_velocity_controller:
230 joint: RFJ4
231 motor_min_force_threshold: 40
232 position_pid:
233 d: 0.0
234 i: -1.5
235 i_clamp: 0.3
236 max_velocity: 1.5
237 min_velocity: -1.5
238 p: -4.0
239 position_deadband: 0.003
240 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
241 velocity_pid:
242 d: 0.0
243 friction_deadband: 5000.0
244 i: -210.0
245 i_clamp: 160.0
246 max_force: 0.0
247 p: -150.0
248sh_thj1_mixed_position_velocity_controller:
249 joint: THJ1
250 motor_min_force_threshold: 40
251 position_pid:
252 d: 0.0
253 i: -1.5
254 i_clamp: 0.3
255 max_velocity: 3.0
256 min_velocity: -3.0
257 p: -4.0
258 position_deadband: 0.002
259 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
260 velocity_pid:
261 d: 0.0
262 friction_deadband: 100.0
263 i: 210.0
264 i_clamp: 160.0
265 max_force: 0.0
266 p: 150.0
267sh_thj2_mixed_position_velocity_controller:
268 joint: THJ2
269 motor_min_force_threshold: 40
270 position_pid:
271 d: 0.0
272 i: -1.5
273 i_clamp: 0.3
274 max_velocity: 3.0
275 min_velocity: -3.0
276 p: -4.0
277 position_deadband: 0.002
278 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
279 velocity_pid:
280 d: 0.0
281 friction_deadband: 100.0
282 i: 210.0
283 i_clamp: 160.0
284 max_force: 0.0
285 p: 150.0
286sh_thj3_mixed_position_velocity_controller:
287 joint: THJ3
288 motor_min_force_threshold: 40
289 position_pid:
290 d: 0.0
291 i: -1.5
292 i_clamp: 0.3
293 max_velocity: 1.5
294 min_velocity: -1.5
295 p: -4.0
296 position_deadband: 0.002
297 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
298 velocity_pid:
299 d: 0.0
300 friction_deadband: 100.0
301 i: 210.0
302 i_clamp: 160.0
303 max_force: 0.0
304 p: 150.0
305sh_thj4_mixed_position_velocity_controller:
306 joint: THJ4
307 motor_min_force_threshold: 40
308 position_pid:
309 d: 0.0
310 i: -1.5
311 i_clamp: 0.3
312 max_velocity: 1.5
313 min_velocity: -1.5
314 p: -4.0
315 position_deadband: 0.003
316 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
317 velocity_pid:
318 d: 0.0
319 friction_deadband: 5000.0
320 i: -260.0
321 i_clamp: 180.0
322 max_force: 0.0
323 p: -210.0
324sh_thj5_mixed_position_velocity_controller:
325 joint: THJ5
326 motor_min_force_threshold: 40
327 position_pid:
328 d: 0.0
329 i: -1.5
330 i_clamp: 0.3
331 max_velocity: 1.5
332 min_velocity: -1.5
333 p: -4.0
334 position_deadband: 0.003
335 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
336 velocity_pid:
337 d: 0.0
338 friction_deadband: 5000.0
339 i: 210.0
340 i_clamp: 160.0
341 max_force: 0.0
342 p: 150.0
343sh_wrj1_mixed_position_velocity_controller:
344 joint: WRJ1
345 motor_min_force_threshold: 40
346 position_pid:
347 d: 0.0
348 i: -1.5
349 i_clamp: 0.3
350 max_velocity: 0.5
351 min_velocity: -0.5
352 p: -4.0
353 position_deadband: 0.002
354 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
355 velocity_pid:
356 d: 0.0
357 friction_deadband: 100.0
358 i: 460.0
359 i_clamp: 270.0
360 max_force: 0.0
361 p: 320.0
362sh_wrj2_mixed_position_velocity_controller:
363 joint: WRJ2
364 motor_min_force_threshold: 40
365 position_pid:
366 d: 0.0
367 i: -1.5
368 i_clamp: 0.3
369 max_velocity: 0.5
370 min_velocity: -0.5
371 p: -4.0
372 position_deadband: 0.002
373 type: sr_mechanism_controllers/SrhMixedPositionVelocityJointController
374 velocity_pid:
375 d: 0.0
376 friction_deadband: 100.0
377 i: -280.0
378 i_clamp: 190.0
379 max_force: 0.0
380 p: -230.0
0381
=== added file 'sr_ethercat_hand_config/controls/sr_edc_default_controllers.launch'
--- sr_ethercat_hand_config/controls/sr_edc_default_controllers.launch 1970-01-01 00:00:00 +0000
+++ sr_ethercat_hand_config/controls/sr_edc_default_controllers.launch 2012-10-30 14:29:21 +0000
@@ -0,0 +1,20 @@
1<launch>
2 <!-- <rosparam command="load" file="$(find sr_ethercat_hand_config)/controls/motors/motor_board_effort_controllers_stopped.yaml" /> -->
3 <!-- <rosparam command="load" file="$(find sr_ethercat_hand_config)/controls/motors/motor_board_effort_controllers_ff_and_th.yaml" /> -->
4 <rosparam command="load" file="$(find sr_ethercat_hand_config)/controls/motors/motor_board_effort_controllers.yaml" />
5 <rosparam command="load" file="$(find sr_ethercat_hand_config)/controls/friction_compensation.yaml" />
6
7 <!-- Parameters for the controllers if we're using torque control mode, i.e. sending force commands to
8 the force control loop in the motor board (that uses the data from the tendon strain gauges) -->
9 <rosparam unless="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_effort_controllers.yaml" />
10 <rosparam unless="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_joint_position_controllers.yaml" />
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" />
12 <rosparam unless="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_joint_velocity_controllers.yaml" />
13
14 <!-- Parameters for the controllers if we're using PWM control mode, i.e. sending direct PWM commands from the host to the motor,
15 WITHOUT using the force control loop in the motor board (that uses the data from the tendon strain gauges) -->
16 <rosparam if="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_effort_controllers_PWM.yaml" />
17 <rosparam if="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_joint_position_controllers_PWM.yaml" />
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" />
19 <rosparam if="$(optenv PWM_CONTROL 0)" command="load" file="$(find sr_ethercat_hand_config)/controls/host/sr_edc_joint_velocity_controllers_PWM.yaml" />
20</launch>

Subscribers

People subscribed via source and target branches

to all changes: