-
Notifications
You must be signed in to change notification settings - Fork 0
/
gripper_node.py
executable file
·37 lines (28 loc) · 993 Bytes
/
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
#!/usr/bin/env python
import serial
import time
import rospy
from std_msgs.msg import Bool
ser = serial.Serial(port="/dev/ttyUSB0",baudrate=115200,timeout=1,parity=serial.PARITY_NONE,stopbits=serial.STOPBITS_ONE,bytesize=serial.EIGHTBITS)
time.sleep(0.05)
def open_close(switch):
# opens / closes the gripper
if switch.data:
print "Closing gripper"
ser.write("\x09\x10\x03\xE8\x00\x03\x06\x09\x00\x00\xFF\xFF\xFF\x42\x29")
time.sleep(1)
else:
print "Opening gripper"
ser.write("\x09\x10\x03\xE8\x00\x03\x06\x09\x00\x00\x00\xFF\xFF\x72\x19")
time.sleep(1)
def gripper_node():
# subscribes to gripper_state topic
rospy.init_node('gripper_node', anonymous=True)
rospy.Subscriber("gripper_state", Bool, open_close)
rospy.loginfo('Subscribing to gripper_state to open/close the gripper')
rospy.spin()
if __name__ == '__main__':
try:
gripper_node()
except rospy.ROSInterruptException:
pass