Classes | Functions | Variables
ur_driver.driver Namespace Reference

Classes

class  CommanderTCPHandler
 
class  EOF
 
class  TCPServer
 
class  URConnection
 
class  URConnectionRT
 
class  URServiceProvider
 
class  URTrajectoryFollower
 

Functions

def dumpstacks ()
 
def get_my_ip (robot_ip, port)
 
def get_segment_duration (traj, index)
 
def getConnectedRobot (wait=False, timeout=-1)
 
def handle_set_io (req)
 
def has_limited_velocities (traj)
 
def has_velocities (traj)
 
def interp_cubic (p0, p1, t_abs)
 
def joinAll (threads)
 
def load_joint_offsets (joint_names)
 
def log (s)
 
def main ()
 
def reconfigure_callback (config, level)
 
def reorder_traj_joints (traj, joint_names)
 
def sample_traj (traj, t)
 
def set_io_server ()
 
def setConnectedRobot (r)
 
def traj_is_finite (traj)
 
def within_tolerance (a_vec, b_vec, tol_vec)
 

Variables

 connected_robot = None
 
 connected_robot_cond = threading.Condition(connected_robot_lock)
 
 connected_robot_lock = threading.Lock()
 
int DEFAULT_REVERSE_PORT = 50001
 
 DigitalIn = Digital
 
 DigitalOut = Digital
 
 Flag = Digital
 
float IO_SLEEP_TIME = 0.05
 
list JOINT_NAMES
 
dictionary joint_offsets = {}
 
 last_joint_states = None
 
 last_joint_states_lock = threading.Lock()
 
float MAX_PAYLOAD = 1.0
 
float MAX_VELOCITY = 10.0
 
float MIN_PAYLOAD = 0.0
 
int MSG_GET_IO = 11
 
int MSG_JOINT_STATES = 3
 
int MSG_MOVEJ = 4
 
int MSG_OUT = 1
 
int MSG_QUIT = 2
 
int MSG_SERVOJ = 7
 
int MSG_SET_ANALOG_OUT = 14
 
int MSG_SET_DIGITAL_OUT = 10
 
int MSG_SET_FLAG = 12
 
int MSG_SET_PAYLOAD = 8
 
int MSG_SET_TOOL_VOLTAGE = 13
 
int MSG_STOPJ = 6
 
int MSG_WAYPOINT_FINISHED = 5
 
int MSG_WRENCH = 9
 
float MULT_analog = 1000000.0
 
float MULT_analog_robotstate = 0.1
 
float MULT_blend = 1000.0
 
float MULT_jointstate = 10000.0
 
float MULT_payload = 1000.0
 
float MULT_time = 1000000.0
 
float MULT_wrench = 10000.0
 
int PORT = 30002
 
bool prevent_programming = False
 
 pub_io_states = rospy.Publisher('io_states', IOStates, queue_size=1)
 
 pub_joint_states = rospy.Publisher('joint_states', JointState, queue_size=1)
 
 pub_wrench = rospy.Publisher('wrench', WrenchStamped, queue_size=1)
 
list Q1 = [2.2,0,-1.57,0,0,0]
 
list Q2 = [1.5,0,-1.57,0,0,0]
 
list Q3 = [1.5,-0.2,-1.57,0,0,0]
 
string RESET_PROGRAM
 
int RT_PORT = 30003
 

Function Documentation

def ur_driver.driver.dumpstacks ( )

Definition at line 101 of file driver.py.

def ur_driver.driver.get_my_ip (   robot_ip,
  port 
)

Definition at line 854 of file driver.py.

def ur_driver.driver.get_segment_duration (   traj,
  index 
)

Definition at line 541 of file driver.py.

def ur_driver.driver.getConnectedRobot (   wait = False,
  timeout = -1 
)

Definition at line 391 of file driver.py.

def ur_driver.driver.handle_set_io (   req)

Definition at line 860 of file driver.py.

def ur_driver.driver.has_limited_velocities (   traj)

Definition at line 604 of file driver.py.

def ur_driver.driver.has_velocities (   traj)

Definition at line 611 of file driver.py.

def ur_driver.driver.interp_cubic (   p0,
  p1,
  t_abs 
)

Definition at line 561 of file driver.py.

def ur_driver.driver.joinAll (   threads)

Definition at line 534 of file driver.py.

def ur_driver.driver.load_joint_offsets (   joint_names)

Definition at line 833 of file driver.py.

def ur_driver.driver.log (   s)

Definition at line 112 of file driver.py.

def ur_driver.driver.main ( )

Definition at line 887 of file driver.py.

def ur_driver.driver.reconfigure_callback (   config,
  level 
)

Definition at line 881 of file driver.py.

def ur_driver.driver.reorder_traj_joints (   traj,
  joint_names 
)

Definition at line 548 of file driver.py.

def ur_driver.driver.sample_traj (   traj,
  t 
)

Definition at line 580 of file driver.py.

def ur_driver.driver.set_io_server ( )

Definition at line 878 of file driver.py.

def ur_driver.driver.setConnectedRobot (   r)

Definition at line 385 of file driver.py.

def ur_driver.driver.traj_is_finite (   traj)

Definition at line 594 of file driver.py.

