ROS2 in UR whitepaper

Introduction

ROS2 versions

Controller is using ROS2 Humble version. Default DDS implementation (Fast RTPS) is used for underlying communication.

Quality of Service settings

Quality of Service(QoS) is feature in ROS 2 that allows users to fine tune the communication between nodes. The policies range from being as reliable as TCP to as best-effort as UDP and many more options in between. A set of policies make a profile, the right set of profiles need to be set based on the application (https://docs.ros.org/en/foxy/Concepts/About-Quality-of-Service-Settings.html#qos-policies). The default profile for a publisher on the robot is as follows

The important point to remember is that the QoS settings have to be compatible (or ideally the same) on the publisher and subscriber side. Incompatible QoS settings will prevent communication entirely. More information about QoS compatibility can be found in https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html#qos-compatibilities.

URinterfaces message library

Universal Robots defined a range of custom ROS2 message types. Intention is to efficiently pass robot state to external and internal client nodes.

Interfaces are available as source code and should be compiled in target ROS2 environment.

Usage on robot

ROS docker images provided with URCap SDK should be used.

Usage off robot

Download from github (TBD repo address), select tag with minimum Polyscope version that should be supported. Add to your project as a source code, and dependency. Compile with colcon.

More usage examples can be found in UR ROS2 examples repository (TBD repo address)

Configuring namespace

To aid in differentiating between multiple robots, most ROS2 topics are prefixed with a namespace. The ROS2 message bus is capable of integrating multiple robots, sensors and other nodes on the same network, namespaces can prevent collisions in such scenarios.

Here are a few tips and tricks related to the namespace:

Topic names and namespaces should follow the ROS2 recommendation "snake case".(https://design.ros2.org/articles/topic_and_service_names.html)

Example topic name with namespace

When serial number is "20225300015" the topic name would be:

/UR20225300015/speed_fraction

Exceptions

There are few topics that are not prefixed with namespace. Reason for that is to keep compatibility with ROS2 tools. These topics are:

All are published without namespace. In this case namespace string is prefixed to joint name. Example: name="UR20225300015_elbow_joint".

Limitations

Integration of complex products is never perfect. This chapter provides a list of features that might be expected by an experienced ROS2 or URScript developer. Limitations might be removed in future software releases.

Threading model, and Impact on processor load

ROS2 library functions are called in a separate thread within the controller, that results in delays for data exchange between realtime thread, and communication threads as well as additional processor load. ROS2 thread is not realtime. Calling read() method on subscriber handle or write() on publisher handle blocks program, allocates communication thread, exchanges information using queue, and waits for communication thread to complete. When communication thread is complete result is handed over to the robot program and execution continues.

There are two options to read the messages from subscriber handle:

The risk with reading the latest message is that if there is drop in synchronization between the thread then the message is lost.

Message rate and jitter

Due to the fact that communication threads don't run with realtime priority there is possibility for overload. Following effects can be observed:

Note: timestamps are derived from realtime thread, so they are not affected by communication thread overload.

Latency of real time data

Message types supported

Data type limitations

Capability across data types: Controller allows publishing and subscribing all ROS2 basic data types, including float64, int8, uint8, int16, uint16, int32, uint32, int64, and uint64.

There is no limitation on floating point values.

Limitations on publishing integer values

Despite the controller's ability to publish across these data types, internal URScript integer type is limited to the INT32. Assigning integer values that exceed INT32 limit will result in a runtime or compile error.

Limitation for subscribing to integer values

Received values will be wrapped around when INT32 limit is exceeded. This behavior is a direct consequence INT32 internal number representation. There is no error, or warning - publisher should ensure that values are within limits, or URScript program should be able to handle wrapped around values.

Basic usage in URScript

URScript supports subscribing and publishing to topics.

In the following sections we provide a hello world example whose purpose is to facilitate experiments to learn how publishing works in URScript. Next we provide a set of examples reflecting the use cases we deem most likely. We then conclude with some limitation and workarounds.

A hello world example!

Communicating between threads in URScript should not generally be done using ROS2, as the overhead makes it incredibly inefficient. It does however make a good example for how to use ROS2 in URScript.

Hello world

global iter = 0
 
# A thread responsible for sending messages
thread publish():
  # Prepare a handle for a topic, that can be used to send messages. The name is test, and the type is std_msgs/String
  pub_handle = ros_publisher_factory(topic="test", msg_type="std_msgs/String", history="keep_last", depth=100, durability="transient_local")
  while(True):
    msg = str_cat("Hello world ",iter) 
    pub_handle.write(struct(data=msg))
    iter = iter + 1
    textmsg(str_cat("Published ", msg))
    sleep(0.5)
  end
end
myPublisher = run publish()
 
thread readOneItem():
 sub_handle = ros_subscriber_factory(topic="test", msg_type="std_msgs/String")
  sleep(3)
  while (True):
    value = sub_handle.read() # This read will block until something is available
    textmsg(str_cat("Read 1 item: ",value))
  end
end
myReadOneItem = run readOneItem()
 
# Insert any other threads you want to use here above the join
 
join myReadOneItem # Avoid the main thread exiting

To experiment with accessing the ROS2 history, the following two threads can added to the above program. Make sure to add it before the join line.

Observe that the subscriber handles operate independently. A read from one handle will not affect the history of the others.

More subscribers

# This thread will repeatedly try to read 10 items from the topics history.
thread subscribe_history():
  sub_handle = ros_subscriber_factory(topic="test", msg_type="std_msgs/String", history="keep_last", depth=100, durability="transient_local")
  sleep(3)
  while (True):
    value = sub_handle.read_history(10) # Read 0-10 items from the history, depending on how many are available
    textmsg(str_cat("Read 10 history items: ",value))
    waittime = (iter % 10)/2.0 # Wait for a pseudo random amount of time, to see how the read reacts to different history sized
    sleep(waittime)
  end
end
mySubscriber = run subscribe_history()
 
thread subscribe2():
 # This subhandle only has a history depth of 1, and thus at most one message will ever be returned by read_history
 sub_handle = ros_subscriber_factory(topic="test", msg_type="std_msgs/String", history="keep_last", depth=1, durability="transient_local")
  sleep(3)
  while (True):
    value = sub_handle.read_history(1) # Read one message from 
    if length(value)>0: # We are not guaranteed any items will be read
      textmsg(str_cat("Read 1 history items: ",value[0]))
    end
    waittime = (iter % 10)/2.0
    sleep(waittime)
  end
end
mySubscriber2 = run subscribe2()

Try playing around with history depth, waits and other parameters to gain a better understanding of the ROS2 functionality.

Typical use cases for subscribers

A set of use cases have been deemed to be common and will be detailed below in order to give a good starting point for customer specific solutions.

Reacting to new messages on a topic

If you are waiting for an event that is published on a given topic, you can use the read() method on the subscriber handle directly. It will block until such a message arrives.

# Place the following somewhere it will only be executed once, such as BeforeStart
myHandle = ros_subscriber_factory(topic="<your topic here>", msg_type="<your message type here>")
 
# The following call will block until a new message is available.
myMessage = myHandle.read()

Getting the latest message from a subscriber

If you read from a topic publishing state changes, and want the latest state published, you need to access the history of the topic.

# Place the following somewhere it will only be executed once, such as BeforeStart
myHandle = ros_subscriber_factory(topic="<your topic here>", msg_type="<your message type here>", history="keep_last", depth=1, durability="transient_local")
 
# The following call will return immediately with an anonymous struct containing at most one item
lastMessageList = myHandle.read_history(1)
 
# Only if a message existed in the history will the anonymous struct have any members
if length(lastMessageList)>0:
  lastMessage = lastMessageList[0]
end

Note that the subscriber is created specifying three optional parameters:

It is also important to realize that ROS2 guarantees a message will only be read by each subscriber once. Thus when a state has been extracted, it should be stored locally as subsequent return values from read_history will have no members until another state change is published.

Reacting to all messages

No guarantee can be given that all messages can be reacted to, as any publisher might be able to produce more data that can be handled by a subscriber. Any messages published that is not read before the history is full will be dropped.

In practice all messages can be read from nearly all topics, and this is done using read_history:

# Place the following somewhere it will only be executed once, such as BeforeStart
myHandle = ros_subscriber_factory(topic="<your topic here>", msg_type="<your message type here>", history="keep_all")
 
while (True):
  # The following call will return immediately with an anonymous struct containing at most ten items
  messageList = myHandle.read_history(10)
 
  # Only if a message existed in the history will the anonymous struct have any members
  i = 0
  while (i<length(messageList)):
    nextMessage = messageList[0]
    # handle nextMessage
        i = i + 1
  end
end

The subscriber is configured to retain all messages, and will consume excessive amount of memory if the subscriber is unable to keep up. Keeping a limited history should be considered if missing messages is acceptable.

The code will loop indefinitely, and read up to 10 items at a time from the topics history, beginning with the oldest message. Each read_history has an overhead of at least a few milliseconds, and the more is read at once, the less of these overheads are incurred. 10 is arbitrarily chosen, but it will allocate space for the maximum number of messages, and as such restraint should be exercised.

Calling services

Calling services from URScript requires creating service client handle. ros_service_client_factory() method can be used in similar fashion to publisher/subscriber factories where service name, message type, and QoS parameters are supplied.

wait_for_service(), and call() methods allow for typical interaction. Both methods take optional timeout parameter - if not specified then functions are blocking indefinitely. Otherwise they block until timeout is reached. Timeout is specified in seconds.

bool wait_for_service(number timeout): Wait until service is available

struct call(struct request, number timeout): Call service with data specified in request structure. Return structure with service reply. NOTE: returned structure is different depending if timeout is specified. See below examples for more details.

close(): closes handle, and releases all resources.

Service call with timeout example

# Place the following somewhere it will only be executed once, such as Before Start
client = ros_service_client_factory("/test", "std_srvs/srv/Empty")
 
# Create data structure corresponding to service call type (empty structure in this case)
request = struct()
 
# Wait for 5s for service to be available
success = client.wait_for_service(5.0)
popup(success)
 
if(success):
  # calling service with timeout - unblocks after timeout, but returned structure is more difficult to process.
  result = client.call(request, 1.0)
  # result is a struct with 2 members: struct(success, reply)
  # success: bool True if call succeeded, or False if it timed-out
  # reply: depending on the success
  #   - success == True - reply contains structure with actual service reply
  #   - success == False - reply contains empty struct
  popup("Service call result: " + result.to_string())
 
  # blocking service call
  # Call service, block until service replies
  reply = client.call(request)
  # reply contains structure with members specified in service message type.
  popup("Service reply: " + reply.to_string())
end
 

Before making a service call, it might be useful to check whether the service is available or not. In the example above, before the ROS2 service call, wait_for_service() function is called to make sure of service availability. Thus, the call will wait for service for 5 seconds. If the given service is not available for 5 seconds, wait_for_service() function will return false. Otherwise, it will return true.

Limitations, bookkeeping and workarounds

As we foresee or hear of common stumbling blocks with ROS2 in URscript, we will add guides on how to handle or mitigate them.

Publisher, and subscriber lifetime

When created, each publisher and subscriber will live as long as the program, unless it is closed with the .close() method. Subsequent use of the publisher or subscriber will result in a runtime exception. Creating handles continuously in a program will leak resources, and is discouraged.

Blocking aspect of subscribers

Creating a subscriber or publisher, as well as calling any method on them comes with a minimum of 2 ms delay. Doing any such operation in between moves might affect their ability to blend, and the robot motion could appear to be stuttering. If ROS2 functionality is needed between moves, reading/publishing in a separate thread and communicating with that thread via global variables is recommended.

Build and deploy dockerized ros node to robot

Using standard ROS2 docker image

# pull docker image
docker pull ros:humble
 
# locally on the robot DDS uses shared memory for node discovery and communication
# start docker, and make host network and shared memory is available to dockerized processes
docker run -it --rm --ipc host --net host -v $(pwd):/opt/ros2_ws ros:humble
 
# Now ros2 commands can be executed. Below example shows how to list topics available on controller:
ros2 topic list
ros2 topic echo --qos-durability transient_local --qos-reliability reliable /20235589725/payload
# where 20235589725 is the local robot serial number

 

Appendix 1 - Message definitions available for programs

Message definitions from urinterfaces library are available

Message definitions from following standard ROS2 libraries are available:

·       libactionlib

·       libaction

·       libdiagnostic

·       libgeometry

·       liblifecycle

·       libmove_base

·       libnav

·       librosgraph

·       libsensor

·       libshape

·       libstatistics

·       libstd

·       libstd_srvs

·       libstereo

·       libtest

·       libtf2

·       libtrajectory

·       libunique_identifier

·       libvisualization

 

Appendix 2 - Topics and services

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

T+ - same as T, but with arm is powered on

Name

Package

Message

QoS (default if not specified)

Queue size = 1 if not specified

Publishing

frequency

Bandwidth

kB/s

Description

target_joint_states

sensor_msgs

JointState.msg

Reliability: RELIABLE
Durability: VOLATILE

RT+

160

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

Effort is computed as target_torque + (target_friction_current) * k_tau

joint_states

sensor_msgs

JointState.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT+

160

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

actual effort is actual current * k_tau

actual_tcp_state

urinterfaces

TCPState.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT+

66

Actual Cartesian coordinates, and velocities of the tool (TCP).

target_tcp_state

urinterfaces

TCPState.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT

66

Target Cartesian coordinates, and velocities of the tool (TCP).

joint_temperature

urinterfaces

JointTemperature.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T+

Temperature of each joint in degrees Celsius

tool_temperature

sensor_msgs

Temperature.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T+

 

Tool temperature in degrees Celsius

control_cycle

urinterfaces

ControlCycle.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

RT

14

Sequential number of real-time controller cycle

execution_time

sensor_msgs

TimeReference.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT

18

Controller real-time thread execution time

safety_status

urinterfaces

SafetyStatus.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

Robot controller safety status

robot_mode

urinterfaces

RobotMode.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

Robot mode

arm_powered_on

urinterfaces

BoolStamped.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

--

Indication if power is applied to robot arm

joint_mode

urinterfaces

JointMode.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

Joint control modes

program_state

urinterfaces

RuntimeState.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

Program state

tcp_offset

geometry_msgs

PoseStamped.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

Tool offset relative to tool flange.

payload

geometry_msgs

InertiaStamped.msg

Reliability: RELIABLE

Durability: TRANSIENT_LOCAL 

T

Active payload mass, center of mass, and inertia parameters

standard_digital_inputs

urinterfaces

DigitalPort.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL 
Queue Size: 10

T

Standard digital outputs state

configurable_digital_inputs

urinterfaces

DigitalPort.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL 
Queue Size: 10

T

Configurable digital outputs state

tool_digital_inputs

urinterfaces

DigitalPort.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

T

Tool connector digital outputs state

standard_digital_outputs

urinterfaces

DigitalPort.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL 
Queue Size: 10

T

Standard digital inputs state

configurable_digital_outputs

urinterfaces

DigitalPort.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL 
Queue Size: 10

T

Configurable digital inputs state

tool_digital_outputs

urinterfaces

DigitalPort.msg

Reliability: BEST_EFFORT 
Durability: VOLATILE

T

Tool connector digital inputs state

standard_analog_input_0

urinterfaces

Analog.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

T

Standard analog input 0 domain (voltage or current) and value

standard_analog_input_1

urinterfaces

Analog.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

T

Standard analog input 1 domain (voltage or current) and value

standard_analog_output_0

urinterfaces

Analog.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

T

Standard analog output 0 domain (voltage or current) and value

standard_analog_output_1

urinterfaces

Analog.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

T

Standard analog output 1 domain (voltage or current) and value

tool_analog_input_0

urinterfaces

Analog.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

T

Tool connector analog input 0 domain (voltage or current) and value

tool_analog_input_1

urinterfaces

Analog.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

T

Tool connector analog input 1 domain (voltage or current) and value

tool_output_mode

urinterfaces

ToolOutputMode.msg

Reliability: RELIABLE 
Durability: TRANSIENT_LOCAL

T

Tool connector digital output modes

tool_voltage_current

urinterfaces

VoltageCurrentStamped.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT+

17

Tool connector power output voltage and current

robot_voltage_current

urinterfaces

VoltageCurrentStamped.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT

17

Robot controller voltage and current

io_current

urinterfaces

Current.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT

Control box IO current

main_voltage

urinterfaces

Float32Stamped.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT

0.3

Safety Control Board: Main voltage

joint_voltage

urinterfaces

JointVoltage.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT+

~0.3 when stationary

2 when moving fast

Actual joint voltages

tool_accelerometer

geometry_msgs

AccelStamped.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT+

38

Tool x, y and z accelerometer values

actual_speed_fraction

urinterfaces

SpeedSliderFraction.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

RT

14

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

now called speed_scaling

target_speed_fraction

urinterfaces

SpeedSliderFraction.msg

Reliability: RELIABLE 
Durability: TRANSIENT_LOCAL

T

Target speed fraction

 

now called speed_fraction

tcp_force_scalar

urinterfaces

Float64Stamped.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT

14

TCP force scalar

actual_momentum

urinterfaces

Float64Stamped.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT+

14

Norm of Cartesian linear momentum

tcp_wrench

geometry_msgs

WrenchStamped.msg

Reliability: BEST_EFFORT
Durability: VOLATILE

RT+

38

Actual TCP forces and torques with compensation for

program_running

urinterfaces

BoolStamped.msg

Reliability: RELIABLE 
Durability: TRANSIENT_LOCAL

T

Set when any foreground program is running

teach_button_pressed

urinterfaces

BoolStamped.msg

Reliability: RELIABLE 
Durability: TRANSIENT_LOCAL

T

Set when any teach input is active

power_button_pressed

urinterfaces

BoolStamped.msg

Reliability: RELIABLE 
Durability: TRANSIENT_LOCAL

T

Set when any power button input is active

/tf

tf2_msgs

TFMessage.msg

Reliability: RELIABLE
Durability: VOLATILE

RT

variable

An array of all named world model frames (and optionally Waypoints, Axis Groups, and Axes ), with the respective child→parent kinematic transforms.

  • Each transform connotes attachment in the world model
  • Order is not guaranteed
  • As this topic is published directly to the root of the namespace, each frame name is prefixed with the robot name

world_model_frames

urinterfaces

WorldModelNames.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

variable

A timestamped array of all  world model frame names.

  • Republishes any time a frame is added or deleted
  • Order is not guaranteed, and may reorder

world_model_waypoints

urinterfaces

WorldModelNames.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

variable

A timestamped array of all  world model waypoint names.

  • Only available when MINOTAUR_WAYPOINTS feature is enabled
  • Republishes any time a waypoint is added or deleted
  • Order is not guaranteed, and may reorder

active_tcp_name

urinterfaces

ActiveTCP.msg

Reliability: RELIABLE
Durability: TRANSIENT_LOCAL

T

variable

Name of the latest active TCP

Subscribed topics

Name

Package

Message

QoS

Description

external_wrench

geometry_msgs

WrenchStamped.msg

Reliability: RELIABLE
Durability: VOLATILE

External force/torque input

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

Appendix 3 - routing ROS2 between subnets

ROS2 by default uses multicast

High level setup for Meraki switches:

  1. Create L3 interface's on each vlan
  2. Create Rendezvous point on the interfaces from step 1, with any multicast group.
  3. Enable the Multicast routing.

Appendix 4 - ROS2 services experiment results

Custom services types(.srv) works between dockers when the name is the same, different names with same type do not work.

Results of testing services between different ROS2 versions

Server/Client

Foxy

Humble

Iron

Foxy

yes

yes

?

?

Humble

yes

yes

yes

?

Iron

sporadic, throws

terminate called after throwing an instance of 'std::bad_alloc'

yes

?

Jazzy

?

?

?

?

Appendix 5 - Frequently Asked Questions

I'm listening to RT topics, and some are published, but others are not, why?

There are 3 possible cases: