Skip to content

Commit

Permalink
Issue #15: rxros::spin() funtion uses unnecessary many threads
Browse files Browse the repository at this point in the history
  • Loading branch information
henrik7264 authored and gavanderhoorn committed Sep 25, 2019
1 parent 024a92b commit 8202ed8
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 3 deletions.
7 changes: 6 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -159,13 +159,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
Expand Down
4 changes: 2 additions & 2 deletions rxros/include/rxros/rxros.h
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

Expand Down

0 comments on commit 8202ed8

Please sign in to comment.