Skip to content

Commit 9b44106

Browse files
ivanpaunoKarsten1987
authored andcommitted
Allow timers to keep up the intended rate in MultiThreadedExecutor (#1516)
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
1 parent e69a5b6 commit 9b44106

File tree

5 files changed

+160
-4
lines changed

5 files changed

+160
-4
lines changed

rclcpp/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ set(${PROJECT_NAME}_SRCS
3939
src/rclcpp/clock.cpp
4040
src/rclcpp/context.cpp
4141
src/rclcpp/contexts/default_context.cpp
42+
src/rclcpp/detail/mutex_two_priorities.cpp
4243
src/rclcpp/detail/rmw_implementation_specific_payload.cpp
4344
src/rclcpp/detail/rmw_implementation_specific_publisher_payload.cpp
4445
src/rclcpp/detail/rmw_implementation_specific_subscription_payload.cpp
Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,75 @@
1+
// Copyright 2021 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef RCLCPP__DETAIL__MUTEX_TWO_PRIORITIES_HPP_
16+
#define RCLCPP__DETAIL__MUTEX_TWO_PRIORITIES_HPP_
17+
18+
#include <mutex>
19+
20+
namespace rclcpp
21+
{
22+
namespace detail
23+
{
24+
/// \internal A mutex that has two locking mechanism, one with higher priority than the other.
25+
/**
26+
* After the current mutex owner release the lock, a thread that used the high
27+
* priority mechanism will have priority over threads that used the low priority mechanism.
28+
*/
29+
class MutexTwoPriorities
30+
{
31+
public:
32+
class HighPriorityLockable
33+
{
34+
public:
35+
explicit HighPriorityLockable(MutexTwoPriorities & parent);
36+
37+
void lock();
38+
39+
void unlock();
40+
41+
private:
42+
MutexTwoPriorities & parent_;
43+
};
44+
45+
class LowPriorityLockable
46+
{
47+
public:
48+
explicit LowPriorityLockable(MutexTwoPriorities & parent);
49+
50+
void lock();
51+
52+
void unlock();
53+
54+
private:
55+
MutexTwoPriorities & parent_;
56+
};
57+
58+
HighPriorityLockable
59+
get_high_priority_lockable();
60+
61+
LowPriorityLockable
62+
get_low_priority_lockable();
63+
64+
private:
65+
// Implementation detail: the idea here is that only one low priority thread can be
66+
// trying to take the data_ mutex while the others are excluded by the barrier_ mutex.
67+
// All high priority threads are already waiting for the data_ mutex.
68+
std::mutex barrier_;
69+
std::mutex data_;
70+
};
71+
72+
} // namespace detail
73+
} // namespace rclcpp
74+
75+
#endif // RCLCPP__DETAIL__MUTEX_TWO_PRIORITIES_HPP_

rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <thread>
2323
#include <unordered_map>
2424

25+
#include "rclcpp/detail/mutex_two_priorities.hpp"
2526
#include "rclcpp/executor.hpp"
2627
#include "rclcpp/macros.hpp"
2728
#include "rclcpp/memory_strategies.hpp"
@@ -81,7 +82,7 @@ class MultiThreadedExecutor : public rclcpp::Executor
8182
private:
8283
RCLCPP_DISABLE_COPY(MultiThreadedExecutor)
8384

84-
std::mutex wait_mutex_;
85+
detail::MutexTwoPriorities wait_mutex_;
8586
size_t number_of_threads_;
8687
bool yield_before_execute_;
8788
std::chrono::nanoseconds next_exec_timeout_;
Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,75 @@
1+
// Copyright 2021 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "rclcpp/detail/mutex_two_priorities.hpp"
16+
17+
#include <mutex>
18+
19+
namespace rclcpp
20+
{
21+
namespace detail
22+
{
23+
24+
using LowPriorityLockable = MutexTwoPriorities::LowPriorityLockable;
25+
using HighPriorityLockable = MutexTwoPriorities::HighPriorityLockable;
26+
27+
HighPriorityLockable::HighPriorityLockable(MutexTwoPriorities & parent)
28+
: parent_(parent)
29+
{}
30+
31+
void
32+
HighPriorityLockable::lock()
33+
{
34+
parent_.data_.lock();
35+
}
36+
37+
void
38+
HighPriorityLockable::unlock()
39+
{
40+
parent_.data_.unlock();
41+
}
42+
43+
LowPriorityLockable::LowPriorityLockable(MutexTwoPriorities & parent)
44+
: parent_(parent)
45+
{}
46+
47+
void
48+
LowPriorityLockable::lock()
49+
{
50+
std::unique_lock<std::mutex> barrier_guard{parent_.barrier_};
51+
parent_.data_.lock();
52+
barrier_guard.release();
53+
}
54+
55+
void
56+
LowPriorityLockable::unlock()
57+
{
58+
std::lock_guard<std::mutex> barrier_guard{parent_.barrier_, std::adopt_lock};
59+
parent_.data_.unlock();
60+
}
61+
62+
HighPriorityLockable
63+
MutexTwoPriorities::get_high_priority_lockable()
64+
{
65+
return HighPriorityLockable{*this};
66+
}
67+
68+
LowPriorityLockable
69+
MutexTwoPriorities::get_low_priority_lockable()
70+
{
71+
return LowPriorityLockable{*this};
72+
}
73+
74+
} // namespace detail
75+
} // namespace rclcpp

rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include "rclcpp/utilities.hpp"
2323
#include "rclcpp/scope_exit.hpp"
2424

25+
using rclcpp::detail::MutexTwoPriorities;
2526
using rclcpp::executors::MultiThreadedExecutor;
2627

2728
MultiThreadedExecutor::MultiThreadedExecutor(
@@ -51,7 +52,8 @@ MultiThreadedExecutor::spin()
5152
std::vector<std::thread> threads;
5253
size_t thread_id = 0;
5354
{
54-
std::lock_guard<std::mutex> wait_lock(wait_mutex_);
55+
auto low_priority_wait_mutex = wait_mutex_.get_low_priority_lockable();
56+
std::lock_guard<MutexTwoPriorities::LowPriorityLockable> wait_lock(low_priority_wait_mutex);
5557
for (; thread_id < number_of_threads_ - 1; ++thread_id) {
5658
auto func = std::bind(&MultiThreadedExecutor::run, this, thread_id);
5759
threads.emplace_back(func);
@@ -76,7 +78,8 @@ MultiThreadedExecutor::run(size_t)
7678
while (rclcpp::ok(this->context_) && spinning.load()) {
7779
rclcpp::AnyExecutable any_exec;
7880
{
79-
std::lock_guard<std::mutex> wait_lock(wait_mutex_);
81+
auto low_priority_wait_mutex = wait_mutex_.get_low_priority_lockable();
82+
std::lock_guard<MutexTwoPriorities::LowPriorityLockable> wait_lock(low_priority_wait_mutex);
8083
if (!rclcpp::ok(this->context_) || !spinning.load()) {
8184
return;
8285
}
@@ -103,7 +106,8 @@ MultiThreadedExecutor::run(size_t)
103106
execute_any_executable(any_exec);
104107

105108
if (any_exec.timer) {
106-
std::lock_guard<std::mutex> wait_lock(wait_mutex_);
109+
auto high_priority_wait_mutex = wait_mutex_.get_high_priority_lockable();
110+
std::lock_guard<MutexTwoPriorities::HighPriorityLockable> wait_lock(high_priority_wait_mutex);
107111
auto it = scheduled_timers_.find(any_exec.timer);
108112
if (it != scheduled_timers_.end()) {
109113
scheduled_timers_.erase(it);

0 commit comments

Comments
 (0)