|
| 1 | +// Copyright 2024 PAL Robotics S.L. |
| 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 | +/// \author Sai Kishor Kothakota |
| 16 | + |
| 17 | +#ifndef REALTIME_TOOLS__MUTEX_HPP_ |
| 18 | +#define REALTIME_TOOLS__MUTEX_HPP_ |
| 19 | + |
| 20 | +#ifdef _WIN32 |
| 21 | +#error "The mutex.hpp header is not supported on Windows platforms" |
| 22 | +#endif |
| 23 | + |
| 24 | +#include <pthread.h> |
| 25 | +#include <cerrno> |
| 26 | +#include <cstring> |
| 27 | +#include <iostream> |
| 28 | +#include <memory> |
| 29 | +#include <stdexcept> |
| 30 | +#include <string> |
| 31 | + |
| 32 | +/** |
| 33 | + * @brief A pthread mutex wrapper that provides a mutex with the priority inheritance |
| 34 | + * protocol and a priority ceiling of 99. |
| 35 | + * The mutex is also error checked and robust. |
| 36 | + * This mutex is intended to be used in real-time contexts. |
| 37 | + * @note This mutex is not recursive. |
| 38 | + */ |
| 39 | +namespace realtime_tools |
| 40 | +{ |
| 41 | +namespace detail |
| 42 | +{ |
| 43 | +struct error_mutex_type_t |
| 44 | +{ |
| 45 | + static constexpr int value = PTHREAD_MUTEX_ERRORCHECK; |
| 46 | +}; |
| 47 | + |
| 48 | +struct recursive_mutex_type_t |
| 49 | +{ |
| 50 | + static constexpr int value = PTHREAD_MUTEX_RECURSIVE; |
| 51 | +}; |
| 52 | + |
| 53 | +struct stalled_robustness_t |
| 54 | +{ |
| 55 | + static constexpr int value = PTHREAD_MUTEX_STALLED; |
| 56 | +}; |
| 57 | + |
| 58 | +struct robust_robustness_t |
| 59 | +{ |
| 60 | + static constexpr int value = PTHREAD_MUTEX_ROBUST; |
| 61 | +}; |
| 62 | +/** |
| 63 | + * @brief A class template that provides a pthread mutex with the priority inheritance protocol |
| 64 | + * |
| 65 | + * @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 |
| 66 | + * @tparam MutexRobustness The robustness of the mutex. It can be one of the following: PTHREAD_MUTEX_STALLED, PTHREAD_MUTEX_ROBUST |
| 67 | + */ |
| 68 | +template <typename MutexType, typename MutexRobustness> |
| 69 | +class mutex |
| 70 | +{ |
| 71 | +public: |
| 72 | + using native_handle_type = pthread_mutex_t *; |
| 73 | + using type = MutexType; |
| 74 | + using robustness = MutexRobustness; |
| 75 | + |
| 76 | + mutex() |
| 77 | + { |
| 78 | + pthread_mutexattr_t attr; |
| 79 | + |
| 80 | + const auto attr_destroy = [](pthread_mutexattr_t * mutex_attr) { |
| 81 | + // Destroy the mutex attributes |
| 82 | + const auto res_destroy = pthread_mutexattr_destroy(mutex_attr); |
| 83 | + if (res_destroy != 0) { |
| 84 | + throw std::system_error( |
| 85 | + res_destroy, std::generic_category(), "Failed to destroy mutex attribute"); |
| 86 | + } |
| 87 | + }; |
| 88 | + using attr_cleanup_t = std::unique_ptr<pthread_mutexattr_t, decltype(attr_destroy)>; |
| 89 | + auto attr_cleanup = attr_cleanup_t(&attr, attr_destroy); |
| 90 | + |
| 91 | + // Initialize the mutex attributes |
| 92 | + const auto res_attr = pthread_mutexattr_init(&attr); |
| 93 | + if (res_attr != 0) { |
| 94 | + throw std::system_error( |
| 95 | + res_attr, std::system_category(), "Failed to initialize mutex attribute"); |
| 96 | + } |
| 97 | + |
| 98 | + // Set the mutex type to MutexType |
| 99 | + const auto res_type = pthread_mutexattr_settype(&attr, MutexType::value); |
| 100 | + |
| 101 | + if (res_type != 0) { |
| 102 | + throw std::system_error(res_type, std::system_category(), "Failed to set mutex type"); |
| 103 | + } |
| 104 | + |
| 105 | + // Set the mutex attribute to use the protocol PTHREAD_PRIO_INHERIT |
| 106 | + const auto res_protocol = pthread_mutexattr_setprotocol(&attr, PTHREAD_PRIO_INHERIT); |
| 107 | + if (res_protocol != 0) { |
| 108 | + throw std::system_error(res_protocol, std::system_category(), "Failed to set mutex protocol"); |
| 109 | + } |
| 110 | + |
| 111 | + // Set the mutex attribute robustness to MutexRobustness |
| 112 | + const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness::value); |
| 113 | + if (res_robust != 0) { |
| 114 | + throw std::system_error(res_robust, std::system_category(), "Failed to set mutex robustness"); |
| 115 | + } |
| 116 | + |
| 117 | + // Initialize the mutex with the attributes |
| 118 | + const auto res_init = pthread_mutex_init(&mutex_, &attr); |
| 119 | + if (res_init != 0) { |
| 120 | + throw std::system_error(res_init, std::system_category(), "Failed to initialize mutex"); |
| 121 | + } |
| 122 | + } |
| 123 | + |
| 124 | + ~mutex() |
| 125 | + { |
| 126 | + const auto res = pthread_mutex_destroy(&mutex_); |
| 127 | + if (res != 0) { |
| 128 | + std::cerr << "Failed to destroy mutex : " << std::strerror(res) << std::endl; |
| 129 | + } |
| 130 | + } |
| 131 | + |
| 132 | + mutex(const mutex &) = delete; |
| 133 | + |
| 134 | + mutex & operator=(const mutex &) = delete; |
| 135 | + |
| 136 | + native_handle_type native_handle() noexcept { return &mutex_; } |
| 137 | + |
| 138 | + void lock() |
| 139 | + { |
| 140 | + const auto res = pthread_mutex_lock(&mutex_); |
| 141 | + if (res == 0) { |
| 142 | + return; |
| 143 | + } |
| 144 | + if (res == EOWNERDEAD) { |
| 145 | + const auto res_consistent = pthread_mutex_consistent(&mutex_); |
| 146 | + if (res_consistent != 0) { |
| 147 | + throw std::runtime_error( |
| 148 | + std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); |
| 149 | + } |
| 150 | + std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" |
| 151 | + << std::endl; |
| 152 | + } else if (res == EDEADLK) { |
| 153 | + throw std::system_error(res, std::system_category(), "Deadlock detected"); |
| 154 | + } else { |
| 155 | + throw std::runtime_error(std::string("Failed to lock mutex : ") + std::strerror(res)); |
| 156 | + } |
| 157 | + } |
| 158 | + |
| 159 | + void unlock() noexcept |
| 160 | + { |
| 161 | + // As per the requirements of BasicLockable concept, unlock should not throw |
| 162 | + const auto res = pthread_mutex_unlock(&mutex_); |
| 163 | + if (res != 0) { |
| 164 | + std::cerr << "Failed to unlock mutex : " << std::strerror(res) << std::endl; |
| 165 | + } |
| 166 | + } |
| 167 | + |
| 168 | + bool try_lock() |
| 169 | + { |
| 170 | + const auto res = pthread_mutex_trylock(&mutex_); |
| 171 | + if (res == 0) { |
| 172 | + return true; |
| 173 | + } |
| 174 | + if (res == EBUSY) { |
| 175 | + return false; |
| 176 | + } else if (res == EOWNERDEAD) { |
| 177 | + const auto res_consistent = pthread_mutex_consistent(&mutex_); |
| 178 | + if (res_consistent != 0) { |
| 179 | + throw std::runtime_error( |
| 180 | + std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent)); |
| 181 | + } |
| 182 | + std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!" |
| 183 | + << std::endl; |
| 184 | + } else if (res == EDEADLK) { |
| 185 | + throw std::system_error(res, std::system_category(), "Deadlock detected"); |
| 186 | + } else { |
| 187 | + throw std::runtime_error(std::string("Failed to try lock mutex : ") + std::strerror(res)); |
| 188 | + } |
| 189 | + return true; |
| 190 | + } |
| 191 | + |
| 192 | +private: |
| 193 | + pthread_mutex_t mutex_; |
| 194 | +}; |
| 195 | +} // namespace detail |
| 196 | +using prio_inherit_mutex = detail::mutex<detail::error_mutex_type_t, detail::robust_robustness_t>; |
| 197 | +using prio_inherit_recursive_mutex = |
| 198 | + detail::mutex<detail::recursive_mutex_type_t, detail::robust_robustness_t>; |
| 199 | +} // namespace realtime_tools |
| 200 | + |
| 201 | +#endif // REALTIME_TOOLS__MUTEX_HPP_ |
0 commit comments