Skip to the main content.

Did you know?

 

RTI is the world’s largest DDS supplier and Connext is the most trusted software framework for critical systems.

Success-Plan-Services-DSSuccess-Plan Services

Our Professional Services and Customer Success teams bring extensive experience to train, problem-solve, mentor, and accelerate customer success.

Learn more

Developers

From downloads to Hello World, we've got you covered. Find all of the tutorials, documentation, peer conversations and inspiration you need to get started using Connext today.

Try the Connectivity Selection Tool ⇢

Resources

RTI provides a broad range of technical and high-level resources designed to assist in understanding industry applications, the RTI Connext product line and its underlying data-centric technology.

Company

RTI is the infrastructure software company for smart-world systems. The company’s RTI Connext product is the world's leading software framework for intelligent distributed systems.

Contact Us

News & Events
Cooperation

3 min read

ROS2 + DDS: Play it Again

ROS2 + DDS: Play it Again

Real-world testing is a necessary – and often expensive – part of creating distributed and autonomous systems. Tests are designed to put the system through lots of different scenarios and real-time data collection can create lasting value from these tests. 

Think about road-testing a (semi-)autonomous vehicle that includes GPS, cameras, LiDAR, RADAR, accelerometers, gyroscopes, compass, speedometer, control signals, plus mapping and environmental data. That is a *lot* of data…and very expensive to obtain. Wouldn’t it be nice if all of this data could be recorded for on-demand replay, as if an actual test were running? What if you could build a digital library of every test session and be able to modify it on playback – thereby creating even more repeatable test scenarios?

Did you know that high-bandwidth/high-capacity recording and playback has been available to DDS users for many years with RTI Recording Service? An example use case for RTI Recording Service would be continuous (24/7) recording of all system data during an extended field deployment, such as an at-sea trial of a Navy ship. Recording bandwidth and capacity are nearly unlimited due to the distributed nature of DDS – multiple instances of Recording Service can be launched to keep pace with the flood of data.

The ROS ecosystem has its own recording service called Rosbag, but as of this writing Rosbag had only recently been released for ROS2. Fortunately ROS2 uses DDS as its underlying connectivity framework so it should be straightforward to use the field-proven RTI Recording Service to record high-bandwidth data from ROS2 for anytime replay.

Let’s make that happen...

Recorder Configuration

RTI Recording Service can be configured by an XML file to record all or selected topics, with whatever QoS settings are needed. In this example, I’ll set up to record a moderate-bandwidth topic (ROS2 LiDAR data), then replay it back into ROS2 – all from a pure DDS toolset. 

RTI Recording Service will normally deserialize the data for recording into the columns of a conventional database. The ROS2 LiDAR data has a large number of points per sample, so in this instance I’ll instruct the recorder not to deserialize the data and record it as a single column in the database. The rest of the XML file tells the recorder which topic and data type to record, and where to store the data.

This is contained in an XML file I’ve created, named “ros2_record.xml”:

<dds xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
 xsi:noNamespaceSchemaLocation="http://community.rti.com/schema/5.3.1/rti_record.xsd">

 <recorder name="simple_example">
   <!-- This enables remote access to RTI Recorder. RTI Recorder creates one
   DataReader and one DataWriter in the domain specified with the <domain> tag. -->
     <remote_access>
       <enabled>true</enabled>
       <remote_access_domain>0</remote_access_domain>
     </remote_access>

     <!-- Base name for the set of files in which recorded data will be stored -->
     <recorder_database>
       <database_name>ros2_replay_example.dat</database_name>
       <overwrite>true</overwrite>
     </recorder_database>

     <!-- Record data from one domain -->
     <domain name="domain0">
       <domain_id>0</domain_id>
       <!-- turn off deserialization for ROS2 'PointCloud2' data type (>5k elements in topic) -->
       <deserialize_mode>RTIDDS_DESERIALIZEMODE_NEVER</deserialize_mode>
     </domain>

     <!-- Create a TopicGroup that only records rt/velodyne_points topics -->
     <topic_group name="ros-rt">
       <topics><topic_expr>rt/velodyne_points</topic_expr></topics>
       <field_expr>*</field_expr>
     </topic_group>

     <!-- Create a RecordGroup -->
     <record_group name="RecordAll">
       <!-- Specify which domains to record from -->
       <domain_ref><element>domain0</element></domain_ref>

       <!-- Specify which TopicGroups to record -->
       <topic_ref><element>ros-rt</element></topic_ref>
     </record_group>

     <!-- add domain and typecode info to record ROS2 'PointCloud2' type -->
     <domain_type_config>
       <domain_group>
         <element>
           <domain_filter>
             <element>domain0</element>
           </domain_filter>
           <type_config>
             <xml>
               <file_group>
                 <element>
                   <file_name>
                     <element>PointCloud2.xml</element>
                   </file_name>
                   <type>
                     <element>
                       <register_top_level>false</register_top_level>
                       <type_name>sensor_msgs::msg::dds_::PointCloud2_</type_name>
                       <registered_type_name>
                         <element>sensor_msgs::msg::dds_::PointCloud2_</element>
                       </registered_type_name>
                       <topics>
                         <element>rt/velodyne_points</element>
                       </topics>
                     </element>
                   </type>
                   <max_sequence>2147483647</max_sequence>
                 </element>
               </file_group>
               <path>
                 <element>.</element>
               </path>
             </xml>
           </type_config>
         </element>
       </domain_group>
     </domain_type_config>
   </recorder>
 </dds>

