diff --git a/include/realtime_tools/realtime_helpers.hpp b/include/realtime_tools/realtime_helpers.hpp index 3f1cd10f..ef486a49 100644 --- a/include/realtime_tools/realtime_helpers.hpp +++ b/include/realtime_tools/realtime_helpers.hpp @@ -63,10 +63,24 @@ bool configure_sched_fifo(int priority); * will not swap out the pages to disk i.e., the pages are guaranteed to stay in * RAM until later unlocked - which is important for realtime applications. * \param[out] message a message describing the result of the operation - * \returns true if memory locking succeeded, false otherwise + * \returns true if memory locking succeeded, false otherwise. */ + +[[deprecated("Use std::pair lock_memory() instead.")]] bool lock_memory(std::string & message); +/** + * Locks the memory pages of the calling thread to prevent page faults. + * By calling this method, the programs locks all pages mapped into the address + * space of the calling process and future mappings. This means that the kernel + * will not swap out the pages to disk i.e., the pages are guaranteed to stay in + * RAM until later unlocked - which is important for realtime applications. + * \param[out] message a message describing the result of the operation + * \returns a pair of a boolean indicating whether the operation succeeded or not + * and a message describing the result of the operation +*/ +std::pair lock_memory(); + /** * Configure the caller thread affinity - Tell the scheduler to prefer a certain * set of cores for the given thread handle. diff --git a/src/realtime_helpers.cpp b/src/realtime_helpers.cpp index 17720c23..e55894ce 100644 --- a/src/realtime_helpers.cpp +++ b/src/realtime_helpers.cpp @@ -65,10 +65,16 @@ bool configure_sched_fifo(int priority) } bool lock_memory(std::string & message) +{ + const auto lock_result = lock_memory(); + message = lock_result.second; + return lock_result.first; +} + +std::pair lock_memory() { #ifdef _WIN32 - message = "Memory locking is not supported on Windows."; - return false; + return {false, "Memory locking is not supported on Windows."}; #else auto is_capable = [](cap_value_t v) -> bool { bool rc = false; @@ -86,6 +92,7 @@ bool lock_memory(std::string & message) return rc; }; + std::string message; if (mlockall(MCL_CURRENT | MCL_FUTURE) == -1) { if (!is_capable(CAP_IPC_LOCK)) { message = "No proper privileges to lock the memory!"; @@ -105,10 +112,10 @@ bool lock_memory(std::string & message) } else { message = "Unknown error occurred!"; } - return false; + return {false, message}; } else { message = "Memory locked successfully!"; - return true; + return {true, message}; } #endif }