driver.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import roslib; roslib.load_manifest('ur_driver')
00003 import time, sys, threading, math
00004 import copy
00005 import datetime
00006 import socket, select
00007 import struct
00008 import traceback, code
00009 import optparse
00010 import SocketServer
00011 
00012 import rospy
00013 import actionlib
00014 from sensor_msgs.msg import JointState
00015 from control_msgs.msg import FollowJointTrajectoryAction
00016 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
00017 from geometry_msgs.msg import WrenchStamped
00018 
00019 from ur_driver.deserialize import RobotState, RobotMode
00020 from ur_driver.deserializeRT import RobotStateRT
00021 
00022 from ur_msgs.srv import SetPayload, SetIO
00023 from ur_msgs.msg import *
00024 
00025 # renaming classes
00026 DigitalIn = Digital
00027 DigitalOut = Digital
00028 Flag  = Digital
00029 
00030 prevent_programming = False
00031 
00032 # Joint offsets, pulled from calibration information stored in the URDF
00033 #
00034 # { "joint_name" : offset }
00035 #
00036 # q_actual = q_from_driver + offset
00037 joint_offsets = {}
00038 
00039 PORT=30002       # 10 Hz, RobotState 
00040 RT_PORT=30003    #125 Hz, RobotStateRT
00041 DEFAULT_REVERSE_PORT = 50001     #125 Hz, custom data (from prog)
00042 
00043 MSG_OUT = 1
00044 MSG_QUIT = 2
00045 MSG_JOINT_STATES = 3
00046 MSG_MOVEJ = 4
00047 MSG_WAYPOINT_FINISHED = 5
00048 MSG_STOPJ = 6
00049 MSG_SERVOJ = 7
00050 MSG_SET_PAYLOAD = 8
00051 MSG_WRENCH = 9
00052 MSG_SET_DIGITAL_OUT = 10
00053 MSG_GET_IO = 11
00054 MSG_SET_FLAG = 12
00055 MSG_SET_TOOL_VOLTAGE = 13
00056 MSG_SET_ANALOG_OUT = 14
00057 MULT_payload = 1000.0
00058 MULT_wrench = 10000.0
00059 MULT_jointstate = 10000.0
00060 MULT_time = 1000000.0
00061 MULT_blend = 1000.0
00062 MULT_analog = 1000000.0
00063 MULT_analog_robotstate = 0.1
00064 
00065 #Max Velocity accepted by ur_driver
00066 MAX_VELOCITY = 10.0
00067 #Using a very high value in order to not limit execution of trajectories being sent from MoveIt!
00068 
00069 #Bounds for SetPayload service
00070 MIN_PAYLOAD = 0.0
00071 MAX_PAYLOAD = 1.0
00072 #Using a very conservative value as it should be set throught the parameter server
00073 
00074 
00075 FUN_SET_DIGITAL_OUT = 1
00076 FUN_SET_FLAG = 2
00077 FUN_SET_ANALOG_OUT = 3
00078 FUN_SET_TOOL_VOLTAGE = 4
00079 
00080 IO_SLEEP_TIME = 0.05
00081 
00082 JOINT_NAMES = ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint',
00083                'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
00084 
00085 Q1 = [2.2,0,-1.57,0,0,0]
00086 Q2 = [1.5,0,-1.57,0,0,0]
00087 Q3 = [1.5,-0.2,-1.57,0,0,0]
00088   
00089 
00090 connected_robot = None
00091 connected_robot_lock = threading.Lock()
00092 connected_robot_cond = threading.Condition(connected_robot_lock)
00093 last_joint_states = None
00094 last_joint_states_lock = threading.Lock()
00095 pub_joint_states = rospy.Publisher('joint_states', JointState)
00096 pub_wrench = rospy.Publisher('wrench', WrenchStamped)
00097 pub_io_states = rospy.Publisher('io_states', IOStates)
00098 #dump_state = open('dump_state', 'wb')
00099 
00100 class EOF(Exception): pass
00101 
00102 def dumpstacks():
00103     id2name = dict([(th.ident, th.name) for th in threading.enumerate()])
00104     code = []
00105     for threadId, stack in sys._current_frames().items():
00106         code.append("\n# Thread: %s(%d)" % (id2name.get(threadId,""), threadId))
00107         for filename, lineno, name, line in traceback.extract_stack(stack):
00108             code.append('File: "%s", line %d, in %s' % (filename, lineno, name))
00109             if line:
00110                 code.append("  %s" % (line.strip()))
00111     print "\n".join(code)
00112 
00113 def log(s):
00114     print "[%s] %s" % (datetime.datetime.now().strftime('%Y-%m-%d %H:%M:%S.%f'), s)
00115 
00116 
00117 RESET_PROGRAM = '''def resetProg():
00118   sleep(0.0)
00119 end
00120 '''
00121 #RESET_PROGRAM = ''
00122     
00123 class URConnection(object):
00124     TIMEOUT = 1.0
00125     
00126     DISCONNECTED = 0
00127     CONNECTED = 1
00128     READY_TO_PROGRAM = 2
00129     EXECUTING = 3
00130     
00131     def __init__(self, hostname, port, program):
00132         self.__thread = None
00133         self.__sock = None
00134         self.robot_state = self.DISCONNECTED
00135         self.hostname = hostname
00136         self.port = port
00137         self.program = program
00138         self.last_state = None
00139 
00140     def connect(self):
00141         if self.__sock:
00142             self.disconnect()
00143         self.__buf = ""
00144         self.robot_state = self.CONNECTED
00145         self.__sock = socket.create_connection((self.hostname, self.port))
00146         self.__keep_running = True
00147         self.__thread = threading.Thread(name="URConnection", target=self.__run)
00148         self.__thread.daemon = True
00149         self.__thread.start()
00150 
00151     def send_program(self):
00152         global prevent_programming
00153         if prevent_programming:
00154             rospy.loginfo("Programming is currently prevented")
00155             return
00156         assert self.robot_state in [self.READY_TO_PROGRAM, self.EXECUTING]
00157         rospy.loginfo("Programming the robot at %s" % self.hostname)
00158         self.__sock.sendall(self.program)
00159         self.robot_state = self.EXECUTING
00160 
00161     def send_reset_program(self):
00162         self.__sock.sendall(RESET_PROGRAM)
00163         self.robot_state = self.READY_TO_PROGRAM
00164         
00165     def disconnect(self):
00166         if self.__thread:
00167             self.__keep_running = False
00168             self.__thread.join()
00169             self.__thread = None
00170         if self.__sock:
00171             self.__sock.close()
00172             self.__sock = None
00173         self.last_state = None
00174         self.robot_state = self.DISCONNECTED
00175 
00176     def ready_to_program(self):
00177         return self.robot_state in [self.READY_TO_PROGRAM, self.EXECUTING]
00178 
00179     def __trigger_disconnected(self):
00180         log("Robot disconnected")
00181         self.robot_state = self.DISCONNECTED
00182     def __trigger_ready_to_program(self):
00183         rospy.loginfo("Robot ready to program")
00184     def __trigger_halted(self):
00185         log("Halted")
00186 
00187     def __on_packet(self, buf):
00188         state = RobotState.unpack(buf)
00189         self.last_state = state
00190         #import deserialize; deserialize.pstate(self.last_state)
00191 
00192         #log("Packet.  Mode=%s" % state.robot_mode_data.robot_mode)
00193 
00194         if not state.robot_mode_data.real_robot_enabled:
00195             rospy.logfatal("Real robot is no longer enabled.  Driver is fuxored")
00196             time.sleep(2)
00197             sys.exit(1)
00198         
00199         ###
00200         # IO-Support is EXPERIMENTAL
00201         # 
00202         # Notes: 
00203         # - Where are the flags coming from? Do we need flags? No, as 'prog' does not use them and other scripts are not running!
00204         # - analog_input2 and analog_input3 are within ToolData
00205         # - What to do with the different analog_input/output_range/domain?
00206         # - Shall we have appropriate ur_msgs definitions in order to reflect MasterboardData, ToolData,...?
00207         ###
00208         
00209         # Use information from the robot state packet to publish IOStates        
00210         msg = IOStates()
00211         #gets digital in states
00212         for i in range(0, 10):
00213             msg.digital_in_states.append(DigitalIn(i, (state.masterboard_data.digital_input_bits & (1<<i))>>i))
00214         #gets digital out states
00215         for i in range(0, 10):
00216             msg.digital_out_states.append(DigitalOut(i, (state.masterboard_data.digital_output_bits & (1<<i))>>i))
00217         #gets analog_in[0] state
00218         inp = state.masterboard_data.analog_input0 / MULT_analog_robotstate
00219         msg.analog_in_states.append(Analog(0, inp))
00220         #gets analog_in[1] state
00221         inp = state.masterboard_data.analog_input1 / MULT_analog_robotstate
00222         msg.analog_in_states.append(Analog(1, inp))      
00223         #gets analog_out[0] state
00224         inp = state.masterboard_data.analog_output0 / MULT_analog_robotstate
00225         msg.analog_out_states.append(Analog(0, inp))     
00226         #gets analog_out[1] state
00227         inp = state.masterboard_data.analog_output1 / MULT_analog_robotstate
00228         msg.analog_out_states.append(Analog(1, inp))     
00229         #print "Publish IO-Data from robot state data"
00230         pub_io_states.publish(msg)
00231         
00232 
00233         # Updates the state machine that determines whether we can program the robot.
00234         can_execute = (state.robot_mode_data.robot_mode in [RobotMode.READY, RobotMode.RUNNING])
00235         if self.robot_state == self.CONNECTED:
00236             if can_execute:
00237                 self.__trigger_ready_to_program()
00238                 self.robot_state = self.READY_TO_PROGRAM
00239         elif self.robot_state == self.READY_TO_PROGRAM:
00240             if not can_execute:
00241                 self.robot_state = self.CONNECTED
00242         elif self.robot_state == self.EXECUTING:
00243             if not can_execute:
00244                 self.__trigger_halted()
00245                 self.robot_state = self.CONNECTED
00246 
00247         # Report on any unknown packet types that were received
00248         if len(state.unknown_ptypes) > 0:
00249             state.unknown_ptypes.sort()
00250             s_unknown_ptypes = [str(ptype) for ptype in state.unknown_ptypes]
00251             self.throttle_warn_unknown(1.0, "Ignoring unknown pkt type(s): %s. "
00252                           "Please report." % ", ".join(s_unknown_ptypes))
00253 
00254     def throttle_warn_unknown(self, period, msg):
00255         self.__dict__.setdefault('_last_hit', 0.0)
00256         # this only works for a single caller
00257         if (self._last_hit + period) <= rospy.get_time():
00258             self._last_hit = rospy.get_time()
00259             rospy.logwarn(msg)
00260 
00261     def __run(self):
00262         while self.__keep_running:
00263             r, _, _ = select.select([self.__sock], [], [], self.TIMEOUT)
00264             if r:
00265                 more = self.__sock.recv(4096)
00266                 if more:
00267                     self.__buf = self.__buf + more
00268 
00269                     #unpack_from requires a buffer of at least 48 bytes
00270                     while len(self.__buf) >= 48:
00271                         # Attempts to extract a packet
00272                         packet_length, ptype = struct.unpack_from("!IB", self.__buf)
00273                         #print("PacketLength: ", packet_length, "; BufferSize: ", len(self.__buf))
00274                         if len(self.__buf) >= packet_length:
00275                             packet, self.__buf = self.__buf[:packet_length], self.__buf[packet_length:]
00276                             self.__on_packet(packet)
00277                         else:
00278                             break
00279 
00280                 else:
00281                     self.__trigger_disconnected()
00282                     self.__keep_running = False
00283                     
00284             else:
00285                 self.__trigger_disconnected()
00286                 self.__keep_running = False
00287 
00288 
00289 class URConnectionRT(object):
00290     TIMEOUT = 1.0
00291     
00292     DISCONNECTED = 0
00293     CONNECTED = 1
00294     
00295     def __init__(self, hostname, port):
00296         self.__thread = None
00297         self.__sock = None
00298         self.robot_state = self.DISCONNECTED
00299         self.hostname = hostname
00300         self.port = port
00301         self.last_stateRT = None
00302 
00303     def connect(self):
00304         if self.__sock:
00305             self.disconnect()
00306         self.__buf = ""
00307         self.robot_state = self.CONNECTED
00308         self.__sock = socket.create_connection((self.hostname, self.port))
00309         self.__keep_running = True
00310         self.__thread = threading.Thread(name="URConnectionRT", target=self.__run)
00311         self.__thread.daemon = True
00312         self.__thread.start()
00313         
00314     def disconnect(self):
00315         if self.__thread:
00316             self.__keep_running = False
00317             self.__thread.join()
00318             self.__thread = None
00319         if self.__sock:
00320             self.__sock.close()
00321             self.__sock = None
00322         self.last_state = None
00323         self.robot_state = self.DISCONNECTED
00324 
00325     def __trigger_disconnected(self):
00326         log("Robot disconnected")
00327         self.robot_state = self.DISCONNECTED
00328 
00329     def __on_packet(self, buf):
00330         global last_joint_states, last_joint_states_lock
00331         now = rospy.get_rostime()
00332         stateRT = RobotStateRT.unpack(buf)
00333         self.last_stateRT = stateRT
00334         
00335         msg = JointState()
00336         msg.header.stamp = now
00337         msg.header.frame_id = "From real-time state data"
00338         msg.name = joint_names
00339         msg.position = [0.0] * 6
00340         for i, q in enumerate(stateRT.q_actual):
00341             msg.position[i] = q + joint_offsets.get(joint_names[i], 0.0)
00342         msg.velocity = stateRT.qd_actual
00343         msg.effort = [0]*6
00344         pub_joint_states.publish(msg)
00345         with last_joint_states_lock:
00346             last_joint_states = msg
00347         
00348         wrench_msg = WrenchStamped()
00349         wrench_msg.header.stamp = now
00350         wrench_msg.wrench.force.x = stateRT.tcp_force[0]
00351         wrench_msg.wrench.force.y = stateRT.tcp_force[1]
00352         wrench_msg.wrench.force.z = stateRT.tcp_force[2]
00353         wrench_msg.wrench.torque.x = stateRT.tcp_force[3]
00354         wrench_msg.wrench.torque.y = stateRT.tcp_force[4]
00355         wrench_msg.wrench.torque.z = stateRT.tcp_force[5]
00356         pub_wrench.publish(wrench_msg)
00357         
00358 
00359     def __run(self):
00360         while self.__keep_running:
00361             r, _, _ = select.select([self.__sock], [], [], self.TIMEOUT)
00362             if r:
00363                 more = self.__sock.recv(4096)
00364                 if more:
00365                     self.__buf = self.__buf + more
00366                     
00367                     #unpack_from requires a buffer of at least 48 bytes
00368                     while len(self.__buf) >= 48:
00369                         # Attempts to extract a packet
00370                         packet_length = struct.unpack_from("!i", self.__buf)[0]
00371                         #print("PacketLength: ", packet_length, "; BufferSize: ", len(self.__buf))
00372                         if len(self.__buf) >= packet_length:
00373                             packet, self.__buf = self.__buf[:packet_length], self.__buf[packet_length:]
00374                             self.__on_packet(packet)
00375                         else:
00376                             break
00377                 else:
00378                     self.__trigger_disconnected()
00379                     self.__keep_running = False
00380                     
00381             else:
00382                 self.__trigger_disconnected()
00383                 self.__keep_running = False
00384 
00385 
00386 def setConnectedRobot(r):
00387     global connected_robot, connected_robot_lock
00388     with connected_robot_lock:
00389         connected_robot = r
00390         connected_robot_cond.notify()
00391 
00392 def getConnectedRobot(wait=False, timeout=-1):
00393     started = time.time()
00394     with connected_robot_lock:
00395         if wait:
00396             while not connected_robot:
00397                 if timeout >= 0 and time.time() > started + timeout:
00398                     break
00399                 connected_robot_cond.wait(0.2)
00400         return connected_robot
00401 
00402 # Receives messages from the robot over the socket
00403 class CommanderTCPHandler(SocketServer.BaseRequestHandler):
00404 
00405     def recv_more(self):
00406         global last_joint_states, last_joint_states_lock
00407         while True:
00408             r, _, _ = select.select([self.request], [], [], 0.2)
00409             if r:
00410                 more = self.request.recv(4096)
00411                 if not more:
00412                     raise EOF("EOF on recv")
00413                 return more
00414             else:
00415                 now = rospy.get_rostime()
00416                 if last_joint_states and \
00417                         last_joint_states.header.stamp < now - rospy.Duration(1.0):
00418                     rospy.logerr("Stopped hearing from robot (last heard %.3f sec ago).  Disconnected" % \
00419                                      (now - last_joint_states.header.stamp).to_sec())
00420                     raise EOF()
00421 
00422     def handle(self):
00423         self.socket_lock = threading.Lock()
00424         setConnectedRobot(self)
00425         print "Handling a request"
00426         try:
00427             buf = self.recv_more()
00428             if not buf: return
00429 
00430             while True:
00431                 #print "Buf:", [ord(b) for b in buf]
00432 
00433                 # Unpacks the message type
00434                 mtype = struct.unpack_from("!i", buf, 0)[0]
00435                 buf = buf[4:]
00436                 #print "Message type:", mtype
00437 
00438                 if mtype == MSG_OUT:
00439                     # Unpacks string message, terminated by tilde
00440                     i = buf.find("~")
00441                     while i < 0:
00442                         buf = buf + self.recv_more()
00443                         i = buf.find("~")
00444                         if len(buf) > 2000:
00445                             raise Exception("Probably forgot to terminate a string: %s..." % buf[:150])
00446                     s, buf = buf[:i], buf[i+1:]
00447                     log("Out: %s" % s)
00448                 
00449                 elif mtype == MSG_QUIT:
00450                     print "Quitting"
00451                     raise EOF("Received quit")
00452                 elif mtype == MSG_WAYPOINT_FINISHED:
00453                     while len(buf) < 4:
00454                         buf = buf + self.recv_more()
00455                     waypoint_id = struct.unpack_from("!i", buf, 0)[0]
00456                     buf = buf[4:]
00457                     print "Waypoint finished (not handled)"
00458                 else:
00459                     raise Exception("Unknown message type: %i" % mtype)
00460 
00461                 if not buf:
00462                     buf = buf + self.recv_more()
00463         except EOF, ex:
00464             print "Connection closed (command):", ex
00465             setConnectedRobot(None)
00466 
00467     def send_quit(self):
00468         with self.socket_lock:
00469             self.request.send(struct.pack("!i", MSG_QUIT))
00470 
00471     def send_servoj(self, waypoint_id, q_actual, t):
00472         assert(len(q_actual) == 6)
00473         q_robot = [0.0] * 6
00474         for i, q in enumerate(q_actual):
00475             q_robot[i] = q - joint_offsets.get(joint_names[i], 0.0)
00476         params = [MSG_SERVOJ, waypoint_id] + \
00477                  [MULT_jointstate * qq for qq in q_robot] + \
00478                  [MULT_time * t]
00479         buf = struct.pack("!%ii" % len(params), *params)
00480         with self.socket_lock:
00481             self.request.send(buf)
00482         
00483     #Experimental set_payload implementation
00484     def send_payload(self,payload):
00485         buf = struct.pack('!ii', MSG_SET_PAYLOAD, payload * MULT_payload)
00486         with self.socket_lock:
00487             self.request.send(buf)
00488 
00489     #Experimental set_digital_output implementation
00490     def set_digital_out(self, pinnum, value):
00491         params = [MSG_SET_DIGITAL_OUT] + \
00492                  [pinnum] + \
00493                  [value]
00494         buf = struct.pack("!%ii" % len(params), *params)
00495         #print params
00496         with self.socket_lock:
00497             self.request.send(buf) 
00498         time.sleep(IO_SLEEP_TIME)
00499 
00500     def set_analog_out(self, pinnum, value):
00501         params = [MSG_SET_ANALOG_OUT] + \
00502                  [pinnum] + \
00503                  [value * MULT_analog]
00504         buf = struct.pack("!%ii" % len(params), *params)
00505         #print params
00506         with self.socket_lock:
00507             self.request.send(buf) 
00508         time.sleep(IO_SLEEP_TIME)
00509 
00510     def set_tool_voltage(self, value):
00511         params = [MSG_SET_TOOL_VOLTAGE] + \
00512                  [value] + \
00513                  [0]
00514         buf = struct.pack("!%ii" % len(params), *params)
00515         #print params
00516         with self.socket_lock:
00517             self.request.send(buf) 
00518         time.sleep(IO_SLEEP_TIME)
00519 
00520     def set_flag(self, pin, val):
00521         params = [MSG_SET_FLAG] + \
00522                  [pin] + \
00523                  [val]
00524         buf = struct.pack("!%ii" % len(params), *params)
00525         #print params
00526         with self.socket_lock:
00527             self.request.send(buf) 
00528         #set_flag will fail if called too closely together--added delay
00529         time.sleep(IO_SLEEP_TIME)
00530 
00531     def send_stopj(self):
00532         with self.socket_lock:
00533             self.request.send(struct.pack("!i", MSG_STOPJ))
00534 
00535     def set_waypoint_finished_cb(self, cb):
00536         self.waypoint_finished_cb = cb
00537 
00538     # Returns the last JointState message sent out
00539     def get_joint_states(self):
00540         global last_joint_states, last_joint_states_lock
00541         return last_joint_states
00542     
00543 
00544 class TCPServer(SocketServer.TCPServer):
00545     allow_reuse_address = True  # Allows the program to restart gracefully on crash
00546     timeout = 5
00547 
00548 
00549 # Waits until all threads have completed.  Allows KeyboardInterrupt to occur
00550 def joinAll(threads):
00551     while any(t.isAlive() for t in threads):
00552         for t in threads:
00553             t.join(0.2)
00554 
00555 # Returns the duration between moving from point (index-1) to point
00556 # index in the given JointTrajectory
00557 def get_segment_duration(traj, index):
00558     if index == 0:
00559         return traj.points[0].time_from_start.to_sec()
00560     return (traj.points[index].time_from_start - traj.points[index-1].time_from_start).to_sec()
00561 
00562 # Reorders the JointTrajectory traj according to the order in
00563 # joint_names.  Destructive.
00564 def reorder_traj_joints(traj, joint_names):
00565     order = [traj.joint_names.index(j) for j in joint_names]
00566 
00567     new_points = []
00568     for p in traj.points:
00569         new_points.append(JointTrajectoryPoint(
00570             positions = [p.positions[i] for i in order],
00571             velocities = [p.velocities[i] for i in order] if p.velocities else [],
00572             accelerations = [p.accelerations[i] for i in order] if p.accelerations else [],
00573             time_from_start = p.time_from_start))
00574     traj.joint_names = joint_names
00575     traj.points = new_points
00576 
00577 def interp_cubic(p0, p1, t_abs):
00578     T = (p1.time_from_start - p0.time_from_start).to_sec()
00579     t = t_abs - p0.time_from_start.to_sec()
00580     q = [0] * 6
00581     qdot = [0] * 6
00582     qddot = [0] * 6
00583     for i in range(len(p0.positions)):
00584         a = p0.positions[i]
00585         b = p0.velocities[i]
00586         c = (-3*p0.positions[i] + 3*p1.positions[i] - 2*T*p0.velocities[i] - T*p1.velocities[i]) / T**2
00587         d = (2*p0.positions[i] - 2*p1.positions[i] + T*p0.velocities[i] + T*p1.velocities[i]) / T**3
00588 
00589         q[i] = a + b*t + c*t**2 + d*t**3
00590         qdot[i] = b + 2*c*t + 3*d*t**2
00591         qddot[i] = 2*c + 6*d*t
00592     return JointTrajectoryPoint(positions=q, velocities=qdot, accelerations=qddot, time_from_start=rospy.Duration(t_abs))
00593 
00594 # Returns (q, qdot, qddot) for sampling the JointTrajectory at time t.
00595 # The time t is the time since the trajectory was started.
00596 def sample_traj(traj, t):
00597     # First point
00598     if t <= 0.0:
00599         return copy.deepcopy(traj.points[0])
00600     # Last point
00601     if t >= traj.points[-1].time_from_start.to_sec():
00602         return copy.deepcopy(traj.points[-1])
00603     
00604     # Finds the (middle) segment containing t
00605     i = 0
00606     while traj.points[i+1].time_from_start.to_sec() < t:
00607         i += 1
00608     return interp_cubic(traj.points[i], traj.points[i+1], t)
00609 
00610 def traj_is_finite(traj):
00611     for pt in traj.points:
00612         for p in pt.positions:
00613             if math.isinf(p) or math.isnan(p):
00614                 return False
00615         for v in pt.velocities:
00616             if math.isinf(v) or math.isnan(v):
00617                 return False
00618     return True
00619         
00620 def has_limited_velocities(traj):
00621     for p in traj.points:
00622         for v in p.velocities:
00623             if math.fabs(v) > max_velocity:
00624                 return False
00625     return True
00626 
00627 def has_velocities(traj):
00628     for p in traj.points:
00629         if len(p.velocities) != len(p.positions):
00630             return False
00631     return True
00632 
00633 def within_tolerance(a_vec, b_vec, tol_vec):
00634     for a, b, tol in zip(a_vec, b_vec, tol_vec):
00635         if abs(a - b) > tol:
00636             return False
00637     return True
00638 
00639 class URServiceProvider(object):
00640     def __init__(self, robot):
00641         self.robot = robot
00642         rospy.Service('ur_driver/setPayload', SetPayload, self.setPayload)
00643 
00644     def set_robot(self, robot):
00645         self.robot = robot
00646 
00647     def setPayload(self, req):
00648         if req.payload < min_payload or req.payload > max_payload:
00649             print 'ERROR: Payload ' + str(req.payload) + ' out of bounds (' + str(min_payload) + ', ' + str(max_payload) + ')'
00650             return False
00651         
00652         if self.robot:
00653             self.robot.send_payload(req.payload)
00654         else:
00655             return False
00656         return True
00657 
00658 class URTrajectoryFollower(object):
00659     RATE = 0.02
00660     def __init__(self, robot, goal_time_tolerance=None):
00661         self.goal_time_tolerance = goal_time_tolerance or rospy.Duration(0.0)
00662         self.joint_goal_tolerances = [0.05, 0.05, 0.05, 0.05, 0.05, 0.05]
00663         self.following_lock = threading.Lock()
00664         self.T0 = time.time()
00665         self.robot = robot
00666         self.server = actionlib.ActionServer("follow_joint_trajectory",
00667                                              FollowJointTrajectoryAction,
00668                                              self.on_goal, self.on_cancel, auto_start=False)
00669 
00670         self.goal_handle = None
00671         self.traj = None
00672         self.traj_t0 = 0.0
00673         self.first_waypoint_id = 10
00674         self.tracking_i = 0
00675         self.pending_i = 0
00676         self.last_point_sent = True
00677 
00678         self.update_timer = rospy.Timer(rospy.Duration(self.RATE), self._update)
00679 
00680     def set_robot(self, robot):
00681         # Cancels any goals in progress
00682         if self.goal_handle:
00683             self.goal_handle.set_canceled()
00684             self.goal_handle = None
00685         self.traj = None
00686         self.robot = robot
00687         if self.robot:
00688             self.init_traj_from_robot()
00689 
00690     # Sets the trajectory to remain stationary at the current position
00691     # of the robot.
00692     def init_traj_from_robot(self):
00693         if not self.robot: raise Exception("No robot connected")
00694         # Busy wait (avoids another mutex)
00695         state = self.robot.get_joint_states()
00696         while not state:
00697             time.sleep(0.1)
00698             state = self.robot.get_joint_states()
00699         self.traj_t0 = time.time()
00700         self.traj = JointTrajectory()
00701         self.traj.joint_names = joint_names
00702         self.traj.points = [JointTrajectoryPoint(
00703             positions = state.position,
00704             velocities = [0] * 6,
00705             accelerations = [0] * 6,
00706             time_from_start = rospy.Duration(0.0))]
00707 
00708     def start(self):
00709         self.init_traj_from_robot()
00710         self.server.start()
00711         print "The action server for this driver has been started"
00712 
00713     def on_goal(self, goal_handle):
00714         log("on_goal")
00715 
00716         # Checks that the robot is connected
00717         if not self.robot:
00718             rospy.logerr("Received a goal, but the robot is not connected")
00719             goal_handle.set_rejected()
00720             return
00721 
00722         # Checks if the joints are just incorrect
00723         if set(goal_handle.get_goal().trajectory.joint_names) != set(joint_names):
00724             rospy.logerr("Received a goal with incorrect joint names: (%s)" % \
00725                          ', '.join(goal_handle.get_goal().trajectory.joint_names))
00726             goal_handle.set_rejected()
00727             return
00728 
00729         if not traj_is_finite(goal_handle.get_goal().trajectory):
00730             rospy.logerr("Received a goal with infinites or NaNs")
00731             goal_handle.set_rejected(text="Received a goal with infinites or NaNs")
00732             return
00733         
00734         # Checks that the trajectory has velocities
00735         if not has_velocities(goal_handle.get_goal().trajectory):
00736             rospy.logerr("Received a goal without velocities")
00737             goal_handle.set_rejected(text="Received a goal without velocities")
00738             return
00739 
00740         # Checks that the velocities are withing the specified limits
00741         if not has_limited_velocities(goal_handle.get_goal().trajectory):
00742             message = "Received a goal with velocities that are higher than %f" % max_velocity
00743             rospy.logerr(message)
00744             goal_handle.set_rejected(text=message)
00745             return
00746 
00747         # Orders the joints of the trajectory according to joint_names
00748         reorder_traj_joints(goal_handle.get_goal().trajectory, joint_names)
00749                 
00750         with self.following_lock:
00751             if self.goal_handle:
00752                 # Cancels the existing goal
00753                 self.goal_handle.set_canceled()
00754                 self.first_waypoint_id += len(self.goal_handle.get_goal().trajectory.points)
00755                 self.goal_handle = None
00756 
00757             # Inserts the current setpoint at the head of the trajectory
00758             now = time.time()
00759             point0 = sample_traj(self.traj, now)
00760             point0.time_from_start = rospy.Duration(0.0)
00761             goal_handle.get_goal().trajectory.points.insert(0, point0)
00762             self.traj_t0 = now
00763 
00764             # Replaces the goal
00765             self.goal_handle = goal_handle
00766             self.traj = goal_handle.get_goal().trajectory
00767             self.goal_handle.set_accepted()
00768 
00769     def on_cancel(self, goal_handle):
00770         log("on_cancel")
00771         if goal_handle == self.goal_handle:
00772             with self.following_lock:
00773                 # Uses the next little bit of trajectory to slow to a stop
00774                 STOP_DURATION = 0.5
00775                 now = time.time()
00776                 point0 = sample_traj(self.traj, now - self.traj_t0)
00777                 point0.time_from_start = rospy.Duration(0.0)
00778                 point1 = sample_traj(self.traj, now - self.traj_t0 + STOP_DURATION)
00779                 point1.velocities = [0] * 6
00780                 point1.accelerations = [0] * 6
00781                 point1.time_from_start = rospy.Duration(STOP_DURATION)
00782                 self.traj_t0 = now
00783                 self.traj = JointTrajectory()
00784                 self.traj.joint_names = joint_names
00785                 self.traj.points = [point0, point1]
00786                 
00787                 self.goal_handle.set_canceled()
00788                 self.goal_handle = None
00789         else:
00790             goal_handle.set_canceled()
00791 
00792     last_now = time.time()
00793     def _update(self, event):
00794         if self.robot and self.traj:
00795             now = time.time()
00796             if (now - self.traj_t0) <= self.traj.points[-1].time_from_start.to_sec():
00797                 self.last_point_sent = False #sending intermediate points
00798                 setpoint = sample_traj(self.traj, now - self.traj_t0)
00799                 try:
00800                     self.robot.send_servoj(999, setpoint.positions, 4 * self.RATE)
00801                 except socket.error:
00802                     pass
00803                     
00804             elif not self.last_point_sent:
00805                 # All intermediate points sent, sending last point to make sure we
00806                 # reach the goal.
00807                 # This should solve an issue where the robot does not reach the final
00808                 # position and errors out due to not reaching the goal point.
00809                 last_point = self.traj.points[-1]
00810                 state = self.robot.get_joint_states()
00811                 position_in_tol = within_tolerance(state.position, last_point.positions, self.joint_goal_tolerances)
00812                 # Performing this check to try and catch our error condition.  We will always
00813                 # send the last point just in case.
00814                 if not position_in_tol:
00815                     rospy.logwarn("Trajectory time exceeded and current robot state not at goal, last point required")
00816                     rospy.logwarn("Current trajectory time: %s, last point time: %s" % \
00817                                 (now - self.traj_t0, self.traj.points[-1].time_from_start.to_sec()))
00818                     rospy.logwarn("Desired: %s\nactual: %s\nvelocity: %s" % \
00819                                           (last_point.positions, state.position, state.velocity))
00820                 setpoint = sample_traj(self.traj, self.traj.points[-1].time_from_start.to_sec())
00821 
00822                 try:
00823                     self.robot.send_servoj(999, setpoint.positions, 4 * self.RATE)
00824                     self.last_point_sent = True
00825                 except socket.error:
00826                     pass
00827                     
00828             else:  # Off the end
00829                 if self.goal_handle:
00830                     last_point = self.traj.points[-1]
00831                     state = self.robot.get_joint_states()
00832                     position_in_tol = within_tolerance(state.position, last_point.positions, [0.1]*6)
00833                     velocity_in_tol = within_tolerance(state.velocity, last_point.velocities, [0.05]*6)
00834                     if position_in_tol and velocity_in_tol:
00835                         # The arm reached the goal (and isn't moving).  Succeeding
00836                         self.goal_handle.set_succeeded()
00837                         self.goal_handle = None
00838                     #elif now - (self.traj_t0 + last_point.time_from_start.to_sec()) > self.goal_time_tolerance.to_sec():
00839                     #    # Took too long to reach the goal.  Aborting
00840                     #    rospy.logwarn("Took too long to reach the goal.\nDesired: %s\nactual: %s\nvelocity: %s" % \
00841                     #                      (last_point.positions, state.position, state.velocity))
00842                     #    self.goal_handle.set_aborted(text="Took too long to reach the goal")
00843                     #    self.goal_handle = None
00844 
00845 
00846 # joint_names: list of joints
00847 #
00848 # returns: { "joint_name" : joint_offset }
00849 def load_joint_offsets(joint_names):
00850     from lxml import etree
00851     robot_description = rospy.get_param("robot_description")
00852     doc = etree.fromstring(robot_description)
00853 
00854     # select only 'calibration_offset' elements whose parent is a joint
00855     # element with a specific value for the name attribute
00856     expr = "/robot/joint[@name=$name]/calibration_offset"
00857     result = {}
00858     for joint in joint_names:
00859         joint_elt = doc.xpath(expr, name=joint)
00860         if len(joint_elt) == 1:
00861             calibration_offset = float(joint_elt[0].get("value"))
00862             result[joint] = calibration_offset
00863             rospy.loginfo("Found calibration offset for joint \"%s\": %.4f" % (joint, calibration_offset))
00864         elif len(joint_elt) > 1:
00865             rospy.logerr("Too many joints matched on \"%s\". Please report to package maintainer(s)." % joint)
00866         else:
00867             rospy.logwarn("No calibration offset for joint \"%s\"" % joint)
00868     return result
00869 
00870 def get_my_ip(robot_ip, port):
00871     s = socket.create_connection((robot_ip, port))
00872     tmp = s.getsockname()[0]
00873     s.close()
00874     return tmp
00875 
00876 def handle_set_io(req):
00877     r = getConnectedRobot(wait=False)
00878     if r:
00879         if req.fun == FUN_SET_DIGITAL_OUT:
00880             r.set_digital_out(req.pin, req.state)
00881             return True
00882         elif req.fun == FUN_SET_FLAG:
00883             r.set_flag(req.pin, req.state)
00884             return True
00885         elif req.fun == FUN_SET_ANALOG_OUT:
00886             r.set_analog_out(req.pin, req.state)
00887             return True
00888         elif req.fun == FUN_SET_TOOL_VOLTAGE:
00889             r.set_tool_voltage(req.pin)
00890             return True
00891     else:
00892         raise ROSServiceException("Robot not connected")
00893 
00894 def set_io_server():
00895     s= rospy.Service('set_io', SetIO, handle_set_io)
00896 
00897 def main():
00898     rospy.init_node('ur_driver', disable_signals=True)
00899     if rospy.get_param("use_sim_time", False):
00900         rospy.logwarn("use_sim_time is set!!!")
00901     global prevent_programming
00902     prevent_programming = rospy.get_param("prevent_programming", False)
00903     prefix = rospy.get_param("~prefix", "")
00904     print "Setting prefix to %s" % prefix
00905     global joint_names
00906     joint_names = [prefix + name for name in JOINT_NAMES]
00907 
00908     # Parses command line arguments
00909     parser = optparse.OptionParser(usage="usage: %prog robot_hostname [reverse_port]")
00910     (options, args) = parser.parse_args(rospy.myargv()[1:])
00911     if len(args) < 1:
00912         parser.error("You must specify the robot hostname")
00913     elif len(args) == 1:
00914         robot_hostname = args[0]
00915         reverse_port = DEFAULT_REVERSE_PORT
00916     elif len(args) == 2:
00917         robot_hostname = args[0]
00918         reverse_port = int(args[1])
00919         if not (0 <= reverse_port <= 65535):
00920                 parser.error("You entered an invalid port number")
00921     else:
00922         parser.error("Wrong number of parameters")
00923 
00924     # Reads the calibrated joint offsets from the URDF
00925     global joint_offsets
00926     joint_offsets = load_joint_offsets(joint_names)
00927     if len(joint_offsets) > 0:
00928         rospy.loginfo("Loaded calibration offsets from urdf: %s" % joint_offsets)
00929     else:
00930         rospy.loginfo("No calibration offsets loaded from urdf")
00931 
00932     # Reads the maximum velocity
00933     # The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits
00934     global max_velocity
00935     max_velocity = rospy.get_param("~max_velocity", MAX_VELOCITY) # [rad/s] 
00936     rospy.loginfo("Max velocity accepted by ur_driver: %s [rad/s]" % max_velocity)
00937     
00938     # Reads the minimum payload
00939     global min_payload
00940     min_payload = rospy.get_param("~min_payload", MIN_PAYLOAD)
00941     # Reads the maximum payload
00942     global max_payload
00943     max_payload = rospy.get_param("~max_payload", MAX_PAYLOAD)
00944     rospy.loginfo("Bounds for Payload: [%s, %s]" % (min_payload, max_payload))
00945     
00946 
00947     # Sets up the server for the robot to connect to
00948     server = TCPServer(("", reverse_port), CommanderTCPHandler)
00949     thread_commander = threading.Thread(name="CommanderHandler", target=server.serve_forever)
00950     thread_commander.daemon = True
00951     thread_commander.start()
00952 
00953     with open(roslib.packages.get_pkg_dir('ur_driver') + '/prog') as fin:
00954         program = fin.read() % {"driver_hostname": get_my_ip(robot_hostname, PORT), "driver_reverseport": reverse_port}
00955     connection = URConnection(robot_hostname, PORT, program)
00956     connection.connect()
00957     connection.send_reset_program()
00958     
00959     connectionRT = URConnectionRT(robot_hostname, RT_PORT)
00960     connectionRT.connect()
00961     
00962     set_io_server()
00963     
00964     service_provider = None
00965     action_server = None
00966     try:
00967         while not rospy.is_shutdown():
00968             # Checks for disconnect
00969             if getConnectedRobot(wait=False):
00970                 time.sleep(0.2)
00971                 prevent_programming = rospy.get_param("prevent_programming", False)
00972                 if prevent_programming:
00973                     print "Programming now prevented"
00974                     connection.send_reset_program()
00975             else:
00976                 print "Disconnected.  Reconnecting"
00977                 if action_server:
00978                     action_server.set_robot(None)
00979 
00980                 rospy.loginfo("Programming the robot")
00981                 while True:
00982                     # Sends the program to the robot
00983                     while not connection.ready_to_program():
00984                         print "Waiting to program"
00985                         time.sleep(1.0)
00986                     prevent_programming = rospy.get_param("prevent_programming", False)
00987                     connection.send_program()
00988 
00989                     r = getConnectedRobot(wait=True, timeout=1.0)
00990                     if r:
00991                         break
00992                 rospy.loginfo("Robot connected")
00993 
00994                 #provider for service calls
00995                 if service_provider:
00996                     service_provider.set_robot(r)
00997                 else:
00998                     service_provider = URServiceProvider(r)
00999                 
01000                 if action_server:
01001                     action_server.set_robot(r)
01002                 else:
01003                     action_server = URTrajectoryFollower(r, rospy.Duration(1.0))
01004                     action_server.start()
01005 
01006     except KeyboardInterrupt:
01007         try:
01008             r = getConnectedRobot(wait=False)
01009             rospy.signal_shutdown("KeyboardInterrupt")
01010             if r: r.send_quit()
01011         except:
01012             pass
01013         raise
01014 
01015 if __name__ == '__main__': main()


ur_driver
Author(s): Stuart Glaser, Shaun Edwards , Felix Messmer
autogenerated on Fri Aug 28 2015 13:31:30