Data streaming with Primary Interface

Data described below are sent by the robot controller at 10Hz by the TCP/IP Primary (and Secondary) Interface protocol.

For more information about Primry Interface, see : https://www.universal-robots.com/articles/ur/interface-communication/remote-control-via-tcpip/

Enable Primary Interface

When creating the ConnectParameters object or when the Connect() method is called by passing the IP address of the robot, the Primary Interface protocol is enabled by default.

You can however connect by specifying a ConnectParameters object. You can then choose the port to connect to.

var robot = new UR();
var param = new ConnectParameters("192.168.0.1");
param.PrimaryInterface.Enable = true; // enable Primary Interface
// param.PrimaryInterface.Enable = false; // Connect to the robot without Primary Interface
param.PrimaryInterface.Port = Interfaces.PrimaryInterface;
// Connect to the robot with custom parameters
robot.Connect(param);
// you can also connect directly without ConnectParameters
// Primary Interface and Dashboard are enabled by default
// robot.Connect("192.168.0.56");
//...
// Access all your data
var value = robot.PrimaryInterface.JointData.Base.ActualSpeed;
//...
// Disconnect only Primary Interface communication
robot.PrimaryInterface.Disconnect();
// Disconnect every interfaces (Primary Interface, Dashboard, RTDE, ...)
robot.Disconnect();

You can also instantiate a PrimaryInterface client directly without using the UR object.

// Create a Prinmary Interface Client alone, outside any UR instance
var client = new PrimaryInterfaceClient();
// Open TCP connection to the robot
client.Connect("192.168.0.1", Interfaces.PrimaryInterface);
//...
// Access all your data
var value = client.JointData.Base.ActualSpeed;
//...
// Close connection to the robot
client.Disconnect();

Get data

Once communication is established with the robot, you will receive data at 10Hz. You can either handle an event that is raised when data is received. But you can also access the last packet received through a property.

// Access last received data with properties
JointDataPackageEventArgs lastJointDataReceived = robot.PrimaryInterface.JointData;
KinematicsInfoPackageEventArgs lastKinematicsInfo = robot.PrimaryInterface.KinematicsInfo;
// Or you can subscribe to an event to be notified as soon as the data arrives
robot.PrimaryInterface.JointDataReceived += PrimaryInterface_JointDataReceived;

Get connection status

The Connected property indicates whether the interface is connected. If the interface disconnects (e.g. the robot is stopped or the network cable is disconnected), this property is set to false without raising a fault.

There is no automatic reconnection mechanism. You will have to call the Connect() function again.

However, if an error occurs inside the library, the InternalErrorOccured event is raised.

// Check if Primary Interface client is still connected
bool isConnected = robot.PrimaryInterface.Connected;
// Handle the event that indicates an internal error
robot.InternalErrorOccured += Robot_InternalErrorOccured;

Try it with the Windows example

