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")
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": 90,
"lh_THJ2": -40,
"lh_THJ3": -10,
"lh_THJ4": 35,
"lh_THJ5": -60}
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": -30,
"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": -30,
"lh_WRJ2": -14}
169 se_wr = {
"lh_WRJ1": -30,
"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 store_1_PST = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 60,
"lh_THJ5": 0,
196 "lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
197 "lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
198 "lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
199 "lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
200 "lh_WRJ1": 0,
"lh_WRJ2": 0}
202 store_2_PST = {
"lh_THJ1": 50,
"lh_THJ2": 12,
"lh_THJ3": 0,
"lh_THJ4": 60,
"lh_THJ5": 27,
203 "lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
204 "lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
205 "lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
206 "lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
207 "lh_WRJ1": 0,
"lh_WRJ2": 0}
209 store_1_BioTac = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 30,
"lh_THJ5": 0,
210 "lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
211 "lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
212 "lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
213 "lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
214 "lh_WRJ1": 0,
"lh_WRJ2": 0}
216 store_2_BioTac = {
"lh_THJ1": 20,
"lh_THJ2": 36,
"lh_THJ3": 0,
"lh_THJ4": 30,
"lh_THJ5": -3,
217 "lh_FFJ1": 90,
"lh_FFJ2": 90,
"lh_FFJ3": 90,
"lh_FFJ4": 0,
218 "lh_MFJ1": 90,
"lh_MFJ2": 90,
"lh_MFJ3": 90,
"lh_MFJ4": 0,
219 "lh_RFJ1": 90,
"lh_RFJ2": 90,
"lh_RFJ3": 90,
"lh_RFJ4": 0,
220 "lh_LFJ1": 90,
"lh_LFJ2": 90,
"lh_LFJ3": 90,
"lh_LFJ4": 0,
"lh_LFJ5": 0,
221 "lh_WRJ1": 0,
"lh_WRJ2": 0}
223 store_3 = {
"lh_THJ1": 0,
"lh_THJ2": 0,
"lh_THJ3": 0,
"lh_THJ4": 65,
"lh_THJ5": 0}
226 for x
in range(0, 100):
227 print "We're on iteration number %d" % (x)
229 hand_commander.move_to_joint_value_target_unsafe(store_3, 1.1,
False, angle_degrees=
True)
231 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.1,
False, angle_degrees=
True)
233 hand_commander.move_to_joint_value_target_unsafe(flex_ff, 1.0,
False, angle_degrees=
True)
235 hand_commander.move_to_joint_value_target_unsafe(ext_ff, 1.0,
False, angle_degrees=
True)
237 hand_commander.move_to_joint_value_target_unsafe(flex_mf, 1.0,
False, angle_degrees=
True)
239 hand_commander.move_to_joint_value_target_unsafe(ext_mf, 1.0,
False, angle_degrees=
True)
241 hand_commander.move_to_joint_value_target_unsafe(flex_rf, 1.0,
False, angle_degrees=
True)
243 hand_commander.move_to_joint_value_target_unsafe(ext_rf, 1.0,
False, angle_degrees=
True)
245 hand_commander.move_to_joint_value_target_unsafe(flex_lf, 1.0,
False, angle_degrees=
True)
247 hand_commander.move_to_joint_value_target_unsafe(ext_lf, 1.0,
False, angle_degrees=
True)
249 hand_commander.move_to_joint_value_target_unsafe(flex_th_1, 0.7,
False, angle_degrees=
True)
251 hand_commander.move_to_joint_value_target_unsafe(flex_th_2, 0.7,
False, angle_degrees=
True)
253 hand_commander.move_to_joint_value_target_unsafe(ext_th_1, 1.5,
False, angle_degrees=
True)
255 hand_commander.move_to_joint_value_target_unsafe(ext_th_2, 0.5,
False, angle_degrees=
True)
257 hand_commander.move_to_joint_value_target_unsafe(l_ext_lf, 0.5,
False, angle_degrees=
True)
259 hand_commander.move_to_joint_value_target_unsafe(l_ext_rf, 0.5,
False, angle_degrees=
True)
261 hand_commander.move_to_joint_value_target_unsafe(l_ext_mf, 0.5,
False, angle_degrees=
True)
263 hand_commander.move_to_joint_value_target_unsafe(l_ext_ff, 0.5,
False, angle_degrees=
True)
265 hand_commander.move_to_joint_value_target_unsafe(l_int_all, 0.5,
False, angle_degrees=
True)
267 hand_commander.move_to_joint_value_target_unsafe(l_ext_all, 0.5,
False, angle_degrees=
True)
269 hand_commander.move_to_joint_value_target_unsafe(l_int_ff, 0.5,
False, angle_degrees=
True)
271 hand_commander.move_to_joint_value_target_unsafe(l_int_mf, 0.5,
False, angle_degrees=
True)
273 hand_commander.move_to_joint_value_target_unsafe(l_int_rf, 0.5,
False, angle_degrees=
True)
275 hand_commander.move_to_joint_value_target_unsafe(l_int_lf, 0.5,
False, angle_degrees=
True)
277 hand_commander.move_to_joint_value_target_unsafe(l_zero_all, 0.5,
False, angle_degrees=
True)
279 hand_commander.move_to_joint_value_target_unsafe(l_spock, 0.5,
False, angle_degrees=
True)
281 hand_commander.move_to_joint_value_target_unsafe(l_zero_all, 0.5,
False, angle_degrees=
True)
283 hand_commander.move_to_joint_value_target_unsafe(pre_ff_ok, 1.0,
False, angle_degrees=
True)
285 hand_commander.move_to_joint_value_target_unsafe(ff_ok, 0.7,
False, angle_degrees=
True)
287 hand_commander.move_to_joint_value_target_unsafe(ff2mf_ok, 0.5,
False, angle_degrees=
True)
289 hand_commander.move_to_joint_value_target_unsafe(mf_ok, 0.7,
False, angle_degrees=
True)
291 hand_commander.move_to_joint_value_target_unsafe(mf2rf_ok, 0.5,
False, angle_degrees=
True)
293 hand_commander.move_to_joint_value_target_unsafe(rf_ok, 0.7,
False, angle_degrees=
True)
295 hand_commander.move_to_joint_value_target_unsafe(rf2lf_ok, 0.5,
False, angle_degrees=
True)
297 hand_commander.move_to_joint_value_target_unsafe(lf_ok, 0.7,
False, angle_degrees=
True)
299 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0,
False, angle_degrees=
True)
301 hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2,
False, angle_degrees=
True)
303 hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2,
False, angle_degrees=
True)
305 hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2,
False, angle_degrees=
True)
307 hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2,
False, angle_degrees=
True)
309 hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2,
False, angle_degrees=
True)
311 hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2,
False, angle_degrees=
True)
313 hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2,
False, angle_degrees=
True)
315 hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2,
False, angle_degrees=
True)
317 hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2,
False, angle_degrees=
True)
319 hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2,
False, angle_degrees=
True)
321 hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2,
False, angle_degrees=
True)
323 hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2,
False, angle_degrees=
True)
325 hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2,
False, angle_degrees=
True)
327 hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2,
False, angle_degrees=
True)
329 hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2,
False, angle_degrees=
True)
331 hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2,
False, angle_degrees=
True)
333 hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2,
False, angle_degrees=
True)
335 hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2,
False, angle_degrees=
True)
337 hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2,
False, angle_degrees=
True)
339 hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2,
False, angle_degrees=
True)
341 hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2,
False, angle_degrees=
True)
343 hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2,
False, angle_degrees=
True)
345 hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2,
False, angle_degrees=
True)
347 hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2,
False, angle_degrees=
True)
349 hand_commander.move_to_joint_value_target_unsafe(pre_ff_ok, 1.0,
False, angle_degrees=
True)
351 hand_commander.move_to_joint_value_target_unsafe(ff_ok, 1.3,
False, angle_degrees=
True)
353 hand_commander.move_to_joint_value_target_unsafe(ne_wr, 1.1,
False, angle_degrees=
True)
355 hand_commander.move_to_joint_value_target_unsafe(nw_wr, 1.1,
False, angle_degrees=
True)
357 hand_commander.move_to_joint_value_target_unsafe(sw_wr, 1.1,
False, angle_degrees=
True)
359 hand_commander.move_to_joint_value_target_unsafe(se_wr, 1.1,
False, angle_degrees=
True)
361 hand_commander.move_to_joint_value_target_unsafe(ne_wr, 0.7,
False, angle_degrees=
True)
363 hand_commander.move_to_joint_value_target_unsafe(nw_wr, 0.7,
False, angle_degrees=
True)
365 hand_commander.move_to_joint_value_target_unsafe(sw_wr, 0.7,
False, angle_degrees=
True)
367 hand_commander.move_to_joint_value_target_unsafe(se_wr, 0.7,
False, angle_degrees=
True)
369 hand_commander.move_to_joint_value_target_unsafe(zero_wr, 0.4,
False, angle_degrees=
True)
371 hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5,
False, angle_degrees=
True)