driver.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 from __future__ import print_function
3 import roslib; roslib.load_manifest('ur_driver')
4 import time, sys, threading, math
5 import copy
6 import datetime
7 import socket, select
8 import struct
9 import traceback, code
10 import optparse
11 import SocketServer
12 
13 import rospy
14 import actionlib
15 from sensor_msgs.msg import JointState
16 from control_msgs.msg import FollowJointTrajectoryAction
17 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
18 from geometry_msgs.msg import WrenchStamped
19 
20 from dynamic_reconfigure.server import Server
21 from ur_driver.cfg import URDriverConfig
22 
23 from ur_driver.deserialize import RobotState, RobotMode
24 from ur_driver.deserializeRT import RobotStateRT
25 
26 from ur_msgs.srv import SetPayload, SetIO
27 from ur_msgs.msg import *
28 
29 # renaming classes
30 DigitalIn = Digital
31 DigitalOut = Digital
32 Flag = Digital
33 
34 prevent_programming = False
35 
36 # Joint offsets, pulled from calibration information stored in the URDF
37 #
38 # { "joint_name" : offset }
39 #
40 # q_actual = q_from_driver + offset
41 joint_offsets = {}
42 
43 PORT=30002 # 10 Hz, RobotState
44 RT_PORT=30003 #125 Hz, RobotStateRT
45 DEFAULT_REVERSE_PORT = 50001 #125 Hz, custom data (from prog)
46 
47 MSG_OUT = 1
48 MSG_QUIT = 2
49 MSG_JOINT_STATES = 3
50 MSG_MOVEJ = 4
51 MSG_WAYPOINT_FINISHED = 5
52 MSG_STOPJ = 6
53 MSG_SERVOJ = 7
54 MSG_SET_PAYLOAD = 8
55 MSG_WRENCH = 9
56 MSG_SET_DIGITAL_OUT = 10
57 MSG_GET_IO = 11
58 MSG_SET_FLAG = 12
59 MSG_SET_TOOL_VOLTAGE = 13
60 MSG_SET_ANALOG_OUT = 14
61 MULT_payload = 1000.0
62 MULT_wrench = 10000.0
63 MULT_jointstate = 10000.0
64 MULT_time = 1000000.0
65 MULT_blend = 1000.0
66 MULT_analog = 1000000.0
67 MULT_analog_robotstate = 0.1
68 
69 #Max Velocity accepted by ur_driver
70 MAX_VELOCITY = 10.0
71 #Using a very high value in order to not limit execution of trajectories being sent from MoveIt!
72 
73 #Bounds for SetPayload service
74 MIN_PAYLOAD = 0.0
75 MAX_PAYLOAD = 1.0
76 #Using a very conservative value as it should be set throught the parameter server
77 
78 
79 IO_SLEEP_TIME = 0.05
80 
81 JOINT_NAMES = ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint',
82  'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
83 
84 Q1 = [2.2,0,-1.57,0,0,0]
85 Q2 = [1.5,0,-1.57,0,0,0]
86 Q3 = [1.5,-0.2,-1.57,0,0,0]
87 
88 
89 connected_robot = None
90 connected_robot_lock = threading.Lock()
91 connected_robot_cond = threading.Condition(connected_robot_lock)
92 last_joint_states = None
93 last_joint_states_lock = threading.Lock()
94 pub_joint_states = rospy.Publisher('joint_states', JointState, queue_size=1)
95 pub_wrench = rospy.Publisher('wrench', WrenchStamped, queue_size=1)
96 pub_io_states = rospy.Publisher('io_states', IOStates, queue_size=1)
97 #dump_state = open('dump_state', 'wb')
98 
99 class EOF(Exception): pass
100 
102  id2name = dict([(th.ident, th.name) for th in threading.enumerate()])
103  code = []
104  for threadId, stack in sys._current_frames().items():
105  code.append("\n# Thread: %s(%d)" % (id2name.get(threadId,""), threadId))
106  for filename, lineno, name, line in traceback.extract_stack(stack):
107  code.append('File: "%s", line %d, in %s' % (filename, lineno, name))
108  if line:
109  code.append(" %s" % (line.strip()))
110  print("\n".join(code))
111 
112 def log(s):
113  print("[%s] %s" % (datetime.datetime.now().strftime('%Y-%m-%d %H:%M:%S.%f'), s))
114 
115 
116 RESET_PROGRAM = '''def resetProg():
117  sleep(0.0)
118 end
119 '''
120 #RESET_PROGRAM = ''
121 
122 class URConnection(object):
123  TIMEOUT = 1.0
124 
125  DISCONNECTED = 0
126  CONNECTED = 1
127  READY_TO_PROGRAM = 2
128  EXECUTING = 3
129 
130  def __init__(self, hostname, port, program):
131  self.__thread = None
132  self.__sock = None
134  self.hostname = hostname
135  self.port = port
136  self.program = program
137  self.last_state = None
138 
139  def connect(self):
140  if self.__sock:
141  self.disconnect()
142  self.__buf = ""
143  self.robot_state = self.CONNECTED
144  self.__sock = socket.create_connection((self.hostname, self.port))
145  self.__keep_running = True
146  self.__thread = threading.Thread(name="URConnection", target=self.__run)
147  self.__thread.daemon = True
148  self.__thread.start()
149 
150  def send_program(self):
151  global prevent_programming
152  if prevent_programming:
153  rospy.loginfo("Programming is currently prevented")
154  return
155  assert self.robot_state in [self.READY_TO_PROGRAM, self.EXECUTING]
156  rospy.loginfo("Programming the robot at %s" % self.hostname)
157  self.__sock.sendall(self.program)
158  self.robot_state = self.EXECUTING
159 
161  self.__sock.sendall(RESET_PROGRAM)
162  self.robot_state = self.READY_TO_PROGRAM
163 
164  def disconnect(self):
165  if self.__thread:
166  self.__keep_running = False
167  self.__thread.join()
168  self.__thread = None
169  if self.__sock:
170  self.__sock.close()
171  self.__sock = None
172  self.last_state = None
173  self.robot_state = self.DISCONNECTED
174 
175  def ready_to_program(self):
176  return self.robot_state in [self.READY_TO_PROGRAM, self.EXECUTING]
177 
179  log("Robot disconnected")
180  self.robot_state = self.DISCONNECTED
182  rospy.loginfo("Robot ready to program")
183  def __trigger_halted(self):
184  log("Halted")
185 
186  def __on_packet(self, buf):
187  state = RobotState.unpack(buf)
188  self.last_state = state
189  #import deserialize; deserialize.pstate(self.last_state)
190 
191  #log("Packet. Mode=%s" % state.robot_mode_data.robot_mode)
192 
193  if not state.robot_mode_data.real_robot_enabled:
194  rospy.logfatal("Real robot is no longer enabled. Driver is fuxored")
195  time.sleep(2)
196  sys.exit(1)
197 
198  ###
199  # IO-Support is EXPERIMENTAL
200  #
201  # Notes:
202  # - Where are the flags coming from? Do we need flags? No, as 'prog' does not use them and other scripts are not running!
203  # - analog_input2 and analog_input3 are within ToolData
204  # - What to do with the different analog_input/output_range/domain?
205  # - Shall we have appropriate ur_msgs definitions in order to reflect MasterboardData, ToolData,...?
206  ###
207 
208  # Use information from the robot state packet to publish IOStates
209  msg = IOStates()
210  #gets digital in states
211  for i in range(0, 10):
212  msg.digital_in_states.append(DigitalIn(i, (state.masterboard_data.digital_input_bits & (1<<i))>>i))
213  #gets digital out states
214  for i in range(0, 10):
215  msg.digital_out_states.append(DigitalOut(i, (state.masterboard_data.digital_output_bits & (1<<i))>>i))
216  #gets analog_in[0] state
217  inp = state.masterboard_data.analog_input0 / MULT_analog_robotstate
218  msg.analog_in_states.append(Analog(0, inp))
219  #gets analog_in[1] state
220  inp = state.masterboard_data.analog_input1 / MULT_analog_robotstate
221  msg.analog_in_states.append(Analog(1, inp))
222  #gets analog_out[0] state
223  inp = state.masterboard_data.analog_output0 / MULT_analog_robotstate
224  msg.analog_out_states.append(Analog(0, inp))
225  #gets analog_out[1] state
226  inp = state.masterboard_data.analog_output1 / MULT_analog_robotstate
227  msg.analog_out_states.append(Analog(1, inp))
228  #print "Publish IO-Data from robot state data"
229  pub_io_states.publish(msg)
230 
231 
232  # Updates the state machine that determines whether we can program the robot.
233  can_execute = (state.robot_mode_data.robot_mode in [RobotMode.READY, RobotMode.RUNNING])
234  if self.robot_state == self.CONNECTED:
235  if can_execute:
237  self.robot_state = self.READY_TO_PROGRAM
238  elif self.robot_state == self.READY_TO_PROGRAM:
239  if not can_execute:
240  self.robot_state = self.CONNECTED
241  elif self.robot_state == self.EXECUTING:
242  if not can_execute:
243  self.__trigger_halted()
244  self.robot_state = self.CONNECTED
245 
246  # Report on any unknown packet types that were received
247  if len(state.unknown_ptypes) > 0:
248  state.unknown_ptypes.sort()
249  s_unknown_ptypes = [str(ptype) for ptype in state.unknown_ptypes]
250  self.throttle_warn_unknown(1.0, "Ignoring unknown pkt type(s): %s. "
251  "Please report." % ", ".join(s_unknown_ptypes))
252 
253  def throttle_warn_unknown(self, period, msg):
254  self.__dict__.setdefault('_last_hit', 0.0)
255  # this only works for a single caller
256  if (self._last_hit + period) <= rospy.get_time():
257  self._last_hit = rospy.get_time()
258  rospy.logwarn(msg)
259 
260  def __run(self):
261  while self.__keep_running:
262  r, _, _ = select.select([self.__sock], [], [], self.TIMEOUT)
263  if r:
264  more = self.__sock.recv(4096)
265  if more:
266  self.__buf = self.__buf + more
267 
268  #unpack_from requires a buffer of at least 48 bytes
269  while len(self.__buf) >= 48:
270  # Attempts to extract a packet
271  packet_length, ptype = struct.unpack_from("!IB", self.__buf)
272  #print("PacketLength: ", packet_length, "; BufferSize: ", len(self.__buf))
273  if len(self.__buf) >= packet_length:
274  packet, self.__buf = self.__buf[:packet_length], self.__buf[packet_length:]
275  self.__on_packet(packet)
276  else:
277  break
278 
279  else:
281  self.__keep_running = False
282 
283  else:
285  self.__keep_running = False
286 
287 
288 class URConnectionRT(object):
289  TIMEOUT = 1.0
290 
291  DISCONNECTED = 0
292  CONNECTED = 1
293 
294  def __init__(self, hostname, port):
295  self.__thread = None
296  self.__sock = None
298  self.hostname = hostname
299  self.port = port
300  self.last_stateRT = None
301 
302  def connect(self):
303  if self.__sock:
304  self.disconnect()
305  self.__buf = ""
306  self.robot_state = self.CONNECTED
307  self.__sock = socket.create_connection((self.hostname, self.port))
308  self.__keep_running = True
309  self.__thread = threading.Thread(name="URConnectionRT", target=self.__run)
310  self.__thread.daemon = True
311  self.__thread.start()
312 
313  def disconnect(self):
314  if self.__thread:
315  self.__keep_running = False
316  self.__thread.join()
317  self.__thread = None
318  if self.__sock:
319  self.__sock.close()
320  self.__sock = None
321  self.last_state = None
322  self.robot_state = self.DISCONNECTED
323 
325  log("Robot disconnected")
326  self.robot_state = self.DISCONNECTED
327 
328  def __on_packet(self, buf):
329  global last_joint_states, last_joint_states_lock
330  now = rospy.get_rostime()
331  stateRT = RobotStateRT.unpack(buf)
332  self.last_stateRT = stateRT
333 
334  msg = JointState()
335  msg.header.stamp = now
336  msg.header.frame_id = "From real-time state data"
337  msg.name = joint_names
338  msg.position = [0.0] * 6
339  for i, q in enumerate(stateRT.q_actual):
340  msg.position[i] = q + joint_offsets.get(joint_names[i], 0.0)
341  msg.velocity = stateRT.qd_actual
342  msg.effort = [0]*6
343  pub_joint_states.publish(msg)
344  with last_joint_states_lock:
345  last_joint_states = msg
346 
347  wrench_msg = WrenchStamped()
348  wrench_msg.header.stamp = now
349  wrench_msg.wrench.force.x = stateRT.tcp_force[0]
350  wrench_msg.wrench.force.y = stateRT.tcp_force[1]
351  wrench_msg.wrench.force.z = stateRT.tcp_force[2]
352  wrench_msg.wrench.torque.x = stateRT.tcp_force[3]
353  wrench_msg.wrench.torque.y = stateRT.tcp_force[4]
354  wrench_msg.wrench.torque.z = stateRT.tcp_force[5]
355  pub_wrench.publish(wrench_msg)
356 
357 
358  def __run(self):
359  while self.__keep_running:
360  r, _, _ = select.select([self.__sock], [], [], self.TIMEOUT)
361  if r:
362  more = self.__sock.recv(4096)
363  if more:
364  self.__buf = self.__buf + more
365 
366  #unpack_from requires a buffer of at least 48 bytes
367  while len(self.__buf) >= 48:
368  # Attempts to extract a packet
369  packet_length = struct.unpack_from("!i", self.__buf)[0]
370  #print("PacketLength: ", packet_length, "; BufferSize: ", len(self.__buf))
371  if len(self.__buf) >= packet_length:
372  packet, self.__buf = self.__buf[:packet_length], self.__buf[packet_length:]
373  self.__on_packet(packet)
374  else:
375  break
376  else:
378  self.__keep_running = False
379 
380  else:
382  self.__keep_running = False
383 
384 
386  global connected_robot, connected_robot_lock
387  with connected_robot_lock:
388  connected_robot = r
389  connected_robot_cond.notify()
390 
391 def getConnectedRobot(wait=False, timeout=-1):
392  started = time.time()
393  with connected_robot_lock:
394  if wait:
395  while not connected_robot:
396  if timeout >= 0 and time.time() > started + timeout:
397  break
398  connected_robot_cond.wait(0.2)
399  return connected_robot
400 
401 # Receives messages from the robot over the socket
402 class CommanderTCPHandler(SocketServer.BaseRequestHandler):
403 
404  def recv_more(self):
405  global last_joint_states, last_joint_states_lock
406  while True:
407  r, _, _ = select.select([self.request], [], [], 0.2)
408  if r:
409  more = self.request.recv(4096)
410  if not more:
411  raise EOF("EOF on recv")
412  return more
413  else:
414  now = rospy.get_rostime()
415  if last_joint_states and \
416  last_joint_states.header.stamp < now - rospy.Duration(1.0):
417  rospy.logerr("Stopped hearing from robot (last heard %.3f sec ago). Disconnected" % \
418  (now - last_joint_states.header.stamp).to_sec())
419  raise EOF()
420 
421  def handle(self):
422  self.__socket_lock = threading.Lock()
423  setConnectedRobot(self)
424  print("Handling a request")
425  try:
426  buf = self.recv_more()
427  if not buf: return
428 
429  while True:
430  #print "Buf:", [ord(b) for b in buf]
431 
432  # Unpacks the message type
433  mtype = struct.unpack_from("!i", buf, 0)[0]
434  buf = buf[4:]
435  #print "Message type:", mtype
436 
437  if mtype == MSG_OUT:
438  # Unpacks string message, terminated by tilde
439  i = buf.find("~")
440  while i < 0:
441  buf = buf + self.recv_more()
442  i = buf.find("~")
443  if len(buf) > 2000:
444  raise Exception("Probably forgot to terminate a string: %s..." % buf[:150])
445  s, buf = buf[:i], buf[i+1:]
446  log("Out: %s" % s)
447 
448  elif mtype == MSG_QUIT:
449  print("Quitting")
450  raise EOF("Received quit")
451  elif mtype == MSG_WAYPOINT_FINISHED:
452  while len(buf) < 4:
453  buf = buf + self.recv_more()
454  waypoint_id = struct.unpack_from("!i", buf, 0)[0]
455  buf = buf[4:]
456  print("Waypoint finished (not handled)")
457  else:
458  raise Exception("Unknown message type: %i" % mtype)
459 
460  if not buf:
461  buf = buf + self.recv_more()
462  except EOF as ex:
463  print("Connection closed (command):", ex)
464  setConnectedRobot(None)
465 
466  def __send_message(self, data):
467  """
468  Send a message to the robot.
469 
470  The message is given as a list of integers that will be packed
471  as 4 bytes each in network byte order (big endian).
472 
473  A lock is acquired before sending the message to prevent race conditions.
474 
475  :param data: list of int, the data to send
476  """
477  buf = struct.pack("!%ii" % len(data), *data)
478  with self.__socket_lock:
479  self.request.send(buf)
480 
481  def send_quit(self):
482  self.__send_message([MSG_QUIT])
483 
484  def send_servoj(self, waypoint_id, q_actual, t):
485  assert(len(q_actual) == 6)
486  q_robot = [0.0] * 6
487  for i, q in enumerate(q_actual):
488  q_robot[i] = q - joint_offsets.get(joint_names[i], 0.0)
489  params = [MSG_SERVOJ, waypoint_id] + \
490  [MULT_jointstate * qq for qq in q_robot] + \
491  [MULT_time * t]
492  self.__send_message(params)
493 
494  #Experimental set_payload implementation
495  def send_payload(self,payload):
496  self.__send_message([MSG_SET_PAYLOAD, payload * MULT_payload])
497 
498  #Experimental set_digital_output implementation
499  def set_digital_out(self, pinnum, value):
500  self.__send_message([MSG_SET_DIGITAL_OUT, pinnum, value])
501  time.sleep(IO_SLEEP_TIME)
502 
503  def set_analog_out(self, pinnum, value):
504  self.__send_message([MSG_SET_ANALOG_OUT, pinnum, value * MULT_analog])
505  time.sleep(IO_SLEEP_TIME)
506 
507  def set_tool_voltage(self, value):
508  self.__send_message([MSG_SET_TOOL_VOLTAGE, value, 0])
509  time.sleep(IO_SLEEP_TIME)
510 
511  def set_flag(self, pin, val):
512  self.__send_message([MSG_SET_FLAG, pin, val])
513  #set_flag will fail if called too closely together--added delay
514  time.sleep(IO_SLEEP_TIME)
515 
516  def send_stopj(self):
517  self.__send_message([MSG_STOPJ])
518 
521 
522  # Returns the last JointState message sent out
523  def get_joint_states(self):
524  global last_joint_states, last_joint_states_lock
525  return last_joint_states
526 
527 
528 class TCPServer(SocketServer.TCPServer):
529  allow_reuse_address = True # Allows the program to restart gracefully on crash
530  timeout = 5
531 
532 
533 # Waits until all threads have completed. Allows KeyboardInterrupt to occur
534 def joinAll(threads):
535  while any(t.isAlive() for t in threads):
536  for t in threads:
537  t.join(0.2)
538 
539 # Returns the duration between moving from point (index-1) to point
540 # index in the given JointTrajectory
541 def get_segment_duration(traj, index):
542  if index == 0:
543  return traj.points[0].time_from_start.to_sec()
544  return (traj.points[index].time_from_start - traj.points[index-1].time_from_start).to_sec()
545 
546 # Reorders the JointTrajectory traj according to the order in
547 # joint_names. Destructive.
548 def reorder_traj_joints(traj, joint_names):
549  order = [traj.joint_names.index(j) for j in joint_names]
550 
551  new_points = []
552  for p in traj.points:
553  new_points.append(JointTrajectoryPoint(
554  positions = [p.positions[i] for i in order],
555  velocities = [p.velocities[i] for i in order] if p.velocities else [],
556  accelerations = [p.accelerations[i] for i in order] if p.accelerations else [],
557  time_from_start = p.time_from_start))
558  traj.joint_names = joint_names
559  traj.points = new_points
560 
561 def interp_cubic(p0, p1, t_abs):
562  T = (p1.time_from_start - p0.time_from_start).to_sec()
563  t = t_abs - p0.time_from_start.to_sec()
564  q = [0] * 6
565  qdot = [0] * 6
566  qddot = [0] * 6
567  for i in range(len(p0.positions)):
568  a = p0.positions[i]
569  b = p0.velocities[i]
570  c = (-3*p0.positions[i] + 3*p1.positions[i] - 2*T*p0.velocities[i] - T*p1.velocities[i]) / T**2
571  d = (2*p0.positions[i] - 2*p1.positions[i] + T*p0.velocities[i] + T*p1.velocities[i]) / T**3
572 
573  q[i] = a + b*t + c*t**2 + d*t**3
574  qdot[i] = b + 2*c*t + 3*d*t**2
575  qddot[i] = 2*c + 6*d*t
576  return JointTrajectoryPoint(positions=q, velocities=qdot, accelerations=qddot, time_from_start=rospy.Duration(t_abs))
577 
578 # Returns (q, qdot, qddot) for sampling the JointTrajectory at time t.
579 # The time t is the time since the trajectory was started.
580 def sample_traj(traj, t):
581  # First point
582  if t <= 0.0:
583  return copy.deepcopy(traj.points[0])
584  # Last point
585  if t >= traj.points[-1].time_from_start.to_sec():
586  return copy.deepcopy(traj.points[-1])
587 
588  # Finds the (middle) segment containing t
589  i = 0
590  while traj.points[i+1].time_from_start.to_sec() < t:
591  i += 1
592  return interp_cubic(traj.points[i], traj.points[i+1], t)
593 
594 def traj_is_finite(traj):
595  for pt in traj.points:
596  for p in pt.positions:
597  if math.isinf(p) or math.isnan(p):
598  return False
599  for v in pt.velocities:
600  if math.isinf(v) or math.isnan(v):
601  return False
602  return True
603 
605  for p in traj.points:
606  for v in p.velocities:
607  if math.fabs(v) > max_velocity:
608  return False
609  return True
610 
611 def has_velocities(traj):
612  for p in traj.points:
613  if len(p.velocities) != len(p.positions):
614  return False
615  return True
616 
617 def within_tolerance(a_vec, b_vec, tol_vec):
618  for a, b, tol in zip(a_vec, b_vec, tol_vec):
619  if abs(a - b) > tol:
620  return False
621  return True
622 
623 class URServiceProvider(object):
624  def __init__(self, robot):
625  self.robot = robot
626  rospy.Service('ur_driver/setPayload', SetPayload, self.setPayload)
627 
628  def set_robot(self, robot):
629  self.robot = robot
630 
631  def setPayload(self, req):
632  if req.payload < min_payload or req.payload > max_payload:
633  print('ERROR: Payload ' + str(req.payload) + ' out of bounds (' + str(min_payload) + ', ' + str(max_payload) + ')')
634  return False
635 
636  if self.robot:
637  self.robot.send_payload(req.payload)
638  else:
639  return False
640  return True
641 
642 class URTrajectoryFollower(object):
643  RATE = 0.02
644  def __init__(self, robot, goal_time_tolerance=None):
645  self.goal_time_tolerance = goal_time_tolerance or rospy.Duration(0.0)
646  self.joint_goal_tolerances = [0.05, 0.05, 0.05, 0.05, 0.05, 0.05]
647  self.following_lock = threading.Lock()
648  self.T0 = time.time()
649  self.robot = robot
650  self.server = actionlib.ActionServer("follow_joint_trajectory",
651  FollowJointTrajectoryAction,
652  self.on_goal, self.on_cancel, auto_start=False)
653 
654  self.goal_handle = None
655  self.traj = None
656  self.traj_t0 = 0.0
658  self.tracking_i = 0
659  self.pending_i = 0
660  self.last_point_sent = True
661 
662  self.update_timer = rospy.Timer(rospy.Duration(self.RATE), self._update)
663 
664  def set_robot(self, robot):
665  # Cancels any goals in progress
666  if self.goal_handle:
667  self.goal_handle.set_canceled()
668  self.goal_handle = None
669  self.traj = None
670  self.robot = robot
671  if self.robot:
672  self.init_traj_from_robot()
673 
674  # Sets the trajectory to remain stationary at the current position
675  # of the robot.
677  if not self.robot: raise Exception("No robot connected")
678  # Busy wait (avoids another mutex)
679  state = self.robot.get_joint_states()
680  while not state:
681  time.sleep(0.1)
682  state = self.robot.get_joint_states()
683  self.traj_t0 = time.time()
684  self.traj = JointTrajectory()
685  self.traj.joint_names = joint_names
686  self.traj.points = [JointTrajectoryPoint(
687  positions = state.position,
688  velocities = [0] * 6,
689  accelerations = [0] * 6,
690  time_from_start = rospy.Duration(0.0))]
691 
692  def start(self):
693  self.init_traj_from_robot()
694  self.server.start()
695  print("The action server for this driver has been started")
696 
697  def on_goal(self, goal_handle):
698  log("on_goal")
699 
700  # Checks that the robot is connected
701  if not self.robot:
702  rospy.logerr("Received a goal, but the robot is not connected")
703  goal_handle.set_rejected()
704  return
705 
706  # Checks if the joints are just incorrect
707  if set(goal_handle.get_goal().trajectory.joint_names) != set(joint_names):
708  rospy.logerr("Received a goal with incorrect joint names: (%s)" % \
709  ', '.join(goal_handle.get_goal().trajectory.joint_names))
710  goal_handle.set_rejected()
711  return
712 
713  if not traj_is_finite(goal_handle.get_goal().trajectory):
714  rospy.logerr("Received a goal with infinites or NaNs")
715  goal_handle.set_rejected(text="Received a goal with infinites or NaNs")
716  return
717 
718  # Checks that the trajectory has velocities
719  if not has_velocities(goal_handle.get_goal().trajectory):
720  rospy.logerr("Received a goal without velocities")
721  goal_handle.set_rejected(text="Received a goal without velocities")
722  return
723 
724  # Checks that the velocities are withing the specified limits
725  if not has_limited_velocities(goal_handle.get_goal().trajectory):
726  message = "Received a goal with velocities that are higher than %f" % max_velocity
727  rospy.logerr(message)
728  goal_handle.set_rejected(text=message)
729  return
730 
731  # Orders the joints of the trajectory according to joint_names
732  reorder_traj_joints(goal_handle.get_goal().trajectory, joint_names)
733 
734  with self.following_lock:
735  if self.goal_handle:
736  # Cancels the existing goal
737  self.goal_handle.set_canceled()
738  self.first_waypoint_id += len(self.goal_handle.get_goal().trajectory.points)
739  self.goal_handle = None
740 
741  # Inserts the current setpoint at the head of the trajectory
742  now = time.time()
743  point0 = sample_traj(self.traj, now - self.traj_t0)
744  point0.time_from_start = rospy.Duration(0.0)
745  goal_handle.get_goal().trajectory.points.insert(0, point0)
746  self.traj_t0 = now
747 
748  # Replaces the goal
749  self.goal_handle = goal_handle
750  self.traj = goal_handle.get_goal().trajectory
751  self.goal_handle.set_accepted()
752 
753  def on_cancel(self, goal_handle):
754  log("on_cancel")
755  if goal_handle == self.goal_handle:
756  with self.following_lock:
757  # Uses the next little bit of trajectory to slow to a stop
758  STOP_DURATION = 0.5
759  now = time.time()
760  point0 = sample_traj(self.traj, now - self.traj_t0)
761  point0.time_from_start = rospy.Duration(0.0)
762  point1 = sample_traj(self.traj, now - self.traj_t0 + STOP_DURATION)
763  point1.velocities = [0] * 6
764  point1.accelerations = [0] * 6
765  point1.time_from_start = rospy.Duration(STOP_DURATION)
766  self.traj_t0 = now
767  self.traj = JointTrajectory()
768  self.traj.joint_names = joint_names
769  self.traj.points = [point0, point1]
770 
771  self.goal_handle.set_canceled()
772  self.goal_handle = None
773  else:
774  goal_handle.set_canceled()
775 
776  last_now = time.time()
777  def _update(self, event):
778  if self.robot and self.traj:
779  now = time.time()
780  if (now - self.traj_t0) <= self.traj.points[-1].time_from_start.to_sec():
781  self.last_point_sent = False #sending intermediate points
782  setpoint = sample_traj(self.traj, now - self.traj_t0)
783  try:
784  self.robot.send_servoj(999, setpoint.positions, 4 * self.RATE)
785  except socket.error:
786  pass
787 
788  elif not self.last_point_sent:
789  # All intermediate points sent, sending last point to make sure we
790  # reach the goal.
791  # This should solve an issue where the robot does not reach the final
792  # position and errors out due to not reaching the goal point.
793  last_point = self.traj.points[-1]
794  state = self.robot.get_joint_states()
795  position_in_tol = within_tolerance(state.position, last_point.positions, self.joint_goal_tolerances)
796  # Performing this check to try and catch our error condition. We will always
797  # send the last point just in case.
798  if not position_in_tol:
799  rospy.logwarn("Trajectory time exceeded and current robot state not at goal, last point required")
800  rospy.logwarn("Current trajectory time: %s, last point time: %s" % \
801  (now - self.traj_t0, self.traj.points[-1].time_from_start.to_sec()))
802  rospy.logwarn("Desired: %s\nactual: %s\nvelocity: %s" % \
803  (last_point.positions, state.position, state.velocity))
804  setpoint = sample_traj(self.traj, self.traj.points[-1].time_from_start.to_sec())
805 
806  try:
807  self.robot.send_servoj(999, setpoint.positions, 4 * self.RATE)
808  self.last_point_sent = True
809  except socket.error:
810  pass
811 
812  else: # Off the end
813  if self.goal_handle:
814  last_point = self.traj.points[-1]
815  state = self.robot.get_joint_states()
816  position_in_tol = within_tolerance(state.position, last_point.positions, [0.1]*6)
817  velocity_in_tol = within_tolerance(state.velocity, last_point.velocities, [0.05]*6)
818  if position_in_tol and velocity_in_tol:
819  # The arm reached the goal (and isn't moving). Succeeding
820  self.goal_handle.set_succeeded()
821  self.goal_handle = None
822  #elif now - (self.traj_t0 + last_point.time_from_start.to_sec()) > self.goal_time_tolerance.to_sec():
823  # # Took too long to reach the goal. Aborting
824  # rospy.logwarn("Took too long to reach the goal.\nDesired: %s\nactual: %s\nvelocity: %s" % \
825  # (last_point.positions, state.position, state.velocity))
826  # self.goal_handle.set_aborted(text="Took too long to reach the goal")
827  # self.goal_handle = None
828 
829 
830 # joint_names: list of joints
831 #
832 # returns: { "joint_name" : joint_offset }
833 def load_joint_offsets(joint_names):
834  from lxml import etree
835  robot_description = rospy.get_param("robot_description")
836  doc = etree.fromstring(robot_description)
837 
838  # select only 'calibration_offset' elements whose parent is a joint
839  # element with a specific value for the name attribute
840  expr = "/robot/joint[@name=$name]/calibration_offset"
841  result = {}
842  for joint in joint_names:
843  joint_elt = doc.xpath(expr, name=joint)
844  if len(joint_elt) == 1:
845  calibration_offset = float(joint_elt[0].get("value"))
846  result[joint] = calibration_offset
847  rospy.loginfo("Found calibration offset for joint \"%s\": %.4f" % (joint, calibration_offset))
848  elif len(joint_elt) > 1:
849  rospy.logerr("Too many joints matched on \"%s\". Please report to package maintainer(s)." % joint)
850  else:
851  rospy.logwarn("No calibration offset for joint \"%s\"" % joint)
852  return result
853 
854 def get_my_ip(robot_ip, port):
855  s = socket.create_connection((robot_ip, port))
856  tmp = s.getsockname()[0]
857  s.close()
858  return tmp
859 
860 def handle_set_io(req):
861  r = getConnectedRobot(wait=False)
862  if r:
863  if req.fun == req.FUN_SET_DIGITAL_OUT:
864  r.set_digital_out(req.pin, req.state)
865  return True
866  elif req.fun == req.FUN_SET_FLAG:
867  r.set_flag(req.pin, req.state)
868  return True
869  elif req.fun == req.FUN_SET_ANALOG_OUT:
870  r.set_analog_out(req.pin, req.state)
871  return True
872  elif req.fun == req.FUN_SET_TOOL_VOLTAGE:
873  r.set_tool_voltage(req.pin)
874  return True
875  else:
876  raise ROSServiceException("Robot not connected")
877 
879  s= rospy.Service('set_io', SetIO, handle_set_io)
880 
881 def reconfigure_callback(config, level):
882  global prevent_programming
883  prevent_programming = config.prevent_programming
884  ## What about updating the value on the parameter server?
885  return config
886 
887 def main():
888  rospy.init_node('ur_driver', disable_signals=True)
889  if rospy.get_param("use_sim_time", False):
890  rospy.logwarn("use_sim_time is set!!!")
891 
892  global prevent_programming
893  reconfigure_srv = Server(URDriverConfig, reconfigure_callback)
894 
895  prefix = rospy.get_param("~prefix", "")
896  print("Setting prefix to %s" % prefix)
897  global joint_names
898  joint_names = [prefix + name for name in JOINT_NAMES]
899 
900  # Parses command line arguments
901  parser = optparse.OptionParser(usage="usage: %prog robot_hostname [reverse_port]")
902  (options, args) = parser.parse_args(rospy.myargv()[1:])
903  if len(args) < 1:
904  parser.error("You must specify the robot hostname")
905  elif len(args) == 1:
906  robot_hostname = args[0]
907  reverse_port = DEFAULT_REVERSE_PORT
908  elif len(args) == 2:
909  robot_hostname = args[0]
910  reverse_port = int(args[1])
911  if not (0 <= reverse_port <= 65535):
912  parser.error("You entered an invalid port number")
913  else:
914  parser.error("Wrong number of parameters")
915 
916  # Reads the calibrated joint offsets from the URDF
917  global joint_offsets
918  joint_offsets = load_joint_offsets(joint_names)
919  if len(joint_offsets) > 0:
920  rospy.loginfo("Loaded calibration offsets from urdf: %s" % joint_offsets)
921  else:
922  rospy.loginfo("No calibration offsets loaded from urdf")
923 
924  # Reads the maximum velocity
925  # The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits
926  global max_velocity
927  max_velocity = rospy.get_param("~max_velocity", MAX_VELOCITY) # [rad/s]
928  rospy.loginfo("Max velocity accepted by ur_driver: %s [rad/s]" % max_velocity)
929 
930  # Reads the minimum payload
931  global min_payload
932  min_payload = rospy.get_param("~min_payload", MIN_PAYLOAD)
933  # Reads the maximum payload
934  global max_payload
935  max_payload = rospy.get_param("~max_payload", MAX_PAYLOAD)
936  rospy.loginfo("Bounds for Payload: [%s, %s]" % (min_payload, max_payload))
937 
938 
939  # Sets up the server for the robot to connect to
940  server = TCPServer(("", reverse_port), CommanderTCPHandler)
941  thread_commander = threading.Thread(name="CommanderHandler", target=server.serve_forever)
942  thread_commander.daemon = True
943  thread_commander.start()
944 
945  with open(roslib.packages.get_pkg_dir('ur_driver') + '/prog') as fin:
946  program = fin.read() % {"driver_hostname": get_my_ip(robot_hostname, PORT), "driver_reverseport": reverse_port}
947  connection = URConnection(robot_hostname, PORT, program)
948  connection.connect()
949  connection.send_reset_program()
950 
951  connectionRT = URConnectionRT(robot_hostname, RT_PORT)
952  connectionRT.connect()
953 
954  set_io_server()
955 
956  service_provider = None
957  action_server = None
958  try:
959  while not rospy.is_shutdown():
960  # Checks for disconnect
961  if getConnectedRobot(wait=False):
962  time.sleep(0.2)
963  try:
964  prevent_programming = rospy.get_param("~prevent_programming")
965  update = {'prevent_programming': prevent_programming}
966  reconfigure_srv.update_configuration(update)
967  except KeyError as ex:
968  print("Parameter 'prevent_programming' not set. Value: " + str(prevent_programming))
969  pass
970  if prevent_programming:
971  print("Programming now prevented")
972  connection.send_reset_program()
973  else:
974  print("Disconnected. Reconnecting")
975  if action_server:
976  action_server.set_robot(None)
977 
978  rospy.loginfo("Programming the robot")
979  while True:
980  # Sends the program to the robot
981  while not connection.ready_to_program():
982  print("Waiting to program")
983  time.sleep(1.0)
984  try:
985  prevent_programming = rospy.get_param("~prevent_programming")
986  update = {'prevent_programming': prevent_programming}
987  reconfigure_srv.update_configuration(update)
988  except KeyError as ex:
989  print("Parameter 'prevent_programming' not set. Value: " + str(prevent_programming))
990  pass
991  connection.send_program()
992 
993  r = getConnectedRobot(wait=True, timeout=1.0)
994  if r:
995  break
996  rospy.loginfo("Robot connected")
997 
998  #provider for service calls
999  if service_provider:
1000  service_provider.set_robot(r)
1001  else:
1002  service_provider = URServiceProvider(r)
1003 
1004  if action_server:
1005  action_server.set_robot(r)
1006  else:
1007  action_server = URTrajectoryFollower(r, rospy.Duration(1.0))
1008  action_server.start()
1009 
1010  except KeyboardInterrupt:
1011  try:
1012  r = getConnectedRobot(wait=False)
1013  rospy.signal_shutdown("KeyboardInterrupt")
1014  if r: r.send_quit()
1015  except:
1016  pass
1017  raise
1018 
1019 if __name__ == '__main__': main()
def joinAll(threads)
Definition: driver.py:534
robot_state
IO-Support is EXPERIMENTAL.
Definition: driver.py:133
def handle_set_io(req)
Definition: driver.py:860
def set_digital_out(self, pinnum, value)
Definition: driver.py:499
def __on_packet(self, buf)
Definition: driver.py:186
def set_io_server()
Definition: driver.py:878
def __init__(self, hostname, port, program)
Definition: driver.py:130
def throttle_warn_unknown(self, period, msg)
Definition: driver.py:253
def __trigger_disconnected(self)
Definition: driver.py:178
def set_analog_out(self, pinnum, value)
Definition: driver.py:503
def set_flag(self, pin, val)
Definition: driver.py:511
def send_servoj(self, waypoint_id, q_actual, t)
Definition: driver.py:484
def log(s)
Definition: driver.py:112
def traj_is_finite(traj)
Definition: driver.py:594
def __init__(self, hostname, port)
Definition: driver.py:294
def __trigger_ready_to_program(self)
Definition: driver.py:181
def on_goal(self, goal_handle)
Definition: driver.py:697
def __init__(self, robot, goal_time_tolerance=None)
Definition: driver.py:644
def set_robot(self, robot)
Definition: driver.py:628
def interp_cubic(p0, p1, t_abs)
Definition: driver.py:561
def getConnectedRobot(wait=False, timeout=-1)
Definition: driver.py:391
def set_tool_voltage(self, value)
Definition: driver.py:507
def send_payload(self, payload)
Definition: driver.py:495
def dumpstacks()
Definition: driver.py:101
def on_cancel(self, goal_handle)
Definition: driver.py:753
def get_segment_duration(traj, index)
Definition: driver.py:541
def within_tolerance(a_vec, b_vec, tol_vec)
Definition: driver.py:617
def setConnectedRobot(r)
Definition: driver.py:385
def get_my_ip(robot_ip, port)
Definition: driver.py:854
def has_velocities(traj)
Definition: driver.py:611
def reorder_traj_joints(traj, joint_names)
Definition: driver.py:548
def set_waypoint_finished_cb(self, cb)
Definition: driver.py:519
def load_joint_offsets(joint_names)
Definition: driver.py:833
def has_limited_velocities(traj)
Definition: driver.py:604
def sample_traj(traj, t)
Definition: driver.py:580
def reconfigure_callback(config, level)
Definition: driver.py:881
def __on_packet(self, buf)
Definition: driver.py:328


ur_driver
Author(s): Stuart Glaser, Shaun Edwards, Felix Messmer
autogenerated on Sun Nov 24 2019 03:36:29