Merge pull request #3 from markwsilliman/master

Robotiq Gripper and README
This commit is contained in:
ORD 2016-04-26 20:05:16 +02:00
commit f8497e0381
4 changed files with 179 additions and 68 deletions

1
.gitignore vendored
View File

@ -1,2 +1,3 @@
docs/_* docs/_*
build build
.idea/

68
README
View File

@ -1,68 +0,0 @@
urx is a python library to control a robot from 'Universal robot'.
It is published under the GPL license and comes with absolutely no
guarantee, althoug it has been used in many application with several
version of UR5 and UR10 robots.
It is meaned as an easy to use module for pick and place operations,
although it has been used for welding and other sensor based applications
that do not require high update rate.
Both the 'secondary port' interface and the real-time/matlab interface of the
UR controller are used. urx can optionally use the python-math3d
https://launchpad.net/pymath3d library to receive and send transformation
matrices to the robot urx is known to work with all release robots from Universal Robot.
urx was primarily developed by Olivier Roulet-Dubonnet for Sintef Raufoss Manufacturing
and : http://www.sintef.no/manufacturing/
Example use:
import urx
rob = urx.robot("192.168.0.100")
rob.set_tcp((0, 0, 0.1, 0, 0, 0))
rob.set_payload(2, (0, 0, 0.1))
rob.movej((1, 2, 3, 4, 5, 6), a, v)
rob.movel((x, y, z, rx, ry, rz), a, v)
print "Current tool pose is: ", rob.getl()
rob.movel((0.1, 0, 0, 0, 0, 0), a, v, relative=true)# move relative to current pose
rob.translate((0.1, 0, 0), a, v) #move tool and keep orientation
rob.stopj(a)
robot.movel(x, y, z, rx, ry, rz), wait=False)
while True :
sleep(0.1) #sleep first since the robot may not have processed the command yet
if robot.is_program_running():
break
robot.movel(x, y, z, rx, ry, rz), wait=False)
while.robot.getForce() < 50:
sleep(0.01)
if not robot.is_program_running():
break
robot.stopl()
try:
robot.movel((0,0,0.1,0,0,0), relative=True)
except RobotError, ex:
print "Robot could not execute move (emergency stop for example), do something", ex
Development using Transform objects from math3d library:
robot = Robot("192.168.1.1")
robot.set_tcp((0,0,0.23,0,0,0)
robot.csys.orient.rotate_zb(pi/4) #just an example
trans = robot.get_pose() # get current transformation matrix (tool to base)
trans.orient.rotate_yt(pi/2)
robot.set_pose(trans)
trans.pos += math3d.Vector(0,0,0.3)
robot.set_pose(trans)
#or only work with orientation part
o = robot.get_orientation()
o.rotate_yb(pi)
robot.set_orientation(o)

92
README.md Normal file
View File

@ -0,0 +1,92 @@
urx is a python library to control a robot from 'Universal robot'. It is published under the GPL license and comes with absolutely no guarantee, although it has been used in many application with several version of UR5 and UR10 robots.
It is meant as an easy to use module for pick and place operations, although it has been used for welding and other sensor based applications that do not require high update rate.
Both the 'secondary port' interface and the real-time/matlab interface of the UR controller are used. urx can optionally use the [python-math3d](https://launchpad.net/pymath3d) library to receive and send transformation matrices to the robot urx is known to work with all release robots from Universal Robot.
urx was primarily developed by [Olivier Roulet-Dubonnet](https://github.com/oroulet) for [Sintef Raufoss Manufacturing](http://www.sintef.no/manufacturing/).
#Example use:
```python
import urx
rob = urx.robot("192.168.0.100")
rob.set_tcp((0, 0, 0.1, 0, 0, 0))
rob.set_payload(2, (0, 0, 0.1))
rob.movej((1, 2, 3, 4, 5, 6), a, v)
rob.movel((x, y, z, rx, ry, rz), a, v)
print "Current tool pose is: ", rob.getl()
rob.movel((0.1, 0, 0, 0, 0, 0), a, v, relative=true)# move relative to current pose
rob.translate((0.1, 0, 0), a, v) #move tool and keep orientation
rob.stopj(a)
robot.movel(x, y, z, rx, ry, rz), wait=False)
while True :
sleep(0.1) #sleep first since the robot may not have processed the command yet
if robot.is_program_running():
break
robot.movel(x, y, z, rx, ry, rz), wait=False)
while.robot.getForce() < 50:
sleep(0.01)
if not robot.is_program_running():
break
robot.stopl()
try:
robot.movel((0,0,0.1,0,0,0), relative=True)
except RobotError, ex:
print "Robot could not execute move (emergency stop for example), do something", ex
```
#Development using Transform objects from math3d library:
```python
robot = Robot("192.168.1.1")
robot.set_tcp((0,0,0.23,0,0,0)
robot.csys.orient.rotate_zb(pi/4) #just an example
trans = robot.get_pose() # get current transformation matrix (tool to base)
trans.orient.rotate_yt(pi/2)
robot.set_pose(trans)
trans.pos += math3d.Vector(0,0,0.3)
robot.set_pose(trans)
#or only work with orientation part
o = robot.get_orientation()
o.rotate_yb(pi)
robot.set_orientation(o)
```
#Robotiq Gripper
urx can also control a Robotiq gripper attached to the UR robot. The robotiq class was primarily developed by [Mark Silliman](https://github.com/markwsilliman).
##Example use:
```python
import sys
import urx
from urx.robotiq_two_finger_gripper import Robotiq_Two_Finger_Gripper
if __name__ == '__main__':
rob = urx.Robot("192.168.0.100")
robotiqgrip = Robotiq_Two_Finger_Gripper()
if(len(sys.argv) != 2):
print "false"
sys.exit()
if(sys.argv[1] == "close") :
robotiqgrip.close_gripper()
if(sys.argv[1] == "open") :
robotiqgrip.open_gripper()
rob.send_program(robotiqgrip.ret_program_to_run())
rob.close()
print "true"
sys.exit()
```

View File

@ -0,0 +1,86 @@
"""
Python library to control Robotiq Two Finger Gripper connected to UR robot via Python-URX
Tested using a UR5 Version CB3 and Robotiq 2-Finger Gripper Version 85
SETUP
You must install the driver first (http://support.robotiq.com/pages/viewpage.action?pageId=5963876) and then power on the gripper from the gripper UI
FAQ
Why does this class group all the commands together and run them as a single program as opposed to running each line seperately (like most of URX)?
- The gripper is controlled by connecting to the robot's computer (TCP/IP) and then communicating with the gripper via a socket (127.0.0.1:63352). The scope of the socket is at the program level. It will be automatically closed whenever a program finishes. Therefore it's important that we run all commands as a single program.
DOCUMENTATION
- This code was developed by downloading the "gripper package" on http://support.robotiq.com/pages/viewpage.action?pageId=5963876
- Open folder "robotiq_2f_gripper_programs_CB3"
- robotiq_2f_gripper_programs_CB3/advanced_template_test.script was referenced to create this class
Future Features
- Though I haven't developed it yet if you look in robotiq_2f_gripper_programs_CB3/advanced_template_test.script and view function "rq_get_var" there is an example of how to determine the current state of the gripper and if it's holding an object.
"""
import logging
class Robotiq_Two_Finger_Gripper(object):
complete_program = ""
header = "def myProg():" + b"\n"
end = b"\n" + "end"
logger = False
def __init__(self):
self.logger = logging.getLogger("urx")
self.reset()
def reset(self):
self.complete_program = ""
self.add_line_to_program("set_analog_inputrange(0, 0)")
self.add_line_to_program("set_analog_inputrange(1, 0)")
self.add_line_to_program("set_analog_inputrange(2, 0)")
self.add_line_to_program("set_analog_inputrange(3, 0)")
self.add_line_to_program("set_analog_outputdomain(0, 0)")
self.add_line_to_program("set_analog_outputdomain(1, 0)")
self.add_line_to_program("set_tool_voltage(0)")
self.add_line_to_program("set_runstate_outputs([])")
self.add_line_to_program("set_payload(0.85)") #0.85 is the weight of the gripper in KG
self.add_line_to_program("socket_close(\"gripper_socket\")")
#self.add_line_to_program("sleep(1)") #in Robotiq's example they do a wait here... I haven't found it nec
self.add_line_to_program("socket_open(\"127.0.0.1\",63352,\"gripper_socket\")")
#self.add_line_to_program("sleep(1)")
self.add_line_to_program("socket_set_var(\"SEP\",255,\"gripper_socket\")") #Speed 0-255 is valid
self.add_line_to_program("sync()")
self.add_line_to_program("socket_set_var(\"FOR\",50,\"gripper_socket\")") #Force 0-255 is valid
self.add_line_to_program("sync()")
self.add_line_to_program("socket_set_var(\"ACT\",1,\"gripper_socket\")") # Activate robot
self.add_line_to_program("sync()")
self.add_line_to_program("socket_set_var(\"GTO\",1,\"gripper_socket\")")
self.add_line_to_program("sync()")
def open_gripper(self):
self.add_line_to_program("socket_set_var(\"POS\",0,\"gripper_socket\")") #0 is open; range is 0-255
self.add_line_to_program("sync()")
self.add_line_to_program("sleep(2)")
def close_gripper(self):
self.add_line_to_program("socket_set_var(\"POS\",255,\"gripper_socket\")") #255 is closed; range is 0-255
self.add_line_to_program("sync()")
self.add_line_to_program("sleep(2)")
def add_line_to_program(self,new_line):
if(self.complete_program != ""):
self.complete_program += b"\n"
self.complete_program += new_line
def ret_program_to_run(self):
if(self.complete_program == ""):
self.logger.debug("robotiq_two_finger_gripper's program is empty")
return ""
prog = self.header
prog += self.complete_program
prog += self.end
return prog