ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

ROS 2: How to quit a node from within a callback?

asked 2022-09-15 04:53:52 -0500

Morris gravatar image

updated 2022-09-17 13:43:42 -0500

I have a node with a callback. Now I want this callback to be able to shut down my node. I could do this in ROS 1 simply by calling rospy.signal_shutdown(). In ROS 2, I tried calling rclpy.shutdown(), but this just hangs the node. Any thoughts?

Below is a modification of the publisher tutorial where I inserted a call to shutdown in the callback that just causes it to hang. How can the callback cause the node to quit properly?

import rclpy
from rclpy.node import Node

from std_msgs.msg import String

class MinimalPublisher(Node):

    def __init__(self):
        super().__init__('minimal_publisher')
        self.publisher_ = self.create_publisher(String, 'topic', 10)
        timer_period = 0.5  # seconds
        self.timer = self.create_timer(timer_period, self.timer_callback)
        self.i = 0

    def timer_callback(self):
        msg = String()
        msg.data = 'Hello World: %d' % self.i
        self.publisher_.publish(msg)
        self.get_logger().info('Publishing: "%s"' % msg.data)
        self.i += 1
        if self.i==10:                 # I could put other non hard-coded tests here
            msg.data = 'Done'
            self.publisher_.publish(msg)
            self.get_logger().info('Publishing: "%s"' % msg.data)
            rclpy.shutdown()           # <-- Here is where I want to the node to quit


def main(args=None):
    rclpy.init(args=args)

    minimal_publisher = MinimalPublisher()

    rclpy.spin(minimal_publisher)

    minimal_publisher.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2022-09-17 11:19:08 -0500

Morris gravatar image

updated 2022-09-18 05:27:53 -0500

One solution for quitting a node in a callback is by raising an exception, raise SystemExit, and to catch this with a try statement around the spin command. I was hoping for something more tightly integrated with the rclpy.spin() function, but using an exception works. Here is my adjusted code that raises an exception:

import rclpy
from rclpy.node import Node

from std_msgs.msg import String

class MinimalPublisher(Node):

    def __init__(self):
        super().__init__('minimal_publisher')
        self.publisher_ = self.create_publisher(String, 'topic', 10)
        timer_period = 0.5  # seconds
        self.timer = self.create_timer(timer_period, self.timer_callback)
        self.i = 0

    def timer_callback(self):
        msg = String()
        msg.data = 'Hello World: %d' % self.i
        self.publisher_.publish(msg)
        self.get_logger().info('Publishing: "%s"' % msg.data)
        self.i += 1
        if self.i==10:                 # I could put other non hard-coded tests here
            raise SystemExit           # <--- here is we exit the node


def main(args=None):
    rclpy.init(args=args)

    minimal_publisher = MinimalPublisher()

    try:
        rclpy.spin(minimal_publisher)
    except SystemExit:                 # <--- process the exception 
        rclpy.logging.get_logger("Quitting").info('Done')

    minimal_publisher.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

And here is the output:

$ ros2 run pubsub pub
[INFO] [1663431130.979032633] [minimal_publisher]: Publishing: "Hello World: 0"
[INFO] [1663431131.470329439] [minimal_publisher]: Publishing: "Hello World: 1"
[INFO] [1663431131.970294597] [minimal_publisher]: Publishing: "Hello World: 2"
[INFO] [1663431132.470316570] [minimal_publisher]: Publishing: "Hello World: 3"
[INFO] [1663431132.970332998] [minimal_publisher]: Publishing: "Hello World: 4"
[INFO] [1663431133.470259482] [minimal_publisher]: Publishing: "Hello World: 5"
[INFO] [1663431133.970132387] [minimal_publisher]: Publishing: "Hello World: 6"
[INFO] [1663431134.470312447] [minimal_publisher]: Publishing: "Hello World: 7"
[INFO] [1663431134.970329859] [minimal_publisher]: Publishing: "Hello World: 8"
[INFO] [1663431135.470194060] [minimal_publisher]: Publishing: "Hello World: 9"
[INFO] [1663431135.470720726] [Quitting]: Done
edit flag offensive delete link more

