Main Content

ros2topicsynchronizer

Time synchronize messages from multiple topics on ROS 2 network

Since R2026a

Description

Use the ros2topicsynchronizer object to time synchronize messages published at different frequencies across multiple topics in the ROS 2 network. You can obtain a set of the most recent messages that are synchronized to be closest in time across all topics included in the object. To add topics to the ros2topicsynchronizer object, use the addTopic object function. Alternatively, you can create a custom callback function and provide that as input to the ros2topicsynchronizer object, enabling the object to run the callback function every time a set of synchronized messages becomes available.

The ros2topicsynchronizer object can time synchronize messages across a minimum of two, to a maximum of nine topics. The ros2topicsynchronizer supports time synchronization of only those messages that contain the std_msgs/header field.

Follow these steps to time synchronize messages across multiple topics:

  1. Create the ros2topicsynchronizer object and specify the desired time-synchronization policy.

  2. Add the desired topics for time synchronization using the addTopic object function.

  3. Initiate the synchronization using the synchronize object function.

The ros2topicsynchronizer object supports various policies that achieve the time-synchronization process in slightly different ways. You can specify the desired policy when you create the ros2topicsynchronizer object.

Creation

Description

syncObj = ros2topicsynchronizer(policy) creates a ros2topicsynchronizer object with the specified synchronization policy.

example

syncObj = ros2topicsynchronizer(policy,Name=Value) specifies additional options using one or more name-value arguments.

example

Input Arguments

expand all

Time-synchronization policy across all included topics, specified as one of these options:

  • "ExactTime" — Synchronizes only messages that have the same timestamp, in seconds and nanoseconds, across all topics.

  • "ApproximateEpsilonTime" — Synchronizes only messages that have timestamps within a specified tolerance, epsilon, across all topics.

  • "ApproximateTime" — Synchronizes messages using an adaptive algorithm with tunable parameters.

You can refine these policies by specifying policy-specific parameters using the PolicySettings name-value argument.

Name-Value Arguments

expand all

Specify optional pairs of arguments as Name1=Value1,...,NameN=ValueN, where Name is the argument name and Value is the corresponding value. Name-value arguments must appear after other arguments, but the order of the pairs does not matter.

Example: syncObj = ros2topicsynchronizer("ApproximateEpsilonTime",SynchronizationCallback=@syncTopics,PolicySettings=syncPolicyStruct) creates a topic synchronizer using approximate epsilon time policy with the policy settings specified by the structure syncPolicyStruct, and assigns syncTopics function as the callback.

Policy-specific settings for time synchronization, specified as a structure with parameter fields based on the specified time-synchronization policy. This table illustrates the parameter fields in the PolicySettings structure for each policy, and their default values. Modify the parameter value fields for your policy as desired, and specify the structure to the PolicySettings argument.

PolicyPolicySettings Structure with Default Values
"ExactTime"
struct("MessageQueueSize",uint32(10))
"ApproximateEpsilonTime"
struct("MessageQueueSize",uint32(10),...
"Epsilon",0.005)
"ApproximateTime"
struct("MessageQueueSize",uint32(10), ...
"AgePenalty",0.1, ...
"InterMessageLowerBound",[0 0], ...
"MaxIntervalDuration",2147483647.999999999)

This table describes each possible parameter field in the PolicySettings structure and how each policy uses them in the time-synchronization process.

Parameter FieldDescriptionDefault ValueApplicable Policies
MessageQueueSize

Queue size allocated to each individual topic by the ros2topicsynchronizer object for storing incoming messages. To ensure that messages from high-frequency topics are not lost while waiting for messages from low-frequency topics, specify MessageQueueSize to be twice the value of the highest frequency.

Messages leave the queue after time synchronization.

10

ExactTime

ApproximateEpsilonTime

ApproximateTime

EpsilonTolerance of timestamp difference between synchronized messages, specified in seconds.0.005 secondsApproximateEpsilonTime
AgePenalty

Penalty on waiting for future messages for synchronization, specified as a positive scalar.

  • Larger Age Penalty values discourage waiting for future messages, causing the object to output synchronized set of messages faster.

  • Smaller Age Penalty values encourage waiting for future messages which can improve synchronization.

0.1ApproximateTime
InterMessageLowerBound

Minimum time difference between messages for each topic added to the ros2topicsynchronizer object, specified as an N-element array. N is the number of topics added to the object, and each value is in seconds

Specifying this value helps the algorithm run faster, especially if you know that messages cannot arrive before a certain time interval.

[0 0] secondsApproximateTime
MaxIntervalDurationMaximum allowed time difference between messages for synchronization.

2147483647.999999999 seconds.

The default value is the maximum duration allowed by a 32-bit integer, in seconds.

ApproximateTime

Synchronized messages callback function , specified as a function handle. The ros2topicsynchronizer object runs this function each time a set of synchronized messages becomes available.

The synchronization callback function must accept the set of time-synchronized messages as input arguments. The number of input arguments must be equal to the number of topics added to the ros2topicsynchronizer object. The order of the input arguments must align exactly with the order in which you add the topics to the ros2topicsynchronizer object.

% Create ROS 2 topic synchronizer object
syncObj = ros2topicsynchronizer("ApproximateEpsilonTime",SyncCallback=@syncTopics);

% Add topics to synchronize
addTopic(syncObj,"/topic1")
addTopic(syncObj,"/topic2")
...
addTopic(syncObj,"/topicN")

% Define Synchronization callback function
function syncTopics(topic1Msg,topic2Msg,...,topicNMsg)
...
end

Properties

expand all

This property is read-only.

