00001
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 from BeautifulSoup import BeautifulSoup
00012
00013 import rospy
00014 import actionlib
00015 from sensor_msgs.msg import JointState
00016 from control_msgs.msg import FollowJointTrajectoryAction
00017 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
00018
00019 from deserialize import RobotState, RobotMode
00020
00021 prevent_programming = False
00022
00023
00024
00025
00026
00027
00028 joint_offsets = {}
00029
00030 PORT=30002
00031 REVERSE_PORT = 50001
00032
00033 MSG_OUT = 1
00034 MSG_QUIT = 2
00035 MSG_JOINT_STATES = 3
00036 MSG_MOVEJ = 4
00037 MSG_WAYPOINT_FINISHED = 5
00038 MSG_STOPJ = 6
00039 MSG_SERVOJ = 7
00040 MULT_jointstate = 10000.0
00041 MULT_time = 1000000.0
00042 MULT_blend = 1000.0
00043
00044 JOINT_NAMES = ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint',
00045 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
00046
00047 Q1 = [2.2,0,-1.57,0,0,0]
00048 Q2 = [1.5,0,-1.57,0,0,0]
00049 Q3 = [1.5,-0.2,-1.57,0,0,0]
00050
00051
00052 connected_robot = None
00053 connected_robot_lock = threading.Lock()
00054 connected_robot_cond = threading.Condition(connected_robot_lock)
00055 pub_joint_states = rospy.Publisher('joint_states', JointState)
00056
00057
00058 class EOF(Exception): pass
00059
00060 def dumpstacks():
00061 id2name = dict([(th.ident, th.name) for th in threading.enumerate()])
00062 code = []
00063 for threadId, stack in sys._current_frames().items():
00064 code.append("\n# Thread: %s(%d)" % (id2name.get(threadId,""), threadId))
00065 for filename, lineno, name, line in traceback.extract_stack(stack):
00066 code.append('File: "%s", line %d, in %s' % (filename, lineno, name))
00067 if line:
00068 code.append(" %s" % (line.strip()))
00069 print "\n".join(code)
00070
00071 def log(s):
00072 print "[%s] %s" % (datetime.datetime.now().strftime('%Y-%m-%d %H:%M:%S.%f'), s)
00073
00074
00075 RESET_PROGRAM = '''def resetProg():
00076 sleep(0.0)
00077 end
00078 '''
00079
00080
00081 class UR5Connection(object):
00082 TIMEOUT = 1.0
00083
00084 DISCONNECTED = 0
00085 CONNECTED = 1
00086 READY_TO_PROGRAM = 2
00087 EXECUTING = 3
00088
00089 def __init__(self, hostname, port, program):
00090 self.__thread = None
00091 self.__sock = None
00092 self.robot_state = self.DISCONNECTED
00093 self.hostname = hostname
00094 self.port = port
00095 self.program = program
00096 self.last_state = None
00097
00098 def connect(self):
00099 if self.__sock:
00100 self.disconnect()
00101 self.__buf = ""
00102 self.robot_state = self.CONNECTED
00103 self.__sock = socket.create_connection((self.hostname, self.port))
00104 self.__keep_running = True
00105 self.__thread = threading.Thread(name="UR5Connection", target=self.__run)
00106 self.__thread.daemon = True
00107 self.__thread.start()
00108
00109 def send_program(self):
00110 global prevent_programming
00111 if prevent_programming:
00112 rospy.loginfo("Programming is currently prevented")
00113 return
00114 assert self.robot_state in [self.READY_TO_PROGRAM, self.EXECUTING]
00115 rospy.loginfo("Programming the robot at %s" % self.hostname)
00116 self.__sock.sendall(self.program)
00117 self.robot_state = self.EXECUTING
00118
00119 def send_reset_program(self):
00120 self.__sock.sendall(RESET_PROGRAM)
00121 self.robot_state = self.READY_TO_PROGRAM
00122
00123 def disconnect(self):
00124 if self.__thread:
00125 self.__keep_running = False
00126 self.__thread.join()
00127 self.__thread = None
00128 if self.__sock:
00129 self.__sock.close()
00130 self.__sock = None
00131 self.last_state = None
00132 self.robot_state = self.DISCONNECTED
00133
00134 def ready_to_program(self):
00135 return self.robot_state in [self.READY_TO_PROGRAM, self.EXECUTING]
00136
00137 def __trigger_disconnected(self):
00138 log("Robot disconnected")
00139 self.robot_state = self.DISCONNECTED
00140 def __trigger_ready_to_program(self):
00141 rospy.loginfo("Robot ready to program")
00142 def __trigger_halted(self):
00143 log("Halted")
00144
00145 def __on_packet(self, buf):
00146 state = RobotState.unpack(buf)
00147 self.last_state = state
00148
00149
00150
00151
00152 if not state.robot_mode_data.real_robot_enabled:
00153 rospy.logfatal("Real robot is no longer enabled. Driver is fuxored")
00154 time.sleep(2)
00155 sys.exit(1)
00156
00157
00158
00159
00160 if self.robot_state != self.EXECUTING:
00161 msg = JointState()
00162 msg.header.stamp = rospy.get_rostime()
00163 msg.header.frame_id = "From binary state data"
00164 msg.name = joint_names
00165 msg.position = [0.0] * 6
00166 for i, jd in enumerate(state.joint_data):
00167 msg.position[i] = jd.q_actual + joint_offsets.get(joint_names[i], 0.0)
00168 msg.velocity = [jd.qd_actual for jd in state.joint_data]
00169 msg.effort = [0]*6
00170 pub_joint_states.publish(msg)
00171 self.last_joint_states = msg
00172
00173
00174 can_execute = (state.robot_mode_data.robot_mode in [RobotMode.READY, RobotMode.RUNNING])
00175 if self.robot_state == self.CONNECTED:
00176 if can_execute:
00177 self.__trigger_ready_to_program()
00178 self.robot_state = self.READY_TO_PROGRAM
00179 elif self.robot_state == self.READY_TO_PROGRAM:
00180 if not can_execute:
00181 self.robot_state = self.CONNECTED
00182 elif self.robot_state == self.EXECUTING:
00183 if not can_execute:
00184 self.__trigger_halted()
00185 self.robot_state = self.CONNECTED
00186
00187
00188 if len(state.unknown_ptypes) > 0:
00189 state.unknown_ptypes.sort()
00190 s_unknown_ptypes = [str(ptype) for ptype in state.unknown_ptypes]
00191 self.throttle_warn_unknown(1.0, "Ignoring unknown pkt type(s): %s. "
00192 "Please report." % ", ".join(s_unknown_ptypes))
00193
00194 def throttle_warn_unknown(self, period, msg):
00195 self.__dict__.setdefault('_last_hit', 0.0)
00196
00197 if (self._last_hit + period) <= rospy.get_time():
00198 self._last_hit = rospy.get_time()
00199 rospy.logwarn(msg)
00200
00201 def __run(self):
00202 while self.__keep_running:
00203 r, _, _ = select.select([self.__sock], [], [], self.TIMEOUT)
00204 if r:
00205 more = self.__sock.recv(4096)
00206 if more:
00207 self.__buf = self.__buf + more
00208
00209
00210 packet_length, ptype = struct.unpack_from("!IB", self.__buf)
00211 if len(self.__buf) >= packet_length:
00212 packet, self.__buf = self.__buf[:packet_length], self.__buf[packet_length:]
00213 self.__on_packet(packet)
00214 else:
00215 self.__trigger_disconnected()
00216 self.__keep_running = False
00217
00218 else:
00219 self.__trigger_disconnected()
00220 self.__keep_running = False
00221
00222
00223 def setConnectedRobot(r):
00224 global connected_robot, connected_robot_lock
00225 with connected_robot_lock:
00226 connected_robot = r
00227 connected_robot_cond.notify()
00228
00229 def getConnectedRobot(wait=False, timeout=-1):
00230 started = time.time()
00231 with connected_robot_lock:
00232 if wait:
00233 while not connected_robot:
00234 if timeout >= 0 and time.time() > started + timeout:
00235 break
00236 connected_robot_cond.wait(0.2)
00237 return connected_robot
00238
00239
00240 class CommanderTCPHandler(SocketServer.BaseRequestHandler):
00241
00242 def recv_more(self):
00243 while True:
00244 r, _, _ = select.select([self.request], [], [], 0.2)
00245 if r:
00246 more = self.request.recv(4096)
00247 if not more:
00248 raise EOF("EOF on recv")
00249 return more
00250 else:
00251 now = rospy.get_rostime()
00252 if self.last_joint_states and \
00253 self.last_joint_states.header.stamp < now - rospy.Duration(1.0):
00254 rospy.logerr("Stopped hearing from robot (last heard %.3f sec ago). Disconnected" % \
00255 (now - self.last_joint_states.header.stamp).to_sec())
00256 raise EOF()
00257
00258 def handle(self):
00259 self.socket_lock = threading.Lock()
00260 self.last_joint_states = None
00261 setConnectedRobot(self)
00262 print "Handling a request"
00263 try:
00264 buf = self.recv_more()
00265 if not buf: return
00266
00267 while True:
00268
00269
00270
00271 mtype = struct.unpack_from("!i", buf, 0)[0]
00272 buf = buf[4:]
00273
00274
00275 if mtype == MSG_OUT:
00276
00277 i = buf.find("~")
00278 while i < 0:
00279 buf = buf + self.recv_more()
00280 i = buf.find("~")
00281 if len(buf) > 2000:
00282 raise Exception("Probably forgot to terminate a string: %s..." % buf[:150])
00283 s, buf = buf[:i], buf[i+1:]
00284 log("Out: %s" % s)
00285
00286 elif mtype == MSG_JOINT_STATES:
00287 while len(buf) < 3*(6*4):
00288 buf = buf + self.recv_more()
00289 state_mult = struct.unpack_from("!%ii" % (3*6), buf, 0)
00290 buf = buf[3*6*4:]
00291 state = [s / MULT_jointstate for s in state_mult]
00292
00293 msg = JointState()
00294 msg.header.stamp = rospy.get_rostime()
00295 msg.name = joint_names
00296 msg.position = [0.0] * 6
00297 for i, q_meas in enumerate(state[:6]):
00298 msg.position[i] = q_meas + joint_offsets.get(joint_names[i], 0.0)
00299 msg.velocity = state[6:12]
00300 msg.effort = state[12:18]
00301 self.last_joint_states = msg
00302 pub_joint_states.publish(msg)
00303 elif mtype == MSG_QUIT:
00304 print "Quitting"
00305 raise EOF("Received quit")
00306 elif mtype == MSG_WAYPOINT_FINISHED:
00307 while len(buf) < 4:
00308 buf = buf + self.recv_more()
00309 waypoint_id = struct.unpack_from("!i", buf, 0)[0]
00310 buf = buf[4:]
00311 print "Waypoint finished (not handled)"
00312 else:
00313 raise Exception("Unknown message type: %i" % mtype)
00314
00315 if not buf:
00316 buf = buf + self.recv_more()
00317 except EOF, ex:
00318 print "Connection closed (command):", ex
00319 setConnectedRobot(None)
00320
00321 def send_quit(self):
00322 with self.socket_lock:
00323 self.request.send(struct.pack("!i", MSG_QUIT))
00324
00325 def send_servoj(self, waypoint_id, q_actual, t):
00326 assert(len(q_actual) == 6)
00327 q_robot = [0.0] * 6
00328 for i, q in enumerate(q_actual):
00329 q_robot[i] = q - joint_offsets.get(joint_names[i], 0.0)
00330 params = [MSG_SERVOJ, waypoint_id] + \
00331 [MULT_jointstate * qq for qq in q_robot] + \
00332 [MULT_time * t]
00333 buf = struct.pack("!%ii" % len(params), *params)
00334 with self.socket_lock:
00335 self.request.send(buf)
00336
00337
00338 def send_stopj(self):
00339 with self.socket_lock:
00340 self.request.send(struct.pack("!i", MSG_STOPJ))
00341
00342 def set_waypoint_finished_cb(self, cb):
00343 self.waypoint_finished_cb = cb
00344
00345
00346 def get_joint_states(self):
00347 return self.last_joint_states
00348
00349
00350 class TCPServer(SocketServer.TCPServer):
00351 allow_reuse_address = True
00352 timeout = 5
00353
00354
00355
00356 def joinAll(threads):
00357 while any(t.isAlive() for t in threads):
00358 for t in threads:
00359 t.join(0.2)
00360
00361
00362
00363 def get_segment_duration(traj, index):
00364 if index == 0:
00365 return traj.points[0].time_from_start.to_sec()
00366 return (traj.points[index].time_from_start - traj.points[index-1].time_from_start).to_sec()
00367
00368
00369
00370 def reorder_traj_joints(traj, joint_names):
00371 order = [traj.joint_names.index(j) for j in joint_names]
00372
00373 new_points = []
00374 for p in traj.points:
00375 new_points.append(JointTrajectoryPoint(
00376 positions = [p.positions[i] for i in order],
00377 velocities = [p.velocities[i] for i in order] if p.velocities else [],
00378 accelerations = [p.accelerations[i] for i in order] if p.accelerations else [],
00379 time_from_start = p.time_from_start))
00380 traj.joint_names = joint_names
00381 traj.points = new_points
00382
00383 def interp_cubic(p0, p1, t_abs):
00384 T = (p1.time_from_start - p0.time_from_start).to_sec()
00385 t = t_abs - p0.time_from_start.to_sec()
00386 q = [0] * 6
00387 qdot = [0] * 6
00388 qddot = [0] * 6
00389 for i in range(len(p0.positions)):
00390 a = p0.positions[i]
00391 b = p0.velocities[i]
00392 c = (-3*p0.positions[i] + 3*p1.positions[i] - 2*T*p0.velocities[i] - T*p1.velocities[i]) / T**2
00393 d = (2*p0.positions[i] - 2*p1.positions[i] + T*p0.velocities[i] + T*p1.velocities[i]) / T**3
00394
00395 q[i] = a + b*t + c*t**2 + d*t**3
00396 qdot[i] = b + 2*c*t + 3*d*t**2
00397 qddot[i] = 2*c + 6*d*t
00398 return JointTrajectoryPoint(q, qdot, qddot, rospy.Duration(t_abs))
00399
00400
00401
00402 def sample_traj(traj, t):
00403
00404 if t <= 0.0:
00405 return copy.deepcopy(traj.points[0])
00406
00407 if t >= traj.points[-1].time_from_start.to_sec():
00408 return copy.deepcopy(traj.points[-1])
00409
00410
00411 i = 0
00412 while traj.points[i+1].time_from_start.to_sec() < t:
00413 i += 1
00414 return interp_cubic(traj.points[i], traj.points[i+1], t)
00415
00416 def traj_is_finite(traj):
00417 for pt in traj.points:
00418 for p in pt.positions:
00419 if math.isinf(p) or math.isnan(p):
00420 return False
00421 for v in pt.velocities:
00422 if math.isinf(v) or math.isnan(v):
00423 return False
00424 return True
00425
00426 def has_limited_velocities(traj):
00427 for p in traj.points:
00428 for v in p.velocities:
00429 if math.fabs(v) > max_velocity:
00430 return False
00431 return True
00432
00433 def has_velocities(traj):
00434 for p in traj.points:
00435 if len(p.velocities) != len(p.positions):
00436 return False
00437 return True
00438
00439 def within_tolerance(a_vec, b_vec, tol_vec):
00440 for a, b, tol in zip(a_vec, b_vec, tol_vec):
00441 if abs(a - b) > tol:
00442 return False
00443 return True
00444
00445 class UR5TrajectoryFollower(object):
00446 RATE = 0.02
00447 def __init__(self, robot, goal_time_tolerance=None):
00448 self.goal_time_tolerance = goal_time_tolerance or rospy.Duration(0.0)
00449 self.joint_goal_tolerances = [0.05, 0.05, 0.05, 0.05, 0.05, 0.05]
00450 self.following_lock = threading.Lock()
00451 self.T0 = time.time()
00452 self.robot = robot
00453 self.server = actionlib.ActionServer("follow_joint_trajectory",
00454 FollowJointTrajectoryAction,
00455 self.on_goal, self.on_cancel, auto_start=False)
00456
00457 self.goal_handle = None
00458 self.traj = None
00459 self.traj_t0 = 0.0
00460 self.first_waypoint_id = 10
00461 self.tracking_i = 0
00462 self.pending_i = 0
00463 self.last_point_sent = True
00464
00465 self.update_timer = rospy.Timer(rospy.Duration(self.RATE), self._update)
00466
00467 def set_robot(self, robot):
00468
00469 if self.goal_handle:
00470 self.goal_handle.set_canceled()
00471 self.goal_handle = None
00472 self.traj = None
00473 self.robot = robot
00474 if self.robot:
00475 self.init_traj_from_robot()
00476
00477
00478
00479 def init_traj_from_robot(self):
00480 if not self.robot: raise Exception("No robot connected")
00481
00482 state = self.robot.get_joint_states()
00483 while not state:
00484 time.sleep(0.1)
00485 state = self.robot.get_joint_states()
00486 self.traj_t0 = time.time()
00487 self.traj = JointTrajectory()
00488 self.traj.joint_names = joint_names
00489 self.traj.points = [JointTrajectoryPoint(
00490 positions = state.position,
00491 velocities = [0] * 6,
00492 accelerations = [0] * 6,
00493 time_from_start = rospy.Duration(0.0))]
00494
00495 def start(self):
00496 self.init_traj_from_robot()
00497 self.server.start()
00498 print "The action server for this driver has been started"
00499
00500 def on_goal(self, goal_handle):
00501 log("on_goal")
00502
00503
00504 if not self.robot:
00505 rospy.logerr("Received a goal, but the robot is not connected")
00506 goal_handle.set_rejected()
00507 return
00508
00509
00510 if set(goal_handle.get_goal().trajectory.joint_names) != set(joint_names):
00511 rospy.logerr("Received a goal with incorrect joint names: (%s)" % \
00512 ', '.join(goal_handle.get_goal().trajectory.joint_names))
00513 goal_handle.set_rejected()
00514 return
00515
00516 if not traj_is_finite(goal_handle.get_goal().trajectory):
00517 rospy.logerr("Received a goal with infinites or NaNs")
00518 goal_handle.set_rejected(text="Received a goal with infinites or NaNs")
00519 return
00520
00521
00522 if not has_velocities(goal_handle.get_goal().trajectory):
00523 rospy.logerr("Received a goal without velocities")
00524 goal_handle.set_rejected(text="Received a goal without velocities")
00525 return
00526
00527
00528 if not has_limited_velocities(goal_handle.get_goal().trajectory):
00529 message = "Received a goal with velocities that are higher than %f" % max_velocity
00530 rospy.logerr(message)
00531 goal_handle.set_rejected(text=message)
00532 return
00533
00534
00535 reorder_traj_joints(goal_handle.get_goal().trajectory, joint_names)
00536
00537 with self.following_lock:
00538 if self.goal_handle:
00539
00540 self.goal_handle.set_canceled()
00541 self.first_waypoint_id += len(self.goal_handle.get_goal().trajectory.points)
00542 self.goal_handle = None
00543
00544
00545 now = time.time()
00546 point0 = sample_traj(self.traj, now)
00547 point0.time_from_start = rospy.Duration(0.0)
00548 goal_handle.get_goal().trajectory.points.insert(0, point0)
00549 self.traj_t0 = now
00550
00551
00552 self.goal_handle = goal_handle
00553 self.traj = goal_handle.get_goal().trajectory
00554 self.goal_handle.set_accepted()
00555
00556 def on_cancel(self, goal_handle):
00557 log("on_cancel")
00558 if goal_handle == self.goal_handle:
00559 with self.following_lock:
00560
00561 STOP_DURATION = 0.5
00562 now = time.time()
00563 point0 = sample_traj(self.traj, now - self.traj_t0)
00564 point0.time_from_start = rospy.Duration(0.0)
00565 point1 = sample_traj(self.traj, now - self.traj_t0 + STOP_DURATION)
00566 point1.velocities = [0] * 6
00567 point1.accelerations = [0] * 6
00568 point1.time_from_start = rospy.Duration(STOP_DURATION)
00569 self.traj_t0 = now
00570 self.traj = JointTrajectory()
00571 self.traj.joint_names = joint_names
00572 self.traj.points = [point0, point1]
00573
00574 self.goal_handle.set_canceled()
00575 self.goal_handle = None
00576 else:
00577 goal_handle.set_canceled()
00578
00579 last_now = time.time()
00580 def _update(self, event):
00581 if self.robot and self.traj:
00582 now = time.time()
00583 if (now - self.traj_t0) <= self.traj.points[-1].time_from_start.to_sec():
00584 self.last_point_sent = False
00585 setpoint = sample_traj(self.traj, now - self.traj_t0)
00586 try:
00587 self.robot.send_servoj(999, setpoint.positions, 4 * self.RATE)
00588 except socket.error:
00589 pass
00590
00591 elif not self.last_point_sent:
00592
00593
00594
00595
00596 last_point = self.traj.points[-1]
00597 state = self.robot.get_joint_states()
00598 position_in_tol = within_tolerance(state.position, last_point.positions, self.joint_goal_tolerances)
00599
00600
00601 if not position_in_tol:
00602 rospy.logwarn("Trajectory time exceeded and current robot state not at goal, last point required")
00603 rospy.logwarn("Current trajectory time: %s, last point time: %s" % \
00604 (now - self.traj_t0, self.traj.points[-1].time_from_start.to_sec()))
00605 rospy.logwarn("Desired: %s\nactual: %s\nvelocity: %s" % \
00606 (last_point.positions, state.position, state.velocity))
00607 setpoint = sample_traj(self.traj, self.traj.points[-1].time_from_start.to_sec())
00608
00609 try:
00610 self.robot.send_servoj(999, setpoint.positions, 4 * self.RATE)
00611 self.last_point_sent = True
00612 except socket.error:
00613 pass
00614
00615 else:
00616 if self.goal_handle:
00617 last_point = self.traj.points[-1]
00618 state = self.robot.get_joint_states()
00619 position_in_tol = within_tolerance(state.position, last_point.positions, [0.1]*6)
00620 velocity_in_tol = within_tolerance(state.velocity, last_point.velocities, [0.05]*6)
00621 if position_in_tol and velocity_in_tol:
00622
00623 self.goal_handle.set_succeeded()
00624 self.goal_handle = None
00625
00626
00627
00628
00629
00630
00631
00632
00633
00634
00635 def load_joint_offsets(joint_names):
00636 robot_description = rospy.get_param("robot_description")
00637 soup = BeautifulSoup(robot_description)
00638
00639 result = {}
00640 for joint in joint_names:
00641 try:
00642 joint_elt = soup.find('joint', attrs={'name': joint})
00643 calibration_offset = float(joint_elt.calibration_offset["value"])
00644 result[joint] = calibration_offset
00645 except Exception, ex:
00646 rospy.logwarn("No calibration offset for joint \"%s\"" % joint)
00647 return result
00648
00649 def get_my_ip(robot_ip, port):
00650 s = socket.create_connection((robot_ip, port))
00651 tmp = s.getsockname()[0]
00652 s.close()
00653 return tmp
00654
00655 def main():
00656 rospy.init_node('ur_driver', disable_signals=True)
00657 if rospy.get_param("use_sim_time", False):
00658 rospy.logwarn("use_sim_time is set!!!")
00659 global prevent_programming
00660 prevent_programming = rospy.get_param("prevent_programming", False)
00661 prefix = rospy.get_param("~prefix", "")
00662 print "Setting prefix to %s" % prefix
00663 global joint_names
00664 joint_names = [prefix + name for name in JOINT_NAMES]
00665
00666
00667 parser = optparse.OptionParser(usage="usage: %prog robot_hostname")
00668 (options, args) = parser.parse_args(rospy.myargv()[1:])
00669 if len(args) != 1:
00670 parser.error("You must specify the robot hostname")
00671 robot_hostname = args[0]
00672
00673
00674 global joint_offsets
00675 joint_offsets = load_joint_offsets(joint_names)
00676 rospy.logerr("Loaded calibration offsets: %s" % joint_offsets)
00677
00678
00679 global max_velocity
00680 max_velocity = rospy.get_param("~max_velocity", 2.0)
00681
00682
00683 server = TCPServer(("", 50001), CommanderTCPHandler)
00684 thread_commander = threading.Thread(name="CommanderHandler", target=server.serve_forever)
00685 thread_commander.daemon = True
00686 thread_commander.start()
00687
00688 with open(roslib.packages.get_pkg_dir('ur_driver') + '/prog') as fin:
00689 program = fin.read() % {"driver_hostname": get_my_ip(robot_hostname, PORT)}
00690 connection = UR5Connection(robot_hostname, PORT, program)
00691 connection.connect()
00692 connection.send_reset_program()
00693
00694 action_server = None
00695 try:
00696 while not rospy.is_shutdown():
00697
00698 if getConnectedRobot(wait=False):
00699 time.sleep(0.2)
00700 prevent_programming = rospy.get_param("prevent_programming", False)
00701 if prevent_programming:
00702 print "Programming now prevented"
00703 connection.send_reset_program()
00704 else:
00705 print "Disconnected. Reconnecting"
00706 if action_server:
00707 action_server.set_robot(None)
00708
00709 rospy.loginfo("Programming the robot")
00710 while True:
00711
00712 while not connection.ready_to_program():
00713 print "Waiting to program"
00714 time.sleep(1.0)
00715 prevent_programming = rospy.get_param("prevent_programming", False)
00716 connection.send_program()
00717
00718 r = getConnectedRobot(wait=True, timeout=1.0)
00719 if r:
00720 break
00721 rospy.loginfo("Robot connected")
00722
00723 if action_server:
00724 action_server.set_robot(r)
00725 else:
00726 action_server = UR5TrajectoryFollower(r, rospy.Duration(1.0))
00727 action_server.start()
00728
00729 except KeyboardInterrupt:
00730 try:
00731 r = getConnectedRobot(wait=False)
00732 rospy.signal_shutdown("KeyboardInterrupt")
00733 if r: r.send_quit()
00734 except:
00735 pass
00736 raise
00737
00738 if __name__ == '__main__': main()