demo_r.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": 10, "rh_THJ2": 20, "rh_THJ3": 5, "rh_THJ4": 35, "rh_THJ5": 25}
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": -20, "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": -20, "rh_WRJ2": -14}
168 # southeast wrist
169 se_wr = {"rh_WRJ1": -20, "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 # grasp for shaking hands step 1
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}
200 # grasp for shaking hands step 2
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}
206 # store step 1 PST
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}
213 # store step 2 PST
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}
220 # store step 1 Bio_Tac
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}
227 # store step 2 Bio_Tac
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}
234 # store step 3
235 store_3 = {"rh_THJ1": 0, "rh_THJ2": 0, "rh_THJ3": 0, "rh_THJ4": 65, "rh_THJ5": 0}
236 # business card pre-zero position
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}
242 # business card zero position
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}
245 # business card position 1
246 bc_1 = {"rh_FFJ1": 47, "rh_FFJ2": 90, "rh_FFJ3": 7}
247 # business card position 2
248 bc_2 = {"rh_FFJ1": 47, "rh_FFJ2": 90, "rh_FFJ3": 58}
249 # business card position 3
250 bc_3 = {"rh_FFJ1": 0, "rh_FFJ2": 60, "rh_FFJ3": 58}
251 # business card position 4
252 bc_4 = {"rh_FFJ1": 90, "rh_FFJ2": 90, "rh_FFJ3": 58, "rh_FFJ4": 15}
253 # business card position 5
254 bc_5 = {"rh_FFJ1": 90, "rh_FFJ2": 90, "rh_FFJ3": 0}
255 # business card position 6
256 bc_6 = {"rh_FFJ1": 0, "rh_FFJ2": 0, "rh_FFJ3": 0, "rh_FFJ4": 10}
257 # business card position 7
258 bc_7 = {"rh_FFJ1": 47, "rh_FFJ2": 90, "rh_FFJ3": 15, "rh_FFJ4": 0}
259 # business card position 8
260 bc_8 = {"rh_FFJ1": 47, "rh_FFJ2": 90, "rh_FFJ3": 58}
261 # business card position 9
262 bc_9 = {"rh_FFJ1": 0, "rh_FFJ2": 71, "rh_FFJ3": 58}
263 # business card position 10
264 bc_10 = {"rh_MFJ3": 64, "rh_FFJ4": 20}
265 # business card position 11
266 bc_11 = {"rh_FFJ1": 0, "rh_FFJ2": 81, "rh_FFJ3": 50, "rh_FFJ4": 20,
267  "rh_THJ4": 57, "rh_THJ5": 20}
268 # business card position 12
269 bc_12 = {"rh_MFJ1": 0, "rh_MFJ2": 20, "rh_MFJ3": 10, "rh_MFJ4": 0}
270 
271 
272 ########################
273 # FUNCTION DEFINITIONS #
274 ########################
275 
277  # Start secuence 1
278  rospy.sleep(1)
279  hand_commander.move_to_joint_value_target_unsafe(store_3, 1.0, False, angle_degrees=True)
280  rospy.sleep(1)
281  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.2, False, angle_degrees=True)
282  rospy.sleep(1.1)
283  hand_commander.move_to_joint_value_target_unsafe(flex_ff, 1.0, False, angle_degrees=True)
284  rospy.sleep(1.3)
285  hand_commander.move_to_joint_value_target_unsafe(ext_ff, 1.0, False, angle_degrees=True)
286  rospy.sleep(1.1)
287  hand_commander.move_to_joint_value_target_unsafe(flex_mf, 1.0, False, angle_degrees=True)
288  rospy.sleep(1.3)
289  hand_commander.move_to_joint_value_target_unsafe(ext_mf, 1.0, False, angle_degrees=True)
290  rospy.sleep(1.1)
291  hand_commander.move_to_joint_value_target_unsafe(flex_rf, 1.0, False, angle_degrees=True)
292  rospy.sleep(1.3)
293  hand_commander.move_to_joint_value_target_unsafe(ext_rf, 1.0, False, angle_degrees=True)
294  rospy.sleep(1.1)
295  hand_commander.move_to_joint_value_target_unsafe(flex_lf, 1.0, False, angle_degrees=True)
296  rospy.sleep(1.3)
297  hand_commander.move_to_joint_value_target_unsafe(ext_lf, 1.0, False, angle_degrees=True)
298  rospy.sleep(1.1)
299  hand_commander.move_to_joint_value_target_unsafe(flex_th_1, 0.7, False, angle_degrees=True)
300  rospy.sleep(1)
301  hand_commander.move_to_joint_value_target_unsafe(flex_th_2, 0.7, False, angle_degrees=True)
302  rospy.sleep(1)
303  hand_commander.move_to_joint_value_target_unsafe(ext_th_2, 0.5, False, angle_degrees=True)
304  rospy.sleep(0.5)
305  hand_commander.move_to_joint_value_target_unsafe(l_ext_lf, 0.5, False, angle_degrees=True)
306  rospy.sleep(0.5)
307  hand_commander.move_to_joint_value_target_unsafe(l_ext_rf, 0.5, False, angle_degrees=True)
308  rospy.sleep(0.5)
309  hand_commander.move_to_joint_value_target_unsafe(l_ext_mf, 0.5, False, angle_degrees=True)
310  rospy.sleep(0.5)
311  hand_commander.move_to_joint_value_target_unsafe(l_ext_ff, 0.5, False, angle_degrees=True)
312  rospy.sleep(0.5)
313  hand_commander.move_to_joint_value_target_unsafe(l_int_all, 0.5, False, angle_degrees=True)
314  rospy.sleep(0.5)
315  hand_commander.move_to_joint_value_target_unsafe(l_ext_all, 0.5, False, angle_degrees=True)
316  rospy.sleep(0.5)
317  hand_commander.move_to_joint_value_target_unsafe(l_int_ff, 0.5, False, angle_degrees=True)
318  rospy.sleep(0.5)
319  hand_commander.move_to_joint_value_target_unsafe(l_int_mf, 0.5, False, angle_degrees=True)
320  rospy.sleep(0.5)
321  hand_commander.move_to_joint_value_target_unsafe(l_int_rf, 0.5, False, angle_degrees=True)
322  rospy.sleep(0.5)
323  hand_commander.move_to_joint_value_target_unsafe(l_int_lf, 0.5, False, angle_degrees=True)
324  rospy.sleep(0.5)
325  hand_commander.move_to_joint_value_target_unsafe(l_zero_all, 0.5, False, angle_degrees=True)
326  rospy.sleep(0.5)
327  hand_commander.move_to_joint_value_target_unsafe(l_spock, 0.5, False, angle_degrees=True)
328  rospy.sleep(0.5)
329  hand_commander.move_to_joint_value_target_unsafe(l_zero_all, 0.5, False, angle_degrees=True)
330  rospy.sleep(0.5)
331  hand_commander.move_to_joint_value_target_unsafe(pre_ff_ok, 1.0, False, angle_degrees=True)
332  rospy.sleep(1)
333  hand_commander.move_to_joint_value_target_unsafe(ff_ok, 1.0, False, angle_degrees=True)
334  rospy.sleep(2)
335  hand_commander.move_to_joint_value_target_unsafe(ff2mf_ok, 0.8, False, angle_degrees=True)
336  rospy.sleep(1.0)
337  hand_commander.move_to_joint_value_target_unsafe(mf_ok, 1.0, False, angle_degrees=True)
338  rospy.sleep(2)
339  hand_commander.move_to_joint_value_target_unsafe(mf2rf_ok, 0.8, False, angle_degrees=True)
340  rospy.sleep(1.0)
341  hand_commander.move_to_joint_value_target_unsafe(rf_ok, 1.0, False, angle_degrees=True)
342  rospy.sleep(2)
343  hand_commander.move_to_joint_value_target_unsafe(rf2lf_ok, 0.8, False, angle_degrees=True)
344  rospy.sleep(1.0)
345  hand_commander.move_to_joint_value_target_unsafe(lf_ok, 1.0, False, angle_degrees=True)
346  rospy.sleep(2)
347  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0, False, angle_degrees=True)
348  rospy.sleep(1)
349  hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2, False, angle_degrees=True)
350  rospy.sleep(0.2)
351  hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2, False, angle_degrees=True)
352  rospy.sleep(0.2)
353  hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2, False, angle_degrees=True)
354  rospy.sleep(0.2)
355  hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2, False, angle_degrees=True)
356  rospy.sleep(0.2)
357  hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2, False, angle_degrees=True)
358  rospy.sleep(0.2)
359  hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2, False, angle_degrees=True)
360  rospy.sleep(0.2)
361  hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2, False, angle_degrees=True)
362  rospy.sleep(0.2)
363  hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2, False, angle_degrees=True)
364  rospy.sleep(0.2)
365  hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2, False, angle_degrees=True)
366  rospy.sleep(0.2)
367  hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2, False, angle_degrees=True)
368  rospy.sleep(0.2)
369  hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2, False, angle_degrees=True)
370  rospy.sleep(0.2)
371  hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2, False, angle_degrees=True)
372  rospy.sleep(0.2)
373  hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2, False, angle_degrees=True)
374  rospy.sleep(0.2)
375  hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2, False, angle_degrees=True)
376  rospy.sleep(0.2)
377  hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2, False, angle_degrees=True)
378  rospy.sleep(0.2)
379  hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2, False, angle_degrees=True)
380  rospy.sleep(0.2)
381  hand_commander.move_to_joint_value_target_unsafe(flex_ff, 0.2, False, angle_degrees=True)
382  rospy.sleep(0.2)
383  hand_commander.move_to_joint_value_target_unsafe(flex_mf, 0.2, False, angle_degrees=True)
384  rospy.sleep(0.2)
385  hand_commander.move_to_joint_value_target_unsafe(flex_rf, 0.2, False, angle_degrees=True)
386  rospy.sleep(0.2)
387  hand_commander.move_to_joint_value_target_unsafe(flex_lf, 0.2, False, angle_degrees=True)
388  rospy.sleep(0.2)
389  hand_commander.move_to_joint_value_target_unsafe(ext_ff, 0.2, False, angle_degrees=True)
390  rospy.sleep(0.2)
391  hand_commander.move_to_joint_value_target_unsafe(ext_mf, 0.2, False, angle_degrees=True)
392  rospy.sleep(0.2)
393  hand_commander.move_to_joint_value_target_unsafe(ext_rf, 0.2, False, angle_degrees=True)
394  rospy.sleep(0.2)
395  hand_commander.move_to_joint_value_target_unsafe(ext_lf, 0.2, False, angle_degrees=True)
396  rospy.sleep(0.2)
397  hand_commander.move_to_joint_value_target_unsafe(pre_ff_ok, 1.0, False, angle_degrees=True)
398  rospy.sleep(1)
399  hand_commander.move_to_joint_value_target_unsafe(ff_ok, 2.0, False, angle_degrees=True)
400  rospy.sleep(2)
401  hand_commander.move_to_joint_value_target_unsafe(ne_wr, 1.4, False, angle_degrees=True)
402  rospy.sleep(1.4)
403  hand_commander.move_to_joint_value_target_unsafe(nw_wr, 1.4, False, angle_degrees=True)
404  rospy.sleep(1.4)
405  hand_commander.move_to_joint_value_target_unsafe(sw_wr, 1.4, False, angle_degrees=True)
406  rospy.sleep(1.4)
407  hand_commander.move_to_joint_value_target_unsafe(se_wr, 1.4, False, angle_degrees=True)
408  rospy.sleep(1.4)
409  hand_commander.move_to_joint_value_target_unsafe(ne_wr, 0.7, False, angle_degrees=True)
410  rospy.sleep(0.7)
411  hand_commander.move_to_joint_value_target_unsafe(nw_wr, 0.7, False, angle_degrees=True)
412  rospy.sleep(0.7)
413  hand_commander.move_to_joint_value_target_unsafe(sw_wr, 0.7, False, angle_degrees=True)
414  rospy.sleep(0.7)
415  hand_commander.move_to_joint_value_target_unsafe(se_wr, 0.7, False, angle_degrees=True)
416  rospy.sleep(0.7)
417  hand_commander.move_to_joint_value_target_unsafe(zero_wr, 0.4, False, angle_degrees=True)
418  rospy.sleep(0.4)
419  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5, False, angle_degrees=True)
420  rospy.sleep(1.5)
421  return
422 
423 
425  # Start the secuence 2
426  rospy.sleep(0.5)
427  # Initialize wake time
428  wake_time = time.time()
429 
430  while True:
431  # Check if any of the tactile senors have been triggered
432  # If so, send the Hand to its start position
434  touched = None
435  for finger in ["FF", "MF", "RF", "LF", "TH"]:
436  if tactile_values[finger] > force_zero[finger]:
437  touched = 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)
441  rospy.sleep(2.0)
442  if touched == "TH":
443  break
444 
445  # If the tactile sensors have not been triggered and the Hand
446  # is not in the middle of a movement, generate a random position
447  # and interpolation time
448  else:
449  if time.time() > wake_time:
450  for i in rand_pos:
451  rand_pos[i] = random.randrange(min_range[i], max_range[i])
452 
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()
456  # rand_pos['interpolation_time'] = max_range['interpolation_time'] * random.random()
457 
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
460  return
461 
462 
464  # Start the secuence 3
465  rospy.sleep(0.5)
466  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0, False, angle_degrees=True)
467  rospy.sleep(1)
468  hand_commander.move_to_joint_value_target_unsafe(bc_pre_zero, 2.0, False, angle_degrees=True)
469  rospy.sleep(2)
470  hand_commander.move_to_joint_value_target_unsafe(bc_zero, 1.0, False, angle_degrees=True)
471  rospy.sleep(4)
472  hand_commander.move_to_joint_value_target_unsafe(bc_1, 1.0, False, angle_degrees=True)
473  rospy.sleep(1)
474  hand_commander.move_to_joint_value_target_unsafe(bc_2, 1.0, False, angle_degrees=True)
475  rospy.sleep(1)
476  hand_commander.move_to_joint_value_target_unsafe(bc_3, 1.0, False, angle_degrees=True)
477  rospy.sleep(1)
478  hand_commander.move_to_joint_value_target_unsafe(bc_4, 1.0, False, angle_degrees=True)
479  rospy.sleep(1)
480  hand_commander.move_to_joint_value_target_unsafe(bc_5, 1.0, False, angle_degrees=True)
481  rospy.sleep(1)
482  hand_commander.move_to_joint_value_target_unsafe(bc_6, 1.0, False, angle_degrees=True)
483  rospy.sleep(1)
484  hand_commander.move_to_joint_value_target_unsafe(bc_7, 1.0, False, angle_degrees=True)
485  rospy.sleep(1)
486  hand_commander.move_to_joint_value_target_unsafe(bc_8, 1.0, False, angle_degrees=True)
487  rospy.sleep(1)
488  hand_commander.move_to_joint_value_target_unsafe(bc_9, 1.0, False, angle_degrees=True)
489  rospy.sleep(1)
490  hand_commander.move_to_joint_value_target_unsafe(bc_11, 1.0, False, angle_degrees=True)
491  rospy.sleep(1)
492  hand_commander.move_to_joint_value_target_unsafe(bc_12, 3.0, False, angle_degrees=True)
493  rospy.sleep(4)
494  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5, False, angle_degrees=True)
495  rospy.sleep(1.5)
496 
497  return
498 
499 
501  # Start the secuence 4
502  # Trigger flag array
503  trigger = [0, 0, 0, 0, 0]
504 
505  # Move Hand to zero position
506  hand_commander.move_to_joint_value_target_unsafe(start_pos, 2.0, False, angle_degrees=True)
507  rospy.sleep(2.0)
508 
509  # Move Hand to starting position
510  hand_commander.move_to_joint_value_target_unsafe(pregrasp_pos, 2.0, False, angle_degrees=True)
511  rospy.sleep(2.0)
512 
513  # Move Hand to close position
514  hand_commander.move_to_joint_value_target_unsafe(grasp_pos, 11.0, False, angle_degrees=True)
515  offset1 = 3
516 
517  # Initialize end time
518  end_time = time.time() + 11
519 
520  while True:
521  # Check the state of the tactile senors
523 
524  # Record current joint positions
525  hand_pos = hand_commander.get_joints_position()
526 
527  # If any tacticle sensor has been triggered, send
528  # the corresponding digit to its current 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'
533  trigger[0] = 1
534 
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'
539  trigger[1] = 1
540 
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'
545  trigger[2] = 1
546 
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'
551  trigger[3] = 1
552 
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'
557  trigger[4] = 1
558 
559  if (trigger[0] == 1 and trigger[1] == 1 and trigger[2] == 1 and trigger[3] == 1 and trigger[4] == 1):
560  break
561 
562  if time.time() > end_time:
563  break
564 
565  # Send all joints to current position to compensate
566  # for minor offsets created in the previous loop
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)
569  rospy.sleep(2.0)
570 
571  # Generate new values to squeeze object slightly
572  offset2 = 3
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})
579 
580  # Squeeze object gently
581  hand_commander.move_to_joint_value_target_unsafe(squeeze, 0.5, False, angle_degrees=True)
582  rospy.sleep(0.5)
583  hand_commander.move_to_joint_value_target_unsafe(hand_pos, 0.5, False, angle_degrees=True)
584  rospy.sleep(0.5)
585  hand_commander.move_to_joint_value_target_unsafe(squeeze, 0.5, False, angle_degrees=True)
586  rospy.sleep(0.5)
587  hand_commander.move_to_joint_value_target_unsafe(hand_pos, 2.0, False, angle_degrees=True)
588  rospy.sleep(2.0)
589  hand_commander.move_to_joint_value_target_unsafe(pregrasp_pos, 2.0, False, angle_degrees=True)
590  rospy.sleep(2.0)
591  hand_commander.move_to_joint_value_target_unsafe(start_pos, 2.0, False, angle_degrees=True)
592  rospy.sleep(2.0)
593 
594  return
595 
596 
598  # Start the secuence 5
599  rospy.sleep(0.5)
600  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.5, False, angle_degrees=True)
601  rospy.sleep(1.5)
602  return
603 
604 
606  # Move Hand to zero position
607  rospy.sleep(0.5)
608  hand_commander.move_to_joint_value_target_unsafe(start_pos, 1.0, False, angle_degrees=True)
609 
610  print '\n\nPLEASE ENSURE THAT THE TACTILE SENSORS ARE NOT PRESSED\n'
611  # raw_input ('Press ENTER to continue')
612  rospy.sleep(1.0)
613 
614  for x in xrange(1, 1000):
615  # Read current state of tactile sensors to zero them
617 
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']
628 
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
634 
635  print 'Force Zero', force_zero
636 
637  rospy.loginfo("\n\nOK, ready for the demo")
638 
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"
645 
646  return
647 
648 
650  # Read tactile type
651  tactile_type = hand_commander.get_tactile_type()
652  # Read current state of tactile sensors
653  tactile_state = hand_commander.get_tactile_state()
654 
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
661 
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]
668 
669  elif tactile_type is None:
670  print "You don't have tactile sensors. Talk to your Shadow representative to purchase some"
671 
672  return
673 
674 
675 ########
676 # MAIN #
677 ########
678 
679 # Zero values in dictionary for tactile sensors (initialized at 0)
680 force_zero = {"FF": 0, "MF": 0, "RF": 0, "LF": 0, "TH": 0}
681 # Initialize values for current tactile values
682 tactile_values = {"FF": 0, "MF": 0, "RF": 0, "LF": 0, "TH": 0}
683 # Zero tactile sensors
685 
686 while not rospy.is_shutdown():
687  # Check the state of the tactile senors
688  touched = None
690  for finger in ["FF", "MF", "RF", "LF", "TH"]:
691  if tactile_values[finger] > force_zero[finger]:
692  touched = finger
693  # If the tactile is touched, trigger the corresponding function
694  if touched is not None:
695  print "{} contact".format(touched)
696  if touched == "FF":
697  secuence_ff()
698  elif touched == "MF":
699  secuence_mf()
700  elif touched == "RF":
701  secuence_rf()
702  elif touched == "LF":
703  secuence_lf()
704  elif touched == "TH":
705  secuence_th()
706  print "{} demo completed".format(touched)
def read_tactile_values()
Definition: demo_r.py:649
def secuence_ff()
FUNCTION DEFINITIONS #.
Definition: demo_r.py:276
def secuence_rf()
Definition: demo_r.py:463
def zero_tactile_sensors()
Definition: demo_r.py:605
def secuence_th()
Definition: demo_r.py:597
def secuence_mf()
Definition: demo_r.py:424
def secuence_lf()
Definition: demo_r.py:500


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