Time-synchronization policy across all topics, represented as ExactTime, ApproximateEpsilonTime, or ApproximateTime.

The policy input argument sets this property.

This property is read-only.

Policy-specific settings for time-synchronization, represented as a structure.

The PolicySettings name-value argument sets this property.

This property is read-only.

Synchronized messages callback function, represented as a function handle. The ros2topicsynchronizer object runs this function each time a set of synchronized messages becomes available.

The SynchronizationCallback name-value argument sets this property.

This property is read-only.

Parameters of topics added for time-synchronization, represented as a structure. The topic parameter structure contains the topic name, message type, and Quality of Service (QoS) parameters for each topic added for time synchronization.

This property is read-only.

Set of the latest time-synchronized messages across all topics, represented as a cell array. After you add topics, you can get the set of latest time-synchronized messages by using the synchronize object function.

Object Functions

addTopicAdd ROS 2 topic for time-synchronization of messages
synchronizeInitiate time synchronization of messages across added ROS 2 topics

Examples

collapse all

This example shows how to use the ros2topicsynchronizer object to get sets of time-synchronized messages from multiple ROS 2 topics publishing at different frequencies.

Read all the messages from the ROS 2 bag file. The bag file contains odometry and laser scan messages which are published at different rates. The odometry messages are published at 25 Hz and the laser scan messages are published at 5 Hz.

unzip("ros2_netwrk_bag.zip");
bagReader = ros2bagreader(fullfile(pwd,"ros2_netwrk_bag"));
odomMsgs = readMessages(select(bagReader,Topic="/odom"));
scanMsgs = readMessages(select(bagReader,Topic="/scan"));

Create two publishers /odom and /scan, which can publish odometry and laserscan messages.

publishNode = ros2node("publisherNode");
odomPub = ros2publisher(publishNode,"/odom","nav_msgs/Odometry",Durability="transientlocal",Depth=10);
scanPub = ros2publisher(publishNode,"/scan","sensor_msgs/LaserScan",Durability="transientlocal",Depth=10);

Create a ros2topicsynchronizer object which uses approximate epsilon time policy to time-synchronize messages. This means that sets of messages with timestamps between an epsilon tolerance are considered to be time-synchronized. Also, to ensure that messages from topics published at higher frequencies are not lost while waiting for those published at lower frequencies, specify the queue size as at least twice the highest frequency.

Use the syncPolicySettings structure to specify:

  • Epsilon tolerance — 0.05 seconds

  • Queue size — 50

Specify the syncOdomScan function as the callback to execute each time a set of time-synchronized messages become available. The syncOdomScan function prints the individual timestamps of odometry and laser scan messages in each time-synchrnized set.

syncPolicySettings = struct("MessageQueueSize",uint32(50),"Epsilon",0.05);
syncObj = ros2topicsynchronizer("ApproximateEpsilonTime",SyncCallback=@syncOdomScan,PolicySettings=syncPolicySettings);

Add the two topics /odom and /scan for time-synchronization using the addTopic object function.

addTopic(syncObj,"/odom")
addTopic(syncObj,"/scan")

Initiate time-synchronization using the synchronize object function.

synchronize(syncObj)

Before publishing messages, create separate ros2rate objects for each topic to control publishing messages at different frequencies.

odomRate = ros2rate(publishNode,25);
scanRate = ros2rate(publishNode,5);

Start publishing messages on the /odom and /scan topics.

j = 1;
i = 1;

nextOdomPubTime = odomRate.TotalElapsedTime;
nextScanPubTime = scanRate.TotalElapsedTime;

while i <= numel(odomMsgs) || j <= numel(scanMsgs)
    currentTime = odomRate.TotalElapsedTime;
    if currentTime >= nextOdomPubTime && i <= numel(odomMsgs)
        send(odomPub,odomMsgs{i});
        i = i+1;
        nextOdomPubTime = nextOdomPubTime + odomRate.DesiredPeriod;
    end

    if currentTime >= nextScanPubTime && j <= numel(scanMsgs)
        send(scanPub,scanMsgs{j});
        j = j+1;
        nextScanPubTime = nextScanPubTime + scanRate.DesiredPeriod;
    end

    waitfor(odomRate);
end

You can also view the latest set of time-synchronized odometry and laser scan messages using the LatestSynchronizedMessages property.

syncMsgs = syncObj.LatestSynchronizedMessages;
syncMsgs{1}
ans = struct with fields:
       MessageType: 'nav_msgs/Odometry'
            header: [1×1 struct]
    child_frame_id: 'base_footprint'
              pose: [1×1 struct]
             twist: [1×1 struct]

syncMsgs{2}
ans = struct with fields:
        MessageType: 'sensor_msgs/LaserScan'
             header: [1×1 struct]
          angle_min: 0
          angle_max: 6.2832
    angle_increment: 0.0175
     time_increment: 0
          scan_time: 0
          range_min: 0.1200
          range_max: 3.5000
             ranges: [360×1 single]
        intensities: [360×1 single]

The syncOdomScan function receives two input arguments odomMsg and scanMsg. These input arguments correspond to a time-synchronized set of odometry and scan messages.

function syncOdomScan(odomMsg,scanMsg)
    t1 = double(odomMsg.header.stamp.sec) + 1e-9*double(odomMsg.header.stamp.nanosec);
    t2 = double(scanMsg.header.stamp.sec) + 1e-9*double(scanMsg.header.stamp.nanosec);
    fprintf("OdomMsgTime: %.3f ScanMsgTime: %.3f\n",t1,t2);
end

Version History

Introduced in R2026a