-
Notifications
You must be signed in to change notification settings - Fork 0
/
sim_gripper_node.py
executable file
·426 lines (241 loc) · 13.5 KB
/
sim_gripper_node.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
#!/usr/bin/env python
import rospy
import tf
from visualization_msgs.msg import InteractiveMarkerUpdate
from std_msgs.msg import Bool
#########################################################################################
#########################################################################################
############################### gripper_tf_callback function ############################
#########################################################################################
#########################################################################################
def gripper_tf_callback(data):
a = data.poses
if len(a) == 1:
br = tf.TransformBroadcaster()
br.sendTransform((a[0].pose.position.x, a[0].pose.position.y, a[0].pose.position.z),
(a[0].pose.orientation.x, a[0].pose.orientation.y, a[0].pose.orientation.z,a[0].pose.orientation.w),
rospy.Time.now(),
"marker_ee_link",
"world")
#########################################################################################
#########################################################################################
#########################################################################################
############################### grasp_callback function #################################
#########################################################################################
#########################################################################################
gripper_pose = 0
def grasp():
global reg
global rev
global regfp
global regfm
global revf
global base
global l1l
global l2l
global l3l
global r1l
global r2l
global r3l
global l1c
global l2c
global l3c
global r1c
global r2c
global r3c
global li1
global li2
global li3
global lf1
global lf2
global lf3
global ri1
global ri2
global ri3
global rf1
global rf2
global rf3
global gripper_pose
if gripper_pose == 1:
# for i in range(100):
br = tf.TransformBroadcaster()
# <!- <node name="temporary_publisher3" pkg="tf" type="static_transform_publisher" args="0.061, 0.013, 0.0, 0.967, -0.256, 0.0, 0.0 robotiq_85_base_link robotiq_85_left_inner_knuckle_link 100"/>
# <node name="temporary_publisher4" pkg="tf" type="static_transform_publisher" args="0.055, 0.031, 0.000, 0.967, -0.256, 0.0, 0.0 robotiq_85_base_link robotiq_85_left_knuckle_link 100"/>
# <node name="temporary_publisher5" pkg="tf" type="static_transform_publisher" args="0.061, -0.013, 0.0, 0.0, 0.0, 0.256, 0.967 robotiq_85_base_link robotiq_85_right_inner_knuckle_link 100"/>
# <node name="temporary_publisher6" pkg="tf" type="static_transform_publisher" args="0.055, -0.031, 0.0, 0.0, 0.0, 0.256, 0.967 robotiq_85_base_link robotiq_85_right_knuckle_link 100"/>
# -->
br.sendTransform((0.061, 0.013, 0.0),
(0.967, -0.256,0.0,0.0),
rospy.Time.now(),
'robotiq_85_left_inner_knuckle_link',
'robotiq_85_base_link')
br.sendTransform((0.055, 0.031, 0.0),
(0.967, -0.256,0.0,0.0),
rospy.Time.now(),
'robotiq_85_left_knuckle_link',
'robotiq_85_base_link')
br.sendTransform((0.061, -0.013, 0.0),
(0.0,0.0,0.256, 0.967),
rospy.Time.now(),
'robotiq_85_right_inner_knuckle_link',
'robotiq_85_base_link')
br.sendTransform((0.055, -0.031, 0.0),
(0.0,0.0,0.256, 0.967),
rospy.Time.now(),
'robotiq_85_right_knuckle_link',
'robotiq_85_base_link')
# <!-- <node name="temporary_publisher7" pkg="tf" type="static_transform_publisher" args="0.043 -0.038 0.0 0.0 0.0 -0.256, 0.967 robotiq_85_left_inner_knuckle_link robotiq_85_left_finger_tip_link 100"/> -->
# <!-- <node name="temporary_publisher8" pkg="tf" type="static_transform_publisher" args="-0.004 -0.031 0.0 0.0 0.0 0.0 1.0 robotiq_85_left_knuckle_link robotiq_85_left_finger_link 100"/>
# -->
# <!-- <node name="temporary_publisher9" pkg="tf" type="static_transform_publisher" args="0.043 -0.038 0.0 0.0 0.0 -0.256, 0.967 robotiq_85_right_inner_knuckle_link robotiq_85_right_finger_tip_link 100"/>
# -->
# <!-- <node name="temporary_publisher10" pkg="tf" type="static_transform_publisher" args="-0.004 -0.031 0.0 0 0 0 1 robotiq_85_right_knuckle_link robotiq_85_right_finger_link 100"/> -->
br.sendTransform((0.043, -0.038, 0.0),
(0,0,-0.256, 0.967),
rospy.Time.now(),
'robotiq_85_left_finger_tip_link',
'robotiq_85_left_inner_knuckle_link')
br.sendTransform((-0.004, -0.031, 0.0),
(0,0,0,1),
rospy.Time.now(),
'robotiq_85_left_finger_link',
'robotiq_85_left_knuckle_link')
br.sendTransform((0.043, -0.038, 0.0),
(0,0,-0.256, 0.967),
rospy.Time.now(),
'robotiq_85_right_finger_tip_link',
'robotiq_85_right_inner_knuckle_link')
br.sendTransform((-0.004, -0.031, 0.0),
(0,0,0,1),
rospy.Time.now(),
'robotiq_85_right_finger_link',
'robotiq_85_right_knuckle_link')
elif gripper_pose == 0:
# for i in range(100):
br = tf.TransformBroadcaster()
# <node name="temporary_publisher3" pkg="tf" type="static_transform_publisher" args="0.061, 0.013, 0.0 1 0 0 0 robotiq_85_base_link robotiq_85_left_inner_knuckle_link 100"/>
# <node name="temporary_publisher4" pkg="tf" type="static_transform_publisher" args="0.055, 0.031, 0.0 1 0 0 0 robotiq_85_base_link robotiq_85_left_knuckle_link 100"/>
# <node name="temporary_publisher5" pkg="tf" type="static_transform_publisher" args="0.061, -0.013, 0.0 0.0 0 0 robotiq_85_base_link robotiq_85_right_inner_knuckle_link 100"/>
# <node name="temporary_publisher6" pkg="tf" type="static_transform_publisher" args="0.055, -0.031, 0.0 0.0 0 0 robotiq_85_base_link robotiq_85_right_knuckle_link 100"/>
# <node name="temporary_publisher7" pkg="tf" type="static_transform_publisher" args="0.043, -0.038, 0.0 0.0 0 0 robotiq_85_left_inner_knuckle_link robotiq_85_left_finger_tip_link 100"/>
# <node name="temporary_publisher8" pkg="tf" type="static_transform_publisher" args="-0.004, -0.031, 0.0 0.0 0 0 robotiq_85_left_knuckle_link robotiq_85_left_finger_link 100"/>
# <node name="temporary_publisher9" pkg="tf" type="static_transform_publisher" args="0.043, -0.038, 0.0 0.0 0 0 robotiq_85_right_inner_knuckle_link robotiq_85_right_finger_tip_link 100"/>
# <node name="temporary_publisher10" pkg="tf" type="static_transform_publisher" args="-0.004, -0.031, 0.0 0.0 0 0 robotiq_85_right_knuckle_link robotiq_85_right_finger_link 100"/>
# -->
br.sendTransform((0.061, 0.013, 0.0),
(1,0,0,0),
rospy.Time.now(),
'robotiq_85_left_inner_knuckle_link',
'robotiq_85_base_link')
br.sendTransform((0.055, 0.031, 0.0),
(1,0,0,0),
rospy.Time.now(),
'robotiq_85_left_knuckle_link',
'robotiq_85_base_link')
br.sendTransform((0.061, -0.013, 0.0),
(0,0,0,1),
rospy.Time.now(),
'robotiq_85_right_inner_knuckle_link',
'robotiq_85_base_link')
br.sendTransform((0.055, -0.031, 0.0),
(0,0,0,1),
rospy.Time.now(),
'robotiq_85_right_knuckle_link',
'robotiq_85_base_link')
br.sendTransform((0.043, -0.038, 0.0),
(0,0,0,1),
rospy.Time.now(),
'robotiq_85_left_finger_tip_link',
'robotiq_85_left_inner_knuckle_link')
br.sendTransform((-0.004, -0.031, 0.0),
(0,0,0,1),
rospy.Time.now(),
'robotiq_85_left_finger_link',
'robotiq_85_left_knuckle_link')
br.sendTransform((0.043, -0.038, 0.0),
(0,0,0,1),
rospy.Time.now(),
'robotiq_85_right_finger_tip_link',
'robotiq_85_right_inner_knuckle_link')
br.sendTransform((-0.004, -0.031, 0.0),
(0,0,0,1),
rospy.Time.now(),
'robotiq_85_right_finger_link',
'robotiq_85_right_knuckle_link')
#########################################################################################
reg = [0,0,0,1]
rev = [1,0,0,0]
regfp = [0,0,0.256,0.967]
regfm = [0,0,-0.256,0.967]
revf = [0.967,-0.256,0,0]
base = 'robotiq_85_base_link'
l1l = 'robotiq_85_left_inner_knuckle_link'
l2l = 'robotiq_85_left_knuckle_link'
l3l = 'robotiq_85_left_finger_tip_link'
r1l = 'robotiq_85_right_inner_knuckle_link'
r2l = 'robotiq_85_right_knuckle_link'
r3l = 'robotiq_85_right_finger_tip_link'
l1c = [0.061 , 0.013 , 0.0]
l2c = [0.055 , 0.031 , 0.0]
l3c = [0.043 ,-0.038 , 0.0]
r1c = [0.061 ,-0.013 , 0.0]
r2c = [0.055 ,-0.031 , 0.0]
r3c = [0.043 ,-0.038 , 0.0]
li1 = [ l1c , rev , [base , l1l] ]
li2 = [ l2c , rev , [base , l2l] ]
li3 = [ l3c , reg , [l1l , l3l] ]
lf1 = [ l1c , revf , [base , l1l] ]
lf2 = [ l2c , revf , [base , l2l] ]
lf3 = [ l3c , regfm , [l1l , l3l] ]
ri1 = [ r1c , reg , [base , r1l] ]
ri2 = [ r2c , reg , [base , r2l] ]
ri3 = [ r3c , reg , [r1l , r3l] ]
rf1 = [ r1c , regfp , [base , r1l] ]
rf2 = [ r2c , regfp , [base , r2l] ]
rf3 = [ r3c , regfm , [r1l , r3l] ]
# args="0.061 0.013 0.0 1 0 0.0 0.0 robotiq_85_base_link robotiq_85_left_inner_knuckle_link 100"/>
# args="0.055, 0.031, 0.000 1 0 0.0 0.0 robotiq_85_base_link robotiq_85_left_knuckle_link 100"/>
# args="0.061 -0.013 0.0 0.0 0.0 0 1 robotiq_85_base_link robotiq_85_right_inner_knuckle_link 100"/>
# args="0.055 -0.031 0.0 0.0 0.0 0.0 1 robotiq_85_base_link robotiq_85_right_knuckle_link 100"/>
# args="0.043 -0.038 0.0 0.0 0.0 0.0 1 robotiq_85_left_inner_knuckle_link robotiq_85_left_finger_tip_link 100"/>
# args="0.043 -0.038 0.0 0.0 0.0 0.0 1 robotiq_85_right_inner_knuckle_link robotiq_85_right_finger_tip_link 100"/>
# <node name="temporary_publisher8" pkg="tf" type="static_transform_publisher" args="-0.004 -0.031 0.0 0.0 0.0 0.0 1.0 robotiq_85_left_knuckle_link robotiq_85_left_finger_link 100"/>
# <node name="temporary_publisher10" pkg="tf" type="static_transform_publisher" args="-0.004 -0.031 0.0 0 0 0 1 robotiq_85_right_knuckle_link robotiq_85_right_finger_link 100"/>
# br.sendTransform((-0.004, -0.031, 0.0),
# (0.0,0.0,0.0,1.0),
# rospy.Time.now(),
# 'robotiq_85_left_finger_link',
# 'robotiq_85_left_knuckle_link')
# br.sendTransform((-0.004, -0.031, 0.0),
# (0.0,0.0,0.0,1.0),
# rospy.Time.now(),
# 'robotiq_85_right_finger_link',
# 'robotiq_85_right_knuckle_link')
# args="0.061 0.013 0.0 0.967 -0.256 0.0 0.0 robotiq_85_base_link robotiq_85_left_inner_knuckle_link 100"/>
# args="0.055, 0.031, 0.000 0.967 -0.256 0.0 0.0 robotiq_85_base_link robotiq_85_left_knuckle_link 100"/>
# args="0.061 -0.013 0.0 0.0 0.0 0.256 0.967 robotiq_85_base_link robotiq_85_right_inner_knuckle_link 100"/>
# args="0.055 -0.031 0.0 0.0 0.0 0.256 0.967 robotiq_85_base_link robotiq_85_right_knuckle_link 100"/>
# args="0.043 -0.038 0.0 0.0 0.0 -0.256 0.967 robotiq_85_left_inner_knuckle_link robotiq_85_left_finger_tip_link 100"/>
# args="0.043 -0.038 0.0 0.0 0.0 -0.256 0.967 robotiq_85_right_inner_knuckle_link robotiq_85_right_finger_tip_link 100"/>
def pose_setter(data):
global gripper_pose
if data.data == True:
gripper_pose = 1
elif data.data == False:
gripper_pose = 0
else:
print "error"
#########################################################################################
#########################################################################################
############################### Initialize function #####################################
#########################################################################################
#########################################################################################
def initialize():
rospy.init_node('marker_pose_rerouter_node', anonymous=True)
rospy.Subscriber("rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update", InteractiveMarkerUpdate, gripper_tf_callback)
rospy.Subscriber("sim_gripper", Bool, pose_setter)
#########################################################################################
if __name__ == '__main__':
initialize()
while (not rospy.is_shutdown()):
grasp()