URInterfaces API reference

This document contains information about URInterface message types.
Documentation regarding ROS2 common message types, can be found at ROS2 Common interfaces.


 Name
 Analog.msg
 BoolStamped.msg
 ControlCycle.msg
 Current.msg
 DigitalPort.msg
 DoubleMultiArrayStamped.msg
 Float32Stamped.msg
 Float64Stamped.msg
 JointMode.msg
 JointTemperature.msg
 JointVoltage.msg
 RobotMode.msg
 RuntimeState.msg
 SafetyStatus.msg
 SetAnalogOutput_Request.msg
 SetAnalogOutput_Response.msg
 SetDigitalOutput_Request.msg
 SetDigitalOutput_Response.msg
 SetSpeedFraction_Request.msg
 SetSpeedFraction_Response.msg
 SpeedSliderFraction.msg
 TCPState.msg
 ToolOutputMode.msg
 VoltageCurrentStamped.msg
 WorldModelNames.msg
 SetAnalogOutput.srv
 SetDigitalOutput.srv
 SetSpeedFraction.srv



Analog.msg
std_msgs/Header header
uint8 CURRENT=0
uint8 VOLTAGE=1

uint8 domain # can be VOLTAGE or CURRENT
float32 value


BoolStamped.msg
std_msgs/Header header
bool data


ControlCycle.msg
std_msgs/Header header
uint64 cycle_counter


Current.msg
std_msgs/Header header
float32 current


DigitalPort.msg
std_msgs/Header header
bool[] state 


DoubleMultiArrayStamped.msg
std_msgs/Header header
float64[] data


Float32Stamped.msg
std_msgs/Header header
float32 data


Float64Stamped.msg
std_msgs/Header header
float64 data


JointMode.msg
uint8 JOINT_MODE_RESET=235
uint8 JOINT_MODE_SHUTTING_DOWN=236
uint8 JOINT_MODE_PART_D_CALIBRATION=237
uint8 JOINT_MODE_BACKDRIVE=238
uint8 JOINT_MODE_POWER_OFF=239
uint8 JOINT_MODE_READY_FOR_POWER_OFF=240
uint8 JOINT_MODE_NOT_RESPONDING=245
uint8 JOINT_MODE_MOTOR_INITIALISATION=246
uint8 JOINT_MODE_BOOTING=247
uint8 JOINT_MODE_PART_D_CALIBRATION_ERROR=248
uint8 JOINT_MODE_BOOTLOADER=249
uint8 JOINT_MODE_CALIBRATION=250
uint8 JOINT_MODE_VIOLATION=251
uint8 JOINT_MODE_FAULT=252
uint8 JOINT_MODE_RUNNING=253
uint8 JOINT_MODE_IDLE=255

std_msgs/Header header
uint8[6] joint_modes
uint8 tool_mode


JointTemperature.msg
std_msgs/Header header
float32[6] joint_temperatures


JointVoltage.msg
std_msgs/Header header
float64[6] voltages


RobotMode.msg
int8 DISCONNECTED=0
int8 CONFIRM_SAFETY=1
int8 BOOTING=2
int8 POWER_OFF=3
int8 POWER_ON=4
int8 IDLE=5
int8 BACKDRIVE=6
int8 RUNNING=7
int8 UPDATING_FIRMWARE=8

std_msgs/Header header
int8 value


RuntimeState.msg
int8 PROGRAM_STATE_UNDEFINED=-1
int8 PROGRAM_STATE_STOPPING=0
int8 PROGRAM_STATE_STOPPED=1
int8 PROGRAM_STATE_RUNNING=2
int8 PROGRAM_STATE_PAUSING=3
int8 PROGRAM_STATE_PAUSED=4
int8 PROGRAM_STATE_RESUMING=5
int8 PROGRAM_STATE_RETRACTING=6

std_msgs/Header header
int8 value


SafetyStatus.msg
int8 NORMAL=1
int8 REDUCED=2
int8 PROTECTIVE_STOP=3
int8 RECOVERY=4
int8 SAFEGUARD_STOP=5
int8 SYSTEM_EMERGENCY_STOP=6
int8 ROBOT_EMERGENCY_STOP=7
int8 VIOLATION=8
int8 FAULT=9
int8 VALIDATE_JOINT_ID=10
int8 UNDEFINED_SAFETY_MODE=11
int8 AUTOMATIC_MODE_SAFEGUARD_STOP=12
int8 SYSTEM_THREE_POSITION_ENABLING_STOP=13

std_msgs/Header header
int8 safety_state


SetAnalogOutput_Request.msg
# Note: 'fun' is short for function of the pin to be selected
bool OUTPUT_CURRENT = 0
bool OUTPUT_VOLTAGE = 1

# The value for pin [0-1]

