[ROS Q&A] 132 – Callback messages being executed one at a time

Written by Marco Arruda

02/07/2018

In this video we are going to see how to make sure callback messages are being executed one at a time.

This is a video trying to answer the following question posted at the ROS answers forum: https://answers.ros.org/question/287612/how-to-be-100-sure-that-only-one-callback-is-being-executed-at-a-time

RELATED LINKS

▸ Original question: https://answers.ros.org/question/287612/how-to-be-100-sure-that-only-one-callback-is-being-executed-at-a-time
Robot Ignite Academy
ROS Basics in 5 days (Python)
ROS Development Studio (ROSDS)

Step 1. Create a project in ROS Development Studio(ROSDS)

We’ll answer this question by walking you through an example with ROSDS. With ROSDS, we can focus on solving the problem directly instead of finding Linux pc, install ROS and etc. You can create an account here for free. After registering, let’s create a new project and call it q_a_callback_processing.

Step 2. Create package

Then, we’ll create a package with dependencies

cd catkin_ws/src
catkin_create_pkg my_pkg rospy std_msgs

Then create a folder called script under the package directory and a file called publisher.py under the script directory with the content

#!/usr/bin/env python

import rospy
from std_msgs.msg import Int32

def publisher():
    pub = rospy.Publisher('topic_name', Int32, queue_size=10)
    rospy.init_node('publisher')
    r = rospy.Rate(30)
    
    count = 1
    msg = Int32()
    while not rospy.is_shutdown():
        msg.data = count
        count = count+1 if count < 30 else 1
        pub.publish(msg)
        rospy.loginfo(msg)
        r.sleep()

if __name__ == '__main__':
    publisher()

You can see that the topic is publishing at 30 Hz.

To run it, you have to give it permission first with chmod +x publisher.py , then you can run it with rosrun my_pkg publisher.py . You’ll see the script starts to publishing message.

Now the publisher is working, let’s create a subscriber to subscribe to the topic. Let’s call it subscriber.py and fill it with the following content

#!/usr/bin/env python

import rospy
from std_msgs.msg import Int32

processing = False
new_msg = False
msg = None

def callback(data):
    global processing, new_msg, msg
    if not processing:
        new_msg = True
        msg = data

def listener():
    global processing, new_msg, msg
    rospy.init_node('subscriber')
    rospy.Subscriber('topic_name', Int32, callback)
    r = rospy.Rate(5)
    while not rospy.is_shutdown():
        if new_msg:
            #set processing to True
            processing = True
            new_msg = False
            #simulate a process that take 0.2 seconds
            rospy.loginfo(msg)
            r.sleep()
            #set processing to False
            processing = False
    
if __name__ == '__main__':
    listener()

Here in the subscriber, we only run it for 5 Hz. Now you have to give it permission and run it. You’ll see that the subscriber only get 5 messages every second. This is the answer!

 

Take away today:

You can specify different rates and r.sleep() function for publisher and subscriber in order to make sure the node has enough time to run your algorithm.

 

Edit by: Tony Huang


Feedback

Did you like this video? Whatever the case, please leave a comment on the comments section below, so we can interact and learn from each other.

If you want to learn about other ROS topics, please let us know on the comments area and we will do a video about it.

Topics:
Masterclass 2023 batch2 blog banner

Check Out These Related Posts

129. ros2ai

129. ros2ai

I would like to dedicate this episode to all the ROS Developers who believe that ChatGPT or...

read more

1 Comment

  1. Harith

    Hi. i have doubts with rospy publishing and i was hoping you could help me clear my doubts.
    i have a code for the turtlebot3 burger, and i want it to follow a certain path and to follow this path it is using only 90 degrees movement. So in my code, i have four different function to move front, left, right and backwards. And all are publishing to the topic cmd_vel.
    Q1. the steps inside “while not rospy.is_shutdown():” , i want it to occur once. not in a loop. is it possible to make the steps run once and if its possible how can i achieve it?
    Q2. Is there a problem in having four rospy publishing fucntions in the same code?

    Reply

Submit a Comment

Your email address will not be published.

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Pin It on Pinterest

Share This