Skip to content

Commit

Permalink
added CMake option USE_PI_MUTEX
Browse files Browse the repository at this point in the history
Signed-off-by: Martin Mayer <[email protected]>
  • Loading branch information
WideAwakeTN committed Feb 17, 2023
1 parent 4e81d58 commit 54db1d3
Show file tree
Hide file tree
Showing 6 changed files with 50 additions and 22 deletions.
10 changes: 10 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,16 @@ if(WIN32)
target_compile_definitions(${PROJECT_NAME}
PRIVATE "RCPPUTILS_BUILDING_LIBRARY")
endif()

option(USE_PI_MUTEX "Enables priority inheritance mutexes." ON)
if(USE_PI_MUTEX)
if(WIN32 OR APPLE)
message("Mutexes with priority inheritance are not supported on your system. Using std mutexes.")
else()
target_compile_definitions(${PROJECT_NAME} PUBLIC "RCPPUTILS_USE_PIMUTEX")
endif()
endif()

ament_target_dependencies(${PROJECT_NAME} rcutils)

# Export old-style CMake variables
Expand Down
1 change: 1 addition & 0 deletions Doxyfile
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ EXPAND_ONLY_PREDEF = YES
PREDEFINED += __declspec(x)=
PREDEFINED += RCPPUTILS_PUBLIC=
PREDEFINED += RCPPUTILS_PUBLIC_TYPE=
PREDEFINED += RCPPUTILS_USE_PIMUTEX

# Tag files that do not exist will produce a warning and cross-project linking will not work.
TAGFILES += "../../../doxygen_tag_files/cppreference-doxygen-web.tag.xml=http://en.cppreference.com/w/"
Expand Down
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ This package currently contains:
* String helpers
* File system helpers
* Type traits helpers
* Mutex classes that support thread priority inheritance
* Class that dynamically loads, unloads and get symbols from shared libraries at run-time.

Features are described in more detail at [docs/FEATURES.md](docs/FEATURES.md)
15 changes: 11 additions & 4 deletions include/rcpputils/mutex.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Open Source Robotics Foundation, Inc.
// Copyright 2023 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -21,11 +21,18 @@

namespace rcpputils
{
#ifndef RCPPUTILS_USE_PIMUTEX

// Fallback code path
using PIMutex = std::mutex;
using RecursivePIMutex = std::recursive_mutex;

#else

/**
* Mutex with priority inheritance on systems that support it.
* This class derives from std::mutex to be fully compatible with standard C++.
* This implementation is a workaround that is needed until the C++ standard library offers the same mutex functionality.
* This implementation is needed because the C++ standard library doesn't support priority inheritance.
**/
class PIMutex : public std::mutex
{
Expand All @@ -42,7 +49,7 @@ class PIMutex : public std::mutex
/**
* Recursive mutex with priority inheritance on systems that support it.
* This class derives from std::recursive_mutex to be fully compatible with standard C++.
* This implementation is a workaround that is needed until the C++ standard library offers the same mutex functionality.
* This implementation is needed because the C++ standard library doesn't support priority inheritance.
**/
class RecursivePIMutex : public std::recursive_mutex
{
Expand All @@ -56,6 +63,6 @@ class RecursivePIMutex : public std::recursive_mutex
~RecursivePIMutex();
};

#endif // RCPPUTILS_USE_PIMUTEX
} // namespace rcpputils

#endif // RCPPUTILS__MUTEX_HPP_
18 changes: 5 additions & 13 deletions src/mutex.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Open Source Robotics Foundation, Inc.
// Copyright 2023 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -14,14 +14,13 @@

#include "rcpputils/mutex.hpp"

#ifndef _WIN32
#ifdef RCPPUTILS_USE_PIMUTEX

#include <pthread.h>
#endif

namespace rcpputils
{

#ifndef _WIN32
PIMutex::PIMutex()
{
// Destroy the underlying mutex
Expand Down Expand Up @@ -60,15 +59,6 @@ RecursivePIMutex::RecursivePIMutex()
// The attribute object isn't needed any more
pthread_mutexattr_destroy(&attr);
}
#else
PIMutex::PIMutex()
{
}

RecursivePIMutex::RecursivePIMutex()
{
}
#endif // _WIN32

PIMutex::~PIMutex()
{
Expand All @@ -77,4 +67,6 @@ PIMutex::~PIMutex()
RecursivePIMutex::~RecursivePIMutex()
{
}

} // namespace rcpputils
#endif // RCPPUTILS_USE_PIMUTEX
27 changes: 22 additions & 5 deletions test/test_mutex.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
// Copyright 2023 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -19,10 +19,14 @@

#include "rcpputils/mutex.hpp"

#ifdef __linux__
#ifdef RCPPUTILS_USE_PIMUTEX
#include <pthread.h>
#include "rcutils/types/rcutils_ret.h"
#endif // __linux__
#ifdef __QNXNTO__
#include <sys/neutrino.h>
#include <sys/syspage.h>
#endif // __QNXNTO__
#endif // RCPPUTILS_USE_PIMUTEX

using namespace std::chrono_literals;

Expand Down Expand Up @@ -99,7 +103,7 @@ TEST(test_mutex, pimutex_lockthread) {
test_thread.join();
}

#ifdef __linux__
#ifdef RCPPUTILS_USE_PIMUTEX
//
// The test cases pimutex_priority_inversion & rpimutex_priority_inversion provoke
// a thread priority inversion. To do so they need to configure the cpu priority,
Expand Down Expand Up @@ -160,14 +164,27 @@ rcutils_ret_t configure_native_realtime_thread(
RCUTILS_RET_OK ? 1 : 0);
success &= (pthread_setschedparam(native_handle, SCHED_FIFO, &params) == 0);

#ifdef __QNXNTO__
// run_mask is a bit mask to set which cpu a thread runs on
// where each bit corresponds to a cpu core
int64_t run_mask = cpu_bitmask;

// change thread affinity of thread associated with native_handle
success &= (ThreadCtlExt(
0, native_handle, _NTO_TCTL_RUNMASK,
reinterpret_cast<void *>(run_mask)) != -1);
#else // __QNXNTO__
cpu_set_t cpuset;
CPU_ZERO(&cpuset);
for (unsigned int i = 0; i < sizeof(cpu_bitmask) * 8; i++) {
if ( (cpu_bitmask & (1 << i)) != 0) {
CPU_SET(i, &cpuset);
}
}

// change thread affinity of thread associated with native_handle
success &= (pthread_setaffinity_np(native_handle, sizeof(cpu_set_t), &cpuset) == 0);
#endif // __QNXNTO__

return success ? RCUTILS_RET_OK : RCUTILS_RET_ERROR;
}
Expand Down Expand Up @@ -285,4 +302,4 @@ TEST(test_mutex, rpimutex_priority_inversion) {
priority_inheritance_test<rcpputils::RecursivePIMutex>();
}

#endif // __linux__
#endif // RCPPUTILS_USE_PIMUTEX

0 comments on commit 54db1d3

Please sign in to comment.