-
Notifications
You must be signed in to change notification settings - Fork 4
/
grip.py
67 lines (35 loc) · 1.16 KB
/
grip.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
import serial
import time
import binascii
ser = serial.Serial(port='COM11', baudrate=115200, timeout=1,
parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, bytesize=serial.EIGHTBITS)
counter = 0
while counter < 1:
counter = counter + 1
ser.write("\x09\x10\x03\xE8\x00\x03\x06\x00\x00\x00\x00\x00\x00\x73\x30")
data_raw = ser.readline()
print(data_raw)
data = binascii.hexlify(data_raw)
print "Response 1 ", data
time.sleep(0.01)
ser.write("\x09\x03\x07\xD0\x00\x01\x85\xCF")
data_raw = ser.readline()
print(data_raw)
data = binascii.hexlify(data_raw)
print "Response 2 ", data
time.sleep(1)
while (True):
print "Close gripper"
ser.write("\x09\x10\x03\xE8\x00\x03\x06\x09\x00\x00\xFF\xFF\xFF\x42\x29")
data_raw = ser.readline()
print(data_raw)
data = binascii.hexlify(data_raw)
print "Response 3 ", data
time.sleep(2)
print "Open gripper"
ser.write("\x09\x10\x03\xE8\x00\x03\x06\x09\x00\x00\x00\xFF\xFF\x72\x19")
data_raw = ser.readline()
print(data_raw)
data = binascii.hexlify(data_raw)
print "Response 4 ", data
time.sleep(2)