Skip to main content

UR5e

Inherits from: Arm A class to control the Universal Robots UR5e robotic arm. Attributes: rtde_c: RTDE Control interface object rtde_r: RTDE Receive interface object rtde_i: RTDE IO interface object end_effector: Gripper/end effector object if attached, should be an INSTANTIATED object ee_state (int): Current state of end effector (OPEN/CLOSED)

Inherited methods

  • From Arm: setNamedPose, removeNamedPose, getNamedPose
  • From Robot: addSensor, cleanup

init

UR5e.__init__(robot_ip: str = '192.168.1.102', end_effector = None, cameras: Optional[Dict[str, Camera]] = None, enable_control: bool = True)
Initialize the UR5e robot arm.
Arguments
robot_ip (str)
str
IP address of the robot. Defaults to “192.168.1.102”.
end_effector (optional)
optional
End effector instance to use. Defaults to None.
cameras (Optional[Dict[str, Camera]])
Optional[Dict[str, Camera]]
Named camera interfaces. Defaults to None.
enable_control (bool)
bool
Whether to enable the rtde_c interface of the robot. For free-drive mode, set to False.

getImage

UR5e.getImage(camera_name: str, image_type: str = 'rgb') -> Image
Get an image from the robot’s camera. Note: Camera names must match those defined during robot configuration.
Arguments
camera_name (str)
str
required
Name of the camera to get an image from.
image_type (str)
str
Type of image to retrieve. One of [“rgb”, “depth_meters”]. Defaults to “rgb”.
Returns
Image
Image
image from the specified camera

moveToDeltaPose

UR5e.moveToDeltaPose(delta_position: Position, delta_orientation: Orientation = Orientation(0, 0, 0, 1.0), blocking: bool = True, moving_time: float = 0.5, accel_time: float = 0.2)
Move the robot end effector by a relative pose offset from its current pose.
Arguments
delta_position (Position)
Position
required
position offset (relative to the current position) added to current XYZ coordinates (meters)
delta_orientation (Orientation)
Orientation
orientation offset (relative to the current orientation) composed with current orientation. Defaults to the identity orientation.
blocking (bool)
bool
Wait for movement to complete. Defaults to True.
moving_time (float)
float
Time to complete the movement. Defaults to 0.5.
accel_time (float)
float
Time to accelerate/decelerate. Defaults to 0.2.
Returns
bool
True if the movement command was successful, False otherwise

getState

UR5e.getState() -> dict
Get the complete state (mode, joint positions, velocities, end effector force, pose, speed) of the ur5e as a dictionary.
Returns
dict
dict
Current state of the robot containing: - robot_mode: int, Current robot mode (eg. 0 = Disconnected, 2 = Booting, 7 = Running, etc.) - joint_positions: 6-element list, Current joint positions (radians) - joint_velocities: 6-element list, Current joint velocities (radians/s) - tcp_force: 6-element list, Generalized forces in the Tool Center Point (N) - tcp_pose: 6-element list, Current TCP pose [x, y, z, rx, ry, rz] where rotation is in rotation vector format - tcp_speed: 6-element list, Actual speed of the tool given in Cartesian coordinates (m/s)

moveToPose

UR5e.moveToPose(position: Position, orientation: Orientation, blocking: bool = True, moving_time: float = 2.0, accel_time: float = 0.5, avoid_force: bool = False, stop_acceleration: float = 5, force_threshold: float = 10)
Move the robot end effector to a specified pose with respect to the base frame. The argument avoid_force can be used to stop the movement early if the force applied to the end effector exceeds a threshold, useful for soft placement or other movements where a collision is possible/ expected.
Arguments
position (Position)
Position
required
Target pose position (meters)
orientation (Orientation)
Orientation
required
Target pose orientation
blocking (bool)
bool
Wait for movement to complete. Defaults to True.
moving_time (float)
float
Time to complete the movement (seconds). Defaults to 2.0s.
accel_time (float)
float
Time to spend accelerating and decelerating (seconds). Defaults to 0.5s.
avoid_force (bool)
bool
If True, the robot will stop the movement early if the force applied to the end effector exceeds a threshold. Defaults to False.
stop_acceleration (float)
float
Acceleration to use when stopping the movement. Defaults to 1.0.
force_threshold (float)
float
Threshold for force to consider the movement successful. Defaults to 10.0.
Returns
bool
True if the movement command was successful, False otherwise
Raises
ValueError
If moving_time or accel_time are not positive floats or integers

startFreeDrive

UR5e.startFreeDrive()
Starts free drive mode, in which the robot is compliant and can be moved by hand but supports its own weight.

endFreeDrive

UR5e.endFreeDrive()
Ends free drive mode, allowing the robot to be controlled by moveToPose() or moveToDeltaPose() (but no longer movable by hand)

moveToNamedPose

UR5e.moveToNamedPose(pose_name: str, blocking: bool = True, moving_time: float = 2.0, accel_time: float = 0.75)
Move the robot to the joint angles of a named pose.
Arguments
pose_name (str)
str
required
Name of the pose to move to. Options are “home”, “sleep”, and “upright”.
blocking (bool)
bool
Wait for movement to complete. Defaults to True.
moving_time (float)
float
Time to complete the movement. Defaults to 2.0.
accel_time (float)
float
Time to accelerate/decelerate. Defaults to 0.75.
Returns
bool
True if the movement command was successful, False otherwise

