2 from __future__
import print_function
3 import roslib; roslib.load_manifest(
'ur_driver')
4 import time, sys, threading, math
15 from sensor_msgs.msg
import JointState
18 from geometry_msgs.msg
import WrenchStamped
20 from dynamic_reconfigure.server
import Server
21 from ur_driver.cfg
import URDriverConfig
34 prevent_programming =
False 45 DEFAULT_REVERSE_PORT = 50001
51 MSG_WAYPOINT_FINISHED = 5
56 MSG_SET_DIGITAL_OUT = 10
59 MSG_SET_TOOL_VOLTAGE = 13
60 MSG_SET_ANALOG_OUT = 14
63 MULT_jointstate = 10000.0
66 MULT_analog = 1000000.0
67 MULT_analog_robotstate = 0.1
81 JOINT_NAMES = [
'shoulder_pan_joint',
'shoulder_lift_joint',
'elbow_joint',
82 'wrist_1_joint',
'wrist_2_joint',
'wrist_3_joint']
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]
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)
99 class EOF(Exception):
pass 102 id2name = dict([(th.ident, th.name)
for th
in threading.enumerate()])
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))
109 code.append(
" %s" % (line.strip()))
110 print(
"\n".join(code))
113 print(
"[%s] %s" % (datetime.datetime.now().strftime(
'%Y-%m-%d %H:%M:%S.%f'), s))
116 RESET_PROGRAM =
'''def resetProg(): 146 self.
__thread = threading.Thread(name=
"URConnection", target=self.
__run)
147 self.__thread.daemon =
True 148 self.__thread.start()
151 global prevent_programming
152 if prevent_programming:
153 rospy.loginfo(
"Programming is currently prevented")
156 rospy.loginfo(
"Programming the robot at %s" % self.
hostname)
157 self.__sock.sendall(self.
program)
161 self.__sock.sendall(RESET_PROGRAM)
179 log(
"Robot disconnected")
182 rospy.loginfo(
"Robot ready to program")
187 state = RobotState.unpack(buf)
193 if not state.robot_mode_data.real_robot_enabled:
194 rospy.logfatal(
"Real robot is no longer enabled. Driver is fuxored")
211 for i
in range(0, 10):
212 msg.digital_in_states.append(
DigitalIn(i, (state.masterboard_data.digital_input_bits & (1<<i))>>i))
214 for i
in range(0, 10):
215 msg.digital_out_states.append(
DigitalOut(i, (state.masterboard_data.digital_output_bits & (1<<i))>>i))
217 inp = state.masterboard_data.analog_input0 / MULT_analog_robotstate
218 msg.analog_in_states.append(Analog(0, inp))
220 inp = state.masterboard_data.analog_input1 / MULT_analog_robotstate
221 msg.analog_in_states.append(Analog(1, inp))
223 inp = state.masterboard_data.analog_output0 / MULT_analog_robotstate
224 msg.analog_out_states.append(Analog(0, inp))
226 inp = state.masterboard_data.analog_output1 / MULT_analog_robotstate
227 msg.analog_out_states.append(Analog(1, inp))
229 pub_io_states.publish(msg)
233 can_execute = (state.robot_mode_data.robot_mode
in [RobotMode.READY, RobotMode.RUNNING])
247 if len(state.unknown_ptypes) > 0:
248 state.unknown_ptypes.sort()
249 s_unknown_ptypes = [str(ptype)
for ptype
in state.unknown_ptypes]
251 "Please report." %
", ".join(s_unknown_ptypes))
254 self.__dict__.setdefault(
'_last_hit', 0.0)
256 if (self.
_last_hit + period) <= rospy.get_time():
264 more = self.__sock.recv(4096)
269 while len(self.
__buf) >= 48:
271 packet_length, ptype = struct.unpack_from(
"!IB", self.
__buf)
273 if len(self.
__buf) >= packet_length:
274 packet, self.
__buf = self.
__buf[:packet_length], self.
__buf[packet_length:]
309 self.
__thread = threading.Thread(name=
"URConnectionRT", target=self.
__run)
310 self.__thread.daemon =
True 311 self.__thread.start()
325 log(
"Robot disconnected")
329 global last_joint_states, last_joint_states_lock
330 now = rospy.get_rostime()
331 stateRT = RobotStateRT.unpack(buf)
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
343 pub_joint_states.publish(msg)
344 with last_joint_states_lock:
345 last_joint_states = msg
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)
362 more = self.__sock.recv(4096)
367 while len(self.
__buf) >= 48:
369 packet_length = struct.unpack_from(
"!i", self.
__buf)[0]
371 if len(self.
__buf) >= packet_length:
372 packet, self.
__buf = self.
__buf[:packet_length], self.
__buf[packet_length:]
386 global connected_robot, connected_robot_lock
387 with connected_robot_lock:
389 connected_robot_cond.notify()
392 started = time.time()
393 with connected_robot_lock:
395 while not connected_robot:
396 if timeout >= 0
and time.time() > started + timeout:
398 connected_robot_cond.wait(0.2)
399 return connected_robot
405 global last_joint_states, last_joint_states_lock
407 r, _, _ = select.select([self.request], [], [], 0.2)
409 more = self.request.recv(4096)
411 raise EOF(
"EOF on recv")
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())
424 print(
"Handling a request")
433 mtype = struct.unpack_from(
"!i", buf, 0)[0]
444 raise Exception(
"Probably forgot to terminate a string: %s..." % buf[:150])
445 s, buf = buf[:i], buf[i+1:]
448 elif mtype == MSG_QUIT:
450 raise EOF(
"Received quit")
451 elif mtype == MSG_WAYPOINT_FINISHED:
454 waypoint_id = struct.unpack_from(
"!i", buf, 0)[0]
456 print(
"Waypoint finished (not handled)")
458 raise Exception(
"Unknown message type: %i" % mtype)
463 print(
"Connection closed (command):", ex)
468 Send a message to the robot. 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). 473 A lock is acquired before sending the message to prevent race conditions. 475 :param data: list of int, the data to send 477 buf = struct.pack(
"!%ii" % len(data), *data)
479 self.request.send(buf)
485 assert(len(q_actual) == 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] + \
501 time.sleep(IO_SLEEP_TIME)
504 self.
__send_message([MSG_SET_ANALOG_OUT, pinnum, value * MULT_analog])
505 time.sleep(IO_SLEEP_TIME)
509 time.sleep(IO_SLEEP_TIME)
514 time.sleep(IO_SLEEP_TIME)
524 global last_joint_states, last_joint_states_lock
525 return last_joint_states
529 allow_reuse_address =
True 535 while any(t.isAlive()
for t
in threads):
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()
549 order = [traj.joint_names.index(j)
for j
in joint_names]
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
562 T = (p1.time_from_start - p0.time_from_start).to_sec()
563 t = t_abs - p0.time_from_start.to_sec()
567 for i
in range(len(p0.positions)):
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
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))
583 return copy.deepcopy(traj.points[0])
585 if t >= traj.points[-1].time_from_start.to_sec():
586 return copy.deepcopy(traj.points[-1])
590 while traj.points[i+1].time_from_start.to_sec() < t:
592 return interp_cubic(traj.points[i], traj.points[i+1], t)
595 for pt
in traj.points:
596 for p
in pt.positions:
597 if math.isinf(p)
or math.isnan(p):
599 for v
in pt.velocities:
600 if math.isinf(v)
or math.isnan(v):
605 for p
in traj.points:
606 for v
in p.velocities:
607 if math.fabs(v) > max_velocity:
612 for p
in traj.points:
613 if len(p.velocities) != len(p.positions):
618 for a, b, tol
in zip(a_vec, b_vec, tol_vec):
626 rospy.Service(
'ur_driver/setPayload', SetPayload, self.
setPayload)
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) +
')')
637 self.robot.send_payload(req.payload)
644 def __init__(self, robot, goal_time_tolerance=None):
648 self.
T0 = time.time()
651 FollowJointTrajectoryAction,
667 self.goal_handle.set_canceled()
677 if not self.
robot:
raise Exception(
"No robot connected")
679 state = self.robot.get_joint_states()
682 state = self.robot.get_joint_states()
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))]
695 print(
"The action server for this driver has been started")
702 rospy.logerr(
"Received a goal, but the robot is not connected")
703 goal_handle.set_rejected()
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()
714 rospy.logerr(
"Received a goal with infinites or NaNs")
715 goal_handle.set_rejected(text=
"Received a goal with infinites or NaNs")
720 rospy.logerr(
"Received a goal without velocities")
721 goal_handle.set_rejected(text=
"Received a goal without velocities")
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)
737 self.goal_handle.set_canceled()
744 point0.time_from_start = rospy.Duration(0.0)
745 goal_handle.get_goal().trajectory.points.insert(0, point0)
750 self.
traj = goal_handle.get_goal().trajectory
751 self.goal_handle.set_accepted()
761 point0.time_from_start = rospy.Duration(0.0)
763 point1.velocities = [0] * 6
764 point1.accelerations = [0] * 6
765 point1.time_from_start = rospy.Duration(STOP_DURATION)
767 self.
traj = JointTrajectory()
768 self.traj.joint_names = joint_names
769 self.traj.points = [point0, point1]
771 self.goal_handle.set_canceled()
774 goal_handle.set_canceled()
776 last_now = time.time()
780 if (now - self.
traj_t0) <= self.traj.points[-1].time_from_start.to_sec():
784 self.robot.send_servoj(999, setpoint.positions, 4 * self.
RATE)
793 last_point = self.traj.points[-1]
794 state = self.robot.get_joint_states()
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())
807 self.robot.send_servoj(999, setpoint.positions, 4 * self.
RATE)
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:
820 self.goal_handle.set_succeeded()
834 from lxml
import etree
835 robot_description = rospy.get_param(
"robot_description")
836 doc = etree.fromstring(robot_description)
840 expr =
"/robot/joint[@name=$name]/calibration_offset" 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)
851 rospy.logwarn(
"No calibration offset for joint \"%s\"" % joint)
855 s = socket.create_connection((robot_ip, port))
856 tmp = s.getsockname()[0]
863 if req.fun == req.FUN_SET_DIGITAL_OUT:
864 r.set_digital_out(req.pin, req.state)
866 elif req.fun == req.FUN_SET_FLAG:
867 r.set_flag(req.pin, req.state)
869 elif req.fun == req.FUN_SET_ANALOG_OUT:
870 r.set_analog_out(req.pin, req.state)
872 elif req.fun == req.FUN_SET_TOOL_VOLTAGE:
873 r.set_tool_voltage(req.pin)
876 raise ROSServiceException(
"Robot not connected")
879 s= rospy.Service(
'set_io', SetIO, handle_set_io)
882 global prevent_programming
883 prevent_programming = config.prevent_programming
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!!!")
892 global prevent_programming
893 reconfigure_srv = Server(URDriverConfig, reconfigure_callback)
895 prefix = rospy.get_param(
"~prefix",
"")
896 print(
"Setting prefix to %s" % prefix)
898 joint_names = [prefix + name
for name
in JOINT_NAMES]
901 parser = optparse.OptionParser(usage=
"usage: %prog robot_hostname [reverse_port]")
902 (options, args) = parser.parse_args(rospy.myargv()[1:])
904 parser.error(
"You must specify the robot hostname")
906 robot_hostname = args[0]
907 reverse_port = DEFAULT_REVERSE_PORT
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")
914 parser.error(
"Wrong number of parameters")
919 if len(joint_offsets) > 0:
920 rospy.loginfo(
"Loaded calibration offsets from urdf: %s" % joint_offsets)
922 rospy.loginfo(
"No calibration offsets loaded from urdf")
927 max_velocity = rospy.get_param(
"~max_velocity", MAX_VELOCITY)
928 rospy.loginfo(
"Max velocity accepted by ur_driver: %s [rad/s]" % max_velocity)
932 min_payload = rospy.get_param(
"~min_payload", MIN_PAYLOAD)
935 max_payload = rospy.get_param(
"~max_payload", MAX_PAYLOAD)
936 rospy.loginfo(
"Bounds for Payload: [%s, %s]" % (min_payload, max_payload))
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()
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)
949 connection.send_reset_program()
952 connectionRT.connect()
956 service_provider =
None 959 while not rospy.is_shutdown():
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))
970 if prevent_programming:
971 print(
"Programming now prevented")
972 connection.send_reset_program()
974 print(
"Disconnected. Reconnecting")
976 action_server.set_robot(
None)
978 rospy.loginfo(
"Programming the robot")
981 while not connection.ready_to_program():
982 print(
"Waiting to program")
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))
991 connection.send_program()
996 rospy.loginfo(
"Robot connected")
1000 service_provider.set_robot(r)
1005 action_server.set_robot(r)
1008 action_server.start()
1010 except KeyboardInterrupt:
1013 rospy.signal_shutdown(
"KeyboardInterrupt")
1019 if __name__ ==
'__main__':
main()
def get_joint_states(self)
robot_state
IO-Support is EXPERIMENTAL.
def set_robot(self, robot)
def set_digital_out(self, pinnum, value)
def __on_packet(self, buf)
def __init__(self, hostname, port, program)
def throttle_warn_unknown(self, period, msg)
def __send_message(self, data)
def ready_to_program(self)
def __trigger_disconnected(self)
def init_traj_from_robot(self)
def set_analog_out(self, pinnum, value)
def set_flag(self, pin, val)
def send_servoj(self, waypoint_id, q_actual, t)
def __init__(self, hostname, port)
def __trigger_ready_to_program(self)
def on_goal(self, goal_handle)
def __init__(self, robot, goal_time_tolerance=None)
def set_robot(self, robot)
def interp_cubic(p0, p1, t_abs)
def __trigger_disconnected(self)
def getConnectedRobot(wait=False, timeout=-1)
def set_tool_voltage(self, value)
def send_payload(self, payload)
def on_cancel(self, goal_handle)
def get_segment_duration(traj, index)
def within_tolerance(a_vec, b_vec, tol_vec)
def __trigger_halted(self)
def get_my_ip(robot_ip, port)
def reorder_traj_joints(traj, joint_names)
def __init__(self, robot)
def set_waypoint_finished_cb(self, cb)
def load_joint_offsets(joint_names)
def has_limited_velocities(traj)
def reconfigure_callback(config, level)
def send_reset_program(self)
def __on_packet(self, buf)
def setPayload(self, req)