MultiThreadedExecutor thread affinity for certain callbacks?
I'd like have certain callbacks have thread affinity and others get whatever they are handed from the pool. There is some related affinity discussion here from a few years ago: https://github.com/ros2/rclcpp/issues...
In my current case it is a timer update that needs to run on the same thread id, while service and topic callbacks ought to run concurrently on any thread available (subject to lock guards where needed within them).
I'd like to do something expedient in the short term but also make progress towards a better and longer term solution (if in discussion only).
Some ideas come to mind:
Very quick and very dirty solution: Have the timer callback check the thread id and the time since it last complete update, return immediately if on wrong thread, otherwise do a regular update. Set the callback rate to the number of threads times an extra margin factor times the original desired update rate. The callback could sleep until the next proper update time, and this would allow that large update rate to be smaller, combined with the MutuallyExclusive callback group type later scheduled same callbacks that can't be run just get dropped instead of wasting resources getting scheduled over and over on the wrong threads?
One callback that is only run once and then has a while loop with a sleep doesn't sound too bad. Is there a ros2
rate
? Does that mess with the Executor code to never return, at the least it'll never assign anything else to that one thread even if it is sleeping most of the time.Nest a single threaded node within a multi-threaded node (or the other way around), the outer node has a timer update which calls spin_once or spins_some on the inner node, and with proper mutexes sharing can be done between the two. I'll likely try this first because the first option is so ugly.
Inside the callback, somehow spawn a new job ('future'?) to only be run on a specific thread. Would it have to interact with the Executor machinery, or could it be done with pure std::thread calls? Haven't looked into this much.
Figure out how to run current code with constantly changing thread id- the current issue is with OpenGL in combination with SDL- SDL_GL_CreateContext. Maybe the context can be updated to the new thread id, maybe there is a large cost involved in doing that. It wouldn't be hard to switch to glfw if that can to it more easily. Off topic for this website.
Create a hacked new executor type based off of https://github.com/ros2/rclcpp/blob/m... , just make so all timer callbacks use just one thread id, don't worry about multi timers initially. Digging into this better paves the way to a more proper solution even if the first thing that works is ugly. But it may not work very easily, likelihood of breaking it and having ...
It's looking like std::async and rclcpp::WallRate with the number 2 option will work for me.
Not an answer, but perhaps can be a(nother) source of inspiration/information: Mixed Real-Time Criticality with ROS2 - the Callback-group-level Executor (slides).