def ur_driver.driver.within_tolerance (   a_vec,
  b_vec,
  tol_vec 
)

Definition at line 617 of file driver.py.

Variable Documentation

ur_driver.driver.connected_robot = None

Definition at line 89 of file driver.py.

ur_driver.driver.connected_robot_cond = threading.Condition(connected_robot_lock)

Definition at line 91 of file driver.py.

ur_driver.driver.connected_robot_lock = threading.Lock()

Definition at line 90 of file driver.py.

int ur_driver.driver.DEFAULT_REVERSE_PORT = 50001

Definition at line 45 of file driver.py.

ur_driver.driver.DigitalIn = Digital

Definition at line 30 of file driver.py.

ur_driver.driver.DigitalOut = Digital

Definition at line 31 of file driver.py.

ur_driver.driver.Flag = Digital

Definition at line 32 of file driver.py.

float ur_driver.driver.IO_SLEEP_TIME = 0.05

Definition at line 79 of file driver.py.

list ur_driver.driver.JOINT_NAMES
Initial value:
1 = ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint',
2  'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']

Definition at line 81 of file driver.py.

dictionary ur_driver.driver.joint_offsets = {}

Definition at line 41 of file driver.py.

ur_driver.driver.last_joint_states = None

Definition at line 92 of file driver.py.

ur_driver.driver.last_joint_states_lock = threading.Lock()

Definition at line 93 of file driver.py.

float ur_driver.driver.MAX_PAYLOAD = 1.0

Definition at line 75 of file driver.py.

float ur_driver.driver.MAX_VELOCITY = 10.0

Definition at line 70 of file driver.py.

float ur_driver.driver.MIN_PAYLOAD = 0.0

Definition at line 74 of file driver.py.

int ur_driver.driver.MSG_GET_IO = 11

Definition at line 57 of file driver.py.

int ur_driver.driver.MSG_JOINT_STATES = 3

Definition at line 49 of file driver.py.

int ur_driver.driver.MSG_MOVEJ = 4

Definition at line 50 of file driver.py.

int ur_driver.driver.MSG_OUT = 1

Definition at line 47 of file driver.py.

int ur_driver.driver.MSG_QUIT = 2

Definition at line 48 of file driver.py.

int ur_driver.driver.MSG_SERVOJ = 7

Definition at line 53 of file driver.py.

int ur_driver.driver.MSG_SET_ANALOG_OUT = 14

Definition at line 60 of file driver.py.

int ur_driver.driver.MSG_SET_DIGITAL_OUT = 10

Definition at line 56 of file driver.py.

int ur_driver.driver.MSG_SET_FLAG = 12

Definition at line 58 of file driver.py.

int ur_driver.driver.MSG_SET_PAYLOAD = 8

Definition at line 54 of file driver.py.

int ur_driver.driver.MSG_SET_TOOL_VOLTAGE = 13

Definition at line 59 of file driver.py.

int ur_driver.driver.MSG_STOPJ = 6

Definition at line 52 of file driver.py.

int ur_driver.driver.MSG_WAYPOINT_FINISHED = 5

Definition at line 51 of file driver.py.

int ur_driver.driver.MSG_WRENCH = 9

Definition at line 55 of file driver.py.

float ur_driver.driver.MULT_analog = 1000000.0

Definition at line 66 of file driver.py.

float ur_driver.driver.MULT_analog_robotstate = 0.1

Definition at line 67 of file driver.py.

float ur_driver.driver.MULT_blend = 1000.0

Definition at line 65 of file driver.py.

float ur_driver.driver.MULT_jointstate = 10000.0

Definition at line 63 of file driver.py.

float ur_driver.driver.MULT_payload = 1000.0

Definition at line 61 of file driver.py.

float ur_driver.driver.MULT_time = 1000000.0

Definition at line 64 of file driver.py.

float ur_driver.driver.MULT_wrench = 10000.0

Definition at line 62 of file driver.py.

int ur_driver.driver.PORT = 30002

Definition at line 43 of file driver.py.

bool ur_driver.driver.prevent_programming = False

Definition at line 34 of file driver.py.

ur_driver.driver.pub_io_states = rospy.Publisher('io_states', IOStates, queue_size=1)

Definition at line 96 of file driver.py.

ur_driver.driver.pub_joint_states = rospy.Publisher('joint_states', JointState, queue_size=1)

Definition at line 94 of file driver.py.

ur_driver.driver.pub_wrench = rospy.Publisher('wrench', WrenchStamped, queue_size=1)

Definition at line 95 of file driver.py.

list ur_driver.driver.Q1 = [2.2,0,-1.57,0,0,0]

Definition at line 84 of file driver.py.

list ur_driver.driver.Q2 = [1.5,0,-1.57,0,0,0]

Definition at line 85 of file driver.py.

list ur_driver.driver.Q3 = [1.5,-0.2,-1.57,0,0,0]

Definition at line 86 of file driver.py.

string ur_driver.driver.RESET_PROGRAM
Initial value:
1 = '''def resetProg():
2  sleep(0.0)
3 end
4 '''

Definition at line 116 of file driver.py.

int ur_driver.driver.RT_PORT = 30003

Definition at line 44 of file driver.py.



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