Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Foxy: backport mutex_two_priorities #1516 #1636

Merged
merged 3 commits into from
May 11, 2021

Conversation

hsgwa
Copy link
Contributor

@hsgwa hsgwa commented Apr 16, 2021

This is a backport of #1516

This change is somewhat aggressive, but this change will greatly improve MultiThreadedExecutor performance.
I added static variables, so it should be ABI compatible.
I would appreciate any comments.

related issues: #1618, ros-controls/ros2_control#275

Signed-off-by: hsgwa hasegawa@isp.co.jp

Signed-off-by: hsgwa <hasegawa@isp.co.jp>
Copy link
Collaborator

@fujitatomoya fujitatomoya left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

thanks for opening discussion here and contribution. actually MutexTwoPriorities has been update via #1628 by @ivanpauno . so if we possibly do backport to foxy, probably rebase on #1628 would be better.

hsgwa added 2 commits April 16, 2021 17:19
Signed-off-by: hsgwa <hasegawa@isp.co.jp>
Signed-off-by: hsgwa <hasegawa@isp.co.jp>
@hsgwa
Copy link
Contributor Author

hsgwa commented Apr 16, 2021

Thanks for the information!
I've reflected update #1628.

@clalancette clalancette changed the title backport mutex_two_priorities #1516 Foxy: backport mutex_two_priorities #1516 Apr 16, 2021
@ivanpauno
Copy link
Member

did you test locally if this solve #1487 and #1008?
I'm afraid that the extra global mutex can affect the behavior.

@hsgwa
Copy link
Contributor Author

hsgwa commented Apr 19, 2021

I see. I didn't test it enough.
I'll check the behavior of the two issues.

@hsgwa
Copy link
Contributor Author

hsgwa commented Apr 19, 2021

Sure, there is a risk because the variables are not encapsulated.
I'd like to focus on performance though, is there any better implementation?

Or, how about changing them from member variables to static global variables in multi_threaded_executor.cpp?

// multi_threaded_executor.cpp
static std::unordered_map<MultiThreadedExecutor *, std::shared_ptr<MutexTwoPriorities>> wait_mutex_set_;
static std::mutex MultiThreadedExecutor::shared_wait_mutex_;

At any rate, the test results look fine.


I compared single-threaded and multi-threaded executor, ref: #1487 (comment).
source code : https://github.com/hsgwa/executor_comparison.git

Comparison: Multi-threaded Executor

publish rate

origin/foxy foxy_backport_mutex_two_priorities
average rate: 317.183
min: 0.000s max: 0.033s std dev: 0.00297s window: 954
average rate: 999.976
min: 0.000s max: 0.004s std dev: 0.00008s window: 10000
average rate: 311.748
min: 0.000s max: 0.049s std dev: 0.00329s window: 1250
average rate: 999.977
min: 0.000s max: 0.004s std dev: 0.00009s window: 10000

%CPU

The following is a comparison of the %cpu columns of pidstat.

origin/foxy foxy_backport_mutex_two_priorities
105.00 0
105.00 6
106.00 2
72.00 0
70.00 6
63.00 3

Comparison: Single-threaded Executor

origin/foxy foxy_backport_mutex_two_priorities
average rate: 999.883
min: 0.001s max: 0.002s std dev: 0.00007s window: 3002
average rate: 999.959
min: 0.000s max: 0.004s std dev: 0.00010s window: 10000
average rate: 999.959
min: 0.000s max: 0.002s std dev: 0.00008s window: 4003
average rate: 999.968
min: 0.000s max: 0.004s std dev: 0.00010s window: 10000

%CPU

origin/foxy foxy_backport_mutex_two_priorities
35.00 0
36.00 2
34.00 6
41.00 3
39.00 4
35.00 4

Comparison: timer_over_take test

I compared the diff to be evaluated, ref : #1008.

diff --git a/rclcpp/test/rclcpp/executors/test_multi_threaded_executor.cpp b/rclcpp/test/rclcpp/executors/test_multi_threaded_executor.cpp
index b6fd2c3f..ca27da2c 100644
--- a/rclcpp/test/rclcpp/executors/test_multi_threaded_executor.cpp
+++ b/rclcpp/test/rclcpp/executors/test_multi_threaded_executor.cpp
@@ -17,6 +17,7 @@
#include <chrono>
#include <string>
#include <memory>
+#include <iostream>

#include "rclcpp/exceptions.hpp"
#include "rclcpp/node.hpp"
@@ -90,6 +91,7 @@ TEST_F(TestMultiThreadedExecutor, timer_over_take) {
          executor.cancel();
          ASSERT_GT(diff, PERIOD - TOLERANCE);
        }
+       std::cout << diff << std::endl;
      }
    };
origin/foxy foxy_backport_mutex_two_priorities
1.00047 1.00045
1.00218 0.99986
0.99765 0.99999
1.00128 1.00001
0.99871 0.999998
1.00112 0.999999

@ivanpauno
Copy link
Member

I compared the diff to be evaluated, ref : #1008.

Instead of that, could you repeat the test to see if it's flaky or not?

stress --cpu 8 &  # use number of cores instead of 8
for i in {1..100}; do ./test_multi_threaded_executor; if [ $? -ne 0 ]; then break;fi;clear; done

Thanks!

@hsgwa
Copy link
Contributor Author

hsgwa commented Apr 20, 2021

I tried to test it in a loop 100 times, but it failed in the middle.

$ stress --cpu 8 &  # use number of cores
$ for i in {1..100}; do ./test_multi_threaded_executor; if [ $? -ne 0 ]; then break;fi;clear; done

To check the effect before and after the modification, I executed the following commands 10 times each and counted the number of consecutive successful tests.

$ stress --cpu 8 &  # use number of cores
$ for i in {1..100}; do ./test_multi_threaded_executor; if [ $? -ne 0 ]; then break;fi; done | grep "PASSED" --line-buffered | wc -l

Both failed in the middle of the test, so there seems to be no obvious difference.

origin/foxy foxy_backport_mutex_two_priorities
4 11
3 2
21 61
16 6
5 6
15 11
4 5
21 9
1 2
33 5

@hsgwa hsgwa marked this pull request as ready for review April 26, 2021 04:00
@hsgwa
Copy link
Contributor Author

hsgwa commented May 11, 2021

@jacobperron friendly ping. could you give me a review if you don't mind?

@fujitatomoya
Copy link
Collaborator

CI:

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

Copy link
Member

@jacobperron jacobperron left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The changes look alright to me:

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

@jacobperron jacobperron merged commit d12ed36 into ros2:foxy May 11, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants