22 from sr_robot_commander.sr_hand_commander
import SrHandCommander
24 rospy.init_node(
"left_hand_demo", anonymous=
True)
26 hand_commander = SrHandCommander(name=
"left_hand", prefix=
"lh_")
35 min_range = {
"lh_THJ2": -40,
"lh_THJ3": -12,
"lh_THJ4": 0,
"lh_THJ5": -55,
36 "lh_FFJ1": 0,
"lh_FFJ2": 20,
"lh_FFJ3": 0,
"lh_FFJ4": -20,
37 "lh_MFJ1": 0,
"lh_MFJ2": 20,
"lh_MFJ3": 0,
"lh_MFJ4": -10,
38 "lh_RFJ1": 0,
"lh_RFJ2": 20,
"lh_RFJ3": 0,
"lh_RFJ4": -10,
39 "lh_LFJ1": 10,
"lh_LFJ2": 10,
"lh_LFJ3": 0,
"lh_LFJ4": -20,
"lh_LFJ5": 0,
40 "lh_WRJ1": -20,
"lh_WRJ2": -10}
43 max_range = {
"lh_THJ2": 20,
"lh_THJ3": 12,
"lh_THJ4": 70,
"lh_THJ5": 0,
44 "lh_FFJ1": 20,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
45 "lh_MFJ1": 20,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
46 "lh_RFJ1": 20,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
47 "lh_LFJ1": 20,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 1,
48 "lh_WRJ1": 10,
"lh_WRJ2": 5}
55 start_pos = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 0,
"lh_THJ5": 0,
56 "lh_FFJ1": 0,
"lh_FFJ2": 0,
"lh_FFJ3": 0,
"lh_FFJ4": 0,
57 "lh_MFJ1": 0,
"lh_MFJ2": 0,
"lh_MFJ3": 0,
"lh_MFJ4": 0,
58 "lh_RFJ1": 0,
"lh_RFJ2": 0,
"lh_RFJ3": 0,
"lh_RFJ4": 0,
59 "lh_LFJ1": 0,
"lh_LFJ2": 0,
"lh_LFJ3": 0,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
60 "lh_WRJ1": 0,
"lh_WRJ2": 0}
62 pregrasp_pos = {
"lh_THJ2": 12,
"lh_THJ3": 15,
"lh_THJ4": 69,
"lh_THJ5": -23,
63 "lh_FFJ1": 0,
"lh_FFJ2": 40,
"lh_FFJ3": 21,
"lh_FFJ4": -15,
64 "lh_MFJ1": 0,
"lh_MFJ2": 40,
"lh_MFJ3": 21,
"lh_MFJ4": 0,
65 "lh_RFJ1": 0,
"lh_RFJ2": 40,
"lh_RFJ3": 21,
"lh_RFJ4": -7,
66 "lh_LFJ1": 0,
"lh_LFJ2": 40,
"lh_LFJ3": 21,
"lh_LFJ4": -10,
"lh_LFJ5": 0,
67 "lh_WRJ1": 0,
"lh_WRJ2": 0}
69 grasp_pos = {
"lh_THJ2": 30,
"lh_THJ3": 15,
"lh_THJ4": 69,
"lh_THJ5": -3,
70 "lh_FFJ1": 0,
"lh_FFJ2": 77,
"lh_FFJ3": 67,
"lh_FFJ4": -19,
71 "lh_MFJ1": 0,
"lh_MFJ2": 82,
"lh_MFJ3": 62,
"lh_MFJ4": 0,
72 "lh_RFJ1": 0,
"lh_RFJ2": 89,
"lh_RFJ3": 64,
"lh_RFJ4": -18,
73 "lh_LFJ1": 7,
"lh_LFJ2": 90,
"lh_LFJ3": 64,
"lh_LFJ4": -19,
"lh_LFJ5": 0,
74 "lh_WRJ1": 0,
"lh_WRJ2": 0}
76 rand_pos = {
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 0,
"lh_THJ5": 0,
77 "lh_FFJ1": 0,
"lh_FFJ2": 0,
"lh_FFJ3": 0,
"lh_FFJ4": 0,
78 "lh_MFJ1": 0,
"lh_MFJ2": 0,
"lh_MFJ3": 0,
"lh_MFJ4": 0,
79 "lh_RFJ1": 0,
"lh_RFJ2": 0,
"lh_RFJ3": 0,
"lh_RFJ4": 0,
80 "lh_LFJ1": 0,
"lh_LFJ2": 0,
"lh_LFJ3": 0,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
81 "lh_WRJ1": 0,
"lh_WRJ2": 0}
83 flex_ff = {
"lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0}
85 ext_ff = {
"lh_FFJ1": 0,
"lh_FFJ2": 0,
"lh_FFJ3": 0,
"lh_FFJ4": 0}
87 flex_mf = {
"lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0}
89 ext_mf = {
"lh_MFJ1": 0,
"lh_MFJ2": 0,
"lh_MFJ3": 0,
"lh_MFJ4": 0}
91 flex_rf = {
"lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0}
93 ext_rf = {
"lh_RFJ1": 0,
"lh_RFJ2": 0,
"lh_RFJ3": 0,
"lh_RFJ4": 0}
95 flex_lf = {
"lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0}
97 ext_lf = {
"lh_LFJ1": 0,
"lh_LFJ2": 0,
"lh_LFJ3": 0,
"lh_LFJ4": 0}
99 flex_th_1 = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 70,
"lh_THJ5": 0}
101 flex_th_2 = {
"lh_THJ1": 35,
"lh_THJ2": 38,
"lh_THJ3": 10,
"lh_THJ4": 70,
"lh_THJ5": 58}
103 ext_th_1 = {
"lh_THJ1": 10,
"lh_THJ2": 20,
"lh_THJ3": 5,
"lh_THJ4": 35,
"lh_THJ5": 25}
105 ext_th_2 = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 0,
"lh_THJ5": 0}
107 zero_th = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 0,
"lh_THJ5": 0}
109 pre_ff_ok = {
"lh_THJ4": 70}
111 ff_ok = {
"lh_THJ1": 17,
"lh_THJ2": 20,
"lh_THJ3": 0,
"lh_THJ4": 56,
"lh_THJ5": 18,
112 "lh_FFJ1": 0,
"lh_FFJ2": 75,
"lh_FFJ3": 52,
"lh_FFJ4": -0.2,
113 "lh_MFJ1": 0,
"lh_MFJ2": 42,
"lh_MFJ3": 33,
"lh_MFJ4": -3,
114 "lh_RFJ1": 0,
"lh_RFJ2": 50,
"lh_RFJ3": 18,
"lh_RFJ4": 0.5,
115 "lh_LFJ1": 0,
"lh_LFJ2": 30,
"lh_LFJ3": 0,
"lh_LFJ4": -6,
"lh_LFJ5": 7}
117 ff2mf_ok = {
"lh_THJ1": 5,
"lh_THJ2": 12,
"lh_THJ3": 4,
"lh_THJ4": 60,
"lh_THJ5": 2,
118 "lh_FFJ1": 0,
"lh_FFJ2": 14,
"lh_FFJ3": 7,
"lh_FFJ4": -0.4,
119 "lh_MFJ1": 0,
"lh_MFJ2": 42,
"lh_MFJ3": 33,
"lh_MFJ4": -3,
120 "lh_RFJ1": 0,
"lh_RFJ2": 50,
"lh_RFJ3": 18,
"lh_RFJ4": 0.5,
121 "lh_LFJ1": 0,
"lh_LFJ2": 30,
"lh_LFJ3": 0,
"lh_LFJ4": -6,
"lh_LFJ5": 7}
123 mf_ok = {
"lh_THJ1": 19,
"lh_THJ2": 17,
"lh_THJ3": 6,
"lh_THJ4": 66,
"lh_THJ5": 31,
124 "lh_FFJ1": 0,
"lh_FFJ2": 15,
"lh_FFJ3": 7,
"lh_FFJ4": -0.4,
125 "lh_MFJ1": 11,
"lh_MFJ2": 71,
"lh_MFJ3": 49,
"lh_MFJ4": 10,
126 "lh_RFJ1": 0,
"lh_RFJ2": 50,
"lh_RFJ3": 18,
"lh_RFJ4": -10,
127 "lh_LFJ1": 0,
"lh_LFJ2": 30,
"lh_LFJ3": 0,
"lh_LFJ4": -6,
"lh_LFJ5": 7}
129 mf2rf_ok = {
"lh_THJ1": 5,
"lh_THJ2": -5,
"lh_THJ3": 15,
"lh_THJ4": 70,
"lh_THJ5": 19,
130 "lh_FFJ1": 0,
"lh_FFJ2": 14,
"lh_FFJ3": 7,
"lh_FFJ4": -0.4,
131 "lh_MFJ1": 0,
"lh_MFJ2": 45,
"lh_MFJ3": 4,
"lh_MFJ4": -1,
132 "lh_RFJ1": 0,
"lh_RFJ2": 50,
"lh_RFJ3": 18,
"lh_RFJ4": -19,
133 "lh_LFJ1": 0,
"lh_LFJ2": 30,
"lh_LFJ3": 0,
"lh_LFJ4": -12,
"lh_LFJ5": 7}
135 rf_ok = {
"lh_THJ1": 8,
"lh_THJ2": 15,
"lh_THJ3": 15,
"lh_THJ4": 70,
"lh_THJ5": 45,
136 "lh_FFJ1": 0,
"lh_FFJ2": 14,
"lh_FFJ3": 7,
"lh_FFJ4": -0.4,
137 "lh_MFJ1": 0,
"lh_MFJ2": 45,
"lh_MFJ3": 4,
"lh_MFJ4": -1,
138 "lh_RFJ1": 3,
"lh_RFJ2": 90,
"lh_RFJ3": 42,
"lh_RFJ4": -19,
139 "lh_LFJ1": 0,
"lh_LFJ2": 30,
"lh_LFJ3": 0,
"lh_LFJ4": -12,
"lh_LFJ5": 7}
141 rf2lf_ok = {
"lh_THJ1": 5,
"lh_THJ2": 4.5,
"lh_THJ3": 8,
"lh_THJ4": 60,
"lh_THJ5": 21,
142 "lh_FFJ1": 0,
"lh_FFJ2": 14,
"lh_FFJ3": 7,
"lh_FFJ4": -0.4,
143 "lh_MFJ1": 0,
"lh_MFJ2": 45,
"lh_MFJ3": 4,
"lh_MFJ4": -1,
144 "lh_RFJ1": 0,
"lh_RFJ2": 30,
"lh_RFJ3": 6,
"lh_RFJ4": 0.5,
145 "lh_LFJ1": 0,
"lh_LFJ2": 30,
"lh_LFJ3": 0,
"lh_LFJ4": -10,
"lh_LFJ5": 7}
147 lf_ok = {
"lh_THJ1": 25,
"lh_THJ2": 14,
"lh_THJ3": 10,
"lh_THJ4": 69,
"lh_THJ5": 22,
148 "lh_FFJ1": 0,
"lh_FFJ2": 14,
"lh_FFJ3": 7,
"lh_FFJ4": -0.4,
149 "lh_MFJ1": 0,
"lh_MFJ2": 15,
"lh_MFJ3": 4,
"lh_MFJ4": -1,
150 "lh_RFJ1": 0,
"lh_RFJ2": 15,
"lh_RFJ3": 6,
"lh_RFJ4": 0.5,
151 "lh_LFJ1": 0,
"lh_LFJ2": 78,
"lh_LFJ3": 26,
"lh_LFJ4": 5,
"lh_LFJ5": 37}
153 zero_wr = {
"lh_WRJ1": 0,
"lh_WRJ2": 0}
155 n_wr = {
"lh_WRJ1": 15,
"lh_WRJ2": 0}
157 s_wr = {
"lh_WRJ1": -20,
"lh_WRJ2": 0}
159 e_wr = {
"lh_WRJ1": 0,
"lh_WRJ2": 8}
161 w_wr = {
"lh_WRJ1": 0,
"lh_WRJ2": -14}
163 ne_wr = {
"lh_WRJ1": 15,
"lh_WRJ2": 8}
165 nw_wr = {
"lh_WRJ1": 15,
"lh_WRJ2": -14}
167 sw_wr = {
"lh_WRJ1": -20,
"lh_WRJ2": -14}
169 se_wr = {
"lh_WRJ1": -20,
"lh_WRJ2": 8}
171 l_ext_lf = {
"lh_LFJ4": -15}
173 l_ext_rf = {
"lh_RFJ4": -15}
175 l_ext_mf = {
"lh_MFJ4": 15}
177 l_ext_ff = {
"lh_FFJ4": 15}
179 l_int_all = {
"lh_FFJ4": -15,
"lh_MFJ4": -15,
"lh_RFJ4": 15,
"lh_LFJ4": 15}
181 l_ext_all = {
"lh_FFJ4": 15,
"lh_MFJ4": 15,
"lh_RFJ4": -15,
"lh_LFJ4": -15}
183 l_int_ff = {
"lh_FFJ4": -15}
185 l_int_mf = {
"lh_MFJ4": -15}
187 l_int_rf = {
"lh_RFJ4": 15}
189 l_int_lf = {
"lh_LFJ4": 15}
191 l_zero_all = {
"lh_FFJ4": 0,
"lh_MFJ4": 0,
"lh_RFJ4": 0,
"lh_LFJ4": 0}
193 l_spock = {
"lh_FFJ4": -20,
"lh_MFJ4": -20,
"lh_RFJ4": -20,
"lh_LFJ4": -20}
195 shake_grasp_1 = {
"lh_THJ1": 0,
"lh_THJ2": 6,
"lh_THJ3": 10,
"lh_THJ4": 37,
"lh_THJ5": 9,
196 "lh_FFJ1": 0,
"lh_FFJ2": 21,
"lh_FFJ3": 26,
"lh_FFJ4": 0,
197 "lh_MFJ1": 0,
"lh_MFJ2": 18,
"lh_MFJ3": 24,
"lh_MFJ4": 0,
198 "lh_RFJ1": 0,
"lh_RFJ2": 30,
"lh_RFJ3": 16,
"lh_RFJ4": 0,
199 "lh_LFJ1": 0,
"lh_LFJ2": 30,
"lh_LFJ3": 0,
"lh_LFJ4": -10,
"lh_LFJ5": 10}
201 shake_grasp_2 = {
"lh_THJ1": 21,
"lh_THJ2": 21,
"lh_THJ3": 10,
"lh_THJ4": 42,
"lh_THJ5": 21,
202 "lh_FFJ1": 0,
"lh_FFJ2": 75,
"lh_FFJ3": 29,
"lh_FFJ4": 0,
203 "lh_MFJ1": 0,
"lh_MFJ2": 75,
"lh_MFJ3": 41,
"lh_MFJ4": 0,
204 "lh_RFJ1": 0,
"lh_RFJ2": 75,
"lh_RFJ3": 41,
"lh_RFJ4": 0,
205 "lh_LFJ1": 10,
"lh_LFJ2": 90,
"lh_LFJ3": 41,
"lh_LFJ4": 0,
"lh_LFJ5": 0}
207 store_1_PST = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 60,
"lh_THJ5": 0,
208 "lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
209 "lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
210 "lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
211 "lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
212 "lh_WRJ1": 0,
"lh_WRJ2": 0}
214 store_2_PST = {
"lh_THJ1": 50,
"lh_THJ2": 12,
"lh_THJ3": 0,
"lh_THJ4": 60,
"lh_THJ5": 27,
215 "lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
216 "lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
217 "lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
218 "lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
219 "lh_WRJ1": 0,
"lh_WRJ2": 0}
221 store_1_BioTac = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 30,
"lh_THJ5": 0,
222 "lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
223 "lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
224 "lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
225 "lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
226 "lh_WRJ1": 0,
"lh_WRJ2": 0}
228 store_2_BioTac = {
"lh_THJ1": 20,
"lh_THJ2": 36,
"lh_THJ3": 0,
"lh_THJ4": 30,
"lh_THJ5": -3,
229 "lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
230 "lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
231 "lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
232 "lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
233 "lh_WRJ1": 0,
"lh_WRJ2": 0}
235 store_3 = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 65,
"lh_THJ5": 0}
237 bc_pre_zero = {
"lh_THJ1": 15,
"lh_THJ2": 7,
"lh_THJ3": -4,
"lh_THJ4": 41,
"lh_THJ5": -20,
238 "lh_FFJ1": 0,
"lh_FFJ2": 14,
"lh_FFJ3": 7,
"lh_FFJ4": -1,
239 "lh_MFJ1": 0,
"lh_MFJ2": 51,
"lh_MFJ3": 33,
"lh_MFJ4": 20,
240 "lh_RFJ1": 0,
"lh_RFJ2": 50,
"lh_RFJ3": 18,
"lh_RFJ4": -20,
241 "lh_LFJ1": 0,
"lh_LFJ2": 30,
"lh_LFJ3": 0,
"lh_LFJ4": -20,
"lh_LFJ5": 7}
243 bc_zero = {
"lh_THJ1": 38,
"lh_THJ2": 4,
"lh_THJ3": 0,
"lh_THJ4": 48,
"lh_THJ5": -5,
244 "lh_MFJ1": 7,
"lh_MFJ2": 64,
"lh_MFJ3": 20,
"lh_MFJ4": 18}
246 bc_1 = {
"lh_FFJ1": 47,
"lh_FFJ2": 90,
"lh_FFJ3": 7}
248 bc_2 = {
"lh_FFJ1": 47,
"lh_FFJ2": 90,
"lh_FFJ3": 58}
250 bc_3 = {
"lh_FFJ1": 0,
"lh_FFJ2": 60,
"lh_FFJ3": 58}
252 bc_4 = {
"lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 58,
"lh_FFJ4": 15}
254 bc_5 = {
"lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 0}
256 bc_6 = {
"lh_FFJ1": 0,
"lh_FFJ2": 0,
"lh_FFJ3": 0,
"lh_FFJ4": 10}
258 bc_7 = {
"lh_FFJ1": 47,
"lh_FFJ2": 90,
"lh_FFJ3": 15,
"lh_FFJ4": 0}
260 bc_8 = {
"lh_FFJ1": 47,
"lh_FFJ2": 90,
"lh_FFJ3": 58}
262 bc_9 = {
"lh_FFJ1": 0,
"lh_FFJ2": 71,
"lh_FFJ3": 58}
264 bc_10 = {
"lh_MFJ3": 64,
"lh_FFJ4": 20}
266 bc_11 = {
"lh_FFJ1": 0,
"lh_FFJ2": 81,
"lh_FFJ3": 50,
"lh_FFJ4": 20,
267 "lh_THJ4": 57,
"lh_THJ5": 20,}
269 bc_12 = {
"lh_MFJ1": 0,
"lh_MFJ2": 20,
"lh_MFJ3": 10,
"lh_MFJ4": 0}
279 hand_commander.move_to_joint_value_target_unsafe(store_3, 1.0,
False, angle_degrees=
True)
281 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.2,
False, angle_degrees=
True)
283 hand_commander.move_to_joint_value_target_unsafe(flex_ff, 1.0,
False, angle_degrees=
True)
285 hand_commander.move_to_joint_value_target_unsafe(ext_ff, 1.0,
False, angle_degrees=
True)
287 hand_commander.move_to_joint_value_target_unsafe(flex_mf, 1.0,
False, angle_degrees=
True)
289 hand_commander.move_to_joint_value_target_unsafe(ext_mf, 1.0,
False, angle_degrees=
True)
291 hand_commander.move_to_joint_value_target_unsafe(flex_rf, 1.0,
False, angle_degrees=
True)
293 hand_commander.move_to_joint_value_target_unsafe(ext_rf, 1.0,
False, angle_degrees=
True)
295 hand_commander.move_to_joint_value_target_unsafe(flex_lf, 1.0,
False, angle_degrees=
True)
297 hand_commander.move_to_joint_value_target_unsafe(ext_lf, 1.0,
False, angle_degrees=
True)
299 hand_commander.move_to_joint_value_target_unsafe(flex_th_1, 0.7,
False, angle_degrees=
True)
301 hand_commander.move_to_joint_value_target_unsafe(flex_th_2, 0.7,
False, angle_degrees=
True)
303 hand_commander.move_to_joint_value_target_unsafe(ext_th_2, 0.5,
False, angle_degrees=
True)
305 hand_commander.move_to_joint_value_target_unsafe(l_ext_lf, 0.5,
False, angle_degrees=
True)
307 hand_commander.move_to_joint_value_target_unsafe(l_ext_rf, 0.5,
False, angle_degrees=
True)
309 hand_commander.move_to_joint_value_target_unsafe(l_ext_mf, 0.5,
False, angle_degrees=
True)
311 hand_commander.move_to_joint_value_target_unsafe(l_ext_ff, 0.5,
False, angle_degrees=
True)
313 hand_commander.move_to_joint_value_target_unsafe(l_int_all, 0.5,
False, angle_degrees=
True)
315 hand_commander.move_to_joint_value_target_unsafe(l_ext_all, 0.5,
False, angle_degrees=
True)
317 hand_commander.move_to_joint_value_target_unsafe(l_int_ff, 0.5,
False, angle_degrees=
True)
319 hand_commander.move_to_joint_value_target_unsafe(l_int_mf, 0.5,
False, angle_degrees=
True)
321 hand_commander.move_to_joint_value_target_unsafe(l_int_rf, 0.5,
False, angle_degrees=
True)
323 hand_commander.move_to_joint_value_target_unsafe(l_int_lf, 0.5,
False, angle_degrees=
True)
325 hand_commander.move_to_joint_value_target_unsafe(l_zero_all, 0.5,
False, angle_degrees=
True)
327 hand_commander.move_to_joint_value_target_unsafe(l_spock, 0.5,
False, angle_degrees=
True)
329 hand_commander.move_to_joint_value_target_unsafe(l_zero_all, 0.5,
False, angle_degrees=
True)
331 hand_commander.move_to_joint_value_target_unsafe(pre_ff_ok, 1.0,
False, angle_degrees=
True)
333 hand_commander.move_to_joint_value_target_unsafe(ff_ok, 1.0,
False, angle_degrees=
True)
335 hand_commander.move_to_joint_value_target_unsafe(ff2mf_ok, 0.8,
False, angle_degrees=
True)
337 hand_commander.move_to_joint_value_target_unsafe(mf_ok, 1.0,
False, angle_degrees=
True)
339 hand_commander.move_to_joint_value_target_unsafe(mf2rf_ok, 0.8,
False, angle_degrees=
True)
341 hand_commander.move_to_joint_value_target_unsafe(rf_ok, 1.0,
False, angle_degrees=
True)
343 hand_commander.move_to_joint_value_target_unsafe(rf2lf_ok, 0.8,
False, angle_degrees=
True)
345 hand_commander.move_to_joint_value_target_unsafe(lf_ok, 1.0,
False, angle_degrees=
True)
347 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0,
False, angle_degrees=
True)
349 hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2,
False, angle_degrees=
True)
351 hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2,
False, angle_degrees=
True)
353 hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2,
False, angle_degrees=
True)
355 hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2,
False, angle_degrees=
True)
357 hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2,
False, angle_degrees=
True)
359 hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2,
False, angle_degrees=
True)
361 hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2,
False, angle_degrees=
True)
363 hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2,
False, angle_degrees=
True)
365 hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2,
False, angle_degrees=
True)
367 hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2,
False, angle_degrees=
True)
369 hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2,
False, angle_degrees=
True)
371 hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2,
False, angle_degrees=
True)
373 hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2,
False, angle_degrees=
True)
375 hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2,
False, angle_degrees=
True)
377 hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2,
False, angle_degrees=
True)
379 hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2,
False, angle_degrees=
True)
381 hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2,
False, angle_degrees=
True)
383 hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2,
False, angle_degrees=
True)
385 hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2,
False, angle_degrees=
True)
387 hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2,
False, angle_degrees=
True)
389 hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2,
False, angle_degrees=
True)
391 hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2,
False, angle_degrees=
True)
393 hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2,
False, angle_degrees=
True)
395 hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2,
False, angle_degrees=
True)
397 hand_commander.move_to_joint_value_target_unsafe(pre_ff_ok, 1.0,
False, angle_degrees=
True)
399 hand_commander.move_to_joint_value_target_unsafe(ff_ok, 2.0,
False, angle_degrees=
True)
401 hand_commander.move_to_joint_value_target_unsafe(ne_wr, 1.4,
False, angle_degrees=
True)
403 hand_commander.move_to_joint_value_target_unsafe(nw_wr, 1.4,
False, angle_degrees=
True)
405 hand_commander.move_to_joint_value_target_unsafe(sw_wr, 1.4,
False, angle_degrees=
True)
407 hand_commander.move_to_joint_value_target_unsafe(se_wr, 1.4,
False, angle_degrees=
True)
409 hand_commander.move_to_joint_value_target_unsafe(ne_wr, 0.7,
False, angle_degrees=
True)
411 hand_commander.move_to_joint_value_target_unsafe(nw_wr, 0.7,
False, angle_degrees=
True)
413 hand_commander.move_to_joint_value_target_unsafe(sw_wr, 0.7,
False, angle_degrees=
True)
415 hand_commander.move_to_joint_value_target_unsafe(se_wr, 0.7,
False, angle_degrees=
True)
417 hand_commander.move_to_joint_value_target_unsafe(zero_wr, 0.4,
False, angle_degrees=
True)
419 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5,
False, angle_degrees=
True)
428 wake_time = time.time()
434 if (tactile_values[
'FF'] > force_zero[
'FF']
or 435 tactile_values[
'MF'] > force_zero[
'MF']
or 436 tactile_values[
'RF'] > force_zero[
'RF']
or 437 tactile_values[
'LF'] > force_zero[
'LF']
or 438 tactile_values[
'TH'] > force_zero[
'TH']):
440 hand_commander.move_to_joint_value_target_unsafe(start_pos, 2.0,
False, angle_degrees=
True)
441 print 'HAND TOUCHED!' 444 if (tactile_values[
'TH'] > force_zero[
'TH']):
451 if time.time() > wake_time:
453 rand_pos[i] = random.randrange(min_range[i], max_range[i])
455 rand_pos[
'lh_FFJ4'] = random.randrange(min_range[
'lh_FFJ4'], rand_pos[
'lh_MFJ4'])
456 rand_pos[
'lh_LFJ4'] = random.randrange(min_range[
'lh_LFJ4'], rand_pos[
'lh_RFJ4'])
457 inter_time = inter_time_max * random.random()
460 hand_commander.move_to_joint_value_target_unsafe(rand_pos, inter_time,
False, angle_degrees=
True)
461 wake_time = time.time() + inter_time * 0.9
468 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0,
False, angle_degrees=
True)
470 hand_commander.move_to_joint_value_target_unsafe(bc_pre_zero, 2.0,
False, angle_degrees=
True)
472 hand_commander.move_to_joint_value_target_unsafe(bc_zero, 1.0,
False, angle_degrees=
True)
474 hand_commander.move_to_joint_value_target_unsafe(bc_1, 1.0,
False, angle_degrees=
True)
476 hand_commander.move_to_joint_value_target_unsafe(bc_2, 1.0,
False, angle_degrees=
True)
478 hand_commander.move_to_joint_value_target_unsafe(bc_3, 1.0,
False, angle_degrees=
True)
480 hand_commander.move_to_joint_value_target_unsafe(bc_4, 1.0,
False, angle_degrees=
True)
482 hand_commander.move_to_joint_value_target_unsafe(bc_5, 1.0,
False, angle_degrees=
True)
484 hand_commander.move_to_joint_value_target_unsafe(bc_6, 1.0,
False, angle_degrees=
True)
486 hand_commander.move_to_joint_value_target_unsafe(bc_7, 1.0,
False, angle_degrees=
True)
488 hand_commander.move_to_joint_value_target_unsafe(bc_8, 1.0,
False, angle_degrees=
True)
490 hand_commander.move_to_joint_value_target_unsafe(bc_9, 1.0,
False, angle_degrees=
True)
492 hand_commander.move_to_joint_value_target_unsafe(bc_11, 1.0,
False, angle_degrees=
True)
494 hand_commander.move_to_joint_value_target_unsafe(bc_12, 3.0,
False, angle_degrees=
True)
496 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5,
False, angle_degrees=
True)
505 trigger = [0, 0, 0, 0, 0]
508 hand_commander.move_to_joint_value_target_unsafe(start_pos, 2.0,
False, angle_degrees=
True)
512 hand_commander.move_to_joint_value_target_unsafe(pregrasp_pos, 2.0,
False, angle_degrees=
True)
516 hand_commander.move_to_joint_value_target_unsafe(grasp_pos, 11.0,
False, angle_degrees=
True)
520 end_time = time.time() + 11
527 hand_pos = hand_commander.get_joints_position()
531 if (tactile_values[
'FF'] > force_zero[
'FF']
and trigger[0] == 0):
532 hand_pos_incr_f = {
"lh_FFJ1": hand_pos[
'lh_FFJ1'] + offset1,
"lh_FFJ3": hand_pos[
'lh_FFJ3'] + offset1}
533 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_f, 0.5,
False, angle_degrees=
True)
534 print 'First finger contact' 537 if (tactile_values[
'MF'] > force_zero[
'MF']
and trigger[1] == 0):
538 hand_pos_incr_m = {
"lh_MFJ1": hand_pos[
'lh_MFJ1'] + offset1,
"lh_MFJ3": hand_pos[
'lh_MFJ3'] + offset1}
539 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_m, 0.5,
False, angle_degrees=
True)
540 print 'Middle finger contact' 543 if (tactile_values[
'RF'] > force_zero[
'RF']
and trigger[2] == 0):
544 hand_pos_incr_r = {
"lh_RFJ1": hand_pos[
'lh_RFJ1'] + offset1,
"lh_RFJ3": hand_pos[
'lh_RFJ3'] + offset1}
545 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_r, 0.5,
False, angle_degrees=
True)
546 print 'Ring finger contact' 549 if (tactile_values[
'LF'] > force_zero[
'LF']
and trigger[3] == 0):
550 hand_pos_incr_l = {
"lh_LFJ1": hand_pos[
'lh_LFJ1'] + offset1,
"lh_LFJ3": hand_pos[
'lh_LFJ3'] + offset1}
551 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_l, 0.5,
False, angle_degrees=
True)
552 print 'Little finger contact' 555 if (tactile_values[
'TH'] > force_zero[
'TH']
and trigger[4] == 0):
556 hand_pos_incr_th = {
"lh_THJ2": hand_pos[
'lh_THJ2'] + offset1,
"lh_THJ5": hand_pos[
'lh_THJ5'] + offset1}
557 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_th, 0.5,
False, angle_degrees=
True)
558 print 'Thumb contact' 561 if (trigger[0] == 1
and 568 if time.time() > end_time:
573 hand_pos = hand_commander.get_joints_position()
574 hand_commander.move_to_joint_value_target_unsafe(hand_pos, 2.0,
False, angle_degrees=
True)
579 squeeze = hand_pos.copy()
580 squeeze.update({
"lh_THJ5": hand_pos[
'lh_THJ5'] + offset2,
"lh_THJ2": hand_pos[
'lh_THJ2'] + offset2,
581 "lh_FFJ3": hand_pos[
'lh_FFJ3'] + offset2,
"lh_FFJ1": hand_pos[
'lh_FFJ1'] + offset2,
582 "lh_MFJ3": hand_pos[
'lh_MFJ3'] + offset2,
"lh_MFJ1": hand_pos[
'lh_MFJ1'] + offset2,
583 "lh_RFJ3": hand_pos[
'lh_RFJ3'] + offset2,
"lh_RFJ1": hand_pos[
'lh_RFJ1'] + offset2,
584 "lh_LFJ3": hand_pos[
'lh_LFJ3'] + offset2,
"lh_LFJ1": hand_pos[
'lh_LFJ1'] + offset2})
587 hand_commander.move_to_joint_value_target_unsafe(squeeze, 0.5,
False, angle_degrees=
True)
589 hand_commander.move_to_joint_value_target_unsafe(hand_pos, 0.5,
False, angle_degrees=
True)
591 hand_commander.move_to_joint_value_target_unsafe(squeeze, 0.5,
False, angle_degrees=
True)
593 hand_commander.move_to_joint_value_target_unsafe(hand_pos, 2.0,
False, angle_degrees=
True)
595 hand_commander.move_to_joint_value_target_unsafe(pregrasp_pos, 2.0,
False, angle_degrees=
True)
597 hand_commander.move_to_joint_value_target_unsafe(start_pos, 2.0,
False, angle_degrees=
True)
606 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5,
False, angle_degrees=
True)
614 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0,
False, angle_degrees=
True)
616 print '\n\nPLEASE ENSURE THAT THE TACTILE SENSORS ARE NOT PRESSED\n' 620 for x
in xrange(1, 1000):
624 if tactile_values[
'FF'] > force_zero[
'FF']:
625 force_zero[
'FF'] = tactile_values[
'FF']
626 if tactile_values[
'MF'] > force_zero[
'MF']:
627 force_zero[
'MF'] = tactile_values[
'MF']
628 if tactile_values[
'RF'] > force_zero[
'RF']:
629 force_zero[
'RF'] = tactile_values[
'RF']
630 if tactile_values[
'LF'] > force_zero[
'LF']:
631 force_zero[
'LF'] = tactile_values[
'LF']
632 if tactile_values[
'TH'] > force_zero[
'TH']:
633 force_zero[
'TH'] = tactile_values[
'TH']
635 force_zero[
'FF'] = force_zero[
'FF'] + 5
636 force_zero[
'MF'] = force_zero[
'MF'] + 5
637 force_zero[
'RF'] = force_zero[
'RF'] + 5
638 force_zero[
'LF'] = force_zero[
'LF'] + 5
639 force_zero[
'TH'] = force_zero[
'TH'] + 5
641 print 'Force Zero', force_zero
643 rospy.loginfo(
"\n\nOK, ready for the demo")
645 print "\nPRESS ONE OF THE TACTILES TO START A DEMO" 646 print " FF: Standard Demo" 647 print " MF: Shy Hand Demo" 648 print " RF: Card Trick Demo" 649 print " LF: Grasp Demo" 650 print " TH: Open Hand" 657 tactile_type = hand_commander.get_tactile_type()
659 tactile_state = hand_commander.get_tactile_state()
661 if tactile_type ==
"biotac":
662 tactile_values[
'FF'] = tactile_state.tactiles[0].pdc
663 tactile_values[
'MF'] = tactile_state.tactiles[1].pdc
664 tactile_values[
'RF'] = tactile_state.tactiles[2].pdc
665 tactile_values[
'LF'] = tactile_state.tactiles[3].pdc
666 tactile_values[
'TH'] = tactile_state.tactiles[4].pdc
668 elif tactile_type ==
"PST":
669 tactile_values[
'FF'] = tactile_state.pressure[0]
670 tactile_values[
'MF'] = tactile_state.pressure[1]
671 tactile_values[
'RF'] = tactile_state.pressure[2]
672 tactile_values[
'LF'] = tactile_state.pressure[3]
673 tactile_values[
'TH'] = tactile_state.pressure[4]
675 elif tactile_type ==
None:
676 print "You don't have tactile sensors. Talk to your Shadow representative to purchase some" 686 force_zero = {
"FF": 0,
"MF": 0,
"RF": 0,
"LF": 0,
"TH": 0}
688 tactile_values = {
"FF": 0,
"MF": 0,
"RF": 0,
"LF": 0,
"TH": 0}
692 while not rospy.is_shutdown():
697 if (tactile_values[
'FF'] > force_zero[
'FF']):
698 print 'First finger contact' 700 print 'FF demo completed' 702 if (tactile_values[
'MF'] > force_zero[
'MF']):
703 print 'Middle finger contact' 705 print 'MF demo completed' 707 if (tactile_values[
'RF'] > force_zero[
'RF']):
708 print 'Ring finger contact' 710 print 'RF demo completed' 712 if (tactile_values[
'LF'] > force_zero[
'LF']):
713 print 'Little finger contact' 715 print 'LF demo completed' 717 if (tactile_values[
'TH'] > force_zero[
'TH']):
718 print 'Thumb finger contact' 720 print 'TH demo completed'
def read_tactile_values()
def secuence_ff()
FUNCTION DEFINITIONS #.
def zero_tactile_sensors()