Comments

Why did you put "Quitting" as a parameter for the get_logger function?

andrestoga gravatar image andrestoga  ( 2023-04-24 15:13:11 -0500 )edit
0

answered 2022-09-15 06:39:34 -0500

ravijoshi gravatar image

updated 2022-09-15 06:42:06 -0500

Please replace rclpy.shutdown() with self.destroy_node(). However, I am not sure if destroying a node inside a callback is a good idea. Nevertheless, please see the code snippet:

# Copyright 2016 Open Source Robotics Foundation, Inc.
# license removed for brevity

import rclpy
from rclpy.node import Node
from std_msgs.msg import String


class MinimalPublisher(Node):

    def __init__(self):
        super().__init__('minimal_publisher')
        self.publisher_ = self.create_publisher(String, 'topic', 10)
        timer_period = 0.5  # seconds
        self.timer = self.create_timer(timer_period, self.timer_callback)
        self.i = 0

    def timer_callback(self):
        msg = String()
        msg.data = 'Hello World: %d' % self.i
        self.publisher_.publish(msg)
        self.get_logger().info('Publishing: "%s"' % msg.data)
        self.i += 1
        if self.i==10:                   # I could put other non hard-coded tests here
            msg.data = 'Done'
            self.publisher_.publish(msg)
            self.get_logger().info('Publishing: "%s"' % msg.data)
            self.destroy_node()           # <-- Here is where I want to the node to quit

def main(args=None):
    rclpy.init(args=args)

    minimal_publisher = MinimalPublisher()

    rclpy.spin(minimal_publisher)
    rclpy.shutdown()


if __name__ == '__main__':
    main()

Below is the info it prints at terminal:

$ ros2 run examples_rclpy_minimal_publisher publisher_member_function 
[INFO] [1663241782.469494158] [minimal_publisher]: Publishing: "Hello World: 0"
[INFO] [1663241782.963022122] [minimal_publisher]: Publishing: "Hello World: 1"
[INFO] [1663241783.464649394] [minimal_publisher]: Publishing: "Hello World: 2"
[INFO] [1663241783.963231469] [minimal_publisher]: Publishing: "Hello World: 3"
[INFO] [1663241784.464505740] [minimal_publisher]: Publishing: "Hello World: 4"
[INFO] [1663241784.964727795] [minimal_publisher]: Publishing: "Hello World: 5"
[INFO] [1663241785.464552693] [minimal_publisher]: Publishing: "Hello World: 6"
[INFO] [1663241785.963467024] [minimal_publisher]: Publishing: "Hello World: 7"
[INFO] [1663241786.464590671] [minimal_publisher]: Publishing: "Hello World: 8"
[INFO] [1663241786.965043845] [minimal_publisher]: Publishing: "Hello World: 9"
[INFO] [1663241786.966554516] [minimal_publisher]: Publishing: "Done"
edit flag offensive delete link more

Comments

Hmmm, it looks like it works for you, but it does not work for me -- mine still hangs at that line. A difference is that I am using ROS foxy on Windows. Also, it does seem a little risky to destroy a node from within the node, but I don't really know.

Morris gravatar image Morris  ( 2022-09-15 12:43:11 -0500 )edit

I am also using ROS Foxy but in Ubuntu 20.04 LTS. I am sorry, but I can not confirm the Windows version. Is it possible for you to test it in Ubuntu? Just for this testing, maybe you can use a VM or a container based on your preference! Good luck.

ravijoshi gravatar image ravijoshi  ( 2022-09-16 11:24:06 -0500 )edit

The self.destroy_node() does not work for me in Ubuntu -- it still hangs. But I did think of a solution which is to raise SystemExit, and then to catch this with a try statement around the spin. I'll post this as an answer

Morris gravatar image Morris  ( 2022-09-17 11:13:12 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2022-09-15 04:53:52 -0500

Seen: 4,651 times

Last updated: Sep 18 '22