22 from sr_robot_commander.sr_hand_commander
import SrHandCommander
24 rospy.init_node(
"right_hand_demo", anonymous=
True)
26 hand_commander = SrHandCommander(name=
"right_hand")
35 min_range = {
"rh_THJ2": -40,
"rh_THJ3": -12,
"rh_THJ4": 0,
"rh_THJ5": -55,
36 "rh_FFJ1": 0,
"rh_FFJ2": 20,
"rh_FFJ3": 0,
"rh_FFJ4": -20,
37 "rh_MFJ1": 0,
"rh_MFJ2": 20,
"rh_MFJ3": 0,
"rh_MFJ4": -10,
38 "rh_RFJ1": 0,
"rh_RFJ2": 20,
"rh_RFJ3": 0,
"rh_RFJ4": -10,
39 "rh_LFJ1": 10,
"rh_LFJ2": 10,
"rh_LFJ3": 0,
"rh_LFJ4": -20,
"rh_LFJ5": 0,
40 "rh_WRJ1": -20,
"rh_WRJ2": -10}
43 max_range = {
"rh_THJ2": 20,
"rh_THJ3": 12,
"rh_THJ4": 70,
"rh_THJ5": 0,
44 "rh_FFJ1": 20,
"rh_FFJ2": 90,
"rh_FFJ3": 90,
"rh_FFJ4": 0,
45 "rh_MFJ1": 20,
"rh_MFJ2": 90,
"rh_MFJ3": 90,
"rh_MFJ4": 0,
46 "rh_RFJ1": 20,
"rh_RFJ2": 90,
"rh_RFJ3": 90,
"rh_RFJ4": 0,
47 "rh_LFJ1": 20,
"rh_LFJ2": 90,
"rh_LFJ3": 90,
"rh_LFJ4": 0,
"rh_LFJ5": 1,
48 "rh_WRJ1": 10,
"rh_WRJ2": 5}
55 start_pos = {
"rh_THJ1": 0,
"rh_THJ2": 0,
"rh_THJ3": 0,
"rh_THJ4": 0,
"rh_THJ5": 0,
56 "rh_FFJ1": 0,
"rh_FFJ2": 0,
"rh_FFJ3": 0,
"rh_FFJ4": 0,
57 "rh_MFJ1": 0,
"rh_MFJ2": 0,
"rh_MFJ3": 0,
"rh_MFJ4": 0,
58 "rh_RFJ1": 0,
"rh_RFJ2": 0,
"rh_RFJ3": 0,
"rh_RFJ4": 0,
59 "rh_LFJ1": 0,
"rh_LFJ2": 0,
"rh_LFJ3": 0,
"rh_LFJ4": 0,
"rh_LFJ5": 0,
60 "rh_WRJ1": 0,
"rh_WRJ2": 0}
62 pregrasp_pos = {
"rh_THJ2": 12,
"rh_THJ3": 15,
"rh_THJ4": 69,
"rh_THJ5": -23,
63 "rh_FFJ1": 0,
"rh_FFJ2": 40,
"rh_FFJ3": 21,
"rh_FFJ4": -15,
64 "rh_MFJ1": 0,
"rh_MFJ2": 40,
"rh_MFJ3": 21,
"rh_MFJ4": 0,
65 "rh_RFJ1": 0,
"rh_RFJ2": 40,
"rh_RFJ3": 21,
"rh_RFJ4": -7,
66 "rh_LFJ1": 0,
"rh_LFJ2": 40,
"rh_LFJ3": 21,
"rh_LFJ4": -10,
"rh_LFJ5": 0,
67 "rh_WRJ1": 0,
"rh_WRJ2": 0}
69 grasp_pos = {
"rh_THJ2": 30,
"rh_THJ3": 15,
"rh_THJ4": 69,
"rh_THJ5": -3,
70 "rh_FFJ1": 0,
"rh_FFJ2": 77,
"rh_FFJ3": 67,
"rh_FFJ4": -19,
71 "rh_MFJ1": 0,
"rh_MFJ2": 82,
"rh_MFJ3": 62,
"rh_MFJ4": 0,
72 "rh_RFJ1": 0,
"rh_RFJ2": 89,
"rh_RFJ3": 64,
"rh_RFJ4": -18,
73 "rh_LFJ1": 7,
"rh_LFJ2": 90,
"rh_LFJ3": 64,
"rh_LFJ4": -19,
"rh_LFJ5": 0,
74 "rh_WRJ1": 0,
"rh_WRJ2": 0}
76 rand_pos = {
"rh_THJ2": 0,
"rh_THJ3": 0,
"rh_THJ4": 0,
"rh_THJ5": 0,
77 "rh_FFJ1": 0,
"rh_FFJ2": 0,
"rh_FFJ3": 0,
"rh_FFJ4": 0,
78 "rh_MFJ1": 0,
"rh_MFJ2": 0,
"rh_MFJ3": 0,
"rh_MFJ4": 0,
79 "rh_RFJ1": 0,
"rh_RFJ2": 0,
"rh_RFJ3": 0,
"rh_RFJ4": 0,
80 "rh_LFJ1": 0,
"rh_LFJ2": 0,
"rh_LFJ3": 0,
"rh_LFJ4": 0,
"rh_LFJ5": 0,
81 "rh_WRJ1": 0,
"rh_WRJ2": 0}
83 flex_ff = {
"rh_FFJ1": 90,
"rh_FFJ2": 90,
"rh_FFJ3": 90,
"rh_FFJ4": 0}
85 ext_ff = {
"rh_FFJ1": 0,
"rh_FFJ2": 0,
"rh_FFJ3": 0,
"rh_FFJ4": 0}
87 flex_mf = {
"rh_MFJ1": 90,
"rh_MFJ2": 90,
"rh_MFJ3": 90,
"rh_MFJ4": 0}
89 ext_mf = {
"rh_MFJ1": 0,
"rh_MFJ2": 0,
"rh_MFJ3": 0,
"rh_MFJ4": 0}
91 flex_rf = {
"rh_RFJ1": 90,
"rh_RFJ2": 90,
"rh_RFJ3": 90,
"rh_RFJ4": 0}
93 ext_rf = {
"rh_RFJ1": 0,
"rh_RFJ2": 0,
"rh_RFJ3": 0,
"rh_RFJ4": 0}
95 flex_lf = {
"rh_LFJ1": 90,
"rh_LFJ2": 90,
"rh_LFJ3": 90,
"rh_LFJ4": 0}
97 ext_lf = {
"rh_LFJ1": 0,
"rh_LFJ2": 0,
"rh_LFJ3": 0,
"rh_LFJ4": 0}
99 flex_th_1 = {
"rh_THJ1": 0,
"rh_THJ2": 0,
"rh_THJ3": 0,
"rh_THJ4": 70,
"rh_THJ5": 0}
101 flex_th_2 = {
"rh_THJ1": 35,
"rh_THJ2": 38,
"rh_THJ3": 10,
"rh_THJ4": 70,
"rh_THJ5": 58}
103 ext_th_1 = {
"rh_THJ1": 10,
"rh_THJ2": 20,
"rh_THJ3": 5,
"rh_THJ4": 35,
"rh_THJ5": 25}
105 ext_th_2 = {
"rh_THJ1": 0,
"rh_THJ2": 0,
"rh_THJ3": 0,
"rh_THJ4": 0,
"rh_THJ5": 0}
107 zero_th = {
"rh_THJ1": 0,
"rh_THJ2": 0,
"rh_THJ3": 0,
"rh_THJ4": 0,
"rh_THJ5": 0}
109 pre_ff_ok = {
"rh_THJ4": 70}
111 ff_ok = {
"rh_THJ1": 17,
"rh_THJ2": 20,
"rh_THJ3": 0,
"rh_THJ4": 56,
"rh_THJ5": 18,
112 "rh_FFJ1": 0,
"rh_FFJ2": 75,
"rh_FFJ3": 52,
"rh_FFJ4": -0.2,
113 "rh_MFJ1": 0,
"rh_MFJ2": 42,
"rh_MFJ3": 33,
"rh_MFJ4": -3,
114 "rh_RFJ1": 0,
"rh_RFJ2": 50,
"rh_RFJ3": 18,
"rh_RFJ4": 0.5,
115 "rh_LFJ1": 0,
"rh_LFJ2": 30,
"rh_LFJ3": 0,
"rh_LFJ4": -6,
"rh_LFJ5": 7}
117 ff2mf_ok = {
"rh_THJ1": 5,
"rh_THJ2": 12,
"rh_THJ3": 4,
"rh_THJ4": 60,
"rh_THJ5": 2,
118 "rh_FFJ1": 0,
"rh_FFJ2": 14,
"rh_FFJ3": 7,
"rh_FFJ4": -0.4,
119 "rh_MFJ1": 0,
"rh_MFJ2": 42,
"rh_MFJ3": 33,
"rh_MFJ4": -3,
120 "rh_RFJ1": 0,
"rh_RFJ2": 50,
"rh_RFJ3": 18,
"rh_RFJ4": 0.5,
121 "rh_LFJ1": 0,
"rh_LFJ2": 30,
"rh_LFJ3": 0,
"rh_LFJ4": -6,
"rh_LFJ5": 7}
123 mf_ok = {
"rh_THJ1": 19,
"rh_THJ2": 17,
"rh_THJ3": 6,
"rh_THJ4": 66,
"rh_THJ5": 31,
124 "rh_FFJ1": 0,
"rh_FFJ2": 15,
"rh_FFJ3": 7,
"rh_FFJ4": -0.4,
125 "rh_MFJ1": 11,
"rh_MFJ2": 71,
"rh_MFJ3": 49,
"rh_MFJ4": 10,
126 "rh_RFJ1": 0,
"rh_RFJ2": 50,
"rh_RFJ3": 18,
"rh_RFJ4": -10,
127 "rh_LFJ1": 0,
"rh_LFJ2": 30,
"rh_LFJ3": 0,
"rh_LFJ4": -6,
"rh_LFJ5": 7}
129 mf2rf_ok = {
"rh_THJ1": 5,
"rh_THJ2": -5,
"rh_THJ3": 15,
"rh_THJ4": 70,
"rh_THJ5": 19,
130 "rh_FFJ1": 0,
"rh_FFJ2": 14,
"rh_FFJ3": 7,
"rh_FFJ4": -0.4,
131 "rh_MFJ1": 0,
"rh_MFJ2": 45,
"rh_MFJ3": 4,
"rh_MFJ4": -1,
132 "rh_RFJ1": 0,
"rh_RFJ2": 50,
"rh_RFJ3": 18,
"rh_RFJ4": -19,
133 "rh_LFJ1": 0,
"rh_LFJ2": 30,
"rh_LFJ3": 0,
"rh_LFJ4": -12,
"rh_LFJ5": 7}
135 rf_ok = {
"rh_THJ1": 8,
"rh_THJ2": 15,
"rh_THJ3": 15,
"rh_THJ4": 70,
"rh_THJ5": 45,
136 "rh_FFJ1": 0,
"rh_FFJ2": 14,
"rh_FFJ3": 7,
"rh_FFJ4": -0.4,
137 "rh_MFJ1": 0,
"rh_MFJ2": 45,
"rh_MFJ3": 4,
"rh_MFJ4": -1,
138 "rh_RFJ1": 3,
"rh_RFJ2": 90,
"rh_RFJ3": 42,
"rh_RFJ4": -19,
139 "rh_LFJ1": 0,
"rh_LFJ2": 30,
"rh_LFJ3": 0,
"rh_LFJ4": -12,
"rh_LFJ5": 7}
141 rf2lf_ok = {
"rh_THJ1": 5,
"rh_THJ2": 4.5,
"rh_THJ3": 8,
"rh_THJ4": 60,
"rh_THJ5": 21,
142 "rh_FFJ1": 0,
"rh_FFJ2": 14,
"rh_FFJ3": 7,
"rh_FFJ4": -0.4,
143 "rh_MFJ1": 0,
"rh_MFJ2": 45,
"rh_MFJ3": 4,
"rh_MFJ4": -1,
144 "rh_RFJ1": 0,
"rh_RFJ2": 30,
"rh_RFJ3": 6,
"rh_RFJ4": 0.5,
145 "rh_LFJ1": 0,
"rh_LFJ2": 30,
"rh_LFJ3": 0,
"rh_LFJ4": -10,
"rh_LFJ5": 7}
147 lf_ok = {
"rh_THJ1": 25,
"rh_THJ2": 14,
"rh_THJ3": 10,
"rh_THJ4": 69,
"rh_THJ5": 22,
148 "rh_FFJ1": 0,
"rh_FFJ2": 14,
"rh_FFJ3": 7,
"rh_FFJ4": -0.4,
149 "rh_MFJ1": 0,
"rh_MFJ2": 15,
"rh_MFJ3": 4,
"rh_MFJ4": -1,
150 "rh_RFJ1": 0,
"rh_RFJ2": 15,
"rh_RFJ3": 6,
"rh_RFJ4": 0.5,
151 "rh_LFJ1": 0,
"rh_LFJ2": 78,
"rh_LFJ3": 26,
"rh_LFJ4": 5,
"rh_LFJ5": 37}
153 zero_wr = {
"rh_WRJ1": 0,
"rh_WRJ2": 0}
155 n_wr = {
"rh_WRJ1": 15,
"rh_WRJ2": 0}
157 s_wr = {
"rh_WRJ1": -20,
"rh_WRJ2": 0}
159 e_wr = {
"rh_WRJ1": 0,
"rh_WRJ2": 8}
161 w_wr = {
"rh_WRJ1": 0,
"rh_WRJ2": -14}
163 ne_wr = {
"rh_WRJ1": 15,
"rh_WRJ2": 8}
165 nw_wr = {
"rh_WRJ1": 15,
"rh_WRJ2": -14}
167 sw_wr = {
"rh_WRJ1": -20,
"rh_WRJ2": -14}
169 se_wr = {
"rh_WRJ1": -20,
"rh_WRJ2": 8}
171 l_ext_lf = {
"rh_LFJ4": -15}
173 l_ext_rf = {
"rh_RFJ4": -15}
175 l_ext_mf = {
"rh_MFJ4": 15}
177 l_ext_ff = {
"rh_FFJ4": 15}
179 l_int_all = {
"rh_FFJ4": -15,
"rh_MFJ4": -15,
"rh_RFJ4": 15,
"rh_LFJ4": 15}
181 l_ext_all = {
"rh_FFJ4": 15,
"rh_MFJ4": 15,
"rh_RFJ4": -15,
"rh_LFJ4": -15}
183 l_int_ff = {
"rh_FFJ4": -15}
185 l_int_mf = {
"rh_MFJ4": -15}
187 l_int_rf = {
"rh_RFJ4": 15}
189 l_int_lf = {
"rh_LFJ4": 15}
191 l_zero_all = {
"rh_FFJ4": 0,
"rh_MFJ4": 0,
"rh_RFJ4": 0,
"rh_LFJ4": 0}
193 l_spock = {
"rh_FFJ4": -20,
"rh_MFJ4": -20,
"rh_RFJ4": -20,
"rh_LFJ4": -20}
195 shake_grasp_1 = {
"rh_THJ1": 0,
"rh_THJ2": 6,
"rh_THJ3": 10,
"rh_THJ4": 37,
"rh_THJ5": 9,
196 "rh_FFJ1": 0,
"rh_FFJ2": 21,
"rh_FFJ3": 26,
"rh_FFJ4": 0,
197 "rh_MFJ1": 0,
"rh_MFJ2": 18,
"rh_MFJ3": 24,
"rh_MFJ4": 0,
198 "rh_RFJ1": 0,
"rh_RFJ2": 30,
"rh_RFJ3": 16,
"rh_RFJ4": 0,
199 "rh_LFJ1": 0,
"rh_LFJ2": 30,
"rh_LFJ3": 0,
"rh_LFJ4": -10,
"rh_LFJ5": 10}
201 shake_grasp_2 = {
"rh_THJ1": 21,
"rh_THJ2": 21,
"rh_THJ3": 10,
"rh_THJ4": 42,
"rh_THJ5": 21,
202 "rh_FFJ1": 0,
"rh_FFJ2": 75,
"rh_FFJ3": 29,
"rh_FFJ4": 0,
203 "rh_MFJ1": 0,
"rh_MFJ2": 75,
"rh_MFJ3": 41,
"rh_MFJ4": 0,
204 "rh_RFJ1": 0,
"rh_RFJ2": 75,
"rh_RFJ3": 41,
"rh_RFJ4": 0,
205 "rh_LFJ1": 10,
"rh_LFJ2": 90,
"rh_LFJ3": 41,
"rh_LFJ4": 0,
"rh_LFJ5": 0}
207 store_1_PST = {
"rh_THJ1": 0,
"rh_THJ2": 0,
"rh_THJ3": 0,
"rh_THJ4": 60,
"rh_THJ5": 0,
208 "rh_FFJ1": 90,
"rh_FFJ2": 90,
"rh_FFJ3": 90,
"rh_FFJ4": 0,
209 "rh_MFJ1": 90,
"rh_MFJ2": 90,
"rh_MFJ3": 90,
"rh_MFJ4": 0,
210 "rh_RFJ1": 90,
"rh_RFJ2": 90,
"rh_RFJ3": 90,
"rh_RFJ4": 0,
211 "rh_LFJ1": 90,
"rh_LFJ2": 90,
"rh_LFJ3": 90,
"rh_LFJ4": 0,
"rh_LFJ5": 0,
212 "rh_WRJ1": 0,
"rh_WRJ2": 0}
214 store_2_PST = {
"rh_THJ1": 50,
"rh_THJ2": 12,
"rh_THJ3": 0,
"rh_THJ4": 60,
"rh_THJ5": 27,
215 "rh_FFJ1": 90,
"rh_FFJ2": 90,
"rh_FFJ3": 90,
"rh_FFJ4": 0,
216 "rh_MFJ1": 90,
"rh_MFJ2": 90,
"rh_MFJ3": 90,
"rh_MFJ4": 0,
217 "rh_RFJ1": 90,
"rh_RFJ2": 90,
"rh_RFJ3": 90,
"rh_RFJ4": 0,
218 "rh_LFJ1": 90,
"rh_LFJ2": 90,
"rh_LFJ3": 90,
"rh_LFJ4": 0,
"rh_LFJ5": 0,
219 "rh_WRJ1": 0,
"rh_WRJ2": 0}
221 store_1_BioTac = {
"rh_THJ1": 0,
"rh_THJ2": 0,
"rh_THJ3": 0,
"rh_THJ4": 30,
"rh_THJ5": 0,
222 "rh_FFJ1": 90,
"rh_FFJ2": 90,
"rh_FFJ3": 90,
"rh_FFJ4": 0,
223 "rh_MFJ1": 90,
"rh_MFJ2": 90,
"rh_MFJ3": 90,
"rh_MFJ4": 0,
224 "rh_RFJ1": 90,
"rh_RFJ2": 90,
"rh_RFJ3": 90,
"rh_RFJ4": 0,
225 "rh_LFJ1": 90,
"rh_LFJ2": 90,
"rh_LFJ3": 90,
"rh_LFJ4": 0,
"rh_LFJ5": 0,
226 "rh_WRJ1": 0,
"rh_WRJ2": 0}
228 store_2_BioTac = {
"rh_THJ1": 20,
"rh_THJ2": 36,
"rh_THJ3": 0,
"rh_THJ4": 30,
"rh_THJ5": -3,
229 "rh_FFJ1": 90,
"rh_FFJ2": 90,
"rh_FFJ3": 90,
"rh_FFJ4": 0,
230 "rh_MFJ1": 90,
"rh_MFJ2": 90,
"rh_MFJ3": 90,
"rh_MFJ4": 0,
231 "rh_RFJ1": 90,
"rh_RFJ2": 90,
"rh_RFJ3": 90,
"rh_RFJ4": 0,
232 "rh_LFJ1": 90,
"rh_LFJ2": 90,
"rh_LFJ3": 90,
"rh_LFJ4": 0,
"rh_LFJ5": 0,
233 "rh_WRJ1": 0,
"rh_WRJ2": 0}
235 store_3 = {
"rh_THJ1": 0,
"rh_THJ2": 0,
"rh_THJ3": 0,
"rh_THJ4": 65,
"rh_THJ5": 0}
237 bc_pre_zero = {
"rh_THJ1": 15,
"rh_THJ2": 7,
"rh_THJ3": -4,
"rh_THJ4": 41,
"rh_THJ5": -20,
238 "rh_FFJ1": 0,
"rh_FFJ2": 14,
"rh_FFJ3": 7,
"rh_FFJ4": -1,
239 "rh_MFJ1": 0,
"rh_MFJ2": 51,
"rh_MFJ3": 33,
"rh_MFJ4": 20,
240 "rh_RFJ1": 0,
"rh_RFJ2": 50,
"rh_RFJ3": 18,
"rh_RFJ4": -20,
241 "rh_LFJ1": 0,
"rh_LFJ2": 30,
"rh_LFJ3": 0,
"rh_LFJ4": -20,
"rh_LFJ5": 7}
243 bc_zero = {
"rh_THJ1": 38,
"rh_THJ2": 4,
"rh_THJ3": 0,
"rh_THJ4": 48,
"rh_THJ5": -5,
244 "rh_MFJ1": 7,
"rh_MFJ2": 64,
"rh_MFJ3": 20,
"rh_MFJ4": 18}
246 bc_1 = {
"rh_FFJ1": 47,
"rh_FFJ2": 90,
"rh_FFJ3": 7}
248 bc_2 = {
"rh_FFJ1": 47,
"rh_FFJ2": 90,
"rh_FFJ3": 58}
250 bc_3 = {
"rh_FFJ1": 0,
"rh_FFJ2": 60,
"rh_FFJ3": 58}
252 bc_4 = {
"rh_FFJ1": 90,
"rh_FFJ2": 90,
"rh_FFJ3": 58,
"rh_FFJ4": 15}
254 bc_5 = {
"rh_FFJ1": 90,
"rh_FFJ2": 90,
"rh_FFJ3": 0}
256 bc_6 = {
"rh_FFJ1": 0,
"rh_FFJ2": 0,
"rh_FFJ3": 0,
"rh_FFJ4": 10}
258 bc_7 = {
"rh_FFJ1": 47,
"rh_FFJ2": 90,
"rh_FFJ3": 15,
"rh_FFJ4": 0}
260 bc_8 = {
"rh_FFJ1": 47,
"rh_FFJ2": 90,
"rh_FFJ3": 58}
262 bc_9 = {
"rh_FFJ1": 0,
"rh_FFJ2": 71,
"rh_FFJ3": 58}
264 bc_10 = {
"rh_MFJ3": 64,
"rh_FFJ4": 20}
266 bc_11 = {
"rh_FFJ1": 0,
"rh_FFJ2": 81,
"rh_FFJ3": 50,
"rh_FFJ4": 20,
267 "rh_THJ4": 57,
"rh_THJ5": 20}
269 bc_12 = {
"rh_MFJ1": 0,
"rh_MFJ2": 20,
"rh_MFJ3": 10,
"rh_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()
435 for finger
in [
"FF",
"MF",
"RF",
"LF",
"TH"]:
436 if tactile_values[finger] > force_zero[finger]:
438 if touched
is not None:
439 hand_commander.move_to_joint_value_target_unsafe(start_pos, 2.0,
False, angle_degrees=
True)
440 print '{} touched!'.format(finger)
449 if time.time() > wake_time:
451 rand_pos[i] = random.randrange(min_range[i], max_range[i])
453 rand_pos[
'rh_FFJ4'] = random.randrange(min_range[
'rh_FFJ4'], rand_pos[
'rh_MFJ4'])
454 rand_pos[
'rh_LFJ4'] = random.randrange(min_range[
'rh_LFJ4'], rand_pos[
'rh_RFJ4'])
455 inter_time = inter_time_max * random.random()
458 hand_commander.move_to_joint_value_target_unsafe(rand_pos, inter_time,
False, angle_degrees=
True)
459 wake_time = time.time() + inter_time * 0.9
466 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0,
False, angle_degrees=
True)
468 hand_commander.move_to_joint_value_target_unsafe(bc_pre_zero, 2.0,
False, angle_degrees=
True)
470 hand_commander.move_to_joint_value_target_unsafe(bc_zero, 1.0,
False, angle_degrees=
True)
472 hand_commander.move_to_joint_value_target_unsafe(bc_1, 1.0,
False, angle_degrees=
True)
474 hand_commander.move_to_joint_value_target_unsafe(bc_2, 1.0,
False, angle_degrees=
True)
476 hand_commander.move_to_joint_value_target_unsafe(bc_3, 1.0,
False, angle_degrees=
True)
478 hand_commander.move_to_joint_value_target_unsafe(bc_4, 1.0,
False, angle_degrees=
True)
480 hand_commander.move_to_joint_value_target_unsafe(bc_5, 1.0,
False, angle_degrees=
True)
482 hand_commander.move_to_joint_value_target_unsafe(bc_6, 1.0,
False, angle_degrees=
True)
484 hand_commander.move_to_joint_value_target_unsafe(bc_7, 1.0,
False, angle_degrees=
True)
486 hand_commander.move_to_joint_value_target_unsafe(bc_8, 1.0,
False, angle_degrees=
True)
488 hand_commander.move_to_joint_value_target_unsafe(bc_9, 1.0,
False, angle_degrees=
True)
490 hand_commander.move_to_joint_value_target_unsafe(bc_11, 1.0,
False, angle_degrees=
True)
492 hand_commander.move_to_joint_value_target_unsafe(bc_12, 3.0,
False, angle_degrees=
True)
494 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5,
False, angle_degrees=
True)
503 trigger = [0, 0, 0, 0, 0]
506 hand_commander.move_to_joint_value_target_unsafe(start_pos, 2.0,
False, angle_degrees=
True)
510 hand_commander.move_to_joint_value_target_unsafe(pregrasp_pos, 2.0,
False, angle_degrees=
True)
514 hand_commander.move_to_joint_value_target_unsafe(grasp_pos, 11.0,
False, angle_degrees=
True)
518 end_time = time.time() + 11
525 hand_pos = hand_commander.get_joints_position()
529 if (tactile_values[
'FF'] > force_zero[
'FF']
and trigger[0] == 0):
530 hand_pos_incr_f = {
"rh_FFJ1": hand_pos[
'rh_FFJ1'] + offset1,
"rh_FFJ3": hand_pos[
'rh_FFJ3'] + offset1}
531 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_f, 0.5,
False, angle_degrees=
True)
532 print 'First finger contact' 535 if (tactile_values[
'MF'] > force_zero[
'MF']
and trigger[1] == 0):
536 hand_pos_incr_m = {
"rh_MFJ1": hand_pos[
'rh_MFJ1'] + offset1,
"rh_MFJ3": hand_pos[
'rh_MFJ3'] + offset1}
537 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_m, 0.5,
False, angle_degrees=
True)
538 print 'Middle finger contact' 541 if (tactile_values[
'RF'] > force_zero[
'RF']
and trigger[2] == 0):
542 hand_pos_incr_r = {
"rh_RFJ1": hand_pos[
'rh_RFJ1'] + offset1,
"rh_RFJ3": hand_pos[
'rh_RFJ3'] + offset1}
543 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_r, 0.5,
False, angle_degrees=
True)
544 print 'Ring finger contact' 547 if (tactile_values[
'LF'] > force_zero[
'LF']
and trigger[3] == 0):
548 hand_pos_incr_l = {
"rh_LFJ1": hand_pos[
'rh_LFJ1'] + offset1,
"rh_LFJ3": hand_pos[
'rh_LFJ3'] + offset1}
549 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_l, 0.5,
False, angle_degrees=
True)
550 print 'Little finger contact' 553 if (tactile_values[
'TH'] > force_zero[
'TH']
and trigger[4] == 0):
554 hand_pos_incr_th = {
"rh_THJ2": hand_pos[
'rh_THJ2'] + offset1,
"rh_THJ5": hand_pos[
'rh_THJ5'] + offset1}
555 hand_commander.move_to_joint_value_target_unsafe(hand_pos_incr_th, 0.5,
False, angle_degrees=
True)
556 print 'Thumb contact' 559 if (trigger[0] == 1
and trigger[1] == 1
and trigger[2] == 1
and trigger[3] == 1
and trigger[4] == 1):
562 if time.time() > end_time:
567 hand_pos = hand_commander.get_joints_position()
568 hand_commander.move_to_joint_value_target_unsafe(hand_pos, 2.0,
False, angle_degrees=
True)
573 squeeze = hand_pos.copy()
574 squeeze.update({
"rh_THJ5": hand_pos[
'rh_THJ5'] + offset2,
"rh_THJ2": hand_pos[
'rh_THJ2'] + offset2,
575 "rh_FFJ3": hand_pos[
'rh_FFJ3'] + offset2,
"rh_FFJ1": hand_pos[
'rh_FFJ1'] + offset2,
576 "rh_MFJ3": hand_pos[
'rh_MFJ3'] + offset2,
"rh_MFJ1": hand_pos[
'rh_MFJ1'] + offset2,
577 "rh_RFJ3": hand_pos[
'rh_RFJ3'] + offset2,
"rh_RFJ1": hand_pos[
'rh_RFJ1'] + offset2,
578 "rh_LFJ3": hand_pos[
'rh_LFJ3'] + offset2,
"rh_LFJ1": hand_pos[
'rh_LFJ1'] + offset2})
581 hand_commander.move_to_joint_value_target_unsafe(squeeze, 0.5,
False, angle_degrees=
True)
583 hand_commander.move_to_joint_value_target_unsafe(hand_pos, 0.5,
False, angle_degrees=
True)
585 hand_commander.move_to_joint_value_target_unsafe(squeeze, 0.5,
False, angle_degrees=
True)
587 hand_commander.move_to_joint_value_target_unsafe(hand_pos, 2.0,
False, angle_degrees=
True)
589 hand_commander.move_to_joint_value_target_unsafe(pregrasp_pos, 2.0,
False, angle_degrees=
True)
591 hand_commander.move_to_joint_value_target_unsafe(start_pos, 2.0,
False, angle_degrees=
True)
600 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5,
False, angle_degrees=
True)
608 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0,
False, angle_degrees=
True)
610 print '\n\nPLEASE ENSURE THAT THE TACTILE SENSORS ARE NOT PRESSED\n' 614 for x
in xrange(1, 1000):
618 if tactile_values[
'FF'] > force_zero[
'FF']:
619 force_zero[
'FF'] = tactile_values[
'FF']
620 if tactile_values[
'MF'] > force_zero[
'MF']:
621 force_zero[
'MF'] = tactile_values[
'MF']
622 if tactile_values[
'RF'] > force_zero[
'RF']:
623 force_zero[
'RF'] = tactile_values[
'RF']
624 if tactile_values[
'LF'] > force_zero[
'LF']:
625 force_zero[
'LF'] = tactile_values[
'LF']
626 if tactile_values[
'TH'] > force_zero[
'TH']:
627 force_zero[
'TH'] = tactile_values[
'TH']
629 force_zero[
'FF'] = force_zero[
'FF'] + 5
630 force_zero[
'MF'] = force_zero[
'MF'] + 5
631 force_zero[
'RF'] = force_zero[
'RF'] + 5
632 force_zero[
'LF'] = force_zero[
'LF'] + 5
633 force_zero[
'TH'] = force_zero[
'TH'] + 5
635 print 'Force Zero', force_zero
637 rospy.loginfo(
"\n\nOK, ready for the demo")
639 print "\nPRESS ONE OF THE TACTILES TO START A DEMO" 640 print " FF: Standard Demo" 641 print " MF: Shy Hand Demo" 642 print " RF: Card Trick Demo" 643 print " LF: Grasp Demo" 644 print " TH: Open Hand" 651 tactile_type = hand_commander.get_tactile_type()
653 tactile_state = hand_commander.get_tactile_state()
655 if tactile_type ==
"biotac":
656 tactile_values[
'FF'] = tactile_state.tactiles[0].pdc
657 tactile_values[
'MF'] = tactile_state.tactiles[1].pdc
658 tactile_values[
'RF'] = tactile_state.tactiles[2].pdc
659 tactile_values[
'LF'] = tactile_state.tactiles[3].pdc
660 tactile_values[
'TH'] = tactile_state.tactiles[4].pdc
662 elif tactile_type ==
"PST":
663 tactile_values[
'FF'] = tactile_state.pressure[0]
664 tactile_values[
'MF'] = tactile_state.pressure[1]
665 tactile_values[
'RF'] = tactile_state.pressure[2]
666 tactile_values[
'LF'] = tactile_state.pressure[3]
667 tactile_values[
'TH'] = tactile_state.pressure[4]
669 elif tactile_type
is None:
670 print "You don't have tactile sensors. Talk to your Shadow representative to purchase some" 680 force_zero = {
"FF": 0,
"MF": 0,
"RF": 0,
"LF": 0,
"TH": 0}
682 tactile_values = {
"FF": 0,
"MF": 0,
"RF": 0,
"LF": 0,
"TH": 0}
686 while not rospy.is_shutdown():
690 for finger
in [
"FF",
"MF",
"RF",
"LF",
"TH"]:
691 if tactile_values[finger] > force_zero[finger]:
694 if touched
is not None:
695 print "{} contact".format(touched)
698 elif touched ==
"MF":
700 elif touched ==
"RF":
702 elif touched ==
"LF":
704 elif touched ==
"TH":
706 print "{} demo completed".format(touched)
def read_tactile_values()
def secuence_ff()
FUNCTION DEFINITIONS #.
def zero_tactile_sensors()