diff --git a/ur_driver/src/ur_driver/deserialize.py b/ur_driver/src/ur_driver/deserialize.py
index 4a88aa79ecec3729eefed8fe671c97761225c7a9..124b963ef7c55e62055bf1c96136665aeea7e720 100755
--- a/ur_driver/src/ur_driver/deserialize.py
+++ b/ur_driver/src/ur_driver/deserialize.py
@@ -1,3 +1,4 @@
+from __future__ import print_function
 import struct
 
 class PackageType(object):
@@ -79,7 +80,7 @@ class RobotModeData(object):
         elif plen == 38:
             return RobotModeData_V30.unpack(buf)
         else:
-            print "RobotModeData has wrong length: " + str(plen)
+            print("RobotModeData has wrong length: " + str(plen))
             return rmd
 
 #this parses RobotModeData for versions <= v1.8 (i.e. 1.6, 1.7, 1.8)
@@ -159,8 +160,8 @@ class MasterboardData(object):
         elif (plen == 72) or (plen == 92): # Euromap67 interface = 20 bytes
             return MasterboardData_V30.unpack(buf)
         else:
-            print "MasterboardData has wrong length: " + str(plen)
-            print "Euromap67Interface is ignored"
+            print("MasterboardData has wrong length: " + str(plen))
+            print("Euromap67Interface is ignored")
             return md
 
 #this parses MasterboardData for versions <= v1.8 (i.e. 1.6, 1.7, 1.8)
@@ -282,7 +283,7 @@ class AdditionalInfo(object):
         elif plen == 7:
             return AdditionalInfoNew.unpack(buf)
         else:
-            print "AdditionalInfo has wrong length: " + str(plen)
+            print("AdditionalInfo has wrong length: " + str(plen))
             return ai
 
 class AdditionalInfoOld(object):
@@ -319,8 +320,8 @@ class RobotState(object):
             raise Exception("Could not unpack packet: length field is incorrect")
         if mtype != 16:
             if mtype == 20:
-                print "Likely a syntax error:"
-                print buf[:2048]
+                print("Likely a syntax error:")
+                print(buf[:2048])
             raise Exception("Fatal error when unpacking RobotState packet")
 
         rs = RobotState()
@@ -359,14 +360,14 @@ def pstate(o, indent=''):
     for s in o.__slots__:
         child = getattr(o, s, None)
         if child is None:
-            print "%s%s: None" % (indent, s)
+            print("%s%s: None" % (indent, s))
         elif hasattr(child, '__slots__'):
-            print "%s%s:" % (indent, s)
+            print("%s%s:" % (indent, s))
             pstate(child, indent + '    ')
         elif hasattr(child, '__iter__'):
-            print "%s%s:" % (indent, s)
+            print("%s%s:" % (indent, s))
             for i, c in enumerate(child):
-                print "%s  [%i]:" % (indent, i)
+                print("%s  [%i]:" % (indent, i))
                 pstate(c, indent + '    ')
         else:
-            print "%s%s: %s" % (indent, s, child)
+            print("%s%s: %s" % (indent, s, child))
diff --git a/ur_driver/src/ur_driver/deserializeRT.py b/ur_driver/src/ur_driver/deserializeRT.py
index ff6750cd42c10f8403cd9b91c0025b1656b83a47..ea2b625a6e5ae7073ed5a6fd9af95fcd3ef81b59 100644
--- a/ur_driver/src/ur_driver/deserializeRT.py
+++ b/ur_driver/src/ur_driver/deserializeRT.py
@@ -1,3 +1,4 @@
+from __future__ import print_function
 import struct
 import copy
 
@@ -14,7 +15,7 @@ class RobotStateRT(object):
         elif plen == 1044:
             return RobotStateRT_V30.unpack(buf)
         else:
-            print "RobotStateRT has wrong length: " + str(plen)
+            print("RobotStateRT has wrong length: " + str(plen))
             return rs
 
 #this parses RobotStateRT for versions = v1.5
@@ -34,7 +35,7 @@ class RobotStateRT_V15(object):
         message_size = struct.unpack_from("!i", buf, offset)[0]
         offset+=4
         if message_size != len(buf):
-            print("MessageSize: ", message_size, "; BufferSize: ", len(buf))
+            print(("MessageSize: ", message_size, "; BufferSize: ", len(buf)))
             raise Exception("Could not unpack RobotStateRT packet: length field is incorrect")
 
         rs = RobotStateRT_V15()
@@ -145,7 +146,7 @@ class RobotStateRT_V18(object):
         message_size = struct.unpack_from("!i", buf, offset)[0]
         offset+=4
         if message_size != len(buf):
-            print("MessageSize: ", message_size, "; BufferSize: ", len(buf))
+            print(("MessageSize: ", message_size, "; BufferSize: ", len(buf)))
             raise Exception("Could not unpack RobotStateRT packet: length field is incorrect")
 
         rs = RobotStateRT_V18()
@@ -268,7 +269,7 @@ class RobotStateRT_V30(object):
         message_size = struct.unpack_from("!i", buf, offset)[0]
         offset+=4
         if message_size != len(buf):
-            print("MessageSize: ", message_size, "; BufferSize: ", len(buf))
+            print(("MessageSize: ", message_size, "; BufferSize: ", len(buf)))
             raise Exception("Could not unpack RobotStateRT packet: length field is incorrect")
 
         rs = RobotStateRT_V30()
diff --git a/ur_driver/src/ur_driver/driver.py b/ur_driver/src/ur_driver/driver.py
index 20e25f3b3c16a97741efdacc527e0eaf4ff9556b..0245191366a40d9178f01216d135c28d896949ed 100755
--- a/ur_driver/src/ur_driver/driver.py
+++ b/ur_driver/src/ur_driver/driver.py
@@ -1,4 +1,5 @@
 #!/usr/bin/env python
+from __future__ import print_function
 import roslib; roslib.load_manifest('ur_driver')
 import time, sys, threading, math
 import copy
@@ -106,10 +107,10 @@ def dumpstacks():
             code.append('File: "%s", line %d, in %s' % (filename, lineno, name))
             if line:
                 code.append("  %s" % (line.strip()))
-    print "\n".join(code)
+    print("\n".join(code))
 
 def log(s):
