Skip to content

Commit df9c120

Browse files
ToivoSjlaforgacarebare47mikramarcBeatriz Leon
authored
Demohand a with ur10e updated (#187)
* Final calibration and control tuning after hand upgrade process * adding grasp controller to demohand_A * adding coupled calibration * setting for right hand * fixing format * Update demo_l.py * Update demo_l.py * partial calibration * Calibration correction after fix. * Calibration and control tunes updated * Final calibration, tuning and demos after hand flesh update * Update sr_edc_default_controllers.launch Co-authored-by: Juan <[email protected]> Co-authored-by: carebare47 <[email protected]> Co-authored-by: mikramarc <[email protected]> Co-authored-by: Beatriz Leon <[email protected]> Co-authored-by: giusebar <[email protected]> Co-authored-by: David Bazso <[email protected]> Co-authored-by: ToivoS <toivo@shadowrobot>
1 parent d8c2f53 commit df9c120

File tree

8 files changed

+248
-83
lines changed

8 files changed

+248
-83
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,52 +1,52 @@
11
sr_calibrations: [
2-
["FFJ1", [[2929.0, 0.0], [2189.0, 22.5], [1554.0, 45.0], [859.0, 67.5], [416.0, 90.0]]],
3-
["FFJ2", [[3027.0, 0.0], [2814.0, 22.5], [2359.0, 45.0], [1986.0, 67.5], [1563.0, 90.0]]],
4-
["FFJ3", [[1471.0, 0.0], [1750.0, 22.5], [2084.0, 45.0], [2371.0, 67.5], [2605.0, 90.0]]],
5-
["FFJ4", [[2365.0, -20.0], [2037.0, -10.0], [1711.0, 0.0], [1364.0, 10.0], [1119.0, 20.0]]],
6-
["MFJ1", [[3234.0, 0.0], [2565.0, 22.5], [1768.0, 45.0], [928.0, 67.5], [368.0, 90.0]]],
7-
["MFJ2", [[2802.0, 0.0], [2511.0, 22.5], [2151.0, 45.0], [1792.0, 67.5], [1458.0, 90.0]]],
8-
["MFJ3", [[1679.0, 0.0], [1911.0, 22.5], [2164.0, 45.0], [2392.0, 67.5], [2571.0, 90.0]]],
9-
["MFJ4", [[2007.0, -20.0], [1614.0, -10.0], [1266.0, 0.0], [897.0, 10.0], [599.0, 20.0]]],
10-
["RFJ1", [[3126.0, 0.0], [2382.0, 22.5], [1609.0, 45.0], [927.0, 67.5], [450.0, 90.0]]],
11-
["RFJ2", [[2837.0, 0.0], [2605.0, 22.5], [2288.0, 45.0], [1936.0, 67.5], [1570.0, 90.0]]],
12-
["RFJ3", [[1523.0, 0.0], [1785.0, 22.5], [2080.0, 45.0], [2364.0, 67.5], [2603.0, 90.0]]],
13-
["RFJ4", [[1114.0, -20.0], [1442.0, -10.0], [1799.0, 0.0], [2136.0, 10.0], [2470.0, 20.0]]],
14-
["LFJ1", [[3142.0, 0.0], [2431.0, 22.5], [1899.0, 45.0], [1309.0, 67.5], [808.0, 90.0]]],
15-
["LFJ2", [[2907.0, 0.0], [2663.0, 22.5], [2313.0, 45.0], [1896.0, 67.5], [1481.0, 90.0]]],
16-
["LFJ3", [[1756.0, 0.0], [2012.0, 22.5], [2303.0, 45.0], [2546.0, 67.5], [2698.0, 90.0]]],
17-
["LFJ4", [[1537.0, -20.0], [1875.0, -10.0], [2200.0, 0.0], [2548.0, 10.0], [2864.0, 20.0]]],
18-
["LFJ5", [[1667.0, 0.0], [2162.0, 22.5], [2807.0, 45.0], [3913.0, 67.5]]],
19-
["THJ3", [[1450.0, -15.0], [2132.0, 0.0], [2543.0, 15.0]]],
20-
["THJ4", [[1661.0, 0.0], [1955.0, 22.5], [2232.0, 45.0], [2503.0, 67.5]]],
21-
["THJ5", [[467.0, -60.0], [707.0, -45.0], [942.0, -30.0], [1279.0, -15.0], [1591.0, 0.0], [1951.0, 15.0], [2329.0, 30.0], [2609.0, 45.0], [2896.0, 60.0]]],
22-
["WRJ1", [[1033.0, -45.0], [865.0, -22.5], [724.0, 0.0], [669.0, 15.0], [617.0, 30.0]]],
23-
["WRJ2", [[2833.0, -30.0], [1269.0, 0.0], [665.0, 10.0]]],
2+
["FFJ1", [[3102.0, 0.0], [2244.0, 22.5], [1458.0, 45.0], [741.0, 67.5], [262.0, 90.0]]],
3+
["FFJ2", [[3338.0, 0.0], [3192.0, 22.5], [2726.0, 45.0], [2195.0, 67.5], [1652.0, 90.0]]],
4+
["FFJ3", [[1408.0, 0.0], [1910.0, 22.5], [2400.0, 45.0], [2819.0, 67.5], [3160.0, 90.0]]],
5+
["FFJ4", [[827.0, -20.0], [1530.0, -10.0], [1870.0, 0.0], [1968.0, 10.0], [2023.0, 20.0]]],
6+
["MFJ1", [[3206.0, 0.0], [2418.0, 22.5], [1695.0, 45.0], [961.0, 67.5], [526.0, 90.0]]],
7+
["MFJ2", [[3232.0, 0.0], [2968.0, 22.5], [2549.0, 45.0], [2143.0, 67.5], [1670.0, 90.0]]],
8+
["MFJ3", [[1645.0, 0.0], [2108.0, 22.5], [2555.0, 45.0], [2929.0, 67.5], [3175.0, 90.0]]],
9+
["MFJ4", [[3291.0, -20.0], [2655.0, -10.0], [2220.0, 0.0], [2076.0, 10.0], [2011.0, 20.0]]],
10+
["RFJ1", [[3099.0, 0.0], [2342.0, 22.5], [1505.0, 45.0], [887.0, 67.5], [403.0, 90.0]]],
11+
["RFJ2", [[3110.0, 0.0], [2897.0, 22.5], [2500.0, 45.0], [2063.0, 67.5], [1570.0, 90.0]]],
12+
["RFJ3", [[1713.0, 0.0], [2155.0, 22.5], [2556.0, 45.0], [2882.0, 67.5], [3084.0, 90.0]]],
13+
["RFJ4", [[2033.0, -20.0], [1964.0, -10.0], [1843.0, 0.0], [1469.0, 10.0], [940.0, 20.0]]],
14+
["LFJ1", [[3262.0, 0.0], [2584.0, 22.5], [1752.0, 45.0], [1118.0, 67.5], [606.0, 90.0]]],
15+
["LFJ2", [[3146.0, 0.0], [2950.0, 22.5], [2482.0, 45.0], [1966.0, 67.5], [1512.0, 90.0]]],
16+
["LFJ3", [[1703.0, 0.0], [2207.0, 22.5], [2675.0, 45.0], [3030.0, 67.5], [3186.0, 90.0]]],
17+
["LFJ4", [[2044.0, -20.0], [2000.0, -10.0], [1826.0, 0.0], [1543.0, 10.0], [1158.0, 20.0]]],
18+
["LFJ5", [[3035.0, 0.0], [2282.0, 22.5], [1805.0, 45.0], [1185.0, 67.5]]],
19+
["THJ3", [[1348.0, -15.0], [2353.0, 0.0], [2737.0, 15.0]]],
20+
["THJ4", [[1647.0, 0.0], [1978.0, 22.5], [2323.0, 45.0], [2531.0, 67.5]]],
21+
["THJ5", [[357.0, -60.0], [674.0, -45.0], [941.0, -30.0], [1277.0, -15.0], [1535.0, 0.0], [1847.0, 15.0], [2318.0, 30.0], [2634.0, 45.0], [2942.0, 60.0]]],
22+
["WRJ1", [[2464.0, -45.0], [2361.0, -22.5], [2162.0, 0.0], [1996.0, 15.0], [1853.0, 30.0]]],
23+
["WRJ2", [[2796.0, -30.0], [1052.0, 0.0], [326.0, 10.0]]],
2424
]
2525

2626
sr_calibrations_coupled: [
27-
[["THJ1", "THJ2"], [[[2613.0, 2296.0], 0.0, 40.0],
28-
[[2598.0, 2160.0], 0.0, 20.0],
29-
[[2581.0, 1959.0], 0.0, 0.0],
30-
[[2565.0, 1795.0], 0.0, -20.0],
31-
[[2552.0, 1668.0], 0.0, -40.0],
32-
[[2189.0, 2281.0], 22.5, 40.0],
33-
[[2179.0, 2122.0], 22.5, 20.0],
34-
[[2162.0, 1936.0], 22.5, 0.0],
35-
[[2147.0, 1771.0], 22.5, -20.0],
36-
[[2132.0, 1642.0], 22.5, -40.0],
37-
[[1732.0, 2258.0], 45.0, 40.0],
38-
[[1704.0, 2092.0], 45.0, 20.0],
39-
[[1685.0, 1907.0], 45.0, 0.0],
40-
[[1668.0, 1737.0], 45.0, -20.0],
41-
[[1656.0, 1613.0], 45.0, -40.0],
42-
[[1361.0, 2231.0], 67.5, 40.0],
43-
[[1347.0, 2069.0], 67.5, 20.0],
44-
[[1329.0, 1889.0], 67.5, 0.0],
45-
[[1312.0, 1712.0], 67.5, -20.0],
46-
[[1302.0, 1589.0], 67.5, -40.0],
47-
[[1082.0, 2219.0], 90.0, 40.0],
48-
[[1068.0, 2069.0], 90.0, 20.0],
49-
[[1050.0, 1868.0], 90.0, 0.0],
50-
[[1039.0, 1697.0], 90.0, -20.0],
51-
[[1025.0, 1577.0], 90.0, -40.0]]]
27+
[["THJ1", "THJ2"], [[[2776.0, 2386.0], 0.0, 40.0],
28+
[[2744.0, 2204.0], 0.0, 20.0],
29+
[[2712.0, 1994.0], 0.0, 0.0],
30+
[[2688.0, 1799.0], 0.0, -20.0],
31+
[[2662.0, 1649.0], 0.0, -40.0],
32+
[[2384.0, 2338.0], 22.5, 40.0],
33+
[[2345.0, 2193.0], 22.5, 20.0],
34+
[[2313.0, 1987.0], 22.5, 0.0],
35+
[[2288.0, 1784.0], 22.5, -20.0],
36+
[[2300.0, 1630.0], 22.5, -40.0],
37+
[[1980.0, 2315.0], 45.0, 40.0],
38+
[[1948.0, 2165.0], 45.0, 20.0],
39+
[[1900.0, 1969.0], 45.0, 0.0],
40+
[[1888.0, 1765.0], 45.0, -20.0],
41+
[[1873.0, 1608.0], 45.0, -40.0],
42+
[[1484.0, 2253.0], 67.5, 40.0],
43+
[[1466.0, 2144.0], 67.5, 20.0],
44+
[[1429.0, 1963.0], 67.5, 0.0],
45+
[[1408.0, 1758.0], 67.5, -20.0],
46+
[[1394.0, 1584.0], 67.5, -40.0],
47+
[[1135.0, 2295.0], 90.0, 40.0],
48+
[[1113.0, 2125.0], 90.0, 20.0],
49+
[[1104.0, 1917.0], 90.0, 0.0],
50+
[[1088.0, 1717.0], 90.0, -20.0],
51+
[[1075.0, 1568.0], 90.0, -40.0]]]
5252
]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,165 @@
1+
sh_rh_grasp_controller:
2+
gains:
3+
rh_FFJ0:
4+
d: 0.0
5+
i: 0.0
6+
i_clamp: 0.0
7+
p: -4900.0
8+
position_deadband: 0.002
9+
friction_deadband: 2000.0
10+
max_force: 600.0
11+
rh_FFJ3:
12+
d: 290.0
13+
i: 0.0
14+
i_clamp: 0.0
15+
p: 6300.0
16+
position_deadband: 0.002
17+
friction_deadband: 2000.0
18+
max_force: 600.0
19+
rh_FFJ4:
20+
d: -270.0
21+
i: 0.0
22+
i_clamp: 0.0
23+
p: -6700.0
24+
position_deadband: 0.003
25+
friction_deadband: 2000.0
26+
max_force: 400.0
27+
rh_LFJ0:
28+
d: 0.0
29+
i: 0.0
30+
i_clamp: 0.0
31+
p: 4300.0
32+
position_deadband: 0.002
33+
friction_deadband: 2000.0
34+
max_force: 600.0
35+
rh_LFJ3:
36+
d: -290.0
37+
i: 0.0
38+
i_clamp: 0.0
39+
p: -5900.0
40+
position_deadband: 0.002
41+
friction_deadband: 2000.0
42+
max_force: 600.0
43+
rh_LFJ4:
44+
d: 270.0
45+
i: 0.0
46+
i_clamp: 0.0
47+
p: 6900.0
48+
position_deadband: 0.003
49+
friction_deadband: 2000.0
50+
max_force: 400.0
51+
rh_LFJ5:
52+
d: 270.0
53+
i: 0.0
54+
i_clamp: 0.0
55+
p: 6300.0
56+
position_deadband: 0.003
57+
friction_deadband: 2000.0
58+
max_force: 500.0
59+
rh_MFJ0:
60+
d: 0.0
61+
i: 0.0
62+
i_clamp: 0.0
63+
p: -4400.0
64+
position_deadband: 0.002
65+
friction_deadband: 2000.0
66+
max_force: 600.0
67+
rh_MFJ3:
68+
d: 300.0
69+
i: 0.0
70+
i_clamp: 0.0
71+
p: 5500.0
72+
position_deadband: 0.002
73+
friction_deadband: 2000.0
74+
max_force: 600.0
75+
rh_MFJ4:
76+
d: -270.0
77+
i: 0.0
78+
i_clamp: 0.0
79+
p: -6700.0
80+
position_deadband: 0.003
81+
friction_deadband: 2000.0
82+
max_force: 400.0
83+
rh_RFJ0:
84+
d: 0.0
85+
i: 0.0
86+
i_clamp: 0.0
87+
p: -4300.0
88+
position_deadband: 0.002
89+
friction_deadband: 2000.0
90+
max_force: 600.0
91+
rh_RFJ3:
92+
d: 200.0
93+
i: 0.0
94+
i_clamp: 0.0
95+
p: 4300.0
96+
position_deadband: 0.002
97+
friction_deadband: 2000.0
98+
max_force: 600.0
99+
rh_RFJ4:
100+
d: -270.0
101+
i: 0.0
102+
i_clamp: 0.0
103+
p: -6100.0
104+
position_deadband: 0.003
105+
friction_deadband: 2000.0
106+
max_force: 400.0
107+
rh_THJ1:
108+
d: 270.0
109+
i: 0.0
110+
i_clamp: 0.0
111+
p: 5300.0
112+
position_deadband: 0.002
113+
friction_deadband: 2000.0
114+
max_force: 600.0
115+
rh_THJ2:
116+
d: 270.0
117+
i: 0.0
118+
i_clamp: 0.0
119+
p: 5700.0
120+
position_deadband: 0.002
121+
friction_deadband: 2000.0
122+
max_force: 600.0
123+
rh_THJ3:
124+
d: -370.0
125+
i: 0.0
126+
i_clamp: 0.0
127+
p: -7900.0
128+
position_deadband: 0.003
129+
friction_deadband: 2000.0
130+
max_force: 400.0
131+
rh_THJ4:
132+
d: 270.0
133+
i: 0.0
134+
i_clamp: 0.0
135+
p: 5100.0
136+
position_deadband: 0.003
137+
friction_deadband: 2000.0
138+
max_force: 500.0
139+
rh_THJ5:
140+
d: 330.0
141+
i: 0.0
142+
i_clamp: 0.0
143+
p: 5900.0
144+
position_deadband: 0.003
145+
friction_deadband: 2000.0
146+
max_force: 500.0
147+
rh_WRJ1:
148+
d: 270.0
149+
i: 0.0
150+
i_clamp: 0.0
151+
p: 6700.0
152+
position_deadband: 0.003
153+
friction_deadband: 2000.0
154+
max_force: 600.0
155+
rh_WRJ2:
156+
d: -120.0
157+
i: 0.0
158+
i_clamp: 0.0
159+
p: -8100.0
160+
position_deadband: 0.003
161+
friction_deadband: 2000.0
162+
max_force: 600.0
163+
164+
type: sr_grasp_controllers/SrhGraspController
165+
joints: [rh_FFJ0, rh_FFJ3, rh_FFJ4, rh_LFJ0, rh_LFJ3, rh_LFJ4, rh_LFJ5, rh_MFJ0, rh_MFJ3, rh_MFJ4, rh_RFJ0, rh_RFJ3, rh_RFJ4, rh_THJ1, rh_THJ2, rh_THJ3, rh_THJ4, rh_THJ5, rh_WRJ1, rh_WRJ2]

sr_ethercat_hand_config/controls/host/rh/sr_edc_joint_position_controllers_PWM.yaml

+14-14
Original file line numberDiff line numberDiff line change
@@ -25,13 +25,13 @@ sh_rh_ffj3_position_controller:
2525
sh_rh_ffj4_position_controller:
2626
joint: rh_FFJ4
2727
pid:
28-
d: 310.0
28+
d: -310.0
2929
deadband: 0.02
3030
friction_deadband: 2000.0
3131
i: 0.0
3232
i_clamp: 0.0
3333
max_force: 500.0
34-
p: 7100.0
34+
p: -7100.0
3535
position_deadband: 0.003
3636
type: sr_mechanism_controllers/SrhJointPositionController
3737
sh_rh_lfj0_position_controller:
@@ -60,25 +60,25 @@ sh_rh_lfj3_position_controller:
6060
sh_rh_lfj4_position_controller:
6161
joint: rh_LFJ4
6262
pid:
63-
d: -310.0
63+
d: 310.0
6464
deadband: 0
6565
friction_deadband: 2000.0
6666
i: 0.0
6767
i_clamp: 0.0
6868
max_force: 500.0
69-
p: -7100.0
69+
p: 7100.0
7070
position_deadband: 0.003
7171
type: sr_mechanism_controllers/SrhJointPositionController
7272
sh_rh_lfj5_position_controller:
7373
joint: rh_LFJ5
7474
pid:
75-
d: -290.0
75+
d: 290.0
7676
deadband: 0.0
7777
friction_deadband: 2000.0
7878
i: 0.0
7979
i_clamp: 0.0
8080
max_force: 500.0
81-
p: -6900.0
81+
p: 6900.0
8282
position_deadband: 0.003
8383
type: sr_mechanism_controllers/SrhJointPositionController
8484
sh_rh_mfj0_position_controller:
@@ -95,13 +95,13 @@ sh_rh_mfj0_position_controller:
9595
sh_rh_mfj3_position_controller:
9696
joint: rh_MFJ3
9797
pid:
98-
d: -280.0
98+
d: 280.0
9999
deadband: 0.0
100100
friction_deadband: 2000.0
101101
i: 0.0
102102
i_clamp: 0.0
103103
max_force: 600.0
104-
p: -5900.0
104+
p: 5900.0
105105
position_deadband: 0.002
106106
type: sr_mechanism_controllers/SrhJointPositionController
107107
sh_rh_mfj4_position_controller:
@@ -130,25 +130,25 @@ sh_rh_rfj0_position_controller:
130130
sh_rh_rfj3_position_controller:
131131
joint: rh_RFJ3
132132
pid:
133-
d: -270.0
133+
d: 270.0
134134
deadband: 0.0
135135
friction_deadband: 2000.0
136136
i: 0.0
137137
i_clamp: 0.0
138138
max_force: 600.0
139-
p: -5900.0
139+
p: 5900.0
140140
position_deadband: 0.002
141141
type: sr_mechanism_controllers/SrhJointPositionController
142142
sh_rh_rfj4_position_controller:
143143
joint: rh_RFJ4
144144
pid:
145-
d: 310.0
145+
d: -310.0
146146
deadband: 0.0
147147
friction_deadband: 2000.0
148148
i: 0.0
149149
i_clamp: 0.0
150150
max_force: 500.0
151-
p: 7100.0
151+
p: -7100.0
152152
position_deadband: 0.003
153153
type: sr_mechanism_controllers/SrhJointPositionController
154154
sh_rh_thj1_position_controller:
@@ -178,13 +178,13 @@ sh_rh_thj2_position_controller:
178178
sh_rh_thj3_position_controller:
179179
joint: rh_THJ3
180180
pid:
181-
d: 330.0
181+
d: -330.0
182182
deadband: 0.0
183183
friction_deadband: 2000.0
184184
i: 0.0
185185
i_clamp: 0.0
186186
max_force: 400.0
187-
p: 7300.0
187+
p: -7300.0
188188
position_deadband: 0.003
189189
type: sr_mechanism_controllers/SrhJointPositionController
190190
sh_rh_thj4_position_controller:

0 commit comments

Comments
 (0)