ROS2 Topics and Services

Topic naming

Each topic is prefixed with a namespace. ROS message bus permits multiple robots, and other ROS nodes on the same network. Multiple nodes can publish to the same topic - in some cases this behavior is desirable, but in general namespaces are used to prevent collisions.

Namespace:

Topics are prepended with a namespace to identify the robot. In python the namespace can be retrieved from the environment variable called ROS2_NAMESPACE.

Example topic names:

Robot namespace is UR20185300015:

/UR20185300015/actual_joint_trajectory

Naming follows ROS2 recommendations. For more information see: using  ROS 2 Topic and Service Name Constraints.

Publishers

Some publishers have filters associated that ensure a topic is published only when an underlying value changes.

Timestamp

Each topic contains a header with a timestamp. The timestamp is not derived from the system clock, but from the real time control loop instead.

It is reset to 0 each time the controller process is restarted.

All messages that belong to the same control cycle are guaranteed to have exactly the same timestamp.

QoS

Default publisher QoS (more info see:  Quality of Service):


QoS settings have to be equal or less strict on the subscriber side, otherwise the subscription silently fails (as of Foxy).

One particular example is Durability Transient Local. If a subscriber expects to receive the last published value (for example arm_powered_on that is published only when the value changes) then it also has to specify Transient Local Durability.

Published topics

Publishing frequency:

RT - Controller real time loop frequency = 500Hz

RT1k - Controller 1k loop frequency = 1000Hz

RT+ - RT when arm is powered on

T - Published only when value changes

Published Topics
Name Package Message QoS (default if not specified) Publishing frequency Bandwidth Description
actual_momentum urinterfaces Float64Stamped.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+ 0.03 KB Norm of Cartesian linear momentum
actual_speed_fraction urinterfaces SpeedSliderFraction.msg Durability - Transient local RT ?  

Effective speed scaling, including both speed slider and trajectory limiting.

Note: this is not the same as in RTDE. But it makes it easier for client to scale based on this value.

actual_tcp_state urinterfaces TCPState.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+ 0.13 KB Actual Cartesian coordinates, and velocities of the tool (TCP).
arm_powered_on urinterfaces BoolStamped.msg Depth  - Queue size[n] =1

Durability - Transient local

T -- Indication if power is applied to robot arm
configurable_digital_inputs urinterfaces DigitalPort.msg Durability - Transient local T 0.03 KB Configurable digital outputs state
configurable_digital_outputs urinterfaces DigitalPort.msg

Depth  - Queue size[n]=1

Durability - Transient local
T 0.03 KB Configurable digital inputs state
control_cycle urinterfaces ControlCycle.msg Depth  - Queue size[n] =1

Durability - Transient local

RT 0.03 KB Sequential number of real-time controller cycle
execution_time

sensor_msgs

TimeReference.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT 0.04 KB Controller real-time thread execution time
io_current urinterfaces Current.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT 0.02 KB Control box IO current
joint_mode urinterfaces JointMode.msg Durability - Transient local T   Joint control modes
joint_states sensor_msgs JointState.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+  

Target joint names, positions, velocities, and efforts [Nm]

actual effort is actual current * k_tau

joint_temperature

urinterfaces

JointTemperature.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+ 0.04 KB Temperature of each joint in degrees Celsius
joint_voltage urinterfaces JointVoltage.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+  

Actual joint voltages

main_voltage urinterfaces Float32Stamped.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT  

Safety Control Board: Main voltage

payload geometry_msgs InertiaStamped.msg Depth  - Queue size[n]=1

Durability - Transient local

T   Active payload mass, center of mass, and inertia parameters
power_button_pressed urinterfaces BoolStamped.msg Depth  - Queue size[n]=1 Durability - Transient local T   Set when any power button input is active
program_running urinterfaces BoolStamped.msg Depth  - Queue size[n]=1

Durability - Transient local

