From c2e1c108d9d1c0e926b685d1b1277cc0bfd60786 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 13 Nov 2024 23:26:03 +0100 Subject: [PATCH 01/25] add first version of the mutex with priority inheritance --- include/realtime_tools/mutex.hpp | 148 +++++++++++++++++++++++++++++++ 1 file changed, 148 insertions(+) create mode 100644 include/realtime_tools/mutex.hpp diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp new file mode 100644 index 00000000..35f93d9c --- /dev/null +++ b/include/realtime_tools/mutex.hpp @@ -0,0 +1,148 @@ +// Copyright 2024 PAL Robotics S.L. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \author Sai Kishor Kothakota + +#ifndef REALTIME_TOOLS__MUTEX_HPP_ +#define REALTIME_TOOLS__MUTEX_HPP_ + +#include +#include +#include +#include +#include +#include + +namespace realtime_tools +{ +class mutex +{ +public: + mutex() + { + pthread_mutexattr_t attr; + + // Initialize the mutex attributes + const auto res_attr = pthread_mutexattr_init(&attr); + if (res_attr != 0) { + throw std::runtime_error( + std::string("Failed to initialize mutex attribute : ") + std::strerror(res_attr)); + } + + // Set the mutex type to PTHREAD_MUTEX_ERRORCHECK + const auto res_type = pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_ERRORCHECK); + if (res_type != 0) { + throw std::runtime_error( + std::string("Failed to set mutex type : ") + std::strerror(res_type)); + } + + // Set the mutex attribute to use the protocol PTHREAD_PRIO_INHERIT + const auto res_protocol = pthread_mutexattr_setprotocol(&attr, PTHREAD_PRIO_INHERIT); + if (res_protocol != 0) { + throw std::runtime_error( + std::string("Failed to set mutex protocol : ") + std::strerror(res_protocol)); + } + + // Set the mutex attribute to have a priority ceiling of 99 + const auto res_ceiling = pthread_mutexattr_setprioceiling(&attr, 99); + if (res_ceiling != 0) { + throw std::runtime_error( + std::string("Failed to set mutex prio ceiling : ") + std::strerror(res_ceiling)); + } + + // Set the mutex attribute robustness to PTHREAD_MUTEX_ROBUST + const auto res_robust = pthread_mutexattr_setrobust(&attr, PTHREAD_MUTEX_ROBUST); + if (res_robust != 0) { + throw std::runtime_error( + std::string("Failed to set mutex robustness : ") + std::strerror(res_robust)); + } + + // Initialize the mutex with the attributes + const auto res_init = pthread_mutex_init(&mutex_, &attr); + if (res_init != 0) { + throw std::runtime_error( + std::string("Failed to initialize mutex : ") + std::strerror(res_init)); + } + + // Destroy the mutex attributes + const auto res_destroy = pthread_mutexattr_destroy(&attr); + if (res_destroy != 0) { + throw std::runtime_error( + std::string("Failed to destroy mutex attribute : ") + std::strerror(res_destroy)); + } + } + + ~mutex() + { + const auto res = pthread_mutex_destroy(&mutex_); + if (res != 0) { + std::cerr << "Failed to destroy mutex : " << std::strerror(res) << std::endl; + } + } + + const pthread_mutex_t * get_mutex() const { return &mutex_; } + + pthread_mutex_t * get_mutex() { return &mutex_; } + + void lock() + { + const auto res = pthread_mutex_lock(&mutex_); + if (res != 0) { + if (res == EOWNERDEAD) { + const auto res_consistent = pthread_mutex_consistent(&mutex_); + if (res_consistent != 0) { + throw std::runtime_error( + std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); + } + } else { + throw std::runtime_error(std::string("Failed to lock mutex : ") + std::strerror(res)); + } + } + } + + void unlock() + { + // As per the requirements of BasicLockable concept, unlock should not throw + const auto res = pthread_mutex_unlock(&mutex_); + if (res != 0) { + std::cerr << "Failed to unlock mutex : " << std::strerror(res) << std::endl; + } + } + + bool try_lock() + { + const auto res = pthread_mutex_trylock(&mutex_); + if (res != 0) { + if (res == EBUSY) { + return false; + } else if (res == EOWNERDEAD) { + const auto res_consistent = pthread_mutex_consistent(&mutex_); + if (res_consistent != 0) { + throw std::runtime_error( + std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); + } + } else { + throw std::runtime_error(std::string("Failed to try lock mutex : ") + std::strerror(res)); + } + } + return true; + } + +private: + pthread_mutex_t mutex_; +}; + +} // namespace realtime_tools + +#endif // REALTIME_TOOLS__MUTEX_HPP_ From 05ce6bc45468caef6f0181cd169c6de16c6e5a6a Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 14 Nov 2024 09:15:34 +0100 Subject: [PATCH 02/25] added documentation and remove the copy constructor and assignment operator --- include/realtime_tools/mutex.hpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 35f93d9c..d8b5cfb2 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -24,6 +24,13 @@ #include #include +/** + * @brief A pthread mutex wrapper that provides a mutex with the priority inheritance + * protocol and a priority ceiling of 99. + * The mutex is also error checked and robust. + * This mutex is intended to be used in real-time contexts. + * @note This mutex is not recursive. + */ namespace realtime_tools { class mutex @@ -91,6 +98,10 @@ class mutex } } + mutex(const mutex &) = delete; + + mutex & operator=(const mutex &) = delete; + const pthread_mutex_t * get_mutex() const { return &mutex_; } pthread_mutex_t * get_mutex() { return &mutex_; } From 1921f216d6190050b2189c0db2680b653247c189 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 19 Nov 2024 19:04:26 +0100 Subject: [PATCH 03/25] change the name of the mutex to priority_inheritance_mutex --- include/realtime_tools/mutex.hpp | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index d8b5cfb2..d4044825 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -33,10 +33,12 @@ */ namespace realtime_tools { -class mutex +class priority_inheritance_mutex { public: - mutex() + using native_handle_type = pthread_mutex_t *; + + priority_inheritance_mutex() { pthread_mutexattr_t attr; @@ -90,7 +92,7 @@ class mutex } } - ~mutex() + ~priority_inheritance_mutex() { const auto res = pthread_mutex_destroy(&mutex_); if (res != 0) { @@ -98,13 +100,13 @@ class mutex } } - mutex(const mutex &) = delete; + priority_inheritance_mutex(const priority_inheritance_mutex &) = delete; - mutex & operator=(const mutex &) = delete; + priority_inheritance_mutex & operator=(const priority_inheritance_mutex &) = delete; - const pthread_mutex_t * get_mutex() const { return &mutex_; } + native_handle_type native_handle() { return &mutex_; } - pthread_mutex_t * get_mutex() { return &mutex_; } + const native_handle_type native_handle() const { return &mutex_; } void lock() { From 1a18c6ea34f826f33b07047e7abd2da1b8d8e192 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 19 Nov 2024 22:36:46 +0100 Subject: [PATCH 04/25] Remove pthread_mutexattr_setprioceiling as the protocol is set to PTHREAD_PRIO_INHERIT --- include/realtime_tools/mutex.hpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index d4044825..6b7fadbb 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -63,13 +63,6 @@ class priority_inheritance_mutex std::string("Failed to set mutex protocol : ") + std::strerror(res_protocol)); } - // Set the mutex attribute to have a priority ceiling of 99 - const auto res_ceiling = pthread_mutexattr_setprioceiling(&attr, 99); - if (res_ceiling != 0) { - throw std::runtime_error( - std::string("Failed to set mutex prio ceiling : ") + std::strerror(res_ceiling)); - } - // Set the mutex attribute robustness to PTHREAD_MUTEX_ROBUST const auto res_robust = pthread_mutexattr_setrobust(&attr, PTHREAD_MUTEX_ROBUST); if (res_robust != 0) { From 040a904ad2425576cf8fc6a37064a69d496f592b Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 19 Nov 2024 23:56:38 +0100 Subject: [PATCH 05/25] templatize the class and create different instance with using --- include/realtime_tools/mutex.hpp | 30 ++++++++++++++++++------------ 1 file changed, 18 insertions(+), 12 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 6b7fadbb..fec43774 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -33,12 +33,15 @@ */ namespace realtime_tools { -class priority_inheritance_mutex +namespace priority_inheritance +{ +template +class MutexBase { public: using native_handle_type = pthread_mutex_t *; - priority_inheritance_mutex() + MutexBase() { pthread_mutexattr_t attr; @@ -49,8 +52,9 @@ class priority_inheritance_mutex std::string("Failed to initialize mutex attribute : ") + std::strerror(res_attr)); } - // Set the mutex type to PTHREAD_MUTEX_ERRORCHECK - const auto res_type = pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_ERRORCHECK); + // Set the mutex type to MutexType + const auto res_type = pthread_mutexattr_settype(&attr, MutexType); + if (res_type != 0) { throw std::runtime_error( std::string("Failed to set mutex type : ") + std::strerror(res_type)); @@ -85,7 +89,7 @@ class priority_inheritance_mutex } } - ~priority_inheritance_mutex() + ~MutexBase() { const auto res = pthread_mutex_destroy(&mutex_); if (res != 0) { @@ -93,15 +97,13 @@ class priority_inheritance_mutex } } - priority_inheritance_mutex(const priority_inheritance_mutex &) = delete; + MutexBase(const MutexBase &) = delete; - priority_inheritance_mutex & operator=(const priority_inheritance_mutex &) = delete; + MutexBase & operator=(const MutexBase &) = delete; native_handle_type native_handle() { return &mutex_; } - const native_handle_type native_handle() const { return &mutex_; } - - void lock() + virtual void lock() { const auto res = pthread_mutex_lock(&mutex_); if (res != 0) { @@ -117,7 +119,7 @@ class priority_inheritance_mutex } } - void unlock() + virtual void unlock() { // As per the requirements of BasicLockable concept, unlock should not throw const auto res = pthread_mutex_unlock(&mutex_); @@ -126,7 +128,7 @@ class priority_inheritance_mutex } } - bool try_lock() + virtual bool try_lock() { const auto res = pthread_mutex_trylock(&mutex_); if (res != 0) { @@ -149,6 +151,10 @@ class priority_inheritance_mutex pthread_mutex_t mutex_; }; +using mutex = MutexBase; +using error_mutex = MutexBase; +using recursive_mutex = MutexBase; +} // namespace priority_inheritance } // namespace realtime_tools #endif // REALTIME_TOOLS__MUTEX_HPP_ From 742177edebca55fecda265b20ab4c1818c529571 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 20 Nov 2024 00:03:11 +0100 Subject: [PATCH 06/25] Add cerr to mention that the owner is died so user is aware of it --- include/realtime_tools/mutex.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index fec43774..805c7370 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -113,6 +113,8 @@ class MutexBase throw std::runtime_error( std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); } + std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" + << std::endl; } else { throw std::runtime_error(std::string("Failed to lock mutex : ") + std::strerror(res)); } @@ -140,6 +142,8 @@ class MutexBase throw std::runtime_error( std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); } + std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" + << std::endl; } else { throw std::runtime_error(std::string("Failed to try lock mutex : ") + std::strerror(res)); } From f392b21bc2085ebac0c845ed7b9309583b675469 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 20 Nov 2024 00:03:51 +0100 Subject: [PATCH 07/25] Add tests to the priority inheritance mutex --- CMakeLists.txt | 3 + test/realtime_mutex_tests.cpp | 298 ++++++++++++++++++++++++++++++++++ 2 files changed, 301 insertions(+) create mode 100644 test/realtime_mutex_tests.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index d1ea6f27..05a1fba1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -86,6 +86,9 @@ if(BUILD_TESTING) ament_add_gmock(test_async_function_handler test/test_async_function_handler.cpp) target_link_libraries(test_async_function_handler realtime_tools thread_priority) ament_target_dependencies(test_async_function_handler lifecycle_msgs rclcpp_lifecycle) + + ament_add_gmock(realtime_mutex_tests test/realtime_mutex_tests.cpp) + target_link_libraries(realtime_mutex_tests realtime_tools) endif() # Install diff --git a/test/realtime_mutex_tests.cpp b/test/realtime_mutex_tests.cpp new file mode 100644 index 00000000..a160921a --- /dev/null +++ b/test/realtime_mutex_tests.cpp @@ -0,0 +1,298 @@ +// Copyright 2024 PAL Robotics S.L. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \author Sai Kishor Kothakota + +#include + +#include +#include + +#include + +TEST(PriorityInheritanceMutexTests, lock_unlock) +{ + // The mutex is locked and unlocked correctly + realtime_tools::priority_inheritance::mutex mutex; + { + mutex.lock(); + mutex.unlock(); + } +} + +TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded) +{ + // The mutex is locked and unlocked correctly in a multithreaded environment + realtime_tools::priority_inheritance::mutex mutex; + std::thread t1([&mutex]() { + mutex.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex.unlock(); + }); + std::thread t2([&mutex]() { + mutex.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex.unlock(); + }); + t1.join(); + t2.join(); +} + +TEST(PriorityInheritanceMutexTests, recursive_lock_lock_unlock_multithreaded) +{ + // The mutex is locked and unlocked correctly in a multithreaded environment + realtime_tools::priority_inheritance::recursive_mutex mutex; + std::thread t1([&mutex]() { + mutex.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex.unlock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex.unlock(); + }); + std::thread t2([&mutex]() { + mutex.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex.unlock(); + }); + t1.join(); + t2.join(); +} + +TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_multiple_mutexes) +{ + // The mutex is locked and unlocked correctly in a multithreaded environment with multiple mutexes + realtime_tools::priority_inheritance::mutex mutex1; + realtime_tools::priority_inheritance::mutex mutex2; + std::thread t1([&mutex1, &mutex2]() { + mutex1.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex1.unlock(); + mutex2.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex2.unlock(); + }); + std::thread t2([&mutex1, &mutex2]() { + mutex1.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex1.unlock(); + mutex2.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex2.unlock(); + }); + t1.join(); + t2.join(); +} + +TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_multiple_mutexes_different_types) +{ + // The mutex is locked and unlocked correctly in a multithreaded environment with multiple mutexes + realtime_tools::priority_inheritance::mutex mutex1; + realtime_tools::priority_inheritance::recursive_mutex mutex2; + std::thread t1([&mutex1, &mutex2]() { + mutex1.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex1.unlock(); + mutex2.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex2.unlock(); + }); + std::thread t2([&mutex1, &mutex2]() { + mutex1.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex1.unlock(); + mutex2.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex2.unlock(); + }); + t1.join(); + t2.join(); +} + +TEST(PriorityInheritanceMutexTests, lock_unlock_recursive_mutex) +{ + // Test to check that the mutex is recursive + realtime_tools::priority_inheritance::recursive_mutex mutex; + mutex.lock(); + mutex.lock(); + mutex.unlock(); + mutex.unlock(); +} + +TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_recursive_mutex_multiple_mutexes) +{ + realtime_tools::priority_inheritance::recursive_mutex mutex1; + realtime_tools::priority_inheritance::recursive_mutex mutex2; + std::thread t1([&mutex1, &mutex2]() { + mutex1.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex1.unlock(); + mutex2.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex2.unlock(); + }); + std::thread t2([&mutex1, &mutex2]() { + mutex1.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex1.unlock(); + mutex2.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + mutex2.unlock(); + }); + t1.join(); + t2.join(); +} + +TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_mutex_one_thread_dies) +{ + realtime_tools::priority_inheritance::mutex mutex; + std::thread t1([&mutex]() { + mutex.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + // simulating no unlock. Due to the robustness of the mutex, the mutex should be consistent + }); + std::thread t2([&mutex]() { + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + mutex.lock(); + mutex.unlock(); + }); + t1.join(); + t2.join(); + mutex.lock(); + mutex.unlock(); +} + +TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_recursive_mutex_one_thread_dies) +{ + realtime_tools::priority_inheritance::recursive_mutex mutex; + std::thread t1([&mutex]() { + mutex.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + // simulating no unlock. Due to the robustness of the mutex, the mutex should be consistent + }); + std::thread t2([&mutex]() { + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + mutex.lock(); + mutex.unlock(); + }); + t1.join(); + t2.join(); + mutex.lock(); + mutex.unlock(); +} + +TEST(PriorityInheritanceMutexTests, lock_guard_mutex) +{ + realtime_tools::priority_inheritance::mutex mutex; + { + std::lock_guard lock(mutex); + } + + realtime_tools::priority_inheritance::recursive_mutex recursive_mutex; + { + std::lock_guard lock(recursive_mutex); + } +} + +TEST(PriorityInheritanceMutexTests, unique_lock_mutex) +{ + realtime_tools::priority_inheritance::mutex mutex; + { + std::unique_lock lock(mutex); + } + + realtime_tools::priority_inheritance::recursive_mutex recursive_mutex; + { + std::unique_lock lock(recursive_mutex); + } +} + +TEST(PriorityInheritanceMutexTests, try_lock_mutex) +{ + { + realtime_tools::priority_inheritance::mutex mutex; + ASSERT_TRUE(mutex.try_lock()); + ASSERT_FALSE(mutex.try_lock()); + ASSERT_FALSE(mutex.try_lock()); + mutex.unlock(); + ASSERT_TRUE(mutex.try_lock()); + ASSERT_FALSE(mutex.try_lock()); + mutex.unlock(); + } + + { + realtime_tools::priority_inheritance::recursive_mutex recursive_mutex; + ASSERT_TRUE(recursive_mutex.try_lock()); + ASSERT_TRUE(recursive_mutex.try_lock()); + ASSERT_TRUE(recursive_mutex.try_lock()); + recursive_mutex.unlock(); + recursive_mutex.unlock(); + recursive_mutex.unlock(); + } +} + +TEST(PriorityInheritanceMutexTests, standard_lock_test) +{ + realtime_tools::priority_inheritance::mutex mutex1; + realtime_tools::priority_inheritance::mutex mutex2; + { + std::lock(mutex1, mutex2); + // do work + mutex1.unlock(); + mutex2.unlock(); + } + { + std::scoped_lock lock(mutex1, mutex2); + } + ASSERT_TRUE(mutex1.try_lock()); + ASSERT_TRUE(mutex2.try_lock()); + mutex1.unlock(); + mutex2.unlock(); +} + +TEST(PriorityInheritanceMutexTests, native_handle_mutex) +{ + { + realtime_tools::priority_inheritance::mutex mutex; + auto native_handle = mutex.native_handle(); + ASSERT_NE(native_handle, nullptr); + } + + { + realtime_tools::priority_inheritance::recursive_mutex recursive_mutex; + auto native_handle = recursive_mutex.native_handle(); + ASSERT_NE(native_handle, nullptr); + } +} + +TEST(PriorityInheritanceMutexTests, test_error_mutex) +{ + // Trying to lock again should throw an exception + realtime_tools::priority_inheritance::error_mutex mutex; + mutex.lock(); + ASSERT_THROW(mutex.lock(), std::runtime_error); + mutex.unlock(); + ASSERT_NO_THROW(mutex.lock()); + ASSERT_THROW(mutex.try_lock(), std::runtime_error); + mutex.unlock(); + ASSERT_NO_THROW(mutex.try_lock()); + mutex.unlock(); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} From bad11ed3a58abb55f338ed70c32e54cec54069d8 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 20 Nov 2024 18:06:06 +0100 Subject: [PATCH 08/25] add documentation and more template arguments --- include/realtime_tools/mutex.hpp | 35 ++++++++++++++++++++++++-------- 1 file changed, 27 insertions(+), 8 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 805c7370..ed338405 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -35,7 +35,15 @@ namespace realtime_tools { namespace priority_inheritance { -template +/** + * @brief A class template that provides a pthread mutex with the priority inheritance protocol + * + * @tparam MutexType The type of the mutex. It can be one of the following: PTHREAD_MUTEX_NORMAL, PTHREAD_MUTEX_RECURSIVE, PTHREAD_MUTEX_ERRORCHECK, PTHREAD_MUTEX_DEFAULT + * @tparam MutexProtocol The protocol of the mutex. It can be one of the following: PTHREAD_PRIO_NONE, PTHREAD_PRIO_INHERIT, PTHREAD_PRIO_PROTECT + * @tparam MutexCeiling The priority ceiling of the mutex. It can be any integer value valid for the scheduling policy of the thread. It is only used if MutexProtocol is PTHREAD_PRIO_PROTECT + * @tparam MutexRobustness The robustness of the mutex. It can be one of the following: PTHREAD_MUTEX_STALLED, PTHREAD_MUTEX_ROBUST + */ +template class MutexBase { public: @@ -60,15 +68,24 @@ class MutexBase std::string("Failed to set mutex type : ") + std::strerror(res_type)); } - // Set the mutex attribute to use the protocol PTHREAD_PRIO_INHERIT - const auto res_protocol = pthread_mutexattr_setprotocol(&attr, PTHREAD_PRIO_INHERIT); + // Set the mutex attribute to use the protocol MutexProtocol + const auto res_protocol = pthread_mutexattr_setprotocol(&attr, MutexProtocol); if (res_protocol != 0) { throw std::runtime_error( std::string("Failed to set mutex protocol : ") + std::strerror(res_protocol)); } - // Set the mutex attribute robustness to PTHREAD_MUTEX_ROBUST - const auto res_robust = pthread_mutexattr_setrobust(&attr, PTHREAD_MUTEX_ROBUST); + if (MutexProtocol == PTHREAD_PRIO_PROTECT) { + // Set the mutex attribute to use the priority ceiling + const auto res_ceiling = pthread_mutexattr_setprioceiling(&attr, MutexCeiling); + if (res_ceiling != 0) { + throw std::runtime_error( + std::string("Failed to set mutex priority ceiling : ") + std::strerror(res_ceiling)); + } + } + + // Set the mutex attribute robustness to MutexRobustness + const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness); if (res_robust != 0) { throw std::runtime_error( std::string("Failed to set mutex robustness : ") + std::strerror(res_robust)); @@ -155,9 +172,11 @@ class MutexBase pthread_mutex_t mutex_; }; -using mutex = MutexBase; -using error_mutex = MutexBase; -using recursive_mutex = MutexBase; +using mutex = MutexBase; +using error_mutex = + MutexBase; +using recursive_mutex = + MutexBase; } // namespace priority_inheritance } // namespace realtime_tools From 9f33a30e3a90120eb9cb929cfd64b7032e69718f Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 21 Nov 2024 00:31:59 +0100 Subject: [PATCH 09/25] Address MR comments --- include/realtime_tools/mutex.hpp | 51 +++++++++++++++++--------------- test/realtime_mutex_tests.cpp | 6 ++-- 2 files changed, 29 insertions(+), 28 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index ed338405..a552a4b2 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -123,18 +123,19 @@ class MutexBase virtual void lock() { const auto res = pthread_mutex_lock(&mutex_); - if (res != 0) { - if (res == EOWNERDEAD) { - const auto res_consistent = pthread_mutex_consistent(&mutex_); - if (res_consistent != 0) { - throw std::runtime_error( - std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); - } - std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" - << std::endl; - } else { - throw std::runtime_error(std::string("Failed to lock mutex : ") + std::strerror(res)); + if (res == 0) { + return; + } + if (res == EOWNERDEAD) { + const auto res_consistent = pthread_mutex_consistent(&mutex_); + if (res_consistent != 0) { + throw std::runtime_error( + std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); } + std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" + << std::endl; + } else { + throw std::runtime_error(std::string("Failed to lock mutex : ") + std::strerror(res)); } } @@ -150,20 +151,22 @@ class MutexBase virtual bool try_lock() { const auto res = pthread_mutex_trylock(&mutex_); - if (res != 0) { - if (res == EBUSY) { - return false; - } else if (res == EOWNERDEAD) { - const auto res_consistent = pthread_mutex_consistent(&mutex_); - if (res_consistent != 0) { - throw std::runtime_error( - std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); - } - std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" - << std::endl; - } else { - throw std::runtime_error(std::string("Failed to try lock mutex : ") + std::strerror(res)); + if (res == 0) { + return true; + } + if (res == EBUSY) { + return false; + } + if (res == EOWNERDEAD) { + const auto res_consistent = pthread_mutex_consistent(&mutex_); + if (res_consistent != 0) { + throw std::runtime_error( + std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); } + std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" + << std::endl; + } else { + throw std::runtime_error(std::string("Failed to try lock mutex : ") + std::strerror(res)); } return true; } diff --git a/test/realtime_mutex_tests.cpp b/test/realtime_mutex_tests.cpp index a160921a..b38773aa 100644 --- a/test/realtime_mutex_tests.cpp +++ b/test/realtime_mutex_tests.cpp @@ -25,10 +25,8 @@ TEST(PriorityInheritanceMutexTests, lock_unlock) { // The mutex is locked and unlocked correctly realtime_tools::priority_inheritance::mutex mutex; - { - mutex.lock(); - mutex.unlock(); - } + mutex.lock(); + mutex.unlock(); } TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded) From 0a8343f3445e5197e67061042eb25ce69e029a0a Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 22 Nov 2024 00:12:45 +0100 Subject: [PATCH 10/25] remove the virtual instances from the methods --- include/realtime_tools/mutex.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index a552a4b2..a409a45e 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -120,7 +120,7 @@ class MutexBase native_handle_type native_handle() { return &mutex_; } - virtual void lock() + void lock() { const auto res = pthread_mutex_lock(&mutex_); if (res == 0) { @@ -139,7 +139,7 @@ class MutexBase } } - virtual void unlock() + void unlock() { // As per the requirements of BasicLockable concept, unlock should not throw const auto res = pthread_mutex_unlock(&mutex_); @@ -148,7 +148,7 @@ class MutexBase } } - virtual bool try_lock() + bool try_lock() { const auto res = pthread_mutex_trylock(&mutex_); if (res == 0) { From bb1f880649a4353790a51fabbf11a001a52e934a Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 22 Nov 2024 00:21:15 +0100 Subject: [PATCH 11/25] Change the exceptions to system_error --- include/realtime_tools/mutex.hpp | 26 ++++++++++++-------------- 1 file changed, 12 insertions(+), 14 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index a409a45e..0fbcf8ad 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -56,53 +56,51 @@ class MutexBase // Initialize the mutex attributes const auto res_attr = pthread_mutexattr_init(&attr); if (res_attr != 0) { - throw std::runtime_error( - std::string("Failed to initialize mutex attribute : ") + std::strerror(res_attr)); + throw std::system_error( + res_attr, std::generic_category(), "Failed to initialize mutex attribute"); } // Set the mutex type to MutexType const auto res_type = pthread_mutexattr_settype(&attr, MutexType); if (res_type != 0) { - throw std::runtime_error( - std::string("Failed to set mutex type : ") + std::strerror(res_type)); + throw std::system_error(res_type, std::generic_category(), "Failed to set mutex type"); } // Set the mutex attribute to use the protocol MutexProtocol const auto res_protocol = pthread_mutexattr_setprotocol(&attr, MutexProtocol); if (res_protocol != 0) { - throw std::runtime_error( - std::string("Failed to set mutex protocol : ") + std::strerror(res_protocol)); + throw std::system_error( + res_protocol, std::generic_category(), "Failed to set mutex protocol"); } if (MutexProtocol == PTHREAD_PRIO_PROTECT) { // Set the mutex attribute to use the priority ceiling const auto res_ceiling = pthread_mutexattr_setprioceiling(&attr, MutexCeiling); if (res_ceiling != 0) { - throw std::runtime_error( - std::string("Failed to set mutex priority ceiling : ") + std::strerror(res_ceiling)); + throw std::system_error( + res_ceiling, std::generic_category(), "Failed to set mutex priority ceiling"); } } // Set the mutex attribute robustness to MutexRobustness const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness); if (res_robust != 0) { - throw std::runtime_error( - std::string("Failed to set mutex robustness : ") + std::strerror(res_robust)); + throw std::system_error( + res_robust, std::generic_category(), "Failed to set mutex robustness"); } // Initialize the mutex with the attributes const auto res_init = pthread_mutex_init(&mutex_, &attr); if (res_init != 0) { - throw std::runtime_error( - std::string("Failed to initialize mutex : ") + std::strerror(res_init)); + throw std::system_error(res_init, std::generic_category(), "Failed to initialize mutex"); } // Destroy the mutex attributes const auto res_destroy = pthread_mutexattr_destroy(&attr); if (res_destroy != 0) { - throw std::runtime_error( - std::string("Failed to destroy mutex attribute : ") + std::strerror(res_destroy)); + throw std::system_error( + res_destroy, std::generic_category(), "Failed to destroy mutex attribute"); } } From 1b371cc94e6466b99e09ce6d8d06cb5e4d37ce9f Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 22 Nov 2024 00:23:11 +0100 Subject: [PATCH 12/25] Change to cerrno --- include/realtime_tools/mutex.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 0fbcf8ad..b0b61f4b 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -17,8 +17,8 @@ #ifndef REALTIME_TOOLS__MUTEX_HPP_ #define REALTIME_TOOLS__MUTEX_HPP_ -#include #include +#include #include #include #include From 1d0f9112e5ecc8e5296ea1190f3e460a0d9b8d8e Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 22 Nov 2024 00:27:47 +0100 Subject: [PATCH 13/25] Add noexcept to some methods --- include/realtime_tools/mutex.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index b0b61f4b..0795a028 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -116,7 +116,7 @@ class MutexBase MutexBase & operator=(const MutexBase &) = delete; - native_handle_type native_handle() { return &mutex_; } + native_handle_type native_handle() noexcept { return &mutex_; } void lock() { @@ -137,7 +137,7 @@ class MutexBase } } - void unlock() + void unlock() noexcept { // As per the requirements of BasicLockable concept, unlock should not throw const auto res = pthread_mutex_unlock(&mutex_); From 8ecf33271a60d9d6b84809f9b9c62d413bdd1f85 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 22 Nov 2024 00:45:55 +0100 Subject: [PATCH 14/25] use attr_cleanup_t to cleanup properly without any memory_leaks --- include/realtime_tools/mutex.hpp | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 0795a028..37405aa0 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include @@ -53,6 +54,17 @@ class MutexBase { pthread_mutexattr_t attr; + const auto attr_destroy = [](pthread_mutexattr_t * mutex_attr) { + // Destroy the mutex attributes + const auto res_destroy = pthread_mutexattr_destroy(mutex_attr); + if (res_destroy != 0) { + throw std::system_error( + res_destroy, std::generic_category(), "Failed to destroy mutex attribute"); + } + }; + using attr_cleanup_t = std::unique_ptr; + auto attr_cleanup = attr_cleanup_t(&attr, attr_destroy); + // Initialize the mutex attributes const auto res_attr = pthread_mutexattr_init(&attr); if (res_attr != 0) { @@ -95,13 +107,6 @@ class MutexBase if (res_init != 0) { throw std::system_error(res_init, std::generic_category(), "Failed to initialize mutex"); } - - // Destroy the mutex attributes - const auto res_destroy = pthread_mutexattr_destroy(&attr); - if (res_destroy != 0) { - throw std::system_error( - res_destroy, std::generic_category(), "Failed to destroy mutex attribute"); - } } ~MutexBase() From bbfb3caad822256a315bfbab961a7b012c0e7ab3 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 22 Nov 2024 00:49:57 +0100 Subject: [PATCH 15/25] Remove the protocol and ceiling template arguments --- include/realtime_tools/mutex.hpp | 25 ++++++------------------- 1 file changed, 6 insertions(+), 19 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 37405aa0..816b82f0 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -40,11 +40,9 @@ namespace priority_inheritance * @brief A class template that provides a pthread mutex with the priority inheritance protocol * * @tparam MutexType The type of the mutex. It can be one of the following: PTHREAD_MUTEX_NORMAL, PTHREAD_MUTEX_RECURSIVE, PTHREAD_MUTEX_ERRORCHECK, PTHREAD_MUTEX_DEFAULT - * @tparam MutexProtocol The protocol of the mutex. It can be one of the following: PTHREAD_PRIO_NONE, PTHREAD_PRIO_INHERIT, PTHREAD_PRIO_PROTECT - * @tparam MutexCeiling The priority ceiling of the mutex. It can be any integer value valid for the scheduling policy of the thread. It is only used if MutexProtocol is PTHREAD_PRIO_PROTECT * @tparam MutexRobustness The robustness of the mutex. It can be one of the following: PTHREAD_MUTEX_STALLED, PTHREAD_MUTEX_ROBUST */ -template +template class MutexBase { public: @@ -79,22 +77,13 @@ class MutexBase throw std::system_error(res_type, std::generic_category(), "Failed to set mutex type"); } - // Set the mutex attribute to use the protocol MutexProtocol - const auto res_protocol = pthread_mutexattr_setprotocol(&attr, MutexProtocol); + // Set the mutex attribute to use the protocol PTHREAD_PRIO_INHERIT + const auto res_protocol = pthread_mutexattr_setprotocol(&attr, PTHREAD_PRIO_INHERIT); if (res_protocol != 0) { throw std::system_error( res_protocol, std::generic_category(), "Failed to set mutex protocol"); } - if (MutexProtocol == PTHREAD_PRIO_PROTECT) { - // Set the mutex attribute to use the priority ceiling - const auto res_ceiling = pthread_mutexattr_setprioceiling(&attr, MutexCeiling); - if (res_ceiling != 0) { - throw std::system_error( - res_ceiling, std::generic_category(), "Failed to set mutex priority ceiling"); - } - } - // Set the mutex attribute robustness to MutexRobustness const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness); if (res_robust != 0) { @@ -178,11 +167,9 @@ class MutexBase pthread_mutex_t mutex_; }; -using mutex = MutexBase; -using error_mutex = - MutexBase; -using recursive_mutex = - MutexBase; +using mutex = MutexBase; +using error_mutex = MutexBase; +using recursive_mutex = MutexBase; } // namespace priority_inheritance } // namespace realtime_tools From 3e610d96d16991e3de7fac6a498369bf4a84c19e Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 22 Nov 2024 00:52:20 +0100 Subject: [PATCH 16/25] Add detail namespace as suggested --- include/realtime_tools/mutex.hpp | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 816b82f0..fdf2bf5b 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -36,6 +36,8 @@ namespace realtime_tools { namespace priority_inheritance { +namespace detail +{ /** * @brief A class template that provides a pthread mutex with the priority inheritance protocol * @@ -43,12 +45,12 @@ namespace priority_inheritance * @tparam MutexRobustness The robustness of the mutex. It can be one of the following: PTHREAD_MUTEX_STALLED, PTHREAD_MUTEX_ROBUST */ template -class MutexBase +class mutex { public: using native_handle_type = pthread_mutex_t *; - MutexBase() + mutex() { pthread_mutexattr_t attr; @@ -98,7 +100,7 @@ class MutexBase } } - ~MutexBase() + ~mutex() { const auto res = pthread_mutex_destroy(&mutex_); if (res != 0) { @@ -106,9 +108,9 @@ class MutexBase } } - MutexBase(const MutexBase &) = delete; + mutex(const mutex &) = delete; - MutexBase & operator=(const MutexBase &) = delete; + mutex & operator=(const mutex &) = delete; native_handle_type native_handle() noexcept { return &mutex_; } @@ -166,10 +168,10 @@ class MutexBase private: pthread_mutex_t mutex_; }; - -using mutex = MutexBase; -using error_mutex = MutexBase; -using recursive_mutex = MutexBase; +} // namespace detail +using mutex = detail::mutex; +using error_mutex = detail::mutex; +using recursive_mutex = detail::mutex; } // namespace priority_inheritance } // namespace realtime_tools From 0fab8140e1ec6db689252bcafe414f16d4f298c3 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Sat, 23 Nov 2024 00:19:17 +0100 Subject: [PATCH 17/25] test with different lock constructors --- test/realtime_mutex_tests.cpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/test/realtime_mutex_tests.cpp b/test/realtime_mutex_tests.cpp index b38773aa..02cc6584 100644 --- a/test/realtime_mutex_tests.cpp +++ b/test/realtime_mutex_tests.cpp @@ -289,6 +289,22 @@ TEST(PriorityInheritanceMutexTests, test_error_mutex) mutex.unlock(); } +TEST(PriorityInheritanceMutexTests, test_lock_constructors) +{ + realtime_tools::priority_inheritance::mutex mutex; + { + std::unique_lock lock(mutex, std::defer_lock); + ASSERT_FALSE(lock.owns_lock()); + lock.lock(); + ASSERT_TRUE(lock.owns_lock()); + lock.unlock(); + } + { + std::unique_lock lock(mutex, std::try_to_lock); + ASSERT_TRUE(lock.owns_lock()); + } +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From cee4ee965afe66547d7da1fd6884320b22b43444 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Sat, 23 Nov 2024 00:27:37 +0100 Subject: [PATCH 18/25] Change to system_categeory Co-authored-by: atzaros <128592691+atzaros@users.noreply.github.com> --- include/realtime_tools/mutex.hpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index fdf2bf5b..2d6abeb0 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -69,34 +69,34 @@ class mutex const auto res_attr = pthread_mutexattr_init(&attr); if (res_attr != 0) { throw std::system_error( - res_attr, std::generic_category(), "Failed to initialize mutex attribute"); + res_attr, std::system_category(), "Failed to initialize mutex attribute"); } // Set the mutex type to MutexType const auto res_type = pthread_mutexattr_settype(&attr, MutexType); if (res_type != 0) { - throw std::system_error(res_type, std::generic_category(), "Failed to set mutex type"); + throw std::system_error(res_type, std::system_category(), "Failed to set mutex type"); } // Set the mutex attribute to use the protocol PTHREAD_PRIO_INHERIT const auto res_protocol = pthread_mutexattr_setprotocol(&attr, PTHREAD_PRIO_INHERIT); if (res_protocol != 0) { throw std::system_error( - res_protocol, std::generic_category(), "Failed to set mutex protocol"); + res_protocol, std::system_category(), "Failed to set mutex protocol"); } // Set the mutex attribute robustness to MutexRobustness const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness); if (res_robust != 0) { throw std::system_error( - res_robust, std::generic_category(), "Failed to set mutex robustness"); + res_robust, std::system_category(), "Failed to set mutex robustness"); } // Initialize the mutex with the attributes const auto res_init = pthread_mutex_init(&mutex_, &attr); if (res_init != 0) { - throw std::system_error(res_init, std::generic_category(), "Failed to initialize mutex"); + throw std::system_error(res_init, std::system_category(), "Failed to initialize mutex"); } } From 0611b82074b5e61d54b12ef13f685684a76e75b9 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Sat, 23 Nov 2024 00:51:29 +0100 Subject: [PATCH 19/25] add tests on deadlock detection --- include/realtime_tools/mutex.hpp | 13 +++++++------ test/realtime_mutex_tests.cpp | 13 +++++++++++++ 2 files changed, 20 insertions(+), 6 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 2d6abeb0..cb9aea38 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -82,15 +82,13 @@ class mutex // Set the mutex attribute to use the protocol PTHREAD_PRIO_INHERIT const auto res_protocol = pthread_mutexattr_setprotocol(&attr, PTHREAD_PRIO_INHERIT); if (res_protocol != 0) { - throw std::system_error( - res_protocol, std::system_category(), "Failed to set mutex protocol"); + throw std::system_error(res_protocol, std::system_category(), "Failed to set mutex protocol"); } // Set the mutex attribute robustness to MutexRobustness const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness); if (res_robust != 0) { - throw std::system_error( - res_robust, std::system_category(), "Failed to set mutex robustness"); + throw std::system_error(res_robust, std::system_category(), "Failed to set mutex robustness"); } // Initialize the mutex with the attributes @@ -128,6 +126,8 @@ class mutex } std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" << std::endl; + } else if (res == EDEADLK) { + throw std::system_error(res, std::system_category(), "Deadlock detected"); } else { throw std::runtime_error(std::string("Failed to lock mutex : ") + std::strerror(res)); } @@ -150,8 +150,7 @@ class mutex } if (res == EBUSY) { return false; - } - if (res == EOWNERDEAD) { + } else if (res == EOWNERDEAD) { const auto res_consistent = pthread_mutex_consistent(&mutex_); if (res_consistent != 0) { throw std::runtime_error( @@ -159,6 +158,8 @@ class mutex } std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" << std::endl; + } else if (res == EDEADLK) { + throw std::system_error(res, std::system_category(), "Deadlock detected"); } else { throw std::runtime_error(std::string("Failed to try lock mutex : ") + std::strerror(res)); } diff --git a/test/realtime_mutex_tests.cpp b/test/realtime_mutex_tests.cpp index 02cc6584..0fead077 100644 --- a/test/realtime_mutex_tests.cpp +++ b/test/realtime_mutex_tests.cpp @@ -305,6 +305,19 @@ TEST(PriorityInheritanceMutexTests, test_lock_constructors) } } +TEST(PriorityInheritanceMutexTests, test_deadlock_detection) +{ + realtime_tools::priority_inheritance::error_mutex mutex; + mutex.lock(); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + ASSERT_THROW(mutex.try_lock(), std::system_error); + ASSERT_THROW(mutex.lock(), std::system_error); + // In a different thread, try to lock the mutex should not throw an exception + std::thread t([&mutex]() { ASSERT_FALSE(mutex.try_lock()); }); + t.join(); + mutex.unlock(); +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From 07e4e3a85dd540f6490ff243231ea3afc30064fc Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Sat, 23 Nov 2024 00:56:32 +0100 Subject: [PATCH 20/25] Just use the default mutex with PTHREAD_MUTEX_ERRORCHECK --- include/realtime_tools/mutex.hpp | 3 +-- test/realtime_mutex_tests.cpp | 20 ++++++++++++-------- 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index cb9aea38..ed07564d 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -170,8 +170,7 @@ class mutex pthread_mutex_t mutex_; }; } // namespace detail -using mutex = detail::mutex; -using error_mutex = detail::mutex; +using mutex = detail::mutex; using recursive_mutex = detail::mutex; } // namespace priority_inheritance } // namespace realtime_tools diff --git a/test/realtime_mutex_tests.cpp b/test/realtime_mutex_tests.cpp index 0fead077..f1b1447e 100644 --- a/test/realtime_mutex_tests.cpp +++ b/test/realtime_mutex_tests.cpp @@ -222,11 +222,15 @@ TEST(PriorityInheritanceMutexTests, try_lock_mutex) { realtime_tools::priority_inheritance::mutex mutex; ASSERT_TRUE(mutex.try_lock()); - ASSERT_FALSE(mutex.try_lock()); - ASSERT_FALSE(mutex.try_lock()); + ASSERT_THROW(mutex.try_lock(), std::system_error) + << "Mutex is already locked in the same thread"; + std::thread t([&mutex]() { + ASSERT_FALSE(mutex.try_lock()) + << "try_lock should pass when checking from a different thread"; + }); + t.join(); mutex.unlock(); ASSERT_TRUE(mutex.try_lock()); - ASSERT_FALSE(mutex.try_lock()); mutex.unlock(); } @@ -275,15 +279,15 @@ TEST(PriorityInheritanceMutexTests, native_handle_mutex) } } -TEST(PriorityInheritanceMutexTests, test_error_mutex) +TEST(PriorityInheritanceMutexTests, test_mutex_lock_functionality) { // Trying to lock again should throw an exception - realtime_tools::priority_inheritance::error_mutex mutex; + realtime_tools::priority_inheritance::mutex mutex; mutex.lock(); - ASSERT_THROW(mutex.lock(), std::runtime_error); + ASSERT_THROW(mutex.lock(), std::system_error); mutex.unlock(); ASSERT_NO_THROW(mutex.lock()); - ASSERT_THROW(mutex.try_lock(), std::runtime_error); + ASSERT_THROW(mutex.try_lock(), std::system_error); mutex.unlock(); ASSERT_NO_THROW(mutex.try_lock()); mutex.unlock(); @@ -307,7 +311,7 @@ TEST(PriorityInheritanceMutexTests, test_lock_constructors) TEST(PriorityInheritanceMutexTests, test_deadlock_detection) { - realtime_tools::priority_inheritance::error_mutex mutex; + realtime_tools::priority_inheritance::mutex mutex; mutex.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); ASSERT_THROW(mutex.try_lock(), std::system_error); From 91cce17bde61cc5541c532c8ab648dea4a2c1539 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Sat, 23 Nov 2024 01:02:21 +0100 Subject: [PATCH 21/25] Rename the mutexes prefixing `prio_inherit_` --- include/realtime_tools/mutex.hpp | 7 ++-- test/realtime_mutex_tests.cpp | 62 ++++++++++++++++---------------- 2 files changed, 33 insertions(+), 36 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index ed07564d..06f60cc2 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -34,8 +34,6 @@ */ namespace realtime_tools { -namespace priority_inheritance -{ namespace detail { /** @@ -170,9 +168,8 @@ class mutex pthread_mutex_t mutex_; }; } // namespace detail -using mutex = detail::mutex; -using recursive_mutex = detail::mutex; -} // namespace priority_inheritance +using prio_inherit_mutex = detail::mutex; +using prio_inherit_recursive_mutex = detail::mutex; } // namespace realtime_tools #endif // REALTIME_TOOLS__MUTEX_HPP_ diff --git a/test/realtime_mutex_tests.cpp b/test/realtime_mutex_tests.cpp index f1b1447e..0efdb6f9 100644 --- a/test/realtime_mutex_tests.cpp +++ b/test/realtime_mutex_tests.cpp @@ -24,7 +24,7 @@ TEST(PriorityInheritanceMutexTests, lock_unlock) { // The mutex is locked and unlocked correctly - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; mutex.lock(); mutex.unlock(); } @@ -32,7 +32,7 @@ TEST(PriorityInheritanceMutexTests, lock_unlock) TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded) { // The mutex is locked and unlocked correctly in a multithreaded environment - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; std::thread t1([&mutex]() { mutex.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -50,7 +50,7 @@ TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded) TEST(PriorityInheritanceMutexTests, recursive_lock_lock_unlock_multithreaded) { // The mutex is locked and unlocked correctly in a multithreaded environment - realtime_tools::priority_inheritance::recursive_mutex mutex; + realtime_tools::prio_inherit_recursive_mutex mutex; std::thread t1([&mutex]() { mutex.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -72,8 +72,8 @@ TEST(PriorityInheritanceMutexTests, recursive_lock_lock_unlock_multithreaded) TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_multiple_mutexes) { // The mutex is locked and unlocked correctly in a multithreaded environment with multiple mutexes - realtime_tools::priority_inheritance::mutex mutex1; - realtime_tools::priority_inheritance::mutex mutex2; + realtime_tools::prio_inherit_mutex mutex1; + realtime_tools::prio_inherit_mutex mutex2; std::thread t1([&mutex1, &mutex2]() { mutex1.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -97,8 +97,8 @@ TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_multiple_mutexes) TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_multiple_mutexes_different_types) { // The mutex is locked and unlocked correctly in a multithreaded environment with multiple mutexes - realtime_tools::priority_inheritance::mutex mutex1; - realtime_tools::priority_inheritance::recursive_mutex mutex2; + realtime_tools::prio_inherit_mutex mutex1; + realtime_tools::prio_inherit_recursive_mutex mutex2; std::thread t1([&mutex1, &mutex2]() { mutex1.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -122,7 +122,7 @@ TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_multiple_mutexes_d TEST(PriorityInheritanceMutexTests, lock_unlock_recursive_mutex) { // Test to check that the mutex is recursive - realtime_tools::priority_inheritance::recursive_mutex mutex; + realtime_tools::prio_inherit_recursive_mutex mutex; mutex.lock(); mutex.lock(); mutex.unlock(); @@ -131,8 +131,8 @@ TEST(PriorityInheritanceMutexTests, lock_unlock_recursive_mutex) TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_recursive_mutex_multiple_mutexes) { - realtime_tools::priority_inheritance::recursive_mutex mutex1; - realtime_tools::priority_inheritance::recursive_mutex mutex2; + realtime_tools::prio_inherit_recursive_mutex mutex1; + realtime_tools::prio_inherit_recursive_mutex mutex2; std::thread t1([&mutex1, &mutex2]() { mutex1.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -155,7 +155,7 @@ TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_recursive_mutex_mu TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_mutex_one_thread_dies) { - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; std::thread t1([&mutex]() { mutex.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -174,7 +174,7 @@ TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_mutex_one_thread_d TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_recursive_mutex_one_thread_dies) { - realtime_tools::priority_inheritance::recursive_mutex mutex; + realtime_tools::prio_inherit_recursive_mutex mutex; std::thread t1([&mutex]() { mutex.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -193,34 +193,34 @@ TEST(PriorityInheritanceMutexTests, lock_unlock_multithreaded_recursive_mutex_on TEST(PriorityInheritanceMutexTests, lock_guard_mutex) { - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; { - std::lock_guard lock(mutex); + std::lock_guard lock(mutex); } - realtime_tools::priority_inheritance::recursive_mutex recursive_mutex; + realtime_tools::prio_inherit_recursive_mutex recursive_mutex; { - std::lock_guard lock(recursive_mutex); + std::lock_guard lock(recursive_mutex); } } TEST(PriorityInheritanceMutexTests, unique_lock_mutex) { - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; { - std::unique_lock lock(mutex); + std::unique_lock lock(mutex); } - realtime_tools::priority_inheritance::recursive_mutex recursive_mutex; + realtime_tools::prio_inherit_recursive_mutex recursive_mutex; { - std::unique_lock lock(recursive_mutex); + std::unique_lock lock(recursive_mutex); } } TEST(PriorityInheritanceMutexTests, try_lock_mutex) { { - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; ASSERT_TRUE(mutex.try_lock()); ASSERT_THROW(mutex.try_lock(), std::system_error) << "Mutex is already locked in the same thread"; @@ -235,7 +235,7 @@ TEST(PriorityInheritanceMutexTests, try_lock_mutex) } { - realtime_tools::priority_inheritance::recursive_mutex recursive_mutex; + realtime_tools::prio_inherit_recursive_mutex recursive_mutex; ASSERT_TRUE(recursive_mutex.try_lock()); ASSERT_TRUE(recursive_mutex.try_lock()); ASSERT_TRUE(recursive_mutex.try_lock()); @@ -247,8 +247,8 @@ TEST(PriorityInheritanceMutexTests, try_lock_mutex) TEST(PriorityInheritanceMutexTests, standard_lock_test) { - realtime_tools::priority_inheritance::mutex mutex1; - realtime_tools::priority_inheritance::mutex mutex2; + realtime_tools::prio_inherit_mutex mutex1; + realtime_tools::prio_inherit_mutex mutex2; { std::lock(mutex1, mutex2); // do work @@ -267,13 +267,13 @@ TEST(PriorityInheritanceMutexTests, standard_lock_test) TEST(PriorityInheritanceMutexTests, native_handle_mutex) { { - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; auto native_handle = mutex.native_handle(); ASSERT_NE(native_handle, nullptr); } { - realtime_tools::priority_inheritance::recursive_mutex recursive_mutex; + realtime_tools::prio_inherit_recursive_mutex recursive_mutex; auto native_handle = recursive_mutex.native_handle(); ASSERT_NE(native_handle, nullptr); } @@ -282,7 +282,7 @@ TEST(PriorityInheritanceMutexTests, native_handle_mutex) TEST(PriorityInheritanceMutexTests, test_mutex_lock_functionality) { // Trying to lock again should throw an exception - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; mutex.lock(); ASSERT_THROW(mutex.lock(), std::system_error); mutex.unlock(); @@ -295,23 +295,23 @@ TEST(PriorityInheritanceMutexTests, test_mutex_lock_functionality) TEST(PriorityInheritanceMutexTests, test_lock_constructors) { - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; { - std::unique_lock lock(mutex, std::defer_lock); + std::unique_lock lock(mutex, std::defer_lock); ASSERT_FALSE(lock.owns_lock()); lock.lock(); ASSERT_TRUE(lock.owns_lock()); lock.unlock(); } { - std::unique_lock lock(mutex, std::try_to_lock); + std::unique_lock lock(mutex, std::try_to_lock); ASSERT_TRUE(lock.owns_lock()); } } TEST(PriorityInheritanceMutexTests, test_deadlock_detection) { - realtime_tools::priority_inheritance::mutex mutex; + realtime_tools::prio_inherit_mutex mutex; mutex.lock(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); ASSERT_THROW(mutex.try_lock(), std::system_error); From 6f332bf9aa52a53d1b54a6b3242664faa8caf312 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 27 Nov 2024 09:51:54 +0100 Subject: [PATCH 22/25] Exclude the windows using mutex.hpp --- CMakeLists.txt | 2 ++ include/realtime_tools/mutex.hpp | 4 ++++ 2 files changed, 6 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index df18aea4..3e957f45 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -99,9 +99,11 @@ if(BUILD_TESTING) target_link_libraries(test_async_function_handler realtime_tools thread_priority) ament_target_dependencies(test_async_function_handler lifecycle_msgs rclcpp_lifecycle) +if(NOT WIN32) ament_add_gmock(realtime_mutex_tests test/realtime_mutex_tests.cpp) target_link_libraries(realtime_mutex_tests realtime_tools) endif() +endif() # Install install( diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 06f60cc2..418f5ae6 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -17,6 +17,10 @@ #ifndef REALTIME_TOOLS__MUTEX_HPP_ #define REALTIME_TOOLS__MUTEX_HPP_ +#ifdef _WIN32 +#error "The mutex.hpp header is not supported on Windows platforms" +#endif + #include #include #include From 58452ffda302f87b6aa50172bf18aa0b61ac0dbe Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Mon, 25 Nov 2024 09:46:42 +0100 Subject: [PATCH 23/25] create class enums for defining the template types --- include/realtime_tools/mutex.hpp | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index 418f5ae6..f14b204a 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -40,13 +40,20 @@ namespace realtime_tools { namespace detail { +enum mutex_type_t { + NORMAL = PTHREAD_MUTEX_NORMAL, + ERRORCHECK = PTHREAD_MUTEX_ERRORCHECK, + RECURSIVE = PTHREAD_MUTEX_RECURSIVE +}; + +enum mutex_robustness_t { STALLED = PTHREAD_MUTEX_STALLED, ROBUST = PTHREAD_MUTEX_ROBUST }; /** * @brief A class template that provides a pthread mutex with the priority inheritance protocol * * @tparam MutexType The type of the mutex. It can be one of the following: PTHREAD_MUTEX_NORMAL, PTHREAD_MUTEX_RECURSIVE, PTHREAD_MUTEX_ERRORCHECK, PTHREAD_MUTEX_DEFAULT * @tparam MutexRobustness The robustness of the mutex. It can be one of the following: PTHREAD_MUTEX_STALLED, PTHREAD_MUTEX_ROBUST */ -template +template class mutex { public: @@ -172,8 +179,8 @@ class mutex pthread_mutex_t mutex_; }; } // namespace detail -using prio_inherit_mutex = detail::mutex; -using prio_inherit_recursive_mutex = detail::mutex; +using prio_inherit_mutex = detail::mutex; +using prio_inherit_recursive_mutex = detail::mutex; } // namespace realtime_tools #endif // REALTIME_TOOLS__MUTEX_HPP_ From 5b3028cd756520dc123684eb4991bf00c44ff083 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 27 Nov 2024 18:18:25 +0100 Subject: [PATCH 24/25] Make the mutexes work with the std::is_same for conditioning in code --- include/realtime_tools/mutex.hpp | 35 +++++++++++++++++++++++--------- test/realtime_mutex_tests.cpp | 12 +++++++++++ 2 files changed, 37 insertions(+), 10 deletions(-) diff --git a/include/realtime_tools/mutex.hpp b/include/realtime_tools/mutex.hpp index f14b204a..f781d232 100644 --- a/include/realtime_tools/mutex.hpp +++ b/include/realtime_tools/mutex.hpp @@ -40,24 +40,38 @@ namespace realtime_tools { namespace detail { -enum mutex_type_t { - NORMAL = PTHREAD_MUTEX_NORMAL, - ERRORCHECK = PTHREAD_MUTEX_ERRORCHECK, - RECURSIVE = PTHREAD_MUTEX_RECURSIVE +struct error_mutex_type_t +{ + static constexpr int value = PTHREAD_MUTEX_ERRORCHECK; }; -enum mutex_robustness_t { STALLED = PTHREAD_MUTEX_STALLED, ROBUST = PTHREAD_MUTEX_ROBUST }; +struct recursive_mutex_type_t +{ + static constexpr int value = PTHREAD_MUTEX_RECURSIVE; +}; + +struct stalled_robustness_t +{ + static constexpr int value = PTHREAD_MUTEX_STALLED; +}; + +struct robust_robustness_t +{ + static constexpr int value = PTHREAD_MUTEX_ROBUST; +}; /** * @brief A class template that provides a pthread mutex with the priority inheritance protocol * * @tparam MutexType The type of the mutex. It can be one of the following: PTHREAD_MUTEX_NORMAL, PTHREAD_MUTEX_RECURSIVE, PTHREAD_MUTEX_ERRORCHECK, PTHREAD_MUTEX_DEFAULT * @tparam MutexRobustness The robustness of the mutex. It can be one of the following: PTHREAD_MUTEX_STALLED, PTHREAD_MUTEX_ROBUST */ -template +template class mutex { public: using native_handle_type = pthread_mutex_t *; + using type = MutexType; + using robustness = MutexRobustness; mutex() { @@ -82,7 +96,7 @@ class mutex } // Set the mutex type to MutexType - const auto res_type = pthread_mutexattr_settype(&attr, MutexType); + const auto res_type = pthread_mutexattr_settype(&attr, MutexType::value); if (res_type != 0) { throw std::system_error(res_type, std::system_category(), "Failed to set mutex type"); @@ -95,7 +109,7 @@ class mutex } // Set the mutex attribute robustness to MutexRobustness - const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness); + const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness::value); if (res_robust != 0) { throw std::system_error(res_robust, std::system_category(), "Failed to set mutex robustness"); } @@ -179,8 +193,9 @@ class mutex pthread_mutex_t mutex_; }; } // namespace detail -using prio_inherit_mutex = detail::mutex; -using prio_inherit_recursive_mutex = detail::mutex; +using prio_inherit_mutex = detail::mutex; +using prio_inherit_recursive_mutex = + detail::mutex; } // namespace realtime_tools #endif // REALTIME_TOOLS__MUTEX_HPP_ diff --git a/test/realtime_mutex_tests.cpp b/test/realtime_mutex_tests.cpp index 0efdb6f9..691529c2 100644 --- a/test/realtime_mutex_tests.cpp +++ b/test/realtime_mutex_tests.cpp @@ -322,6 +322,18 @@ TEST(PriorityInheritanceMutexTests, test_deadlock_detection) mutex.unlock(); } +TEST(PriorityInheritanceMutexTests, test_mutex_reflection) +{ + static_assert( + std::is_same< + realtime_tools::prio_inherit_mutex::type, + realtime_tools::detail::error_mutex_type_t>::value == true); + static_assert( + std::is_same< + realtime_tools::prio_inherit_recursive_mutex::type, + realtime_tools::detail::recursive_mutex_type_t>::value == true); +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From 3a7edb28b3761b7f16ba734ae9e88bb1b9c1ba3c Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 3 Dec 2024 19:40:08 +0100 Subject: [PATCH 25/25] indent the condition in CMakeLists.txt --- CMakeLists.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3e957f45..8540aa63 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -99,10 +99,10 @@ if(BUILD_TESTING) target_link_libraries(test_async_function_handler realtime_tools thread_priority) ament_target_dependencies(test_async_function_handler lifecycle_msgs rclcpp_lifecycle) -if(NOT WIN32) - ament_add_gmock(realtime_mutex_tests test/realtime_mutex_tests.cpp) - target_link_libraries(realtime_mutex_tests realtime_tools) -endif() + if(NOT WIN32) + ament_add_gmock(realtime_mutex_tests test/realtime_mutex_tests.cpp) + target_link_libraries(realtime_mutex_tests realtime_tools) + endif() endif() # Install