# Value for 'FUN_CURRENT' must be from [0.002; 0.020] A ;
# Value for 'FUN_VOLTAGE' must be from [0; 10] V ;

# request fields
int8 pin
bool output_type
float64 value


SetAnalogOutput_Response.msg

bool success


SetDigitalOutput_Request.msg
# The value for pin [0-7]

# valid values for 'state' when setting digital IO or flags
bool STATE_OFF = 0
bool STATE_ON = 1

# request fields
int8 pin
bool state


SetDigitalOutput_Response.msg

bool success


SetSpeedFraction_Request.msg
# Set the speed slider on the teach pendant to the specified value.
#
# Value must be from [0; 1.0]; 

float32 value


SetSpeedFraction_Response.msg

bool success


SpeedSliderFraction.msg
std_msgs/Header header
float64 speed_scale


TCPState.msg
std_msgs/Header header

geometry_msgs/Pose pose
geometry_msgs/Twist speed


ToolOutputMode.msg
std_msgs/Header header
uint8 TOOL_OUPUT=0
uint8 TOOL_POWER=1
uint8 TOOL_SAFE=2

uint8 output_mode

uint8 OUTPUT_MODE_DISABLED=0
uint8 OUTPUT_MODE_SINKING=1
uint8 OUTPUT_MODE_SOURCING=2
uint8 OUTPUT_MODE_PUSH_PULL=3

uint8[2] output_pin_mode


VoltageCurrentStamped.msg
std_msgs/Header header
float64  voltage
float64 current


WorldModelNames.msg
std_msgs/Header header

std_msgs/String[] names


SetAnalogOutput.srv
# Note: 'fun' is short for function of the pin to be selected
bool OUTPUT_CURRENT = 0
bool OUTPUT_VOLTAGE = 1

# The value for pin [0-1]

# Value for 'FUN_CURRENT' must be from [0.002; 0.020] A ;
# Value for 'FUN_VOLTAGE' must be from [0; 10] V ;

# request fields
int8 pin
bool output_type
float64 value
---
bool success


SetDigitalOutput.srv
# The value for pin [0-7]

# valid values for 'state' when setting digital IO or flags
bool STATE_OFF = 0
bool STATE_ON = 1

# request fields
int8 pin
bool state
---
bool success


SetSpeedFraction.srv
# Set the speed slider on the teach pendant to the specified value.
#
# Value must be from [0; 1.0]; 

float32 value
---
bool success

Copyright @ Universal Robots 2021URInterfaces API reference

URInterfaces API reference

This document contains information about URInterface message types.
Documentation regarding ROS2 common message types, can be found at ROS2 Common interfaces.


 Name
 Analog.msg
 BoolStamped.msg
 ControlCycle.msg
 Current.msg
 DigitalPort.msg
 DoubleMultiArrayStamped.msg
 Float32Stamped.msg
 Float64Stamped.msg
 JointMode.msg
 JointTemperature.msg
 JointVoltage.msg
 RobotMode.msg
 RuntimeState.msg
 SafetyStatus.msg
 SetAnalogOutput_Request.msg
 SetAnalogOutput_Response.msg
 SetDigitalOutput_Request.msg
 SetDigitalOutput_Response.msg
 SetSpeedFraction_Request.msg
 SetSpeedFraction_Response.msg
 SpeedSliderFraction.msg
 TCPState.msg
 ToolOutputMode.msg
 VoltageCurrentStamped.msg
 WorldModelNames.msg
 SetAnalogOutput.srv
 SetDigitalOutput.srv
 SetSpeedFraction.srv



Analog.msg
std_msgs/Header header
uint8 CURRENT=0
uint8 VOLTAGE=1

uint8 domain # can be VOLTAGE or CURRENT
float32 value


BoolStamped.msg
std_msgs/Header header
bool data


ControlCycle.msg
std_msgs/Header header
uint64 cycle_counter


Current.msg
std_msgs/Header header
float32 current


DigitalPort.msg
std_msgs/Header header
bool[] state 


DoubleMultiArrayStamped.msg
std_msgs/Header header
float64[] data


Float32Stamped.msg
std_msgs/Header header
float32 data


Float64Stamped.msg
std_msgs/Header header
float64 data


JointMode.msg
uint8 JOINT_MODE_RESET=235
uint8 JOINT_MODE_SHUTTING_DOWN=236
uint8 JOINT_MODE_PART_D_CALIBRATION=237
uint8 JOINT_MODE_BACKDRIVE=238
uint8 JOINT_MODE_POWER_OFF=239
uint8 JOINT_MODE_READY_FOR_POWER_OFF=240
uint8 JOINT_MODE_NOT_RESPONDING=245
uint8 JOINT_MODE_MOTOR_INITIALISATION=246
uint8 JOINT_MODE_BOOTING=247
uint8 JOINT_MODE_PART_D_CALIBRATION_ERROR=248
uint8 JOINT_MODE_BOOTLOADER=249
uint8 JOINT_MODE_CALIBRATION=250
uint8 JOINT_MODE_VIOLATION=251
uint8 JOINT_MODE_FAULT=252
uint8 JOINT_MODE_RUNNING=253
uint8 JOINT_MODE_IDLE=255

