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

ROS2 Flask Threading issue

asked 2020-02-27 12:57:17 -0500

AndrewJSchoen gravatar image

updated 2020-03-05 19:30:18 -0500

Hi all,

I am trying to set up a ROS2 rclpy node that functions as a Flask socket server. This node needs to have a thread or timer-based process running (which handles a socket broadcast). The issue I am running into is that when I create a ROS2 timer, it seems that it never executes, and when I use a python thread, it seems to block the main process. The minimal code samples are below:

ROS2 Timer:

class MyNode(Node):

    def __init__(self):
        super(MyNode,self).__init__('my_node')
        self.get_logger().info('Initializing My Node!') # Works fine
        self.app = Flask(__name__) # Flask Stuff
        self.my_ns = NS(self)     # Custom Flask Socket Namespace
        self.socketio = SocketIO(self.app, cors_allowed_origins="*") # Create Socket
        self.socketio.on_namespace(self.my_ns) # Pair the namespace
        self.process_timer = self.create_timer(.1,self.process)
        self.get_logger().info('Initialized!') # Executes

    def process(self):
        self.get_logger().info('Running!') # Never Executes

def main(args=None):
    rclpy.init(args=args)
    node = MyNode()
    node.socketio.run(node.app)

if __name__ == '__main__':
    main()

Python Thread:

class MyNode(Node):

    def __init__(self):
        super(MyNode,self).__init__('my_node')
        self.get_logger().info('Initializing My Node!') # Works fine
        self.app = Flask(__name__) # Flask Stuff
        self.my_ns = NS(self)     # Custom Flask Socket Namespace
        self.socketio = SocketIO(self.app, cors_allowed_origins="*") # Create Socket
        self.socketio.on_namespace(self.my_ns) # Pair the namespace
        self.process_thread = Thread(target=self.process,daemon=True)
        self.process_thread.start()
        self.get_logger().info('Initialized!') # Never Executes

    def process(self):
        alive = True
        while alive:
           try:
              self.assert_liveliness()
              self.get_logger().info('Running!') # Executes
            except:
              alive = False


def main(args=None):
    rclpy.init(args=args)
    node = MyNode()
    node.socketio.run(node.app)

if __name__ == '__main__':
    main()

Thanks for the suggestions, and I will try out those changes. I should share the original code I had, which is the following:

class WizardNode(Node):

    def __init__(self):
        super(WizardNode,self).__init__('wizard')
        self.get_logger().info('Initializing Wizard Node!')
        self.app = Flask(__name__)
        self.cors = CORS(self.app)
        self.wizard = Wizard(self)
        self.socketio = SocketIO(self.app, cors_allowed_origins="*")
        self.socketio.on_namespace(self.wizard)
        self.socket_thread = Thread(target=lambda:self.socketio.run(self.app),daemon=True)
        self.socket_thread.start()
        self.process_timer = self.create_timer(.1,self.process)
        self.get_logger().info('Initialized!')
        self.printer = PrettyPrinter()

    def process(self):
        time = self.get_clock().now()
        self.wizard.timestep()



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

    node = WizardNode()
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass

    node.destroy_node()
    rclpy.shutdown() 

In this version, it seems that the socket.io thread fails to do any sort of broadcasting/emitting, which was why I tried restructuring in the ways above. I should also say that in this example, using eventlet's monkey_patch() basically broke everything.

edit retag flag offensive close merge delete

Comments

1

Due to my very limited experience with python+ROS2 I'm not sure if this will help you, or if this will just be a stupid comment. I also have no clue what Flask threading is.

Anyways, simply creating a ROS2 node and adding a timer, does not make that timer do anything. In C++ you need to spin() the node for anything to happen. Spinning is basically adding the node to an executor which, when the timer triggers, will execute the callback function. I'm not sure how this is setup in python, but could it be that you are missing this?

This is solely based on my c++ experience and the fact that I don't see a spin() anywhere :P so be gentle.