moveByVelocity

UR5e.moveByVelocity(linear_velocity: Velocity, angular_velocity: Velocity, frame: str = 'body')
Move the robot end effector with specified velocities.
Arguments
linear_velocity (Velocity)
Velocity
required
Linear velocity components
angular_velocity (Velocity)
Velocity
required
Angular velocity components
frame (str)
str
No description provided.

stop

UR5e.stop(immediate = False)
Stop any movement of the robot (soft emergency-stop).
Arguments
immediate (bool, optional)
bool, optional
If True, stops immediately by killing script. If False, performs controlled stop and doesn’t kill the script. Defaults to False.

suction_grasp

UR5e.suction_grasp(approach_direction: np.ndarray = None, compliant_force: bool = False, force: float = 20, approach_distance: float = 0.1, approach_time: float = 2, *args, **kwargs)
Performs last step of suction grip, approaches the object and returns to the original position Uses force readings to minimize excessive force on the robot
Arguments
approach_direction (np.ndarray)
np.ndarray
No description provided.
compliant_force (bool)
bool
No description provided.
force (float)
float
No description provided.
approach_distance (float)
float
No description provided.
approach_time (float)
float
No description provided.
args
No description provided.
kwargs
No description provided.

grasp

UR5e.grasp(*args, **kwargs)
Close the gripper to grasp an object. Only works if an end effector is configured. Changes ee_state to CLOSED.
Arguments
args
No description provided.
kwargs
No description provided.

validate_grasp

UR5e.validate_grasp()
Validate that the grasp is successful.
Returns
bool
True if the grasp is successful, False otherwise
None
If the end effector does not support validation

release

UR5e.release()
Open the gripper to release an object. Only works if an end effector is configured. Changes ee_state to OPEN.

shutdown

UR5e.shutdown()
Shutdown the robot safely. Stops the robot and disconnects RTDE interfaces.

getEndEffectorPose

UR5e.getEndEffectorPose() -> Pose
Get the current end effector pose with respect to the base frame.
Returns
Pose
Pose
Current end effector position and orientation

getPosition

UR5e.getPosition() -> Position
Get the current end effector position with respect to the robot base (meters)
Returns
Position
Position
Current end effector position with respect to the robot base

getOrientation

UR5e.getOrientation(name: str = '') -> Orientation
Get the current end effector orientation with respect to the robot base
Arguments
name (str)
str
No description provided.
Returns
Orientation
Orientation
Current end effector orientation with respect to the robot base
name
str, optional
Unused

getJointAngles

UR5e.getJointAngles() -> list
Get a list of the 6 current joint angles in radians
Returns
list
list
List of current joint angles in radians

getJointVelocities

UR5e.getJointVelocities() -> list
Get a list of the 6 current joint velocities in radians/second
Returns
list
list
List of current joint velocities in radians/second

setJointAngles

UR5e.setJointAngles(angles: list, blocking: bool = True, moving_time: float = 2.0, accel_time: float = 0.5)
Set joint angles directly.
Arguments
angles (list)
list
required
List of 6 target joint angles in radians
blocking (bool)
bool
Wait for movement to complete. Defaults to True.
moving_time (float)
float
Time to complete the movement. Defaults to 2.0.
accel_time (float)
float
Time to accelerate/decelerate. Defaults to 0.5.
Returns
bool
True if the movement command was successful, False otherwise
Raises
ValueError
If moving_time or accel_time are not positive floats or integers

moveToHome

UR5e.moveToHome(moving_time: float = 2.0, accel_time: float = 0.75)
Move the robot to a predefined home position.
Arguments
moving_time (float)
float
No description provided.
accel_time (float)
float
No description provided.

servoJointAngles

UR5e.servoJointAngles(angles: list, time: float, lookahead_time: float = 0.03, gain: float = 300.0)
Command the setpoint and gain of the low-level joint position controller (linear in joint-space). This function expects to be called in a 500Hz loop with joint positions that are close to each other. Example use cases: real-time control using classical or Reinforcement-Learning controllers.
Arguments
angles (list)
list
required
List of target joint angles in radians
time (float)
float
required
(seconds) Duration for which the command controls the robot. This is blocking.
lookahead_time (float)
float
(seconds) Range [0.03,0.2]. The current position is projected forward in time with the current velocity, and used to smooth the trajectory. A low value gives fast reaction, a high value prevents overshoot.
gain (float)
float
(range [100,2000]) Proportional gain of the PID controller that tracks target joint position Higher gains will cause the robot to move faster, but could cause jerkiness or oscillations.
Returns
bool
True if the movement command was successful, False otherwise
Raises
ValueError
If time is not a positive float or int

initPeriod

UR5e.initPeriod()
Initialize the control loop period to 0.002 seconds (500Hz).
Returns
Optional[float]
Current time (indicating the start of the current loop iteration), or None if the robot is not in control mode

waitPeriod

UR5e.waitPeriod(t_start: float)
Wait for the rest of the 0.002 second (500Hz) control period using a combination of sleep and spin. Used together with initPeriod and servoJointAngles (see ServoJointAngles documentation for example).
Arguments
t_start (float)
float
required
(float) Time at which the current loop iteration started, from initPeriod()