Skip to content

Commit d6b4113

Browse files
idesign0saikishorchristophfroehlichCopilot
authored
Fix macOS compatibility issues in realtime_tools package (#370)
--------- Signed-off-by: Dhruv Patel <[email protected]> Co-authored-by: Sai Kishor Kothakota <[email protected]> Co-authored-by: Christoph Fröhlich <[email protected]> Co-authored-by: Copilot <[email protected]>
1 parent ada7143 commit d6b4113

File tree

3 files changed

+49
-8
lines changed

3 files changed

+49
-8
lines changed

realtime_tools/CMakeLists.txt

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ target_include_directories(realtime_tools PUBLIC
4545
$<INSTALL_INTERFACE:include/realtime_tools>
4646
)
4747
target_link_libraries(realtime_tools PUBLIC rclcpp::rclcpp rclcpp_action::rclcpp_action rcpputils::rcpputils Threads::Threads Boost::boost)
48-
if(UNIX)
48+
if(UNIX AND NOT APPLE)
4949
target_link_libraries(realtime_tools PUBLIC cap)
5050
endif()
5151

@@ -59,7 +59,7 @@ target_include_directories(thread_priority PUBLIC
5959
$<INSTALL_INTERFACE:include/realtime_tools>
6060
)
6161
target_link_libraries(thread_priority PUBLIC rclcpp::rclcpp rclcpp_action::rclcpp_action rcpputils::rcpputils Threads::Threads)
62-
if(UNIX)
62+
if(UNIX AND NOT APPLE)
6363
target_link_libraries(thread_priority PUBLIC cap)
6464
endif()
6565

@@ -80,8 +80,9 @@ if(BUILD_TESTING)
8080
target_link_libraries(realtime_buffer_tests realtime_tools)
8181

8282
ament_add_gmock(lock_free_queue_tests test/lock_free_queue_tests.cpp)
83+
8384
target_link_libraries(lock_free_queue_tests realtime_tools Boost::boost)
84-
if(UNIX)
85+
if(UNIX AND NOT APPLE)
8586
target_link_libraries(lock_free_queue_tests atomic)
8687
endif()
8788

realtime_tools/include/realtime_tools/mutex.hpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,12 +52,20 @@ struct recursive_mutex_type_t
5252

5353
struct stalled_robustness_t
5454
{
55+
#if defined(__linux__)
5556
static constexpr int value = PTHREAD_MUTEX_STALLED;
57+
#else
58+
static constexpr int value = 0; // macOS, Windows, or other platforms fallback
59+
#endif
5660
};
5761

5862
struct robust_robustness_t
5963
{
64+
#if defined(__linux__)
6065
static constexpr int value = PTHREAD_MUTEX_ROBUST;
66+
#else
67+
static constexpr int value = 0; // macOS, Windows, or other platforms fallback
68+
#endif
6169
};
6270
/**
6371
* @brief A class template that provides a pthread mutex with the priority inheritance protocol
@@ -109,10 +117,14 @@ class mutex
109117
}
110118

111119
// Set the mutex attribute robustness to MutexRobustness
120+
// On platforms like macOS, pthread_mutexattr_setrobust is not available,
121+
// so skip this step
122+
#if defined(__linux__)
112123
const auto res_robust = pthread_mutexattr_setrobust(&attr, MutexRobustness::value);
113124
if (res_robust != 0) {
114125
throw std::system_error(res_robust, std::system_category(), "Failed to set mutex robustness");
115126
}
127+
#endif
116128

117129
// Initialize the mutex with the attributes
118130
const auto res_init = pthread_mutex_init(&mutex_, &attr);
@@ -142,13 +154,20 @@ class mutex
142154
return;
143155
}
144156
if (res == EOWNERDEAD) {
157+
#if defined(__linux__)
145158
const auto res_consistent = pthread_mutex_consistent(&mutex_);
146159
if (res_consistent != 0) {
147160
throw std::runtime_error(
148161
std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent));
149162
}
150163
std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!"
151164
<< std::endl;
165+
#else
166+
// On platforms without pthread_mutex_consistent support, just log a warning
167+
std::cerr
168+
<< "Mutex owner died, but pthread_mutex_consistent is not supported on this platform."
169+
<< std::endl;
170+
#endif
152171
} else if (res == EDEADLK) {
153172
throw std::system_error(res, std::system_category(), "Deadlock detected");
154173
} else {
@@ -174,13 +193,19 @@ class mutex
174193
if (res == EBUSY) {
175194
return false;
176195
} else if (res == EOWNERDEAD) {
196+
#if defined(__linux__)
177197
const auto res_consistent = pthread_mutex_consistent(&mutex_);
178198
if (res_consistent != 0) {
179199
throw std::runtime_error(
180200
std::string("Failed to make mutex consistent : ") + std::strerror(res_consistent));
181201
}
182202
std::cerr << "Mutex owner died, but the mutex is consistent now. This shouldn't happen!"
183203
<< std::endl;
204+
#else
205+
std::cerr
206+
<< "Mutex owner died, but pthread_mutex_consistent is not supported on this platform."
207+
<< std::endl;
208+
#endif
184209
} else if (res == EDEADLK) {
185210
throw std::system_error(res, std::system_category(), "Deadlock detected");
186211
} else {

realtime_tools/src/realtime_helpers.cpp

Lines changed: 20 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -32,10 +32,11 @@
3232
#include <windows.h>
3333
#else
3434
#include <sched.h>
35+
#if defined(__unix__)
3536
#include <sys/capability.h>
37+
#endif
3638
#include <sys/mman.h>
3739
#include <sys/utsname.h>
38-
3940
#include <unistd.h>
4041
#endif
4142

@@ -75,6 +76,20 @@ bool configure_sched_fifo(int priority)
7576
#ifdef _WIN32
7677
HANDLE thread = GetCurrentThread();
7778
return SetThreadPriority(thread, priority);
79+
#elif defined(__APPLE__)
80+
// macOS implementation using pthread_setschedparam with SCHED_FIFO
81+
pthread_t thread = pthread_self();
82+
struct sched_param schedp;
83+
memset(&schedp, 0, sizeof(schedp));
84+
schedp.sched_priority = priority;
85+
86+
int policy = SCHED_FIFO;
87+
if (pthread_setschedparam(thread, policy, &schedp) == 0) {
88+
return true;
89+
} else {
90+
// Optionally log strerror(errno) for debugging
91+
return false;
92+
}
7893
#else
7994
struct sched_param schedp;
8095
memset(&schedp, 0, sizeof(schedp));
@@ -85,8 +100,8 @@ bool configure_sched_fifo(int priority)
85100

86101
std::pair<bool, std::string> lock_memory()
87102
{
88-
#ifdef _WIN32
89-
return {false, "Memory locking is not supported on Windows."};
103+
#if defined(_WIN32) || defined(__APPLE__)
104+
return {false, "Memory locking is not supported on Windows or macOS."};
90105
#else
91106
auto is_capable = [](cap_value_t v) -> bool {
92107
bool rc = false;
@@ -136,8 +151,8 @@ std::pair<bool, std::string> set_thread_affinity(
136151
NATIVE_THREAD_HANDLE thread, const std::vector<int> & cores)
137152
{
138153
std::string message;
139-
#ifdef _WIN32
140-
message = "Thread affinity is not supported on Windows.";
154+
#if defined(_WIN32) || defined(__APPLE__)
155+
message = "Thread affinity is not supported on Windows or macOS.";
141156
return std::make_pair(false, message);
142157
#else
143158
auto set_affinity_result_message = [](int result, std::string & msg) -> bool {

0 commit comments

Comments
 (0)