T   Set when any foreground program is running
robot_mode urinterfaces RobotMode.msg Durability - Transient local T   Robot mode
robot_voltage_current urinterfaces VoltageCurrentStamped.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT   Robot controller voltage and current
program_state urinterfaces RuntimeState.msg Durability - Transient local T   Program state
safety_status urinterfaces SafetyStatus.msg Durability - Transient local T   Robot controller safety status
standard_analog_input_0 urinterfaces Analog.msg Durability - Transient local RT ?   Standard analog input 0 domain (voltage or current) and value
standard_analog_input_1 urinterfaces Analog.msg Durability - Transient local RT ?   Standard analog input 1 domain (voltage or current) and value
standard_analog_output_0 urinterfaces Analog.msg Depth  - Queue size[n]=1

Durability - Transient local

RT ?   Standard analog output 0 domain (voltage or current) and value
standard_analog_output_1 urinterfaces Analog.msg Depth  - Queue size[n]=1

Durability - Transient local

RT ?   Standard analog output 1 domain (voltage or current) and value
standard_digital_inputs urinterfaces DigitalPort.msg Durability - Transient local T   Standard digital outputs state
standard_digital_outputs urinterfaces DigitalPort.msg Depth  - Queue size[n]=1

Durability - Transient local

T   Standard digital inputs state
target_joint_states sensor_msgs JointState.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+  

Target joint names, positions, velocities, and efforts [Nm]

Effort is computed as target_torque + (target_friction_current) * k_tau

target_speed_fraction urinterfaces SpeedSliderFraction.msg Depth  - Queue size[n]=1

Durability - Transient local

T   Target speed fraction
target_tcp_state urinterfaces TCPState.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT 0.26 KB Target Cartesian coordinates and velocities of the tool (TCP).
tcp_force_scalar urinterfaces Float64Stamped.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT   TCP force scalar
tcp_offset geometry_msgs PoseStamped.msg Depth  - Queue size[n]=1

Durability - Transient local

T   Tool offset relative to tool flange.
tcp_wrench geometry_msgs WrenchStamped.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+   Actual TCP forces and torques with compensation for
teach_button_pressed urinterfaces BoolStamped.msg Depth  - Queue size[n]=1

Durability - Transient local

T   Set when any teach input is active
tool_accelerometer geometry_msgs AccelStamped.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+   Tool x, y and z accelerometer values
tool_analog_input_0 urinterfaces Analog.msg Durability - Transient local RT+ ?   Tool connector analog input 0 domain (voltage or current) and value
tool_analog_input_1 urinterfaces Analog.msg Durability - Transient local RT+ ?   Tool connector analog input 1 domain (voltage or current) and value
tool_digital_inputs urinterfaces DigitalPort.msg Durability - Transient local T   Tool connector digital outputs state
tool_digital_outputs urinterfaces DigitalPort.msg Depth  - Queue size[n]=1

Durability - Transient local

T   Tool connector digital inputs state
tool_output_mode urinterfaces ToolOutputMode.msg Depth  - Queue size[n]=1

Durability - Transient local

T   Tool connector digital output modes
tool_temperature sensor_msgs Temperature.msg Depth  - Queue size[n] =1

Reliability - Best effort

T 0.03 KB

Tool temperature in degrees Celsius

(temporarily Float64Stamped)

tool_voltage_current urinterfaces VoltageCurrentStamped.msg Depth  - Queue size[n] =1

Reliability - Best effort

RT+   Tool connector power output voltage and current

Subscribed Topics

Subscribed Topics
Name Package Message QoS (default if not specified) Description
external_wrench geometry_msgs WrenchStamped.msg Sensor data External force/torque input

Services

Services
Name Package Service QoS Description
set_speed_fraction urinterfaces SetSpeedFraction.srv default service Set new speed slider value
set_configurable_digital_output urinterfaces SetDigitalOutput.srv default service Set standard digital output pin state
set_standard_digital_output urinterfaces SetDigitalOutput.srv default service Set configurable digital output pin state
set_standard_analog_output urinterfaces SetAnalogOutput.srv default service Set single analog output domain (current or voltage) and value