std_msgs/Header header
uint8[6] joint_modes
uint8 tool_mode


JointTemperature.msg
std_msgs/Header header
float32[6] joint_temperatures


JointVoltage.msg
std_msgs/Header header
float64[6] voltages


RobotMode.msg
int8 DISCONNECTED=0
int8 CONFIRM_SAFETY=1
int8 BOOTING=2
int8 POWER_OFF=3
int8 POWER_ON=4
int8 IDLE=5
int8 BACKDRIVE=6
int8 RUNNING=7
int8 UPDATING_FIRMWARE=8

std_msgs/Header header
int8 value


RuntimeState.msg
int8 PROGRAM_STATE_UNDEFINED=-1
int8 PROGRAM_STATE_STOPPING=0
int8 PROGRAM_STATE_STOPPED=1
int8 PROGRAM_STATE_RUNNING=2
int8 PROGRAM_STATE_PAUSING=3
int8 PROGRAM_STATE_PAUSED=4
int8 PROGRAM_STATE_RESUMING=5
int8 PROGRAM_STATE_RETRACTING=6

std_msgs/Header header
int8 value


SafetyStatus.msg
int8 NORMAL=1
int8 REDUCED=2
int8 PROTECTIVE_STOP=3
int8 RECOVERY=4
int8 SAFEGUARD_STOP=5
int8 SYSTEM_EMERGENCY_STOP=6
int8 ROBOT_EMERGENCY_STOP=7
int8 VIOLATION=8
int8 FAULT=9
int8 VALIDATE_JOINT_ID=10
int8 UNDEFINED_SAFETY_MODE=11
int8 AUTOMATIC_MODE_SAFEGUARD_STOP=12
int8 SYSTEM_THREE_POSITION_ENABLING_STOP=13

std_msgs/Header header
int8 safety_state


SetAnalogOutput_Request.msg
# Note: 'fun' is short for function of the pin to be selected
bool OUTPUT_CURRENT = 0
bool OUTPUT_VOLTAGE = 1

# The value for pin [0-1]

# Value for 'FUN_CURRENT' must be from [0.002; 0.020] A ;
# Value for 'FUN_VOLTAGE' must be from [0; 10] V ;

# request fields
int8 pin
bool output_type
float64 value


SetAnalogOutput_Response.msg

bool success


SetDigitalOutput_Request.msg
# The value for pin [0-7]

# valid values for 'state' when setting digital IO or flags
bool STATE_OFF = 0
bool STATE_ON = 1

# request fields
int8 pin
bool state


SetDigitalOutput_Response.msg

bool success


SetSpeedFraction_Request.msg
# Set the speed slider on the teach pendant to the specified value.
#
# Value must be from [0; 1.0]; 

float32 value


SetSpeedFraction_Response.msg

bool success


SpeedSliderFraction.msg
std_msgs/Header header
float64 speed_scale


TCPState.msg
std_msgs/Header header

geometry_msgs/Pose pose
geometry_msgs/Twist speed


ToolOutputMode.msg
std_msgs/Header header
uint8 TOOL_OUPUT=0
uint8 TOOL_POWER=1
uint8 TOOL_SAFE=2

uint8 output_mode

uint8 OUTPUT_MODE_DISABLED=0
uint8 OUTPUT_MODE_SINKING=1
uint8 OUTPUT_MODE_SOURCING=2
uint8 OUTPUT_MODE_PUSH_PULL=3

uint8[2] output_pin_mode


VoltageCurrentStamped.msg
std_msgs/Header header
float64  voltage
float64 current


WorldModelNames.msg
std_msgs/Header header

std_msgs/String[] names


SetAnalogOutput.srv
# Note: 'fun' is short for function of the pin to be selected
bool OUTPUT_CURRENT = 0
bool OUTPUT_VOLTAGE = 1

# The value for pin [0-1]

# Value for 'FUN_CURRENT' must be from [0.002; 0.020] A ;
# Value for 'FUN_VOLTAGE' must be from [0; 10] V ;

# request fields
int8 pin
bool output_type
float64 value
---
bool success


SetDigitalOutput.srv
# The value for pin [0-7]

# valid values for 'state' when setting digital IO or flags
bool STATE_OFF = 0
bool STATE_ON = 1

# request fields
int8 pin
bool state
---
bool success


SetSpeedFraction.srv
# Set the speed slider on the teach pendant to the specified value.
#
# Value must be from [0; 1.0]; 

float32 value
---
bool success

Copyright @ Universal Robots 2021