To launch RTI Recording Service using the above XML file, I use the following command (executed from the same directory as the above XML file):

rtirecord -cfgFile ros2_record.xml -cfgName simple_example

This launches the recording service which will subscribe to the LiDAR data and continuously record it until I close the program. The end result is an SQLite database file named “ros2_replay_example.dat_0_0”

Numbers are appended to the file name to differentiate between recording sessions (the first number) and which database file this is in a sequence (the files are automatically limited to a user-selectable size; once they get too large, they are closed and another file is opened to hold the next period of data. This prevents the database files from getting too large).

Replayer Configuration

Now that I have recorded the ROS2 LiDAR data, let’s see if it can be played back into ROS2.

As mentioned in earlier blog articles (A Field Guide to Interoperability and When Ecosystems Merge), ROS2 requires a few settings to ensure compatibility. In this example, sending the type code information during discovery has been suppressed to be compatible with the default configuration of the ROS2 “Bouncy Bolson” release, but this adjustment could also be made in ROS2 if running rmw_connext_cpp as the RMW layer.

These settings– along with topic, domain and file information – are placed in another XML file:

<?xml version="1.0"?>
<dds xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
 xsi:noNamespaceSchemaLocation="http://community.rti.com/schema/5.3.1/rti_replay.xsd">

 <!-- ****************************************************************** -->
 <!-- example configuration for RTI Replay Service 2.0                   -->
 <!-- edited to support ROS2 rt/* topics (PointCloud2 type)              -->
 <!-- ****************************************************************** -->
 <replay_service name="simple_example">
   annotation>
     <documentation>Replay service example</documentation>
   </annotation>
   <time_control>
     <rate>1</rate>      <!-- Optional Rate Multiplier -->
     <start_mode>AUTO</start_mode>
     <start_offset><sec>5</sec></start_offset>
   </time_control>

   <!-- Source Database, Required -->
   <replay_database name="simple_config">
     <filename>ros2_replay_example.dat_0_0</filename>
     <readonly>false</readonly>

     <!-- Participant configuration.  Suppress the sending of typeCode info (for ROS2) -->
     <participant>
       <domain_id>0</domain_id>
       <participant_qos>
         <resource_limits>
           <type_code_max_serialized_length>0</type_code_max_serialized_length>
           <type_object_max_serialized_length>0</type_object_max_serialized_length>
         </resource_limits>
       </participant_qos>
     </participant>

     <!-- get typeCode info for playback (PointCloud2 type) -->
     <type_config>
       <xml>
         <file_group>
           <element>
             <file_name>
               <element>PointCloud2.xml</element>
             </file_name>
             <type>
               <element>
                 <register_top_level>false</register_top_level>
                 <type_name>sensor_msgs::msg::dds_::PointCloud2_</type_name>
                 <registered_type_name>
                   <element>sensor_msgs::msg::dds_::PointCloud2_</element>
                 </registered_type_name>
                 <topics><element>rt/velodyne_points</element></topics>
               </element>
             </type>
             <max_sequence>2147483647</max_sequence>
           </element>
         </file_group>
         <path><element>.</element></path>
       </xml>
     </type_config>

     <session name="A_Session">
       <!-- default values for < time_control > *-->
       <replay_topic name="All_Topic">
         <input>
           <topic_name>*</topic_name>
           <type_name>*</type_name>
           <record_group_name>*</record_group_name>
           <domain_name>*</domain_name>
         </input>
       </replay_topic>
     </session>
   </replay_database>
 </replay_service>
</dds>

To replay the recorded data back into ROS2:

rtireplay -cfgFile ros2_replay.xml -cfgName simple_example

Results

Now I’ve collected ROS2 LiDAR data, generated during a series of auto-simulator sessions, and these are all replayable on-demand, as expected:

ROS2 LiDAR

Nice! I can now replay LiDAR data on-demand without needing a dedicated automotive simulator (or actual vehicle).

It was fun to play with the <time_control><rate> variable in the replay XML file to accelerate the replay of the LiDAR data. It was like being a passenger in a *very* fast car!

For more information on ROS2 and DDS, check out the previous RTI Blog posts:

A Field Guide to Interoperability and When Ecosystems Merge