burn_in_rh.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2019 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation, either version 2 of the License, or (at your option)
8 # any later version.
9 #
10 # This program is distributed in the hope that it will be useful, but WITHOUT
11 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
12 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 # more details.
14 #
15 # You should have received a copy of the GNU General Public License along
16 # with this program. If not, see <http://www.gnu.org/licenses/>.
17 #
18 
19 import rospy
20 import random
21 import time
22 from sr_robot_commander.sr_hand_commander import SrHandCommander
23 
24 rospy.init_node("right_hand_demo", anonymous=True)
25 
26 hand_commander = SrHandCommander(name="right_hand")
27 
28 ##########
29 # RANGES #
30 ##########
31 
32 inter_time_max = 4.0
33 
34 # Minimum alllowed range for the joints in this particular script
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}
41 
42 # Maximum alllowed range for the joints in this particular script
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}
49 
50 ####################
51 # POSE DEFINITIONS #
52 ####################
53 
54 # starting position for the hand
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}
61 # Start position for the Hand
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}
68 # Close position for the Hand
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}
75 # Random position for the Hand (initialied at 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}
82 # flex first finger
83 flex_ff = {"rh_FFJ1": 90, "rh_FFJ2": 90, "rh_FFJ3": 90, "rh_FFJ4": 0}
84 # extend first finger
85 ext_ff = {"rh_FFJ1": 0, "rh_FFJ2": 0, "rh_FFJ3": 0, "rh_FFJ4": 0}
86 # flex middle finger
87 flex_mf = {"rh_MFJ1": 90, "rh_MFJ2": 90, "rh_MFJ3": 90, "rh_MFJ4": 0}
88 # extend middle finger
89 ext_mf = {"rh_MFJ1": 0, "rh_MFJ2": 0, "rh_MFJ3": 0, "rh_MFJ4": 0}
90 # flex ring finger
91 flex_rf = {"rh_RFJ1": 90, "rh_RFJ2": 90, "rh_RFJ3": 90, "rh_RFJ4": 0}
92 # extend ring finger
93 ext_rf = {"rh_RFJ1": 0, "rh_RFJ2": 0, "rh_RFJ3": 0, "rh_RFJ4": 0}
94 # flex little finger
95 flex_lf = {"rh_LFJ1": 90, "rh_LFJ2": 90, "rh_LFJ3": 90, "rh_LFJ4": 0}
96 # extend middle finger
97 ext_lf = {"rh_LFJ1": 0, "rh_LFJ2": 0, "rh_LFJ3": 0, "rh_LFJ4": 0}
98 # flex thumb step 1
99 flex_th_1 = {"rh_THJ1": 0, "rh_THJ2": 0, "rh_THJ3": 0, "rh_THJ4": 70, "rh_THJ5": 0}
100 # flex thumb step 2
101 flex_th_2 = {"rh_THJ1": 35, "rh_THJ2": 38, "rh_THJ3": 10, "rh_THJ4": 70, "rh_THJ5": 58}
102 # extend thumb step 1
103 ext_th_1 = {"rh_THJ1": 90, "rh_THJ2": -40, "rh_THJ3": -10, "rh_THJ4": 35, "rh_THJ5": -60}
104 # extend thumb step 2
105 ext_th_2 = {"rh_THJ1": 0, "rh_THJ2": 0, "rh_THJ3": 0, "rh_THJ4": 0, "rh_THJ5": 0}
106 # zero thumb
107 zero_th = {"rh_THJ1": 0, "rh_THJ2": 0, "rh_THJ3": 0, "rh_THJ4": 0, "rh_THJ5": 0}
108 # Pre O.K. with first finger
109 pre_ff_ok = {"rh_THJ4": 70}
110 # O.K. with first finger
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}
116 # O.K. transition from first finger to middle finger
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}
122 # O.K. with middle finger
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}
128 # O.K. transition from middle finger to ring finger
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}
134 # O.K. with ring finger
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}
140 # O.K. transition from ring finger to little finger
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}
146 # O.K. with little finger
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}
152 # zero wrist
153 zero_wr = {"rh_WRJ1": 0, "rh_WRJ2": 0}
154 # north wrist
155 n_wr = {"rh_WRJ1": 15, "rh_WRJ2": 0}
156 # south wrist
157 s_wr = {"rh_WRJ1": -30, "rh_WRJ2": 0}
158 # east wrist
159 e_wr = {"rh_WRJ1": 0, "rh_WRJ2": 8}
160 # west wrist
161 w_wr = {"rh_WRJ1": 0, "rh_WRJ2": -14}
162 # northeast wrist
163 ne_wr = {"rh_WRJ1": 15, "rh_WRJ2": 8}
164 # northwest wrist
165 nw_wr = {"rh_WRJ1": 15, "rh_WRJ2": -14}
166 # southweast wrist
167 sw_wr = {"rh_WRJ1": -30, "rh_WRJ2": -14}
168 # southeast wrist
169 se_wr = {"rh_WRJ1": -30, "rh_WRJ2": 8}
170 # lateral lf ext side
171 l_ext_lf = {"rh_LFJ4": -15}
172 # lateral rf ext side
173 l_ext_rf = {"rh_RFJ4": -15}
174 # lateral mf ext side
175 l_ext_mf = {"rh_MFJ4": 15}
176 # lateral ff ext side
177 l_ext_ff = {"rh_FFJ4": 15}
178 # lateral all int side
179 l_int_all = {"rh_FFJ4": -15, "rh_MFJ4": -15, "rh_RFJ4": 15, "rh_LFJ4": 15}
180 # lateral all ext side
181 l_ext_all = {"rh_FFJ4": 15, "rh_MFJ4": 15, "rh_RFJ4": -15, "rh_LFJ4": -15}
182 # lateral ff int side
183 l_int_ff = {"rh_FFJ4": -15}
184 # lateral mf int side
185 l_int_mf = {"rh_MFJ4": -15}
186 # lateral rf int side
187 l_int_rf = {"rh_RFJ4": 15}
188 # lateral lf int side
189 l_int_lf = {"rh_LFJ4": 15}
190 # all zero
191 l_zero_all = {"rh_FFJ4": 0, "rh_MFJ4": 0, "rh_RFJ4": 0, "rh_LFJ4": 0}
192 # spock
193 l_spock = {"rh_FFJ4": -20, "rh_MFJ4": -20, "rh_RFJ4": -20, "rh_LFJ4": -20}
194 # store step 1 PST
195 store_1_PST = {"rh_THJ1": 0, "rh_THJ2": 0, "rh_THJ3": 0, "rh_THJ4": 60, "rh_THJ5": 0,
196  "rh_FFJ1": 90, "rh_FFJ2": 90, "rh_FFJ3": 90, "rh_FFJ4": 0,
197  "rh_MFJ1": 90, "rh_MFJ2": 90, "rh_MFJ3": 90, "rh_MFJ4": 0,
198  "rh_RFJ1": 90, "rh_RFJ2": 90, "rh_RFJ3": 90, "rh_RFJ4": 0,
199  "rh_LFJ1": 90, "rh_LFJ2": 90, "rh_LFJ3": 90, "rh_LFJ4": 0, "rh_LFJ5": 0,
200  "rh_WRJ1": 0, "rh_WRJ2": 0}
201 # store step 2 PST
202 store_2_PST = {"rh_THJ1": 50, "rh_THJ2": 12, "rh_THJ3": 0, "rh_THJ4": 60, "rh_THJ5": 27,
203  "rh_FFJ1": 90, "rh_FFJ2": 90, "rh_FFJ3": 90, "rh_FFJ4": 0,
204  "rh_MFJ1": 90, "rh_MFJ2": 90, "rh_MFJ3": 90, "rh_MFJ4": 0,
205  "rh_RFJ1": 90, "rh_RFJ2": 90, "rh_RFJ3": 90, "rh_RFJ4": 0,
206  "rh_LFJ1": 90, "rh_LFJ2": 90, "rh_LFJ3": 90, "rh_LFJ4": 0, "rh_LFJ5": 0,
207  "rh_WRJ1": 0, "rh_WRJ2": 0}
208 # store step 1 Bio_Tac
209 store_1_BioTac = {"rh_THJ1": 0, "rh_THJ2": 0, "rh_THJ3": 0, "rh_THJ4": 30, "rh_THJ5": 0,
210  "rh_FFJ1": 90, "rh_FFJ2": 90, "rh_FFJ3": 90, "rh_FFJ4": 0,
211  "rh_MFJ1": 90, "rh_MFJ2": 90, "rh_MFJ3": 90, "rh_MFJ4": 0,
212  "rh_RFJ1": 90, "rh_RFJ2": 90, "rh_RFJ3": 90, "rh_RFJ4": 0,
213  "rh_LFJ1": 90, "rh_LFJ2": 90, "rh_LFJ3": 90, "rh_LFJ4": 0, "rh_LFJ5": 0,
214  "rh_WRJ1": 0, "rh_WRJ2": 0}
215 # store step 2 Bio_Tac
216 store_2_BioTac = {"rh_THJ1": 20, "rh_THJ2": 36, "rh_THJ3": 0, "rh_THJ4": 30, "rh_THJ5": -3,
217  "rh_FFJ1": 90, "rh_FFJ2": 90, "rh_FFJ3": 90, "rh_FFJ4": 0,
218  "rh_MFJ1": 90, "rh_MFJ2": 90, "rh_MFJ3": 90, "rh_MFJ4": 0,
219  "rh_RFJ1": 90, "rh_RFJ2": 90, "rh_RFJ3": 90, "rh_RFJ4": 0,
220  "rh_LFJ1": 90, "rh_LFJ2": 90, "rh_LFJ3": 90, "rh_LFJ4": 0, "rh_LFJ5": 0,
221  "rh_WRJ1": 0, "rh_WRJ2": 0}
222 # store step 3
223 store_3 = {"rh_THJ1": 0, "rh_THJ2": 0, "rh_THJ3": 0, "rh_THJ4": 65, "rh_THJ5": 0}
224 
225 
226 for x in range(0, 100):
227  print "We're on iteration number %d" % (x)
228  rospy.sleep(1)
229  hand_commander.move_to_joint_value_target_unsafe(store_3, 1.1, False, angle_degrees=True)
230  rospy.sleep(1.1)
231  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.1, False, angle_degrees=True)
232  rospy.sleep(1.1)
233  hand_commander.move_to_joint_value_target_unsafe(flex_ff, 1.0, False, angle_degrees=True)
234  rospy.sleep(1.1)
235  hand_commander.move_to_joint_value_target_unsafe(ext_ff, 1.0, False, angle_degrees=True)
236  rospy.sleep(1.1)
237  hand_commander.move_to_joint_value_target_unsafe(flex_mf, 1.0, False, angle_degrees=True)
238  rospy.sleep(1.1)
239  hand_commander.move_to_joint_value_target_unsafe(ext_mf, 1.0, False, angle_degrees=True)
240  rospy.sleep(1.1)
241  hand_commander.move_to_joint_value_target_unsafe(flex_rf, 1.0, False, angle_degrees=True)
242  rospy.sleep(1.1)
243  hand_commander.move_to_joint_value_target_unsafe(ext_rf, 1.0, False, angle_degrees=True)
244  rospy.sleep(1.1)
245  hand_commander.move_to_joint_value_target_unsafe(flex_lf, 1.0, False, angle_degrees=True)
246  rospy.sleep(1.1)
247  hand_commander.move_to_joint_value_target_unsafe(ext_lf, 1.0, False, angle_degrees=True)
248  rospy.sleep(1.1)
249  hand_commander.move_to_joint_value_target_unsafe(flex_th_1, 0.7, False, angle_degrees=True)
250  rospy.sleep(1)
251  hand_commander.move_to_joint_value_target_unsafe(flex_th_2, 0.7, False, angle_degrees=True)
252  rospy.sleep(1)
253  hand_commander.move_to_joint_value_target_unsafe(ext_th_1, 1.5, False, angle_degrees=True)
254  rospy.sleep(1.5)
255  hand_commander.move_to_joint_value_target_unsafe(ext_th_2, 0.5, False, angle_degrees=True)
256  rospy.sleep(0.5)
257  hand_commander.move_to_joint_value_target_unsafe(l_ext_lf, 0.5, False, angle_degrees=True)
258  rospy.sleep(0.5)
259  hand_commander.move_to_joint_value_target_unsafe(l_ext_rf, 0.5, False, angle_degrees=True)
260  rospy.sleep(0.5)
261  hand_commander.move_to_joint_value_target_unsafe(l_ext_mf, 0.5, False, angle_degrees=True)
262  rospy.sleep(0.5)
263  hand_commander.move_to_joint_value_target_unsafe(l_ext_ff, 0.5, False, angle_degrees=True)
264  rospy.sleep(0.5)
265  hand_commander.move_to_joint_value_target_unsafe(l_int_all, 0.5, False, angle_degrees=True)
266  rospy.sleep(0.5)
267  hand_commander.move_to_joint_value_target_unsafe(l_ext_all, 0.5, False, angle_degrees=True)
268  rospy.sleep(0.5)
269  hand_commander.move_to_joint_value_target_unsafe(l_int_ff, 0.5, False, angle_degrees=True)
270  rospy.sleep(0.5)
271  hand_commander.move_to_joint_value_target_unsafe(l_int_mf, 0.5, False, angle_degrees=True)
272  rospy.sleep(0.5)
273  hand_commander.move_to_joint_value_target_unsafe(l_int_rf, 0.5, False, angle_degrees=True)
274  rospy.sleep(0.5)
275  hand_commander.move_to_joint_value_target_unsafe(l_int_lf, 0.5, False, angle_degrees=True)
276  rospy.sleep(0.5)
277  hand_commander.move_to_joint_value_target_unsafe(l_zero_all, 0.5, False, angle_degrees=True)
278  rospy.sleep(0.5)
279  hand_commander.move_to_joint_value_target_unsafe(l_spock, 0.5, False, angle_degrees=True)
280  rospy.sleep(0.5)
281  hand_commander.move_to_joint_value_target_unsafe(l_zero_all, 0.5, False, angle_degrees=True)
282  rospy.sleep(0.5)
283  hand_commander.move_to_joint_value_target_unsafe(pre_ff_ok, 1.0, False, angle_degrees=True)
284  rospy.sleep(1)
285  hand_commander.move_to_joint_value_target_unsafe(ff_ok, 0.7, False, angle_degrees=True)
286  rospy.sleep(0.9)
287  hand_commander.move_to_joint_value_target_unsafe(ff2mf_ok, 0.5, False, angle_degrees=True)
288  rospy.sleep(0.4)
289  hand_commander.move_to_joint_value_target_unsafe(mf_ok, 0.7, False, angle_degrees=True)
290  rospy.sleep(0.9)
291  hand_commander.move_to_joint_value_target_unsafe(mf2rf_ok, 0.5, False, angle_degrees=True)
292  rospy.sleep(0.4)
293  hand_commander.move_to_joint_value_target_unsafe(rf_ok, 0.7, False, angle_degrees=True)
294  rospy.sleep(0.9)
295  hand_commander.move_to_joint_value_target_unsafe(rf2lf_ok, 0.5, False, angle_degrees=True)
296  rospy.sleep(0.4)
297  hand_commander.move_to_joint_value_target_unsafe(lf_ok, 0.7, False, angle_degrees=True)
298  rospy.sleep(0.9)
299  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0, False, angle_degrees=True)
300  rospy.sleep(1)
301  hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2, False, angle_degrees=True)
302  rospy.sleep(0.2)
303  hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2, False, angle_degrees=True)
304  rospy.sleep(0.2)
305  hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2, False, angle_degrees=True)
306  rospy.sleep(0.2)
307  hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2, False, angle_degrees=True)
308  rospy.sleep(0.2)
309  hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2, False, angle_degrees=True)
310  rospy.sleep(0.2)
311  hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2, False, angle_degrees=True)
312  rospy.sleep(0.2)
313  hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2, False, angle_degrees=True)
314  rospy.sleep(0.2)
315  hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2, False, angle_degrees=True)
316  rospy.sleep(0.2)
317  hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2, False, angle_degrees=True)
318  rospy.sleep(0.2)
319  hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2, False, angle_degrees=True)
320  rospy.sleep(0.2)
321  hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2, False, angle_degrees=True)
322  rospy.sleep(0.2)
323  hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2, False, angle_degrees=True)
324  rospy.sleep(0.2)
325  hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2, False, angle_degrees=True)
326  rospy.sleep(0.2)
327  hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2, False, angle_degrees=True)
328  rospy.sleep(0.2)
329  hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2, False, angle_degrees=True)
330  rospy.sleep(0.2)
331  hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2, False, angle_degrees=True)
332  rospy.sleep(0.2)
333  hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2, False, angle_degrees=True)
334  rospy.sleep(0.2)
335  hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2, False, angle_degrees=True)
336  rospy.sleep(0.2)
337  hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2, False, angle_degrees=True)
338  rospy.sleep(0.2)
339  hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2, False, angle_degrees=True)
340  rospy.sleep(0.2)
341  hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2, False, angle_degrees=True)
342  rospy.sleep(0.2)
343  hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2, False, angle_degrees=True)
344  rospy.sleep(0.2)
345  hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2, False, angle_degrees=True)
346  rospy.sleep(0.2)
347  hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2, False, angle_degrees=True)
348  rospy.sleep(0.2)
349  hand_commander.move_to_joint_value_target_unsafe(pre_ff_ok, 1.0, False, angle_degrees=True)
350  rospy.sleep(1)
351  hand_commander.move_to_joint_value_target_unsafe(ff_ok, 1.3, False, angle_degrees=True)
352  rospy.sleep(1.3)
353  hand_commander.move_to_joint_value_target_unsafe(ne_wr, 1.1, False, angle_degrees=True)
354  rospy.sleep(1.1)
355  hand_commander.move_to_joint_value_target_unsafe(nw_wr, 1.1, False, angle_degrees=True)
356  rospy.sleep(1.1)
357  hand_commander.move_to_joint_value_target_unsafe(sw_wr, 1.1, False, angle_degrees=True)
358  rospy.sleep(1.1)
359  hand_commander.move_to_joint_value_target_unsafe(se_wr, 1.1, False, angle_degrees=True)
360  rospy.sleep(1.1)
361  hand_commander.move_to_joint_value_target_unsafe(ne_wr, 0.7, False, angle_degrees=True)
362  rospy.sleep(0.7)
363  hand_commander.move_to_joint_value_target_unsafe(nw_wr, 0.7, False, angle_degrees=True)
364  rospy.sleep(0.7)
365  hand_commander.move_to_joint_value_target_unsafe(sw_wr, 0.7, False, angle_degrees=True)
366  rospy.sleep(0.7)
367  hand_commander.move_to_joint_value_target_unsafe(se_wr, 0.7, False, angle_degrees=True)
368  rospy.sleep(0.7)
369  hand_commander.move_to_joint_value_target_unsafe(zero_wr, 0.4, False, angle_degrees=True)
370  rospy.sleep(0.4)
371  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5, False, angle_degrees=True)
372  rospy.sleep(1.5)
373 
374 
375 
376 


sr_ethercat_hand_config
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Wed Oct 14 2020 03:24:13