How to Use a ROS Timer in Python to Publish Data at a Fixed Rate

So, you have a sensor from which you read data in a ROS node, and you want to publish this data on a ROS topic.

The easiest and most straightforward way to do that is simply to setup a ROS rate, and then to read and publish the data.

But there is a better way so you have more control over the data you read, the computation you can make on the data (for example: oversampling + averaging), and the rate at which you publish the data.

In this post I will show you how to do that using a ROS Timer in Python. (check out this tutorial for the Cpp version)

Let’s go step by step through code iterations so you can easily understand. To give more clarity, let’s say that the sensor we’re using is a temperature sensor.

The easiest way (no Timer)

#!/usr/bin/env python

import rospy
from std_msgs.msg import Float64

def read_temperature_sensor_data():
    # Here you read the data from your sensor
    # And you return the real value
    return 30

if __name__ == '__main__':
    rospy.init_node("your_sensor_node")

    # Create a ROS publisher
    data_publisher = rospy.Publisher("/temperature", Float64, queue_size=1)

    # Create a rate
    rate = rospy.Rate(10)

    while not rospy.is_shutdown():
        msg = Float64()
        msg.data = read_temperature_sensor_data()
        data_publisher.publish(msg)
        rate.sleep()

In this example, you first initialize your node and create a publisher for the data. Then, with a ROS Rate, you read and publish the temperature data at a given frequency (fixed at 10 Hz for this example).


You are learning ROS?

Check out ROS For Beginners and learn ROS step by step.


Note that the read_temperature_sensor_data() function is not implemented. This is your job to write the code here, depending on the sensor you’re using (maybe you need to read with an I2C library, maybe it’s over serial communication, etc). For the sake of this example I have fixed the value at 30.0 (°C, °F, whatever you want).

The easy way (but with a class)

This code has the exact same behavior as the previous one, except that here we’ll use a class instead. This is a preparation for what comes next.

#!/usr/bin/env python

import rospy
from std_msgs.msg import Float64

class TemperatureSensor:

    def read_temperature_sensor_data(self):
        # Here you read the data from your sensor
        # And you return the real value
        self.temperature = 30.0

    def __init__(self):
        # Create a ROS publisher
        self.temperature_publisher = rospy.Publisher("/temperature", Float64, queue_size=1)

        # Initialize temperature data
        self.temperature = 0

    def publish_temperature(self):
        msg = Float64()
        msg.data = self.temperature
        self.temperature_publisher.publish(msg)

if __name__ == '__main__':
    rospy.init_node("your_sensor_node")

    # Create an instance of Temperature sensor
    ts = TemperatureSensor()

    # Create a rate
    rate = rospy.Rate(10)

    while not rospy.is_shutdown():
        ts.read_temperature_sensor_data()
        ts.publish_temperature()
        rate.sleep()

As you can see the temperature is now an attribute of the TemperatureSensor class. We are still reading the data, publishing the data, and waiting for the next iteration with the ROS Rate.

Read data and publish asynchronously with a ROS Timer

Time to use the ROS Timer functionality!

A ROS Timer allows you to set a callback that will be triggered at a given rate. To create a timer, you need to give it the duration to wait between 2 callback triggers, and of course the function to call.

#!/usr/bin/env python

import rospy
from std_msgs.msg import Float64

class TemperatureSensor:

    def read_temperature_sensor_data(self, event=None):
        # Here you read the data from your sensor
        # And you return the real value
        self.temperature = 30.0

    def __init__(self):
        # Create a ROS publisher
        self.temperature_publisher = rospy.Publisher("/temperature", Float64, queue_size=1)

        # Initialize temperature data
        self.temperature = 0

    def publish_temperature(self, event=None):
        msg = Float64()
        msg.data = self.temperature
        self.temperature_publisher.publish(msg)

if __name__ == '__main__':
    rospy.init_node("your_sensor_node")

    # Create an instance of Temperature sensor
    ts = TemperatureSensor()

    # Create a ROS Timer for reading data
    rospy.Timer(rospy.Duration(1.0/10.0), ts.read_temperature_sensor_data)

    # Create another ROS Timer for publishing data
    rospy.Timer(rospy.Duration(1.0/10.0), ts.publish_temperature)

    # Don't forget this or else the program will exit
    rospy.spin()

As you can see, I have created one Timer to read the temperature data from the sensor, and another one to publish this data.

Note that the callback function will be called with an additional parameter: an event. This event gives you timing information about the Timer. For example, the difference between the expected trigger time and the real trigger time.

We don’t need the event here, but don’t forget to add an extra optional parameter to the functions used for the callbacks.

So, what has changed ?

Well, you are now reading data and publishing data asynchronously! Here we kept 10 Hz for both actions, but you can easily modify the value for both Timers.

Let’s see that with another iteration of the code.

Improvement: Oversampling and averaging

Oversampling means that we’ll increase the frequency at which we read the data. This will allow you to get a more updated value when you publish it.

With more data samples between each publication on the ROS topic, you also have the possibility to filter the data (ex: with a complementary filter or a Kalman filter). In this example, we’ll simply add a filter that updates the temperature with the average of the 2 last read values.

#!/usr/bin/env python

import rospy
from std_msgs.msg import Float64

class TemperatureSensor:

    def read_temperature_sensor_data(self, event=None):
        # Here you read the data from your sensor
        # And you return the real value
        if self.temp_index < self.temp_max_index:
            self.temp_data.append(30.0)
            self.temp_index += 1
        else:
            self.temperature = sum(self.temp_data) / len(self.temp_data)
            self.temp_index = 0
            self.temp_data = []

    def __init__(self):
        # Create a ROS publisher
        self.temperature_publisher = rospy.Publisher("/temperature", Float64, queue_size=1)

        # Initialize temperature data
        self.temperature = 0

        self.temp_data = []
        self.temp_index = 0
        self.temp_max_index = 1

    def publish_temperature(self, event=None):
        msg = Float64()
        msg.data = self.temperature
        self.temperature_publisher.publish(msg)

if __name__ == '__main__':
    rospy.init_node("your_sensor_node")

    # Create an instance of Temperature sensor
    ts = TemperatureSensor()

    # Create a ROS Timer for reading data
    rospy.Timer(rospy.Duration(1.0/100.0), ts.read_temperature_sensor_data)

    # Create another ROS Timer for publishing data
    rospy.Timer(rospy.Duration(1.0/10.0), ts.publish_temperature)

    # Don't forget this or else the program will exit
    rospy.spin()

Now we are reading the temperature data at 100 Hz, while still publishing the data at 10 Hz.

With the filter that we added to compute the average of the last 2 read data, the frequency at which we update the “temperature” attribute is 50 Hz.

It means we have a 5x oversampling on a value which is already filtered.

As you can see it’s not really hard to get to this result with the ROS Timer functionality.

Conclusion: Using this code structure is an efficient way to manage your sensors. By separating the reading, processing, and publishing of the data, you gain more control over your application, which also becomes more scalable.

Did you find this tutorial useful?

Do you want to learn how to program with ROS?

If yes, this course is for you:

ROS For Beginners - A Step By Step Course

>> ROS For Beginners - A Step By Step Course <<