MCornelis gravatar image MCornelis  ( 2020-03-04 04:27:55 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
1

answered 2020-03-05 19:44:35 -0500

AndrewJSchoen gravatar image

This turned out to be a bit of a fun puzzle to get ROS2 and Eventlet working together. In the end, the solution makes a lot of sense, but it just isn't super intuitive. Basically, the solution is first to import eventlet and run monkey_patch() before any other imports.


import eventlet
eventlet.monkey_patch()
from flask import Flask, request, jsonify, make_response
from flask_socketio import SocketIO, emit, Namespace
...

The issue is that when monkey-patching, it basically turns all the threads into blocking threads, which need to be explicitly slept so that other threads can process (i.e. the rest of the code). So the trick is to combine rclpy's spin_once() with the eventlet.greenthread.sleep()

class MyNode(Node):

    def __init__(self):
        super(MyNode,self).__init__('my_node')
        self.get_logger().info('Initializing My Node!') # Works fine
        self.app = Flask(__name__) # Flask Stuff
        self.my_ns = NS(self)     # Custom Flask Socket Namespace
        self.socketio = SocketIO(self.app, cors_allowed_origins="*") # Create Socket
        self.socketio.on_namespace(self.my_ns) # Pair the namespace
        self.process_timer = self.create_timer(.1,self.process)
        self.ros_thread = Thread(target=self.process,daemon=True)
        self.ros_thread.start()
        self.get_logger().info('Initialized!')

    def process(self):
        alive = True
        while alive:
            try:
                # Check that the ROS node is still alive
                self.assert_liveliness()
                # Spin the ROS node once...
                rclpy.spin_once(self,timeout_sec=0.0)
                # ...and then momentarily sleep so the other process (socket.io) can run.
                eventlet.greenthread.sleep()
            except:
                alive = False

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

    node = MyNode()

    # SocketIO's run has eventlet sleeps incorporated when eventlet is imported
    node.socketio.run(node.app)

    node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()
edit flag offensive delete link more

Comments

How do you assert the liveliness of the ROS node?

aniemi gravatar image aniemi  ( 2021-01-03 08:33:18 -0500 )edit

assert_liveliness is a method that Node objects have. Since MyNode inherits from it, I use it there.

AndrewJSchoen gravatar image AndrewJSchoen  ( 2021-01-03 19:17:42 -0500 )edit

Thanks, looks like it's not in foxy yet.

aniemi gravatar image aniemi  ( 2021-01-04 05:38:01 -0500 )edit
0

answered 2023-05-11 16:38:02 -0500

I followed your suggestions here and they worked, thanks for this tip! One thing I'm noticing though is that I'm unable to subscribe to ROS topics when using the setup above. After digging a bit, I discovered that this was because of the timer that you have which also runs the process method (which inside has an infinite loop to process the two threads).

It turns out this timer is actually not necessary. I removed this but left the Thread in to run the process as a daemon and just added a variable to cancel the thread when disposing of it. This allowed me to still process incoming topics while not affecting the SocketIO perfomance!

edit flag offensive delete link more
0

answered 2020-03-04 04:46:35 -0500

tfoote gravatar image

updated 2020-03-05 19:37:05 -0500

As mentioned by @MCornelis you need to spin the ROS node. Your invocation of node.socketio.run(node.app) does not run any of the ROS threads. ROS nodes are not flask Nodes.

I recommend you go through the basic python tutorials here: https://index.ros.org/doc/ros2/Tutori...

Update:

With your original one which uses the rclpy.spin(node) there's nothing processing the Flask app's threads. You need to provide threads for both of them. So that both the Flask app and the rclpy node have threads to do their work. You can't do just one or the other.

edit flag offensive delete link more

Comments

The flask app was being executed as a thread within the MyNode __init__ function. The actual issue was that there was an inconsistency between rclpy.spin() and the expectations around threading that flask-socketio has.

AndrewJSchoen gravatar image AndrewJSchoen  ( 2020-03-05 19:47:28 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-02-27 12:57:17 -0500

Seen: 1,890 times

Last updated: Mar 05 '20