From 66b259e33d8f0f390a64eca5ed2e4de09756ff6b Mon Sep 17 00:00:00 2001 From: Henrik Larsen Date: Wed, 25 Sep 2019 22:08:24 +0200 Subject: [PATCH] Issue #15: rxros::spin() funtion uses unnecessary many threads --- README.md | 7 ++++++- rxros/include/rxros/rxros.h | 4 ++-- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 44ceb7c..953abd7 100644 --- a/README.md +++ b/README.md @@ -163,13 +163,18 @@ The other purpose of the rxros::spin function is to dispatch messages from ROS t Failure to omit the rxros::spin function will cause the program to terminate immediately and observables based on ROS topics will not emit any events. +rxros::spin will per default use one thread for dispatching messages. For most nodes this will be sufficient. +In special cases where a node uses many topics it may be necessary to use more threads for dispatching messages. +This can be achieved by specifying the number of threads the rxros::spin function should use. +A special case is rxros::spin(0) which will allocate a thread for each CPU core. + The Example below shows a minimal RxROS program that creates a ROS node named “my_node”. The program will due to rxros:spin() continue to run until it is either shutdown or terminated. ### Syntax ```cpp -void rxros::spin(); +void rxros::spin(uint32_t thread_count = 1); ``` ### Example diff --git a/rxros/include/rxros/rxros.h b/rxros/include/rxros/rxros.h index 55433ff..9bc0b5a 100644 --- a/rxros/include/rxros/rxros.h +++ b/rxros/include/rxros/rxros.h @@ -48,8 +48,8 @@ namespace rxros ros::init(argc, argv, name); } - static void spin() { - ros::MultiThreadedSpinner spinner(0); // Use a spinner for each available CPU core + static void spin(uint32_t thread_count = 1) { // Use per default 1 thread for spinning + ros::MultiThreadedSpinner spinner(thread_count); spinner.spin(); }