-    print "[%s] %s" % (datetime.datetime.now().strftime('%Y-%m-%d %H:%M:%S.%f'), s)
+    print("[%s] %s" % (datetime.datetime.now().strftime('%Y-%m-%d %H:%M:%S.%f'), s))
 
 
 RESET_PROGRAM = '''def resetProg():
@@ -420,7 +421,7 @@ class CommanderTCPHandler(SocketServer.BaseRequestHandler):
     def handle(self):
         self.__socket_lock = threading.Lock()
         setConnectedRobot(self)
-        print "Handling a request"
+        print("Handling a request")
         try:
             buf = self.recv_more()
             if not buf: return
@@ -445,21 +446,21 @@ class CommanderTCPHandler(SocketServer.BaseRequestHandler):
                     log("Out: %s" % s)
                 
                 elif mtype == MSG_QUIT:
-                    print "Quitting"
+                    print("Quitting")
                     raise EOF("Received quit")
                 elif mtype == MSG_WAYPOINT_FINISHED:
                     while len(buf) < 4:
                         buf = buf + self.recv_more()
                     waypoint_id = struct.unpack_from("!i", buf, 0)[0]
                     buf = buf[4:]
-                    print "Waypoint finished (not handled)"
+                    print("Waypoint finished (not handled)")
                 else:
                     raise Exception("Unknown message type: %i" % mtype)
 
                 if not buf:
                     buf = buf + self.recv_more()
         except EOF, ex:
-            print "Connection closed (command):", ex
+            print("Connection closed (command):", ex)
             setConnectedRobot(None)
 
     def __send_message(self, data):
@@ -629,7 +630,7 @@ class URServiceProvider(object):
 
     def setPayload(self, req):
         if req.payload < min_payload or req.payload > max_payload:
-            print 'ERROR: Payload ' + str(req.payload) + ' out of bounds (' + str(min_payload) + ', ' + str(max_payload) + ')'
+            print('ERROR: Payload ' + str(req.payload) + ' out of bounds (' + str(min_payload) + ', ' + str(max_payload) + ')')
             return False
         
         if self.robot:
@@ -691,7 +692,7 @@ class URTrajectoryFollower(object):
     def start(self):
         self.init_traj_from_robot()
         self.server.start()
-        print "The action server for this driver has been started"
+        print("The action server for this driver has been started")
 
     def on_goal(self, goal_handle):
         log("on_goal")
@@ -892,7 +893,7 @@ def main():
     reconfigure_srv = Server(URDriverConfig, reconfigure_callback)
     
     prefix = rospy.get_param("~prefix", "")
-    print "Setting prefix to %s" % prefix
+    print("Setting prefix to %s" % prefix)
     global joint_names
     joint_names = [prefix + name for name in JOINT_NAMES]
 
@@ -964,13 +965,13 @@ def main():
                     update = {'prevent_programming': prevent_programming}
                     reconfigure_srv.update_configuration(update)
                 except KeyError, ex:
-                    print "Parameter 'prevent_programming' not set. Value: " + str(prevent_programming)
+                    print("Parameter 'prevent_programming' not set. Value: " + str(prevent_programming))
                     pass
                 if prevent_programming:
-                    print "Programming now prevented"
+                    print("Programming now prevented")
                     connection.send_reset_program()
             else:
-                print "Disconnected.  Reconnecting"
+                print("Disconnected.  Reconnecting")
                 if action_server:
                     action_server.set_robot(None)
 
@@ -978,14 +979,14 @@ def main():
                 while True:
                     # Sends the program to the robot
                     while not connection.ready_to_program():
-                        print "Waiting to program"
+                        print("Waiting to program")
                         time.sleep(1.0)
                     try:
                         prevent_programming = rospy.get_param("~prevent_programming")
                         update = {'prevent_programming': prevent_programming}
                         reconfigure_srv.update_configuration(update)
                     except KeyError, ex:
-                        print "Parameter 'prevent_programming' not set. Value: " + str(prevent_programming)
+                        print("Parameter 'prevent_programming' not set. Value: " + str(prevent_programming))
                         pass
                     connection.send_program()
 
diff --git a/ur_driver/test_io.py b/ur_driver/test_io.py
index 7b3c2a82686bbea6d30a6b8b57becabaf7359fe7..48e7b431c6e08dcb6457d4efbe16f2b40791e726 100755
--- a/ur_driver/test_io.py
+++ b/ur_driver/test_io.py
@@ -1,13 +1,14 @@
 #!/usr/bin/env python
+from __future__ import print_function
 import time
 from ur_driver.io_interface import *
 
 if __name__ == "__main__":
-    print "testing io-interface"
+    print("testing io-interface")
     get_states()
-    print "listener has been activated"
+    print("listener has been activated")
     set_states()
-    print "service-server has been started"
+    print("service-server has been started")
     while(True):
         set_tool_voltage(12)
         set_digital_out(0, True)
diff --git a/ur_driver/test_move.py b/ur_driver/test_move.py
index 54b9115fc04a8c1c388efd159dc6ffcc3c982dbd..86b70335dcda715f0eca71f97497d976a742da3a 100755
--- a/ur_driver/test_move.py
+++ b/ur_driver/test_move.py
@@ -1,4 +1,5 @@
 #!/usr/bin/env python
+from __future__ import print_function
 import time
 import roslib; roslib.load_manifest('ur_driver')
 import rospy
@@ -79,7 +80,7 @@ def move_interrupt():
     
     client.send_goal(g)
     time.sleep(2.0)
-    print "Interrupting"
+    print("Interrupting")
     client.send_goal(g)
     try:
         client.wait_for_result()
@@ -92,9 +93,9 @@ def main():
     try:
         rospy.init_node("test_move", anonymous=True, disable_signals=True)
         client = actionlib.SimpleActionClient('follow_joint_trajectory', FollowJointTrajectoryAction)
-        print "Waiting for server..."
+        print("Waiting for server...")
         client.wait_for_server()
-        print "Connected to server"
+        print("Connected to server")
         #move1()
         move_repeated()
         #move_disordered()
diff --git a/ur_kinematics/src/ur_kinematics/test_analytical_ik.py b/ur_kinematics/src/ur_kinematics/test_analytical_ik.py
index c11860bf588dfd9ff17db409d40c7de4d46c8504..74a2e4337ef0e21f5677355f8465c12ac5f83e30 100644
--- a/ur_kinematics/src/ur_kinematics/test_analytical_ik.py
+++ b/ur_kinematics/src/ur_kinematics/test_analytical_ik.py
@@ -1,3 +1,4 @@
+from __future__ import print_function
 import numpy as np
 import sys
 import roslib
@@ -30,21 +31,21 @@ def test_q(q):
         qsol = [999.]*6
     diff = np.sum(np.abs(np.array(qsol) - q))
     if diff > 0.001:
-        print np.array(sols)
-        print 'Best q:', qsol
-        print 'Actual:', np.array(q)
-        print 'Diff:  ', q - qsol
-        print 'Difdiv:', (q - qsol)/np.pi
-        print i1-3, i2-3, i3-3, i4-3, i5-3, i6-3
+        print(np.array(sols))
+        print('Best q:', qsol)
+        print('Actual:', np.array(q))
+        print('Diff:  ', q - qsol)
+        print('Difdiv:', (q - qsol)/np.pi)
+        print(i1-3, i2-3, i3-3, i4-3, i5-3, i6-3)
         if raw_input() == 'q':
             sys.exit()
 
 def main():
     np.set_printoptions(precision=3)
-    print "Testing multiples of pi/2..."
+    print("Testing multiples of pi/2...")
     for i1 in range(0,5):
         for i2 in range(0,5):
-            print i1, i2
+            print(i1, i2)
             for i3 in range(0,5):
                 for i4 in range(0,5):
                     for i5 in range(0,5):
@@ -52,11 +53,11 @@ def main():
                             q = np.array([i1*np.pi/2., i2*np.pi/2., i3*np.pi/2., 
                                           i4*np.pi/2., i5*np.pi/2., i6*np.pi/2.])
                             test_q(q)
-    print "Testing random configurations..."
+    print("Testing random configurations...")
     for i in range(10000):
         q = (np.random.rand(6)-.5)*4*np.pi
         test_q(q)
-    print "Done!"
+    print("Done!")
 
 if __name__ == "__main__":
     if False: