ROS2 equivilant of `while not rospy.is_shutdown()` node structure?

asked 2023-05-03 07:21:18 -0500

Iranaphor gravatar image

updated 2023-05-03 08:22:23 -0500

Within ROS 1, there were two unique methods of structuring a node, where the main thread would either utilise rospy.spin() or while not rospy.is_shutdown().

Both methods were utilised in wiki.ros.org tutorials such as spin and is_shutdown.

Example method using spin:

import rospy
import std_msgs

class MyNode():

    def __init__(self):
        self.sub = rospy.Subscriber('/topic', std_msgs.String, self.cb)
        self.pub = rospy.Publisher('/topic2', std_msgs.String)

    def cb(self, msg):
        self.pub.publish('message recieved')

if __name__ == '__main__':
    rospy.init_node('node_name')
    new_node = MyNode()
    rospy.spin()

Example method using is_shutdown:

import rospy
import std_msgs

class MyNode():

    def __init__(self):
        self.sub = rospy.Subscriber('/topic', std_msgs.String, self.cb)
        self.pub = rospy.Publisher('/topic2', std_msgs.String)

    def cb(self, msg):
        self.pub.publish('message recieved')

    def run(self):
        while not rospy.is_shutdown():
            rospy.sleep(1)
            print("still running")

if __name__ == '__main__':
    rospy.init_node('node_name')
    new_node = MyNode()
    new_node.run()

ROS 2 has plenty of documentation on how to utilise an equivalent of the spin method, however is there an equivalent of the later approach?

As I understand it, messages will only be received by subscribers while a spin, spin_once, or spin_until_future_completes is actively being executed by either a node or executor, so while utilising a while loop with a spin_once(timeout_sec=1) will allow the script to execute, it will only allow subscribers to receive messages during the spin_once portion of the loop rather than on arrival.

edit retag flag offensive close merge delete