def ezg_init_connection(): global dev_name, ids, last_message, connection, gripper try: s = find_servos_on_all_ports(max_id=10) if s: dev_name, ids = s[0] print "dev", dev_name print "ids", ids connection = create_connection(dev_name=dev_name, baudrate=57600) #connection = create_connection(dev_name='/dev/ttyUSB0', baudrate=57600) #connection = create_connection(dev_name='hwgrep://0403:6001', baudrate=57600) #gripper = Gripper(connection, 'gripper1', [1]) gripper = Gripper(connection, 'gripper1', ids) last_message = "" else: last_message = "No grippers found" except Exception, e: last_message = str(e)
#!/usr/bin/python # -*- coding: utf-8 -*- import sys from libezgripper import create_connection, Gripper from PyQt4 import QtGui, QtCore connection = create_connection(dev_name='/dev/ttyUSB0', baudrate=57600) gripper = Gripper(connection, 'gripper1', [1]) #gripper = Gripper(connection, 'gripper1', [1,2,3]) #gripper = Gripper(connection, 'gripper1', [2,3]) class GripperGUI(QtGui.QMainWindow): def __init__(self): super(GripperGUI, self).__init__() self.initUI() def initUI(self): calibrateButton = QtGui.QPushButton("Calibrate", self) calibrateButton.resize(100, 30) # calibrateButton.setStyleSheet("background-color:rgb(153, 153, 153)") calibrateButton.clicked.connect(gripper.calibrate) calibrateButton.move(50, 10) calibrateButton.show() releaseButton = QtGui.QPushButton("Release", self) releaseButton.resize(600, 40) releaseButton.clicked.connect(gripper.release) releaseButton.move(50, 50)
# Main Program rospy.init_node('ezgripper') rospy.loginfo("Started") port_name = rospy.get_param('~port', '/dev/ttyUSB0') baud = int(rospy.get_param('~baud', '1000000')) gripper_params = rospy.get_param('~grippers') diagnostics_pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=1) connection = create_connection(port_name, baud) all_servos = [] references = [] grippers = [] for gripper_name, servo_ids in gripper_params.iteritems(): gripper = Gripper(connection, gripper_name, servo_ids) all_servos += gripper.servos gripper.calibrate() gripper.open() references.append( rospy.Service('~' + gripper_name + '/calibrate', Empty, partial(calibrate_srv, gripper)))