Robot mode

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
RobotModeDataPackageEventArgs _value = ur.RobotModeData;
// Attach a delegate to the event triggered when new package comes
ur.RobotModeDataReceived += Ur_RobotModeDataReceived;
}
private void Ur_RobotModeDataReceived(object sender, RobotModeDataPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.RobotModeDataPackageEventArgs :
public class RobotModeDataPackageEventArgs : PackageEventArgs {
// Current robot control mode
[PackageDescription("Current robot control mode")]
public ControlModes ControlMode { get; set; }
// The button Emergency Stop is pressed
[PackageDescription("The button Emergency Stop is pressed")]
public bool EmergencyStopped { get; set; }
// Robot is connected to its controller
[PackageDescription("Robot is connected to its controller")]
public bool PhysicalRobotConnected { get; set; }
// The running program is paused
[PackageDescription("The running program is paused")]
public bool ProgramPaused { get; set; }
// A program is running
[PackageDescription("A program is running")]
public bool ProgramRunning { get; set; }
// A stop occured due to a fault detection
[PackageDescription("A stop occured due to a fault detection")]
public bool ProtectiveStopped { get; set; }
// Real robot mode active. False if robot is in simulation
[PackageDescription("Real robot mode active. False if robot is in simulation")]
public bool RealRobotEnabled { get; set; }
// Current robot running mode
[PackageDescription("Current robot running mode")]
public RobotModes RobotMode { get; set; }
// Robot is powered on and boot is completed. If false, you need to press "ON" button to power it on
[PackageDescription("Robot is powered on and boot is completed. If false, you need to press \"ON\" button to power it on")]
public bool RobotPowerOn { get; set; }
// Speed scaling
[PackageDescription("Speed scaling")]
public double SpeedScaling { get; set; }
// Overriden speed ratio between 0 (0%) and 1 (100%)
[PackageDescription("Overriden speed ratio between 0 (0%) and 1 (100%)")]
public double TargetSpeedFraction { get; set; }
// Maximum target speed fraction
[PackageDescription("Maximum target speed fraction")]
public double TargetSpeedFractionLimit { get; set; }
// Timespan since the robot controller has started
[PackageDescription("Timespan since the robot controller has started")]
public TimeSpan Timestamp { get; set; }
}
Members of Common.ControlModes :
public enum ControlModes {
// Robot is force controlled. (For example : URScript force_mode() function is called)
Force = 2
// Robot is position controlled
Position = 0
// The robot is hand guided by pushing teached button
Teach = 1
// Robot is torque controlled
Torque = 3
}
Members of Common.RobotModes :
public enum RobotModes {
// The robot is hand guided by pushing teached button
BackDrive = 6
// The robot controller is booting
Booting = 2
// Robot has stopped due to a Safety Stop
ConfirmSafety = 1
// Robot is not connected to its controller
Disconnected = 0
// Power is on but breaks are not released
Idle = 5
// Robot is in an obsolete CB2 mode
Other = -1
// The robot is powered off
PowerOff = 3
// The robot is powered on
PowerOn = 4
// Robot is in normal mode
Running = 7
// Firmware is upgrading
UpdatingFirmware = 8
}

Joint data

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
JointDataPackageEventArgs _value = ur.JointData;
// Attach a delegate to the event triggered when new package comes
ur.JointDataReceived += Ur_JointDataReceived;
}
private void Ur_JointDataReceived(object sender, JointDataPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.JointDataPackageEventArgs :
public class JointDataPackageEventArgs : PackageEventArgs {
// Base joint data
[PackageDescription("Base joint data")]
public JointData Base { get; set; }
// Elbow joint data
[PackageDescription("Elbow joint data")]
public JointData Elbow { get; set; }
// Shoulder joint data
[PackageDescription("Shoulder joint data")]
public JointData Shoulder { get; set; }
// Wrist1 joint data
[PackageDescription("Wrist1 joint data")]
public JointData Wrist1 { get; set; }
// Wrist2 joint data
[PackageDescription("Wrist2 joint data")]
public JointData Wrist2 { get; set; }
// Wrist3 (Tool) joint data
[PackageDescription("Wrist3 (Tool) joint data")]
public JointData Wrist3 { get; set; }
}

Members of PrimaryInterface.JointData :
public class JointData {
// Joint rotation speed in rad/s
[PackageDescription("Joint rotation speed in rad/s", PackageUnit.RadianPerSecond)]
public double ActualSpeed { get; set; }
// Motor current in Amps
[PackageDescription("Motor current in Amps", PackageUnit.Amp)]
public float Current { get; set; }
// Joint mode
[PackageDescription("Joint mode")]
public JointModes JointMode { get; set; }
// Angular joint position in radian
[PackageDescription("Angular joint position in radian", PackageUnit.Radian)]
public double Position { get; set; }
// Angular target position in radian
[PackageDescription("Angular target position in radian", PackageUnit.Radian)]
public double TargetPosition { get; set; }
// Joint temperature in °C
[PackageDescription("Joint temperature in °C", PackageUnit.CelciusDegree)]
public float Temperature { get; set; }
// Motor votage in Volts
[PackageDescription("Motor votage in Volts", PackageUnit.Volt)]
public float Voltage { get; set; }
}
Members of Common.JointModes :
public enum JointModes : byte {
Backdrive = 238
Booting = 247
Bootloder = 249
Calibration = 250
Fault = 252
Idle = 255
MotorInitialisation = 246
NotResponding = 245
PartDCalibration = 237
PartDCalibrationError = 248
PowerOff = 239
Running = 253
ShuttingDown = 236
}

Tool data

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
ToolDataPackageEventArgs _value = ur.ToolData;
// Attach a delegate to the event triggered when new package comes
ur.ToolDataReceived += Ur_ToolDataReceived;
}
private void Ur_ToolDataReceived(object sender, ToolDataPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.ToolDataPackageEventArgs :
public class ToolDataPackageEventArgs : PackageEventArgs {
// Value of Analog input 2 (analog_in[2])
[PackageDescription("Value of Analog input 2 (analog_in[2])")]
public double AnalogInput2 { get; set; }
// Value of Analog input 3 (analog_in[3])
[PackageDescription("Value of Analog input 3 (analog_in[3])")]
public double AnalogInput3 { get; set; }
// Unit of analog input 2 (analog_in[2])
[PackageDescription("Unit of analog input 2 (analog_in[2])")]
public AnalogRanges AnalogInputRange2 { get; set; }
// Unit of analog input 3 (analog_in[3])
[PackageDescription("Unit of analog input 3 (analog_in[3])")]
public AnalogRanges AnalogInputRange3 { get; set; }
// Tool current in Amps
[PackageDescription("Tool current in Amps", PackageUnit.Amp)]
public float ToolCurrent { get; set; }
// Tool mode
[PackageDescription("Tool mode")]
public ToolModes ToolMode { get; set; }
// Tool output voltage
[PackageDescription("Tool output voltage", PackageUnit.Volt)]
public sbyte ToolOutputVoltage { get; set; }
// Tool Temperature in °C
[PackageDescription("Tool Temperature in °C", PackageUnit.CelciusDegree)]
public float ToolTemperature { get; set; }
// Actual robot voltage power supply
[PackageDescription("Actual robot voltage power supply", PackageUnit.Volt)]
public float ToolVoltage48V { get; set; }
}
Members of Common.AnalogRanges :
public enum AnalogRanges {
// The analog value is in Amps (A)
Current = 0
// The analog value is in Volts (V)
Voltage = 1
}
Members of Common.ToolModes :
public enum ToolModes : byte {
// Bootloader
Bootloader = 249
// Idle
Idle = 255
// Running
Running = 253
}

Masterboard data

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
MasterboardDataPackageEventArgs _value = ur.MasterboardData;
// Attach a delegate to the event triggered when new package comes
ur.MasterboardDataReceived += Ur_MasterboardDataReceived;
}
private void Ur_MasterboardDataReceived(object sender, MasterboardDataPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.MasterboardDataPackageEventArgs :
public class MasterboardDataPackageEventArgs : PackageEventArgs {
// Value of analog input 0 (analog_in[0])
[PackageDescription("Value of analog input 0 (analog_in[0])")]
public double AnalogInput0 { get; set; }
// Value of analog input 1 (analog_in[1])
[PackageDescription("Value of analog input 1 (analog_in[1])")]
public double AnalogInput1 { get; set; }
// Unit of analog input 0 (analog_in[0])
[PackageDescription("Unit of analog input 0 (analog_in[0])")]
public AnalogRanges AnalogInputRange0 { get; set; }
// Unit of analog input 1 (analog_in[1])
[PackageDescription("Unit of analog input 1 (analog_in[1])")]
public AnalogRanges AnalogInputRange1 { get; set; }
// Value of analog output 0 (analog_out[0])
[PackageDescription("Value of analog output 0 (analog_out[0])")]
public double AnalogOutput0 { get; set; }
// Value of analog output 1 (analog_out[1])
[PackageDescription("Value of analog output 1 (analog_out[1])")]
public double AnalogOutput1 { get; set; }
// Unit of analog output 0 (analog_out[0])
[PackageDescription("Unit of analog output 0 (analog_out[0])")]
public AnalogRanges AnalogOutputDomain0 { get; set; }
// Unit of analog output 1 (analog_out[1)
[PackageDescription("Unit of analog output 1 (analog_out[1)")]
public AnalogRanges AnalogOutputDomain1 { get; set; }
// Register where each bit is a digital input value
[PackageDescription("Register where each bit is a digital input value")]
public MasterboardDigitalIO DigitalInputs { get; set; }
// Register where each bit is a digital output value
[PackageDescription("Register where each bit is a digital output value")]
public MasterboardDigitalIO DigitalOutputs { get; set; }
// The robot is interfaced to injection molding machines Euromap 67
[PackageDescription("The robot is interfaced to injection molding machines Euromap 67")]
public sbyte Euromap67Installed { get; set; }
// Euromap current
[PackageDescription("Euromap current", PackageUnit.Amp)]
public float EuromapCurrent { get; set; }
// Register where each bit is a digital Euromap input
[PackageDescription("Register where each bit is a digital Euromap input")]
public int EuromapInputBits { get; set; }
// Register where each bit is a digital Euromap output
[PackageDescription("Register where each bit is a digital Euromap output")]
public int EuromapOutputBits { get; set; }
// Euromap votage
[PackageDescription("Euromap votage", PackageUnit.Volt)]
public float EuromapVoltage { get; set; }
// Robot is in reduced speed mode
[PackageDescription("Robot is in reduced speed mode")]
public byte InReducedMode { get; set; }
// Temperature of masterboard in °C
[PackageDescription("Temperature of masterboard in °C", PackageUnit.CelciusDegree)]
public float MasterboardTemperature { get; set; }
// Current of all digital and analog inputs and outputs
[PackageDescription("Current of all digital and analog inputs and outputs", PackageUnit.Amp)]
public float MasterIOCurrent { get; set; }
// Position of operational mode selector input switch
[PackageDescription("Position of operational mode selector input switch")]
public byte OperationalModeSelectorInput { get; set; }
// Robot current consumption in Amps
[PackageDescription("Robot current consumption in Amps", PackageUnit.Amp)]
public float RobotCurrent { get; set; }
// Voltage of internal 48V power supply
[PackageDescription("Voltage of internal 48V power supply", PackageUnit.Volt)]
public float RobotVoltage48V { get; set; }
// Masterboard safety mode
[PackageDescription("Masterboard safety mode")]
public SafetyStatus Safetymode { get; set; }
// Position of the 3-position enabling device
[PackageDescription("Position of the 3-position enabling device")]
public byte ThreePositionEnablingDeviceInput { get; set; }
}
Members of Common.AnalogRanges :
public enum AnalogRanges {
// The analog value is in Amps (A)
Current = 0
// The analog value is in Volts (V)
Voltage = 1
}
Members of PrimaryInterface.MasterboardDigitalIO :
public class MasterboardDigitalIO {
// Register value seen as a bool array
[PackageDescription("Register value seen as a bool array")]
public BitArray BitArray { get; }
public bool Configurable0 { get; }
public bool Configurable1 { get; }
public bool Configurable2 { get; }
public bool Configurable3 { get; }
public bool Configurable4 { get; }
public bool Configurable5 { get; }
public bool Configurable6 { get; }
public bool Configurable7 { get; }
public bool Digital0 { get; }
public bool Digital1 { get; }
public bool Digital2 { get; }
public bool Digital3 { get; }
public bool Digital4 { get; }
public bool Digital5 { get; }
public bool Digital6 { get; }
public bool Digital7 { get; }
public bool ToolDigital0 { get; }
public bool ToolDigital1 { get; }
// Register value
[PackageDescription("Register value")]
public int Value { get; }
}
Members of Common.SafetyStatus :
public enum SafetyStatus : byte {
AutomaticModeSafeguardStop = 10
// Safety is in fault mode
Fault = 9
// Safety is in normal operating conditions
Normal = 1
// Protective safeguard Stop. This safety function is triggeredby an external protective device using safety inputs which will trigger a Cat 2 stop3per IEC 60204-1.
ProtectiveStop = 3
// When a safety limit is violated, the safety system must be restarted.
Recovery = 4
// Speed is reduced
Reduced = 2
// (EA + EB + SBUS->Screen) Physical e-stop interface input activated
RobotEmergencyStop = 7
// (SI0 + SI1 + SBUS) Physical s-stop interface input
SafeguardStop = 5
// (EA + EB + SBUS->Euromap67) Physical e-stop interface input activated
SystemEmergencyStop = 6
SystemThreePositionEnablingStop = 11
// Safety is in violation mode (for example, violation of the allowed delay between redundant signals)
Violation = 8
}

Cartesian information

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
CartesianInfoPackageEventArgs _value = ur.CartesianInfo;
// Attach a delegate to the event triggered when new package comes
ur.CartesianInfoReceived += Ur_CartesianInfoReceived;
}
private void Ur_CartesianInfoReceived(object sender, CartesianInfoPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.CartesianInfoPackageEventArgs :
public class CartesianInfoPackageEventArgs : PackageEventArgs {
// RX axis coordinate in rad of the TCP in the current frame
[PackageDescription("RX axis coordinate in rad of the TCP in the current frame", PackageUnit.Radian)]
public double Rx { get; set; }
// RY axis coordinate in rad of the TCP in the current frame
[PackageDescription("RY axis coordinate in rad of the TCP in the current frame", PackageUnit.Radian)]
public double Ry { get; set; }
// RZ axis coordinate in rad of the TCP in the current frame
[PackageDescription("RZ axis coordinate in rad of the TCP in the current frame", PackageUnit.Radian)]
public double Rz { get; set; }
// RX position of the TCP in the flange frame in rad
[PackageDescription("RX position of the TCP in the flange frame in rad", PackageUnit.Radian)]
public double TCPOffsetRX { get; set; }
// RY position of the TCP in the flange frame in rad
[PackageDescription("RY position of the TCP in the flange frame in rad", PackageUnit.Radian)]
public double TCPOffsetRY { get; set; }
// RZ position of the TCP in the flange frame in rad
[PackageDescription("RZ position of the TCP in the flange frame in rad", PackageUnit.Radian)]
public double TCPOffsetRZ { get; set; }
// X position of the TCP in the flange frame in meter
[PackageDescription("X position of the TCP in the flange frame in meter", PackageUnit.Meter)]
public double TCPOffsetX { get; set; }
// Y position of the TCP in the flange frame in meter
[PackageDescription("Y position of the TCP in the flange frame in meter", PackageUnit.Meter)]
public double TCPOffsetY { get; set; }
// Z position of the TCP in the flange frame in meter
[PackageDescription("Z position of the TCP in the flange frame in meter", PackageUnit.Meter)]
public double TCPOffsetZ { get; set; }
// X axis coordinate in meter of the TCP in the current frame
[PackageDescription("X axis coordinate in meter of the TCP in the current frame", PackageUnit.Meter)]
public double X { get; set; }
// Y axis coordinate in meter of the TCP in the current frame
[PackageDescription("Y axis coordinate in meter of the TCP in the current frame", PackageUnit.Meter)]
public double Y { get; set; }
// Z axis coordinate in meter of the TCP in the current frame
[PackageDescription("Z axis coordinate in meter of the TCP in the current frame", PackageUnit.Meter)]
public double Z { get; set; }
}

Kinematics information

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
KinematicsInfoPackageEventArgs _value = ur.KinematicsInfo;
// Attach a delegate to the event triggered when new package comes
ur.KinematicsInfoReceived += Ur_KinematicsInfoReceived;
}
private void Ur_KinematicsInfoReceived(object sender, KinematicsInfoPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.KinematicsInfoPackageEventArgs :
public class KinematicsInfoPackageEventArgs : PackageEventArgs {
// Base kinematics info
[PackageDescription("Base kinematics info")]
public JointKinematicsInfo Base { get; set; }
// Calibration status (0 : OK)
[PackageDescription("Calibration status (0 : OK)")]
public int CalibrationStatus { get; set; }
// Elbow kinematics info
[PackageDescription("Elbow kinematics info")]
public JointKinematicsInfo Elbow { get; set; }
// Shoulder kinematics info
[PackageDescription("Shoulder kinematics info")]
public JointKinematicsInfo Shoulder { get; set; }
// Wrist1 kinematics info
[PackageDescription("Wrist1 kinematics info")]
public JointKinematicsInfo Wrist1 { get; set; }
// Wrist2 kinematics info
[PackageDescription("Wrist2 kinematics info")]
public JointKinematicsInfo Wrist2 { get; set; }
// Wrist3 (Tool) kinematics info
[PackageDescription("Wrist3 (Tool) kinematics info")]
public JointKinematicsInfo Wrist3 { get; set; }
}

Members of PrimaryInterface.JointKinematicsInfo :
public class JointKinematicsInfo {
// Joint checksum
[PackageDescription("Joint checksum")]
public int Checksum { get; set; }
// DH convention a parameter
[PackageDescription("DH convention a parameter", PackageUnit.Meter)]
public double DHa { get; set; }
// DH convention alpha parameter
[PackageDescription("DH convention alpha parameter", PackageUnit.Radian)]
public double Dhalpha { get; set; }
// DH convention d parameter
[PackageDescription("DH convention d parameter", PackageUnit.Meter)]
public double DHd { get; set; }
// DH convention theta parameter
[PackageDescription("DH convention theta parameter", PackageUnit.Radian)]
public double DHtheta { get; set; }
}

For more information about DH (Denavit-Hartenberg) parameters, please refer the following links :

Configuration data

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
ConfigurationDataPackageEventArgs _value = ur.ConfigurationData;
// Attach a delegate to the event triggered when new package comes
ur.ConfigurationDataReceived += Ur_ConfigurationDataReceived;
}
private void Ur_ConfigurationDataReceived(object sender, ConfigurationDataPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.ConfigurationDataPackageEventArgs :
public class ConfigurationDataPackageEventArgs : PackageEventArgs {
// Default joint acceleration speed in rad/s²
[PackageDescription("Default joint acceleration speed in rad/s²", PackageUnit.RadianPerSecondSquared)]
public double AJointDefault { get; set; }
// Default TCP acceleration speed in m/s²
[PackageDescription("Default TCP acceleration speed in m/s²", PackageUnit.MeterPersSecondSquared)]
public double AToolDefault { get; set; }
// Base joint configuration
[PackageDescription("Base joint configuration")]
public JointConfiguration Base { get; set; }
// Controller box type
[PackageDescription("Controller box type")]
public ControllerBoxTypes ControllerBoxType { get; set; }
// Elbow joint configuration
[PackageDescription("Elbow joint configuration")]
public JointConfiguration Elbow { get; set; }
// Equipment radius in meter
[PackageDescription("Equipment radius in meter", PackageUnit.Meter)]
public double EqRadius { get; set; }
// Masterboard version
[PackageDescription("Masterboard version")]
public int MasterboardVersion { get; set; }
// Robot serie
[PackageDescription("Robot serie")]
public RobotSubTypes RobotSubType { get; set; }
// Model of the robot (UR3, UR5, UR10, UR16)
[PackageDescription("Model of the robot")]
public RobotModels RobotType { get; set; }
// Shoulder joint configuration
[PackageDescription("Shoulder joint configuration")]
public JointConfiguration Shoulder { get; set; }
// Default joint angular speed in rad/s
[PackageDescription("Default joint angular speed in rad/s", PackageUnit.RadianPerSecond)]
public double VJointDefault { get; set; }
// Default TCP speed speed in m/s
[PackageDescription("Default TCP speed speed in m/s", PackageUnit.MeterPerSecond)]
public double VToolDefault { get; set; }
// Wrist1 joint configuration
[PackageDescription("Wrist1 joint configuration")]
public JointConfiguration Wrist1 { get; set; }
// Wrist2 joint configuration
[PackageDescription("Wrist2 joint configuration")]
public JointConfiguration Wrist2 { get; set; }
// Wrist3 (Tool) joint configuration
[PackageDescription("Wrist3 (Tool) joint configuration")]
public JointConfiguration Wrist3 { get; set; }
}
Members of Common.ControllerBoxTypes :
public enum ControllerBoxTypes {
// UR10 controller box
UR10 = 5
// UR16 controller box
UR16 = 16
// UR3 controller box
UR3 = 6
// UR5 controller box
UR5 = 4
}
Members of PrimaryInterface.JointConfiguration :
public class JointConfiguration {
// a parameter of Denavit–Hartenberg (DH) convention
[PackageDescription("a parameter of Denavit–Hartenberg (DH) convention", PackageUnit.Meter)]
public double DHa { get; set; }
// Alpha parameter of Denavit–Hartenberg (DH) convention
[PackageDescription("Alpha parameter of Denavit–Hartenberg (DH) convention", PackageUnit.Radian)]
public double DHalpha { get; set; }
// d parameter of Denavit–Hartenberg (DH) convention
[PackageDescription("d parameter of Denavit–Hartenberg (DH) convention", PackageUnit.Meter)]
public double DHd { get; set; }
// Theta parameter of Denavit–Hartenberg (DH) convention
[PackageDescription("Theta parameter of Denavit–Hartenberg (DH) convention", PackageUnit.Radian)]
public double DHtheta { get; set; }
// Maximum rotation speed in rad/s²
[PackageDescription("Maximum rotation speed in rad/s²", PackageUnit.RadianPerSecondSquared)]
public double JointMaxAcceleration { get; set; }
// Maximum angular position in rad
[PackageDescription("Maximum angular position in rad", PackageUnit.Radian)]
public double JointMaxLimit { get; set; }
// Maximum rotation speed in rad/s
[PackageDescription("Maximum rotation speed in rad/s", PackageUnit.RadianPerSecond)]
public double JointMaxSpeed { get; set; }
// Minimum angular position in rad
[PackageDescription("Minimum angular position in rad", PackageUnit.Radian)]
public double JointMinLimit { get; set; }
}
Members of Common.RobotSubTypes :
public enum RobotSubTypes {
// CB2-series (Firmware 1.x)
CB2Serie = 1
// CB3-series (Firmware 3.x)
CB3Serie = 2
// e-series (Firmware 5.x)
ESerie = 3
}
Members of Common.RobotModels :
public enum RobotModels {
UR10 = 2
UR16 = 4
UR3 = 3
UR5 = 1
}
## Force mode data
private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
ForceModeDataPackageEventArgs _value = ur.ForceModeData;
// Attach a delegate to the event triggered when new package comes
ur.ForceModeDataReceived += Ur_ForceModeDataReceived;
}
private void Ur_ForceModeDataReceived(object sender, ForceModeDataPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.ForceModeDataPackageEventArgs :
public class ForceModeDataPackageEventArgs : PackageEventArgs {
// Dexterity of the robot
public double RobotDexterity { get; set; }
// Rx torque in tool frame in Nm
public double Rx { get; set; }
// Ry torque in tool frame in Nm
public double Ry { get; set; }
// Rz torque in tool frame in Nm
public double Rz { get; set; }
// X force in tool frame in N
public double X { get; set; }
// Y force in tool frame in N
public double Y { get; set; }
// Z force in tool frame in N
public double Z { get; set; }
}

Additional information

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
AdditionalInfoPackageEventArgs _value = ur.AdditionalInfo;
// Attach a delegate to the event triggered when new package comes
ur.AdditionalInfoReceived += Ur_AdditionalInfoReceived;
}
private void Ur_AdditionalInfoReceived(object sender, AdditionalInfoPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.AdditionalInfoPackageEventArgs :
public class AdditionalInfoPackageEventArgs : PackageEventArgs {
// The free drive button is enabled
[PackageDescription("The free drive button is enabled")]
public bool FreedriveButtonEnabled { get; set; }
// The free drive button is pressed
[PackageDescription("The free drive button is pressed")]
public bool FreedriveButtonPressed { get; set; }
// Free drive is enable via IO
[PackageDescription("Free drive is enable via IO")]
public bool IOEnabledFreedrive { get; set; }
}

Calibration data

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
CalibrationDataPackageEventArgs _value = ur.CalibrationData;
// Attach a delegate to the event triggered when new package comes
ur.CalibrationDataReceived += Ur_CalibrationDataReceived;
}
private void Ur_CalibrationDataReceived(object sender, CalibrationDataPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.CalibrationDataPackageEventArgs :
public class CalibrationDataPackageEventArgs : PackageEventArgs {
// Frx calibration data
[PackageDescription("Frx calibration data")]
public double Frx { get; set; }
// Fry calibration data
[PackageDescription("Fry calibration data")]
public double Fry { get; set; }
// Frz calibration data
[PackageDescription("Frz calibration data")]
public double Frz { get; set; }
// Fx calibration data
[PackageDescription("Fx calibration data")]
public double Fx { get; set; }
// Fy calibration data
[PackageDescription("Fy calibration data")]
public double Fy { get; set; }
// Fz calibration data
[PackageDescription("Fz calibration data")]
public double Fz { get; set; }
}

Safety data

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
SafetyDataPackageEventArgs _value = ur.SafetyData;
// Attach a delegate to the event triggered when new package comes
ur.SafetyDataReceived += Ur_SafetyDataReceived;
}
private void Ur_SafetyDataReceived(object sender, SafetyDataPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.SafetyDataPackageEventArgs :
public class SafetyDataPackageEventArgs : PackageEventArgs {
// Irrelevent (Internal use only)
public byte[] Data { get; set; }
}

Tool communication information

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
ToolCommunicationInfoPackageEventArgs _value = ur.ToolCommunicationInfo;
// Attach a delegate to the event triggered when new package comes
ur.ToolCommunicationInfoReceived += Ur_ToolCommunicationInfoReceived;
}
private void Ur_ToolCommunicationInfoReceived(object sender, ToolCommunicationInfoPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.ToolCommunicationInfoPackageEventArgs :
public class ToolCommunicationInfoPackageEventArgs : PackageEventArgs {
// Baude rate
[PackageDescription("Baude rate")]
public int BaudRate { get; set; }
// Parity
[PackageDescription("Parity")]
public int Parity { get; set; }
// RX Idle Chars
[PackageDescription("RX Idle Chars")]
public float RxIdleChars { get; set; }
// Stop bits
[PackageDescription("Stop bits")]
public int StopBits { get; set; }
// Is the tool communication interface enabled
[PackageDescription("Is the tool communication interface enabled")]
public bool ToolCommunicationIsEnabled { get; set; }
// TX Idle Chars
[PackageDescription("TX Idle Chars")]
public float TxIdleChars { get; set; }
}

Tool mode

private UR ur;
private void Start() {
ur = new UR(); // Create a new UR instance
ur.Connect("192.168.0.1"); // Connect to the robot
// ...
// Direct access to last received package
ToolModeInfoPackageEventArgs _value = ur.ToolModeInfo;
// Attach a delegate to the event triggered when new package comes
ur.ToolModeInfoReceived += Ur_ToolModeInfoReceived;
}
private void Ur_ToolModeInfoReceived(object sender, ToolModeInfoPackageEventArgs e) {
// e contains the incoming package
}
Members of PrimaryInterface.ToolModeInfoPackageEventArgs :
public class ToolModeInfoPackageEventArgs : PackageEventArgs {
// Digital output 0 configuration
[PackageDescription("Digital output 0 configuration")]
public DigitalOutputConfigurations DigitalOutputMode0 { get; set; }
// Digital output 1 configuration
[PackageDescription("Digital output 1 configuration")]
public DigitalOutputConfigurations DigitalOutputMode1 { get; set; }
// Digital output mode
[PackageDescription("Digital output mode")]
public OutputModes OutputMode { get; set; }
}
Members of Common.DigitalOutputConfigurations :
public enum DigitalOutputConfigurations {
// Push / Pull
PushPull = 3
// Sinking (NOPN)
SinkingNPN = 1
// Sourcing (PNP)
SourcingPNP = 2
}
Members of Common.OutputModes :
public enum OutputModes {
// Dual Pin Power
DualPinPower = 1
// Standard output
StandardOutput = 0
}

Read more