rclpy
rclpy copied to clipboard
Timer hanging and high CPU load when using MultiThreadedExecutor
Bug report
Required Info:
-
Operating System: Ubuntu 22.04
-
Installation type: Binaries
-
Version or commit hash: Iron
-
DDS implementation: eProsima’s Fast DDS (the default)
-
Client library (if applicable): rclpy
-
CPU info (if needed):
Architecture: x86_64
CPU op-mode(s): 32-bit, 64-bit
Address sizes: 39 bits physical, 48 bits virtual
Byte Order: Little Endian
CPU(s): 12
On-line CPU(s) list: 0-11
Vendor ID: GenuineIntel
Model name: 13th Gen Intel(R) Core(TM) i7-1355U
CPU family: 6
Model: 186
Thread(s) per core: 2
Core(s) per socket: 10
Socket(s): 1
Stepping: 3
CPU max MHz: 5000.0000
CPU min MHz: 400.0000
BogoMIPS: 5222.40
Flags: fpu vme de pse tsc msr pae mce cx8 apic sep mtrr pge mca cmov pat pse36 clflus
h dts acpi mmx fxsr sse sse2 ss ht tm pbe syscall nx pdpe1gb rdtscp lm constan
t_tsc art arch_perfmon pebs bts rep_good nopl xtopology nonstop_tsc cpuid aper
fmperf tsc_known_freq pni pclmulqdq dtes64 monitor ds_cpl vmx smx est tm2 ssse
3 sdbg fma cx16 xtpr pdcm sse4_1 sse4_2 x2apic movbe popcnt tsc_deadline_timer
aes xsave avx f16c rdrand lahf_lm abm 3dnowprefetch cpuid_fault epb ssbd ibrs
ibpb stibp ibrs_enhanced tpr_shadow vnmi flexpriority ept vpid ept_ad fsgsbas
e tsc_adjust bmi1 avx2 smep bmi2 erms invpcid rdseed adx smap clflushopt clwb
intel_pt sha_ni xsaveopt xsavec xgetbv1 xsaves avx_vnni dtherm ida arat pln pt
s hwp hwp_notify hwp_act_window hwp_epp hwp_pkg_req hfi umip pku ospke waitpkg
gfni vaes vpclmulqdq rdpid movdiri movdir64b fsrm md_clear serialize arch_lbr
ibt flush_l1d arch_capabilities
Virtualization features:
Virtualization: VT-x
Caches (sum of all):
L1d: 352 KiB (10 instances)
L1i: 576 KiB (10 instances)
L2: 6.5 MiB (4 instances)
L3: 12 MiB (1 instance)
NUMA:
NUMA node(s): 1
NUMA node0 CPU(s): 0-11
Vulnerabilities:
Gather data sampling: Not affected
Itlb multihit: Not affected
L1tf: Not affected
Mds: Not affected
Meltdown: Not affected
Mmio stale data: Not affected
Retbleed: Not affected
Spec rstack overflow: Not affected
Spec store bypass: Mitigation; Speculative Store Bypass disabled via prctl
Spectre v1: Mitigation; usercopy/swapgs barriers and __user pointer sanitization
Spectre v2: Mitigation; Enhanced IBRS, IBPB conditional, RSB filling, PBRSB-eIBRS SW seque
nce
Srbds: Not affected
Tsx async abort: Not affected
Steps to reproduce issue
My publisher:
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
import time
class MyPublisher(Node):
def __init__(self):
super().__init__('my_publisher')
self.publisher_ = self.create_publisher(String, 'my_topic', 10 )
timer_period = 1 / 500
self.timer = self.create_timer(timer_period, self.timer_callback)
def timer_callback(self):
msg = String()
msg.data = 'Hello, ROS2! '
self.publisher_.publish(msg)
my subscriber:
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class MySubscriber(Node):
def __init__(self):
super().__init__('my_subscriber')
self.subscription = self.create_subscription(
String,
'my_topic',
self.listener_callback,
10)
self.subscription # prevent unused variable warning
def listener_callback(self, msg):
pass
And my main function:
import rclpy
from my_multithreaded_package.publisher import MyPublisher
from my_multithreaded_package.subscriber import MySubscriber
import time
def main(args=None):
rclpy.init(args=args)
publisher = MyPublisher()
subscriber = MySubscriber()
executor = rclpy.executors.MultiThreadedExecutor(4)
executor.add_node(publisher)
executor.add_node(subscriber)
executor.spin()
# Shutdown the ROS client library
rclpy.shutdown()
if __name__ == '__main__':
main()
Expected behavior (which is what I get when using the SingleThreadedExecutor)
ros2 topic hz /my_topic
average rate: 499.945
min: 0.002s max: 0.002s std dev: 0.00007s window: 501
average rate: 499.965
min: 0.001s max: 0.002s std dev: 0.00008s window: 1001
average rate: 499.995
min: 0.001s max: 0.003s std dev: 0.00009s window: 1502
average rate: 499.981
min: 0.001s max: 0.003s std dev: 0.00009s window: 2002
average rate: 499.978
min: 0.001s max: 0.003s std dev: 0.00009s window: 2502
average rate: 500.004
min: 0.001s max: 0.003s std dev: 0.00009s window: 3003
average rate: 499.989
min: 0.001s max: 0.003s std dev: 0.00010s window: 3503
Actual behavior
ros2 topic hz /my_topic
average rate: 25.933
min: 0.002s max: 0.919s std dev: 0.16741s window: 29
average rate: 14.580
min: 0.000s max: 0.937s std dev: 0.21933s window: 41
average rate: 13.928
min: 0.000s max: 0.937s std dev: 0.21447s window: 62
average rate: 12.983
min: 0.000s max: 0.937s std dev: 0.22058s window: 81
average rate: 10.575
min: 0.000s max: 0.937s std dev: 0.24748s window: 85
average rate: 9.774
min: 0.000s max: 0.937s std dev: 0.25675s window: 89
average rate: 9.845
min: 0.000s max: 0.937s std dev: 0.25056s window: 102
average rate: 9.399
Additional information
So similar issues have been brought up with rclcpp, but I have not seen any comments made about rclpy. I found an issue here:https://github.com/ros2/rclcpp/issues/1487, with other people also reporting something like: https://github.com/ros2/rclcpp/issues/1618 and the fix is https://github.com/ros2/rclcpp/pull/1516 and then https://github.com/ros2/rclcpp/pull/1692.
Aside from the timer callback hanging (I assume it to be with after following some tic toc), my CPU load becomes really high using the MultiThreadedExecutor, while the SingleThreadedExecutor does not cause any noticeable CPU load. I have also tried using both the MutuallyExclusiveCallbackGroup and ReentrantCallbackGroup with no change in behaviour.
I am not sure if my QOS settings are the problem, or this is an issue intrinsic to python (because of GIL or etc.) but either a more suitable example for how to use the MultiThreadedExecutor could be provided (if my usage is wrong), or the ROS wiki pages should reflect that this significant problem exists (if no fix is possible).
Thank you for helping!
I have the same issue, +1 for this
From our weekly issue triage meeting:
Assigning @clalancette so he can make a high level tracking issue about known issues with Python's executors.
Also, we think this issue will not make progress without staffing of an engineer, which we don't currently have, or a dedicated community member to investigate and make a good suggestion on what to change and why. This is because executor related issues tend to be very nuanced and complicated to work on. So we're also assigning this the "help wanted" label with that in mind.
Hi @JasperTan97 I recommend you could run py-spy to see where the high CPU load comes from. This helps immensely. Thanks
@KKSTB, it looks like the waiting for ready callbacks are the issue. Do you get the same on your end?
@JasperTan97 i ran py-spy on my ubuntu ROS iron machine and got this result:
And py-spy dump to see what threads they are in the flame graph:
Thread 11386 (idle): "MainThread"
handle (rclpy/guard_condition.py:38)
_wait_for_ready_callbacks (rclpy/executors.py:582)
wait_for_ready_callbacks (rclpy/executors.py:723)
_spin_once_impl (rclpy/executors.py:794)
spin_once (rclpy/executors.py:813)
spin (rclpy/executors.py:295)
main (xavest_gui/main.py:44)
<module> (xavest_gui:33)
Thread 11398 (idle): "ThreadPoolExecutor-0_0"
_worker (concurrent/futures/thread.py:81)
run (threading.py:953)
_bootstrap_inner (threading.py:1016)
_bootstrap (threading.py:973)
Thread 11399 (idle): "ThreadPoolExecutor-0_1"
_worker (concurrent/futures/thread.py:81)
run (threading.py:953)
_bootstrap_inner (threading.py:1016)
_bootstrap (threading.py:973)
Thread 11400 (idle): "ThreadPoolExecutor-0_2"
_worker (concurrent/futures/thread.py:81)
run (threading.py:953)
_bootstrap_inner (threading.py:1016)
_bootstrap (threading.py:973)
Thread 11401 (idle): "ThreadPoolExecutor-0_3"
_worker (concurrent/futures/thread.py:81)
run (threading.py:953)
_bootstrap_inner (threading.py:1016)
_bootstrap (threading.py:973)
This shows the 4 worker threads were mostly idle, which makes sense because there is basically nothing to do inside subscriber and timer node.
The main thread was instead very very busy retrieving tasks for the 4 worker threads to do. It seems such workload of retrieving and distributing tasks and gathering results at high frequency (500Hz) is marginal for one core. Therefore the rate slows down considerably. Although I have no clue why your single core is much slower (I can achieve 3XX-4XX Hz on my i7-9750H).
As for single threaded executor, I can achieve 500Hz. The CPU utilization was half of multi threaded case. I have to push to 2500Hz before the rate starts to drop.
I believe the problem has to do with the efficiency of transferring tasks from main thread to worker threads, relative to the actual useful tasks done in the worker thread.
I experience the same issue, +1
SVG: https://gist.githubusercontent.com/MatthijsBurgh/a5ee1d710e0ff4b6524b279a2688e8be/raw/15da19a2ca8ca0d1e28bfeb46e9726205357a855/profile.svg
But it doesn't show the files and line numbers correct. Therefore I have included another screenshot, which does show this. You should check the linenumbers in this revision of executors.py
update: I have looked at the code a bit, _wait_for_ready_callbacks just looks very inefficient. It constructs many objects and lists. The lists are appended and then iterate over again, etc. The rclcpp::Executor, looks more efficient.
(It is complex code, so if you feel I am wrong, let me know.)
update: I have looked at the code a bit,
_wait_for_ready_callbacksjust looks very inefficient. It constructs many objects and lists. The lists are appended and then iterate over again, etc. Therclcpp::Executor, looks more efficient. (It is complex code, so if you feel I am wrong, let me know.)
Yep, you are correct. And this flame graph is the kind of thing I was waiting to see to confirm. So thanks for spending the time to do that.
We spent a bunch of time over the last year optimizing the rclcpp executor to make things faster; the rclpy one needs a similar effort to become more performant.
@clalancette just let me know whether you need a more detailed graph, etc.
@clalancette just let me know whether you need a more detailed graph, etc.
To be totally transparent; we don't (currently) have plans to work on this. While that could change in the future, if it is something you are interested in, I'd suggest trying to make some improvements and opening PRs. We are more than happy to review them.
@clalancette I don't have all the knowledge to fix this. But I do think this does require to be fixed. As it is baked into many ROS applications, i.e. rqt. But it works much worse than the SingleThreadedExecutor.
I want to help, though I am not able to figure out the design of it. It is very complex. So it would be helpful of someone could explain with enough detail what should be happening. Then me and other people could check the code.
@MatthijsBurgh can you tell what frequency you can achieve? I can achieve 2xx-3xx hz on i7 9750H (9th gen Intel). But @JasperTan97 only managed 2x hz on i7 1355U (13th gen Intel). I think the problem lies on why there's such a big difference.
SingleThreadedExecutor: 500Hz MultiThreadedExecutor(4): 60Hz MultiThreadedExecutor(20): 50Hz MultiThreadedExecutor(): ~5Hz i7-13700H
It is really weird newer hardware is much slower. But still, the MultiThreadedExecutor, should only be slower with very few threads, compared to the SingleThreadedExecutor.
Correction: the results above are with a ReentrantCallbackGroup, with the default MutuallyExclusiveCallbackGroup, the results are more in the range of 5-10Hz for all MultiThreadedExecutor versions.
I have no idea. Maybe try these:
- I suspect its network problem causing a lot of traffic errors. Try to disconnect all networks, or use cyclone DDS and set domain 0 to local only
- Test on a fresh unmodified Ubuntu machine (no realtime kernel) and see if there is any improvement
Commands to use CycloneDDS:
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
export CYCLONEDDS_URI=file:///home/user/ros2_ws/ddsconfig.xml
and ddsconfig.xml:
<?xml version="1.0" encoding="UTF-8" ?>
<CycloneDDS xmlns="https://cdds.io/config" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:schemaLocation="https://cdds.io/config https://raw.githubusercontent.com/eclipse-cyclonedds/cyclonedds/master/etc/cyclonedds.xsd">
<Domain id="0">
<General>
<Interfaces>
<NetworkInterface name="lo"/>
</Interfaces>
</General>
</Domain>
</CycloneDDS>
@KKSTB Using cyclone did fix the issue for me. All MultiThreaded configurations now are able to reach 500Hz.
Now I am still wondering how a bad network/RMW results in the distributing of task to the worker threads being very slow.
My plain guess of reasons:
- Nodes in SingleThreadedExecutor doesn't need to communicate across threads, so there is no network traffic (I am not sure if this is true at all)
- When running in MultiThreadedExecutor, network traffic is generated to communicate across threads (I am not sure as well). If there is network traffic collision then a lot of errors are generated, causing high CPU load. Traffic can collide when there is other application using the same port (https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Domain-ID.html) or there is an incompatible ROS2 node
I have no clue, I can only observe there is a big difference in distribution of the calls.
I have run py-spy with for cyclone and fastrtps. Both with the ReentrantCallbackGroup and the MutuallyExclusiveCallbackGroup, these have the _mutually suffix. Both in a flamegraph SVG but also in speedscope JSON format. Which you need in import on https://www.speedscope.app.
The SVG is not a result of the same execution as the speedscope. I have run all combination such that have around 30.000 samples with a sampling rate of 500Hz, around 60s of runtime)
The results can be found at https://gist.github.com/MatthijsBurgh/cd7871c6597c4cdc196526b658693a18
You should check the linenumbers in this revision of executors.py
@MatthijsBurgh thank you for your analysis. In fact py-spy has an -n option to also sample non-python libraries to get a better look of where takes the most CPU time, similar to the record in https://github.com/ros2/rclpy/issues/1223#issuecomment-2071293729 where rcl_wait and rmw_wait can be seen in the graph. But this option is very slow so the py-spy sampling frequency should be lowered too.
But I think even if you rerun py-spy with this option, it is difficult to look into a C++ problem from py-spy. Probably you can try setting ROS2 log level to debug, i.e. --ros-args --log-level debug, and see what happen. Thanks.
I seem to have a related issue with heavy CPU usage (100%), even when running the sender and receiver in separate processes. In one program, I run a sender that sends strings at a frequency of 10 Hz. In another program, I run a receiver with a MultiThreadedExecutor, which manages a single node.
Initially, I used the MultiThreadedExecutor to spin a single node due to this issue #1133 . However, it appears that the issue #1133 can be avoided by using the SingleThreadedExecutor, which does not cause any performance problems.
@astroseger are you using fastDDS? Would you also try MultiThreadedExecutor with cycloneDDS to see if there is any difference in CPU load? Thanks.
@astroseger are you using fastDDS? Would you also try
MultiThreadedExecutorwith cycloneDDS to see if there is any difference in CPU load? Thanks.
yes. I was using fastrtps (default in ros:jazzy docker). With cycloneDDS I don't have this issue with 100% CPU usage. (I'm referring to the test where I run a sender in a separate process, which sends short strings at a frequency of 10Hz. Meanwhile, I run a receiver in another separate process using MultiThreadedExecutor)
Thanks @astroseger. It seems im able to repeat the CPU high load issue when using fastrtps and separating pub and sub nodes. The sub node has unusually high CPU load. I ran the sub node with --ros-args --log-level debug and got something.
I slowed down the publisher to 1Hz so that the sequence of event can be observed by looking into the timestamp. Also the publisher uses now() timestamp as message content, and subscriber prints the message data so that we can see when the message was published.
Pub:
def timer_callback(self):
msg = std_msgs.msg.String()
time = self.get_clock().now().seconds_nanoseconds()
msg.data = str(time[0]) + '.' + str(time[1])
self.publisher_.publish(msg)
Sub:
def listener_callback(self, msg):
print(msg.data)
Outputs:
FastRTPS multithreaded executor (high CPU load, independent of reliability=reliable / best effort. Num of threads=8):
[DEBUG] [1720419307.456039413] [rcl]: Subscription initialized
[DEBUG] [1720419307.456385128] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419307.456500007] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419308.216722516] [rcl]: Subscription taking message
[DEBUG] [1720419308.216891084] [rcl]: Subscription take succeeded: true
1720419308.215229352
[DEBUG] [1720419308.217743078] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419308.218348298] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419309.217076734] [rcl]: Subscription taking message
[DEBUG] [1720419309.217191860] [rcl]: Subscription take succeeded: true
1720419309.215027607
[DEBUG] [1720419309.218031215] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419309.218595065] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419310.216581528] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419310.217599368] [rcl]: Subscription taking message
[DEBUG] [1720419310.217688306] [rcl]: Subscription take succeeded: true
1720419310.215106041
[DEBUG] [1720419310.218795308] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419310.219327064] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419311.216573971] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419311.217312700] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419311.218147080] [rcl]: Subscription taking message
[DEBUG] [1720419311.218265382] [rcl]: Subscription take succeeded: true
1720419311.215157151
[DEBUG] [1720419311.219372353] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419311.219994004] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419312.214832796] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419312.214954438] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419312.215047577] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419312.215422567] [rcl]: Subscription taking message
[DEBUG] [1720419312.215449510] [rcl]: Subscription take succeeded: true
1720419312.214357740
[DEBUG] [1720419312.215764333] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419312.215921266] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419313.216190809] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419313.216777692] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419313.217275396] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419313.217757792] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419313.218596591] [rcl]: Subscription taking message
[DEBUG] [1720419313.218685762] [rcl]: Subscription take succeeded: true
1720419313.215061179
[DEBUG] [1720419313.219735879] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419313.220260012] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419314.216843316] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419314.217506763] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419314.218109647] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419314.218742170] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419314.219262946] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419314.220197831] [rcl]: Subscription taking message
[DEBUG] [1720419314.220315977] [rcl]: Subscription take succeeded: true
1720419314.215243738
[DEBUG] [1720419314.221423094] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419314.221963801] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419315.216077113] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419315.216993016] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419315.217428412] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419315.217907239] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419315.218393012] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419315.218975870] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419315.219885230] [rcl]: Subscription taking message
[DEBUG] [1720419315.220003436] [rcl]: Subscription take succeeded: true
1720419315.215066373
[DEBUG] [1720419315.221143383] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419315.221747855] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.216631033] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.217307188] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.217900951] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.218477930] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.219117457] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.219768313] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.220330902] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.220935570] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.221498036] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.222102645] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.222800891] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.223413460] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.224010130] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.224582273] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.225170406] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.225777625] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.226313713] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
...
...
(very very long)
...
...
[DEBUG] [1720419316.578384199] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419316.586700047] [rcl]: Subscription taking message
[DEBUG] [1720419316.586748901] [rcl]: Subscription take succeeded: true
1720419316.215120517
For comparison, cycloneDDS multithreaded executor (normal):
[DEBUG] [1720419795.586524559] [rcl]: Subscription initialized
[DEBUG] [1720419795.586911455] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419795.587051947] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419796.552197907] [rcl]: Subscription taking message
[DEBUG] [1720419796.552352889] [rcl]: Subscription take succeeded: true
1720419796.550687816
[DEBUG] [1720419796.553262024] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419796.554021910] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419797.551318431] [rcl]: Subscription taking message
[DEBUG] [1720419797.551379686] [rcl]: Subscription take succeeded: true
1720419797.550229892
[DEBUG] [1720419797.551887717] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419797.552317435] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419798.551026559] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419798.551243434] [rcl]: Subscription taking message
[DEBUG] [1720419798.551284631] [rcl]: Subscription take succeeded: true
1720419798.550366270
[DEBUG] [1720419798.551849814] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419798.552175370] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419799.550720924] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419799.550943817] [rcl]: Subscription taking message
[DEBUG] [1720419799.550999790] [rcl]: Subscription take succeeded: true
1720419799.550141247
[DEBUG] [1720419799.551424436] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419799.551719668] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419800.550757603] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419800.550963706] [rcl]: Subscription taking message
[DEBUG] [1720419800.550995726] [rcl]: Subscription take succeeded: true
1720419800.550184304
[DEBUG] [1720419800.551419239] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419800.551642617] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419801.550608012] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419801.550783952] [rcl]: Subscription taking message
[DEBUG] [1720419801.550830806] [rcl]: Subscription take succeeded: true
1720419801.550085074
[DEBUG] [1720419801.551154643] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419801.551338018] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419802.550932361] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419802.551112091] [rcl]: Subscription taking message
[DEBUG] [1720419802.551144235] [rcl]: Subscription take succeeded: true
1720419802.550271058
[DEBUG] [1720419802.551563636] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419802.551787868] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419803.550830800] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419803.551021123] [rcl]: Subscription taking message
[DEBUG] [1720419803.551057507] [rcl]: Subscription take succeeded: true
1720419803.550209441
[DEBUG] [1720419803.551508357] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419803.551733740] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419804.551854565] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419804.552261925] [rcl]: Subscription taking message
[DEBUG] [1720419804.552339514] [rcl]: Subscription take succeeded: true
1720419804.550696273
[DEBUG] [1720419804.553054886] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '0' services
[DEBUG] [1720419804.553928400] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419805.551931645] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419805.552318730] [rcl]: Subscription taking message
[DEBUG] [1720419805.552391474] [rcl]: Subscription take succeeded: true
1720419805.550731706
[DEBUG] [1720419805.553343097] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419805.553899872] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419806.552023374] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419806.552407456] [rcl]: Subscription taking message
[DEBUG] [1720419806.552479857] [rcl]: Subscription take succeeded: true
1720419806.550885718
FastRTPS / cycloneDDS singlethreaded executor (normal):
[DEBUG] [1720419539.676874043] [rcl]: Subscription initialized
[DEBUG] [1720419539.677244644] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419539.677357378] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419540.215877199] [rcl]: Subscription taking message
[DEBUG] [1720419540.216215196] [rcl]: Subscription take succeeded: true
1720419540.215141946
[DEBUG] [1720419540.217010623] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419540.217564077] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419541.215823588] [rcl]: Subscription taking message
[DEBUG] [1720419541.215949519] [rcl]: Subscription take succeeded: true
1720419541.215093073
[DEBUG] [1720419541.216563692] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419541.217047255] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419542.215809048] [rcl]: Subscription taking message
[DEBUG] [1720419542.215924772] [rcl]: Subscription take succeeded: true
1720419542.215069380
[DEBUG] [1720419542.216496466] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419542.216955887] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '7' services
[DEBUG] [1720419543.214816080] [rcl]: Subscription taking message
[DEBUG] [1720419543.214870414] [rcl]: Subscription take succeeded: true
1720419543.214444717
Observations:
- Wait set with 0 subscription happens when running in multithreaded condition
- There is no wait set with 0 subscription when running in single thread
- The wait on the wait set for fastrtps was initially ok for the first few times. But after some time it fails.
- The number of normal wait for fastrtps depends on number of threads. If number of thread is 4, the first 4 waits are normal.
- The problem is independent of reliability setting
- As can be observed by timestamps, the wait set with 0 subscription happens after the message is generated by the publisher
ROS2 version: Iron
Identical issue: https://github.com/ros2/rmw_fastrtps/issues/705
Possibly similar issue: https://github.com/ros2/rmw_fastrtps/issues/749