proton_ros2
proton_ros2 is a ROS 2 adapter for Proton. It runs both a ROS 2 node and a protoncpp node in the same process, and bridges Proton bundles to ROS 2 topics for publishers and subscribers, or services for servers and clients.
The proton_ros2 package is only released in ROS 2 Jazzy, but can be built from source in other ROS 2 distros.
Converting from Proton to ROS 2
Bundles are dynamic enough that they can support the message structure of most ROS 2 messages. ROS 2 primitives can be mapped to an equivalent Proton Signal primitive, and a Proton Bundle structure can be defined based on the ROS 2 message fields.
Primitive Scalar mapping
| ROS 2 | Proton |
|---|---|
float32 | float |
float64 | double |
int8 | int32 |
int16 | int32 |
int32 | int32 |
int64 | int64 |
uint8 | uint32 |
uint16 | uint32 |
uint32 | uint32 |
uint64 | uint64 |
bool | bool |
char | uint32 |
byte | uint32 |
string | string |
Primitive List mapping
| ROS 2 | Proton |
|---|---|
float32[] | list_float |
float64[] | list_double |
int32[] | list_int32 |
int64[] | list_int64 |
uint8[] | bytes |
uint32[] | list_uint32 |
uint64[] | list_uint64 |
bool[] | list_bool |
byte[] | bytes |
string[] | list_string |
Types outside of these tables are not currently supported
Type Adapters
Using the rclcpp::TypeAdapter struct, conversion functions can be created to convert back and forth between Bundles and ROS 2 messages. proton_ros2 implements a similar ServiceTypeAdapter for ROS 2 service request and response messages.
proton_ros2 implements a Python-based code generated that will generate templated C++ code for all supported ROS 2 messages and services. Each message will have a convert_to_ros and convert_to_custom function generated which implements the logic for converting from Proton to ROS 2. Because ROS 2 messages have the ability to contain nested submessages, the generator will attempt to flatten the message into a format that can be mapped to a Proton Bundle. Flattening is done by recursing through a field in a ROS 2 message until the primitive data type is reached, then creating a signal with an equivalent Proton primitive type. The name of the signal will be the name of each field in the path joined by an underscore.
For example, the sensor_msgs/IMU has a geometry_msgs/Quaternion field called orientation. Within Quaternion are the fields x, y, z, and w of type float64. The Bundle that would be used for this message would then have to have the signals orientation_x, orientation_y, orientation_z, and orientation_w of type double, which would be mapped to the ROS 2 message fields.
Configuration
In the Proton configuration file, a ros2 section can be added to map Proton Bundles to ROS 2 topics or services.
Topics
Topic publishers or subscribers can be configured with the following keys:
| Key | Type | Description | Required |
|---|---|---|---|
topic | string | Topic name | Yes |
message | string | ROS 2 message type | Yes |
bundle | string | The Proton Bundle for this topic | Yes |
qos | string or Map | The QoS profile for this topic | No |
Bundles that the target consumes will create a ROS 2 publisher, while Bundles that the target produces will create a ROS 2 subscriber. The Bundle must have a signal with a name matching the path of the ROS 2 message field, as well as the same equivalent type.
Example
To create a publisher to the topic /my_string of type std_msgs/msg/String, the following configuration can be used:
nodes:
- name: pc
transport:
type: udp4
ip: 127.0.0.1
port: 11416
- name: mcu
transport:
type: udp4
ip: 127.0.0.1
port: 11417
connections:
- first: {node: pc, id: 0}
second: {node: mcu, id: 0}
bundles:
- name: my_string
id: 0x100
producer: mcu
consumer: pc
signals:
- {name: data, type: string, capacity: 64}
ros2:
topics:
- {topic: /my_string, message: std_msgs/msg/String, bundle: my_string}
When the node is launched with pc as the target, it will know that pc consumes the my_string bundle, and so it will create a publisher that will convert the bundle to a std_msgs/msg/String and publish the message as soon as the bundle is consumed.
Note that the signal is named data to match the equivalent ROS 2 field.
Services
Service servers or clients can be configured with the following keys:
| Key | Type | Description | Required |
|---|---|---|---|
topic | string | Service topic name | Yes |
service | string | ROS 2 service type | Yes |
request | string | The Proton Bundle for the request message of this service | Yes |
response | string | The Proton Bundle for the response message of this service | No |
timeout | uint32 | Number of milliseconds to wait for a Proton response or a ROS 2 service server (Default: 1000ms) | No |
qos | string or Map | The QoS profile for this service | No |
If the target produces the request Bundle, then the node will create a service server. Otherwise, it will create a service client. The response Bundle is optional. Each Bundle must have a signal with a name matching the path of the ROS 2 message field for the corresponding Request or Response message, as well as the equivalent primitive type.
Example
To create a service on the topic /light_switch of type std_srvs/srv/SetBool, the following configuration can be used:
nodes:
- name: pc
transport:
type: udp4
ip: 127.0.0.1
port: 11416
- name: mcu
transport:
type: udp4
ip: 127.0.0.1
port: 11417
connections:
- first: {node: pc, id: 0}
second: {node: mcu, id: 0}
bundles:
- name: light_switch_request
id: 0x100
producer: pc
consumer: mcu
signals:
- {name: data, type: bool}
- name: light_switch_response
id: 0x101
producer: mcu
consumer: pc
signals:
- {name: success, type: bool}
- {name: message, type: string, capacity: 64}
ros2:
services:
- {topic: /light_switch, service: std_srvs/srv/SetBool, request: light_switch_request, response: light_switch_response, timeout: 100}
When the node is launched with pc as the target, it will know that pc produces the request bundle, and so it will create a service that will convert a std_srvs/srv/SetBool request to the light_switch_request Bundle, then send it to the mcu target. It will then wait up to 100ms for a light_switch_response Bundle to be received. If successful, that Bundle will be converted to a std_srvs/srv/SetBool response, and returned to the ROS 2 service client.
QoS
The QoS profiles for both Topics and Services can also be configured. You can either choose a predefined standard profile, or create a custom one. To choose a standard profile, set the value of the qos key to the name of the profile.
Standard profiles
The following standard QoS profiles are supported:
| Profile | Description |
|---|---|
default | Default topic profile |
services | Default services profile |
sensor_data | Best Effort sensor data profile |
rosout | Transient Local profile for /rosout |
system_defaults | Default profile based on middleware |
For example, a /rosout topic can be defined like this:
ros2:
topics:
- {topic: /rosout, message: rcl_interfaces/msg/Log, qos: rosout, bundle: log}
Custom profiles
A custom QoS profile can be created by defining the value of the qos key as another map. The map can have the following keys:
| Key | Type | Required |
|---|---|---|
history | string | No |
depth | uint32 | No |
reliability | string | No |
durability | string | No |
History
The history value can be one of the following policies:
| Policy | Description |
|---|---|
keep_last | Keep the last depth messages |
keep_all | Keep all messages |
system_default | Default based on middleware |
The default history is
system_default
Depth
If history is set to keep_last, depth will determine how many messages to keep.
The default depth is
10
Reliability
The reliability value can be one of the following policies:
| Policy | Description |
|---|---|
best_effort | Attempt to deliver samples, but may lose them if the network is not robust |
reliable | Guarantee that samples are delivered, may retry multiple times |
system_default | Default based on middleware |
The default reliability is
system_default
Durability
The durability value can be one of the following policies:
| Policy | Description |
|---|---|
transient_local | The publisher becomes responsible for persisting samples for “late-joining” subscriptions |
volatile | No attempt is made to persist samples |
system_default | Default based on middleware |
The default durability is
system_default
For example, a my_string topic can be defined like this:
ros2:
topics:
- topic: my_string
message: std_msgs/msg/String
qos:
history: keep_last
depth: 15
reliability: best_effort
durability: volatile
bundle: my_string
Usage
The executable produced by proton_ros2 is proton_ros2_node.
It takes two ROS parameters:
config_file(string): path to the Proton YAML configuration filetarget(string): Proton node name this process represents (used to decide which bundles are produced/consumed)
The launch file proton_ros2.launch.py wires these parameters and supports an optional namespace.
Launch the node with ros2 CLI:
ros2 launch proton_ros2 proton_ros2.launch.py config_file:=/path/to/config.yaml target:=target_node namespace:=/my_namespace
The launched node with automatically spin up a ROS 2 and Proton node, connect to Proton peers, and create ROS 2 publishers, subscribers, services, and clients as defined in the configuration file.
Supported messages
The following message and service packages are currently supported in the proton_ros2 binary. Messages marked with a ✅ are supported and follow the standard Proton to ROS 2 mapping convention. Messages with a ✴️ symbol are supported with a custom mapping from Proton to ROS 2. Messages marked with ❌ are not supported at this time.
Messages
clearpath_platform_msgs
| Message | |
|---|---|
DisplayStatus | ✅ |
Drive | ✅ |
DriveFeedback | ✅ |
Fans | ✅ |
Feedback | ✅ |
Lights | ✴️ |
PinoutCommand | ✅ |
PinoutState | ✅ |
Power | ✅ |
RGB | ✅ |
Status | ✅ |
StopStatus | ✅ |
Temperature | ✅ |
geometry_msgs
| Message | |
|---|---|
Accel | ✅ |
AccelStamped | ✅ |
AccelWithCovariance | ✅ |
AccelWithCovarianceStamped | ✅ |
Inertia | ✅ |
InertiaStamped | ✅ |
Point | ✅ |
Point32 | ✅ |
PointStamped | ✅ |
Polygon | ✅ |
PolygonInstance | ❌ |
PolygonInstanceStamped | ❌ |
PolygonStamped | ❌ |
Pose | ✅ |
Pose2D | ✅ |
PoseArray | ❌ |
PoseStamped | ✅ |
PoseWithCovariance | ✅ |
PoseWithCovarianceStamped | ✅ |
Quaternion | ✅ |
QuaternionStamped | ✅ |
Transform | ✅ |
TransformStamped | ✅ |
Twist | ✅ |
TwistStamped | ✅ |
TwistWithCovariance | ✅ |
TwistWithCovarianceStamped | ✅ |
Vector3 | ✅ |
Vector3Stamped | ✅ |
VelocityStamped | ✅ |
Wrench | ✅ |
WrenchStamped | ✅ |
nmea_msgs
| Message | |
|---|---|
Gpgga | ✅ |
Gpgsa | ✅ |
Gpgst | ✅ |
Gpgsv | ✅ |
GpgsvSatellite | ✅ |
Gprmc | ✅ |
Gpvtg | ✅ |
Gpzda | ✅ |
Sentence | ✅ |
rcl_interfaces
| Message | |
|---|---|
FloatingPointRange | ✅ |
IntegerRange | ✅ |
ListParametersResult | ✅ |
Log | ✅ |
LoggerLevel | ✅ |
Parameter | ✅ |
ParameterDescriptor | ❌ |
ParameterEvent | ❌ |
ParameterEventDescriptors | ❌ |
ParameterType | ✅ |
ParameterValue | ✅ |
SetParametersResult | ✅ |
sensor_msgs
| Message | |
|---|---|
BatteryState | ✅ |
CameraInfo | ✅ |
ChannelFloat32 | ✅ |
CompressedImage | ✅ |
FluidPressure | ✅ |
Illuminance | ✅ |
Image | ✅ |
Imu | ✅ |
JointState | ✅ |
Joy | ✅ |
JoyFeedback | ✅ |
JoyFeedbackArray | ✅ |
LaserEcho | ✅ |
LaserScan | ✅ |
MagneticField | ✅ |
MultiDOFJointState | ❌ |
MultiEchoLaserScan | ❌ |
NavSatFix | ✅ |
NavSatStatus | ✅ |
PointCloud | ❌ |
PointCloud2 | ✅ |
PointField | ✅ |
Range | ✅ |
RegionOfInterest | ✅ |
RelativeHumidity | ✅ |
Temperature | ✅ |
TimeReference | ✅ |
std_msgs
| Message | |
|---|---|
Bool | ✅ |
Byte | ✅ |
ByteMultiArray | ✴️ |
Char | ✅ |
ColorRGBA | ✅ |
Empty | ✅ |
Float32 | ✅ |
Float32MultiArray | ✴️ |
Float64 | ✅ |
Float64MultiArray | ✴️ |
Header | ✅ |
Int16 | ✅ |
Int16MultiArray | ❌ |
Int32 | ✅ |
Int32MultiArray | ✴️ |
Int64 | ✅ |
Int64MultiArray | ✴️ |
Int8 | ✅ |
Int8MultiArray | ❌ |
MultiArrayDimension | ✅ |
MultiArrayLayout | ✅ |
String | ✅ |
UInt16 | ✅ |
UInt16MultiArray | ❌ |
UInt32 | ✅ |
UInt32MultiArray | ✴️ |
UInt64 | ✅ |
UInt64MultiArray | ✴️ |
UInt8 | ✅ |
UInt8MultiArray | ✴️ |
Services
clearpath_platform_msgs
| Message | |
|---|---|
ConfigureMcu | ❌ |
SetPinout | ✅ |
std_srvs
| Message | |
|---|---|
Empty | ✅ |
SetBool | ✅ |
Trigger | ✅ |
Adding custom message packages
If you wish to add support for additional message or service packages, the proton_ros2 package will have to be built from source.
First, create a workspace and clone the proton_ros2 package:
mkdir ~/proton_ws/src -p
cd ~/proton_ws/src
git clone https://github.com/clearpathrobotics/proton_ros2.git
Then, modify the CMakelists.txt file to find your package:
find_package(my_msgs REQUIRED)
Finally, add your package to the PROTON_ROS2_MESSAGES list (or PROTON_ROS2_SERVICES for a service package) and build the package.
set(PROTON_ROS2_MESSAGES
clearpath_platform_msgs
geometry_msgs
nmea_msgs
rcl_interfaces
sensor_msgs
std_msgs
my_msgs
)
source /opt/ros/jazzy/setup.bash
cd ~/proton_ws
colcon build
source ~/proton_ws/install/setup.bash
If you encounter errors while building, it may suggest that the generator was not able to flatten a message in your message package. In that case, you may need to create a configuration file to either customize how that message is mapped to a Proton Bundle, or disable that message entirely.
Custom mapping
Generator mappings can be customized through a configuration YAML file specific to the message or service package. To create a configuration file,
create a .yaml file with the same name as your message package underneat the config/messages or config/services folder in proton_ros2. Inside the file,
add a package: entry with the name of your package. Then, add a messages: or services: entry. Under this section, you will add a list of each message that you want to modify:
package: clearpath_platform_msgs
messages:
- name: Lights
path: msg
mapping:
- {ros2.path: lights, ros2.length: 0, ros2.subpath: red, proton.signal: lights, proton.subindex: 0, type: list_bytes}
- {ros2.path: lights, ros2.length: 0, ros2.subpath: green, proton.signal: lights, proton.subindex: 1, type: list_bytes}
- {ros2.path: lights, ros2.length: 0, ros2.subpath: blue, proton.signal: lights, proton.subindex: 2, type: list_bytes}
In this example, the clearpath_platform_msgs/msg/Lights message is being modified to have a custom mapping. The default generator mapping would have created
three Signals called lights_red, lights_green and lights_blue, each of type bytes. Instead, this custom mapping creates a single Signal called lights which is a list_bytes type and maps the indices of the list_bytes to each colour.
Mapping rules
A mapping rule can be created for each ROS 2 field and equivalent Proton Signal. There are several mapping types:
- Scalar:
ros_msg.field = proton.signal - Proton Indexed:
ros_msg.field = proton.signal[proton_index] - ROS Indexed:
ros_msg.field[ros_index] = proton.signal - Both Indexed:
ros_msg.field[ros_index] = proton.signal[proton_index] - Fixed List:
ros_msg.field[n] = proton.signal[n] - Dynamic List:
ros_msg.field[] = proton.signal[] - Fixed Submessage:
ros_msg.field[n].subfield = proton.signal[n] - Dynamic Submessage:
ros_msg.field[].subfield = proton.signal[] - Fixed Subindex:
ros_msg.field[n].subfield = proton.signal[n][proton_subindex](list_bytesonly) - Dynamic Subindex:
ros_msg.field[].subfield = proton.signal[n][proton_subindex](list_bytesonly)
These rules are defined in the YAML file with these parameters:
ros2.path: ROS field path (dot-separated, e.g.layout.data_offset)ros2.index: fixed index into a ROS array/vectorros2.length: list length behavior> 0indicates fixed-size array length0indicates dynamic list (resize destination on Proton->ROS)
ros2.subpath: field name inside a nested message element (used for arrays of nested messages)proton.signal: Proton Signal nameproton.index: fixed index into a Proton list signalproton.subindex: subindex inside alist_byteselementtype: Proton signal type string (e.g.uint32,list_float,bytes,list_bytes)
Signals do not support dynamically sized arrays, so dynamic arrays in ROS 2 will be limited to the length of the Signal array
Diagnostics
proton_ros2 registers diagnostics stats via diagnostic_updater:
- Per-connection RX/TX rates (KB/s) from the embedded
protoncppnode - Per-bundle frequency (Hz) depending on whether
targetproduces or consumes the bundle - Heartbeat frequency checks for peers that have heartbeat enabled in the Proton config
Diagnostics are published through the standard ROS 2 diagnostics pipeline.