From b02e501756d61e93de5c4762abe8736e320c8978 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Sun, 14 Jan 2024 10:33:19 +0100 Subject: [PATCH 01/13] restructured interface in oder to allow replacing the existing RealtimeBox, enable/disable certain methods for pointer types, Box is now usable for pointer types --- CMakeLists.txt | 1 + .../realtime_tools/realtime_box_best_effort.h | 87 ++++++++++++++++--- test/realtime_box_best_effort_tests.cpp | 37 ++++++-- 3 files changed, 103 insertions(+), 22 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 63bd9b67..454f9616 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,6 +9,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS rclcpp rclcpp_action Threads + rcpputils ) find_package(ament_cmake REQUIRED) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 07995c51..7b7ed0f9 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -1,18 +1,22 @@ #pragma once -#include - #include +#include #include +#include namespace realtime_tools { +template +constexpr auto is_ptr_or_smart_ptr = rcpputils::is_pointer::value; + /*! A Box that ensures thread safe access to the boxed contents. Access is best effort. If it can not lock it will return. - Note: Be carefull with pointers as this implementation will actually just copy the pointer - See the tests for an example on how to work with pointers + NOTE about pointers: + You can use pointers with this box but the access will be different. + Only use the get/set methods that take function pointer for accessing the internal value. */ template class RealtimeBoxBestEffort @@ -42,7 +46,8 @@ class RealtimeBoxBestEffort * @brief set a new content with best effort * @return false if mutex could not be locked */ - bool set(const T & value) + template + typename std::enable_if_t, bool> trySet(const T & value) { std::unique_lock guard(lock_, std::defer_lock); if (!guard.try_lock()) { @@ -51,11 +56,23 @@ class RealtimeBoxBestEffort value_ = value; return true; } + + bool trySet(const std::function & func) + { + std::unique_lock guard(lock_, std::defer_lock); + if (!guard.try_lock()) { + return false; + } + + func(value_); + return true; + } /** * @brief get the content with best effort * @return std::nullopt if content could not be access, otherwise the content is returned */ - [[nodiscard]] std::optional get() const + template + [[nodiscard]] typename std::enable_if_t, std::optional> tryGet() const { std::unique_lock guard(lock_, std::defer_lock); if (!guard.try_lock()) { @@ -64,36 +81,80 @@ class RealtimeBoxBestEffort return value_; } + bool tryGet(const std::is_function & func) + { + std::unique_lock guard(lock_, std::defer_lock); + if (!guard.try_lock()) { + return false; + } + + func(value_); + return true; + } + /** * @brief set the content and wait until the mutex could be locked (RealtimeBox behaviour) * @return true */ - bool setNonRT(const T & value) + template + typename std::enable_if_t, void> set(const T & value) { std::lock_guard guard(lock_); value_ = value; - //Also return a bool in order to mimic the behaviour from 'set' - return true; } + + void set(const std::function & func) + { + std::lock_guard guard(lock_); + func(value_); + } + /** * @brief get the content and wait until the mutex could be locked (RealtimeBox behaviour) * @return copy of the value */ - [[nodiscard]] T getNonRT() const + template + [[nodiscard]] typename std::enable_if_t, U> get() const + { + std::lock_guard guard(lock_); + return value_; + } + /** + * @brief get the content and wait until the mutex could be locked + * @note same signature as in the existing RealtimeBox + */ + template + typename std::enable_if_t, void> get(T & in) const { std::lock_guard guard(lock_); return value_; } + + void get(const std::function & func) + { + std::lock_guard guard(lock_); + func(value_); + } + //Make the usage easier by providing a custom assignment operator and a custom conversion operator //Only to be used from non-RT! - void operator=(const T & value) { set(value); } + template + typename std::enable_if_t, void> operator=(const T & value) + { + set(value); + } + template >> [[nodiscard]] operator T() const { //Only makes sense with the getNonRT method otherwise we would return an std::optional - return getNonRT(); + return get(); + } + template >> + [[nodiscard]] operator std::optional() const + { + return tryGet(); } - [[nodiscard]] operator std::optional() const { return get(); } //In case one wants to actually use a pointer in this implementation we allow accessing the lock directly. //Note: Be carefull with lock.unlock(). It may only be called from the thread that locked the mutext! diff --git a/test/realtime_box_best_effort_tests.cpp b/test/realtime_box_best_effort_tests.cpp index 06820f07..b2797f78 100644 --- a/test/realtime_box_best_effort_tests.cpp +++ b/test/realtime_box_best_effort_tests.cpp @@ -29,7 +29,7 @@ TEST(RealtimeBoxBestEffort, empty_construct) { RealtimeBoxBestEffort box; - auto value = box.getNonRT(); + auto value = box.get(); EXPECT_EQ(value.a, 10); EXPECT_EQ(value.str, "hallo"); } @@ -41,7 +41,7 @@ TEST(RealtimeBoxBestEffort, default_construct) RealtimeBoxBestEffort box(data); - auto value = box.getNonRT(); + auto value = box.get(); EXPECT_EQ(value.a, 100); EXPECT_EQ(value.str, "hallo"); } @@ -50,7 +50,7 @@ TEST(RealtimeBoxBestEffort, non_default_constructable) { RealtimeBoxBestEffort box(NonDefaultConstructable(-10, "hello")); - auto value = box.getNonRT(); + auto value = box.get(); EXPECT_EQ(value.a, -10); EXPECT_EQ(value.str, "hello"); } @@ -59,7 +59,7 @@ TEST(RealtimeBoxBestEffort, initializer_list) { RealtimeBoxBestEffort box({1, 2, 3}); - auto value = box.getNonRT(); + auto value = box.get(); EXPECT_EQ(value.data[0], 1); EXPECT_EQ(value.data[1], 2); EXPECT_EQ(value.data[2], 3); @@ -73,7 +73,7 @@ TEST(RealtimeBoxBestEffort, assignment_operator) //Assignement operator is always non RT! box = data; - auto value = box.getNonRT(); + auto value = box.get(); EXPECT_EQ(value.a, 1000); } TEST(RealtimeBoxBestEffort, typecast_operator) @@ -99,10 +99,29 @@ TEST(RealtimeBoxBestEffort, pointer_type) int * ptr = &a; RealtimeBoxBestEffort box(ptr); + //This does not and should not compile! + //auto value = box.get(); - auto value = box.getNonRT(); + //Instead access it via a passed function. This assues that we access the data within the scope of the lock + box.get([](const auto & i) { EXPECT_EQ(*i, 100); }); - //Correctly working with pointer types is nasty... - std::lock_guard guard(box.getMutex()); - EXPECT_EQ(*value, 100); + box.set([](auto & i) { *i = 200; }); + + box.get([](const auto & i) { EXPECT_EQ(*i, 200); }); +} + +TEST(RealtimeBoxBestEffort, smart_ptr_type) +{ + std::shared_ptr ptr = std::make_shared(100); + + RealtimeBoxBestEffort box(ptr); + //This does not and should not compile! + //auto value = box.get(); + + //Instead access it via a passed function. This assues that we access the data within the scope of the lock + box.get([](const auto & i) { EXPECT_EQ(*i, 100); }); + + box.set([](auto & i) { *i = 200; }); + + box.get([](const auto & i) { EXPECT_EQ(*i, 200); }); } \ No newline at end of file From 613c55b487b91bbe2609b19dbd2ea3cfdc803c90 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Sun, 14 Jan 2024 10:43:31 +0100 Subject: [PATCH 02/13] added some additional comments --- .../realtime_tools/realtime_box_best_effort.h | 24 +++++++++++++++---- 1 file changed, 19 insertions(+), 5 deletions(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 7b7ed0f9..0fc3fc17 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -29,7 +29,6 @@ class RealtimeBoxBestEffort using mutex_t = mutex_type; using type = T; //Provide various constructors - constexpr explicit RealtimeBoxBestEffort(const T & init = T{}) : value_(init) {} constexpr explicit RealtimeBoxBestEffort(const T && init) : value_(std::move(init)) {} @@ -45,6 +44,7 @@ class RealtimeBoxBestEffort /** * @brief set a new content with best effort * @return false if mutex could not be locked + * @note disabled for pointer types */ template typename std::enable_if_t, bool> trySet(const T & value) @@ -56,7 +56,11 @@ class RealtimeBoxBestEffort value_ = value; return true; } - + /** + * @brief access the content readable with best effort + * @return false if the mutex could not be locked + * @note only safe way to access pointer type content (rw) + */ bool trySet(const std::function & func) { std::unique_lock guard(lock_, std::defer_lock); @@ -80,7 +84,11 @@ class RealtimeBoxBestEffort } return value_; } - + /** + * @brief access the content (r) with best effort + * @return false if the mutex could not be locked + * @note only safe way to access pointer type content (r) + */ bool tryGet(const std::is_function & func) { std::unique_lock guard(lock_, std::defer_lock); @@ -102,7 +110,9 @@ class RealtimeBoxBestEffort std::lock_guard guard(lock_); value_ = value; } - + /** + * @brief access the content (rw) and wait until the mutex could locked + */ void set(const std::function & func) { std::lock_guard guard(lock_); @@ -129,7 +139,11 @@ class RealtimeBoxBestEffort std::lock_guard guard(lock_); return value_; } - + /** + * @brief access the content (r) and wait until the mutex could be locked + * @note only safe way to access pointer type content (r) + * @note same signature as in the existing RealtimeBox + */ void get(const std::function & func) { std::lock_guard guard(lock_); From 93e14012946f607f1c6a38816cb34eb6b7fec58b Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Sun, 14 Jan 2024 12:31:48 +0100 Subject: [PATCH 03/13] fix bug --- include/realtime_tools/realtime_box_best_effort.h | 2 +- test/realtime_box_best_effort_tests.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 0fc3fc17..6db417e5 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -89,7 +89,7 @@ class RealtimeBoxBestEffort * @return false if the mutex could not be locked * @note only safe way to access pointer type content (r) */ - bool tryGet(const std::is_function & func) + bool tryGet(const std::function & func) { std::unique_lock guard(lock_, std::defer_lock); if (!guard.try_lock()) { diff --git a/test/realtime_box_best_effort_tests.cpp b/test/realtime_box_best_effort_tests.cpp index b2797f78..9e66014f 100644 --- a/test/realtime_box_best_effort_tests.cpp +++ b/test/realtime_box_best_effort_tests.cpp @@ -108,6 +108,8 @@ TEST(RealtimeBoxBestEffort, pointer_type) box.set([](auto & i) { *i = 200; }); box.get([](const auto & i) { EXPECT_EQ(*i, 200); }); + + box.tryGet([](const auto &i){EXPECT_EQ(*i,200);}); } TEST(RealtimeBoxBestEffort, smart_ptr_type) From fc2e4a2595484dbafbc156a0f0851e69aa35f5be Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Sun, 14 Jan 2024 12:40:00 +0100 Subject: [PATCH 04/13] fixed wrong return type in templated method --- include/realtime_tools/realtime_box_best_effort.h | 2 +- test/realtime_box_best_effort_tests.cpp | 15 +++++++++++++++ 2 files changed, 16 insertions(+), 1 deletion(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 6db417e5..f81762f9 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -137,7 +137,7 @@ class RealtimeBoxBestEffort typename std::enable_if_t, void> get(T & in) const { std::lock_guard guard(lock_); - return value_; + in = value_; } /** * @brief access the content (r) and wait until the mutex could be locked diff --git a/test/realtime_box_best_effort_tests.cpp b/test/realtime_box_best_effort_tests.cpp index 9e66014f..1e0642c0 100644 --- a/test/realtime_box_best_effort_tests.cpp +++ b/test/realtime_box_best_effort_tests.cpp @@ -54,6 +54,21 @@ TEST(RealtimeBoxBestEffort, non_default_constructable) EXPECT_EQ(value.a, -10); EXPECT_EQ(value.str, "hello"); } +TEST(RealtimeBoxBestEffort, standard_get) +{ + RealtimeBoxBestEffort box(DefaultConstructable{.a=1000}); + + DefaultConstructable data; + box.get(data); + EXPECT_EQ(data.a,1000); + data.a = 10000; + + + box.set(data); + + auto value = box.get(); + EXPECT_EQ(value.a, 10000); +} TEST(RealtimeBoxBestEffort, initializer_list) { From dce1458bac2e6d7e1ad4d5430ee2e1fbdd925170 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Tue, 16 Jan 2024 11:03:53 +0100 Subject: [PATCH 05/13] added copyright notice --- .../realtime_tools/realtime_box_best_effort.h | 32 ++++++++++++++- test/realtime_box_best_effort_tests.cpp | 41 ++++++++++++++++--- 2 files changed, 66 insertions(+), 7 deletions(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index f81762f9..414d2426 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -1,3 +1,33 @@ +// Copyright (c) 2024, Lennart Nachtigall +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// * Neither the name of the Willow Garage, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +// Author: Lennart Nachtigall + #pragma once #include @@ -179,4 +209,4 @@ class RealtimeBoxBestEffort T value_; mutable mutex_t lock_; }; -} // namespace realtime_tools \ No newline at end of file +} // namespace realtime_tools diff --git a/test/realtime_box_best_effort_tests.cpp b/test/realtime_box_best_effort_tests.cpp index 1e0642c0..c08b1665 100644 --- a/test/realtime_box_best_effort_tests.cpp +++ b/test/realtime_box_best_effort_tests.cpp @@ -1,3 +1,33 @@ +// Copyright (c) 2024, Lennart Nachtigall +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// * Neither the name of the Willow Garage, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +// Author: Lennart Nachtigall + #include #include @@ -56,18 +86,17 @@ TEST(RealtimeBoxBestEffort, non_default_constructable) } TEST(RealtimeBoxBestEffort, standard_get) { - RealtimeBoxBestEffort box(DefaultConstructable{.a=1000}); + RealtimeBoxBestEffort box(DefaultConstructable{.a = 1000}); DefaultConstructable data; box.get(data); - EXPECT_EQ(data.a,1000); + EXPECT_EQ(data.a, 1000); data.a = 10000; - box.set(data); auto value = box.get(); - EXPECT_EQ(value.a, 10000); + EXPECT_EQ(value.a, 10000); } TEST(RealtimeBoxBestEffort, initializer_list) @@ -124,7 +153,7 @@ TEST(RealtimeBoxBestEffort, pointer_type) box.get([](const auto & i) { EXPECT_EQ(*i, 200); }); - box.tryGet([](const auto &i){EXPECT_EQ(*i,200);}); + box.tryGet([](const auto & i) { EXPECT_EQ(*i, 200); }); } TEST(RealtimeBoxBestEffort, smart_ptr_type) @@ -141,4 +170,4 @@ TEST(RealtimeBoxBestEffort, smart_ptr_type) box.set([](auto & i) { *i = 200; }); box.get([](const auto & i) { EXPECT_EQ(*i, 200); }); -} \ No newline at end of file +} From eaedafe027879e9f5e74e81eb519a07586dd9f29 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Tue, 23 Jan 2024 07:32:08 +0100 Subject: [PATCH 06/13] Fixed issues due to merge with master --- CMakeLists.txt | 3 +++ include/realtime_tools/realtime_box_best_effort.h | 6 +++--- test/realtime_box_best_effort_tests.cpp | 2 +- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index de507fbe..21f2e96e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,6 +46,9 @@ if(BUILD_TESTING) ament_add_gmock(realtime_box_tests test/realtime_box_tests.cpp) target_link_libraries(realtime_box_tests realtime_tools) + ament_add_gmock(realtime_box_best_effort_tests test/realtime_box_best_effort_tests.cpp) + target_link_libraries(realtime_box_best_effort_tests realtime_tools) + ament_add_gmock(realtime_buffer_tests test/realtime_buffer_tests.cpp) target_link_libraries(realtime_buffer_tests realtime_tools) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 414d2426..7cd3c79e 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -41,11 +41,11 @@ template constexpr auto is_ptr_or_smart_ptr = rcpputils::is_pointer::value; /*! - A Box that ensures thread safe access to the boxed contents. + A Box that ensures thread safe access to the boxed contents. Access is best effort. If it can not lock it will return. NOTE about pointers: - You can use pointers with this box but the access will be different. + You can use pointers with this box but the access will be different. Only use the get/set methods that take function pointer for accessing the internal value. */ template @@ -115,7 +115,7 @@ class RealtimeBoxBestEffort return value_; } /** - * @brief access the content (r) with best effort + * @brief access the content (r) with best effort * @return false if the mutex could not be locked * @note only safe way to access pointer type content (r) */ diff --git a/test/realtime_box_best_effort_tests.cpp b/test/realtime_box_best_effort_tests.cpp index c08b1665..887644d7 100644 --- a/test/realtime_box_best_effort_tests.cpp +++ b/test/realtime_box_best_effort_tests.cpp @@ -114,7 +114,7 @@ TEST(RealtimeBoxBestEffort, assignment_operator) DefaultConstructable data; data.a = 1000; RealtimeBoxBestEffort box; - //Assignement operator is always non RT! + //Assignment operator is always non RT! box = data; auto value = box.get(); From a22d150703383e9c7249c40684691d9677879c09 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Thu, 25 Jan 2024 07:33:49 +0100 Subject: [PATCH 07/13] fixed spelling mistake --- include/realtime_tools/realtime_box_best_effort.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 7cd3c79e..7f057557 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -201,7 +201,7 @@ class RealtimeBoxBestEffort } //In case one wants to actually use a pointer in this implementation we allow accessing the lock directly. - //Note: Be carefull with lock.unlock(). It may only be called from the thread that locked the mutext! + //Note: Be careful with lock.unlock(). It may only be called from the thread that locked the mutext! [[nodiscard]] const mutex_t & getMutex() const { return lock_; } [[nodiscard]] mutex_t & getMutex() { return lock_; } From 186b4aaf78cc3f3b4bd24d9278456b3b1f4278c8 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Thu, 25 Jan 2024 10:54:49 +0100 Subject: [PATCH 08/13] fixed ament_cpplint issues --- .../realtime_tools/realtime_box_best_effort.h | 18 +++++++++------ test/realtime_box_best_effort_tests.cpp | 22 ++++++++++--------- 2 files changed, 23 insertions(+), 17 deletions(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 7f057557..7934bb62 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -34,6 +34,7 @@ #include #include #include +#include namespace realtime_tools { @@ -58,11 +59,11 @@ class RealtimeBoxBestEffort public: using mutex_t = mutex_type; using type = T; - //Provide various constructors + // Provide various constructors constexpr explicit RealtimeBoxBestEffort(const T & init = T{}) : value_(init) {} constexpr explicit RealtimeBoxBestEffort(const T && init) : value_(std::move(init)) {} - //Only enabled for types that can be constructed from an initializer list + // Only enabled for types that can be constructed from an initializer list template constexpr RealtimeBoxBestEffort( const std::initializer_list & init, @@ -180,8 +181,9 @@ class RealtimeBoxBestEffort func(value_); } - //Make the usage easier by providing a custom assignment operator and a custom conversion operator - //Only to be used from non-RT! + // Make the usage easier by providing a custom assignment operator + // and a custom conversion operator + // Only to be used from non-RT! template typename std::enable_if_t, void> operator=(const T & value) { @@ -191,7 +193,7 @@ class RealtimeBoxBestEffort template >> [[nodiscard]] operator T() const { - //Only makes sense with the getNonRT method otherwise we would return an std::optional + // Only makes sense with the getNonRT method otherwise we would return an std::optional return get(); } template >> @@ -200,8 +202,10 @@ class RealtimeBoxBestEffort return tryGet(); } - //In case one wants to actually use a pointer in this implementation we allow accessing the lock directly. - //Note: Be careful with lock.unlock(). It may only be called from the thread that locked the mutext! + // In case one wants to actually use a pointer + // in this implementation we allow accessing the lock directly. + // Note: Be careful with lock.unlock(). + // It may only be called from the thread that locked the mutext! [[nodiscard]] const mutex_t & getMutex() const { return lock_; } [[nodiscard]] mutex_t & getMutex() { return lock_; } diff --git a/test/realtime_box_best_effort_tests.cpp b/test/realtime_box_best_effort_tests.cpp index 887644d7..16b869cc 100644 --- a/test/realtime_box_best_effort_tests.cpp +++ b/test/realtime_box_best_effort_tests.cpp @@ -53,7 +53,7 @@ struct FromInitializerList std::array data; }; -using namespace realtime_tools; +using realtime_tools::RealtimeBoxBestEffort; TEST(RealtimeBoxBestEffort, empty_construct) { @@ -114,7 +114,7 @@ TEST(RealtimeBoxBestEffort, assignment_operator) DefaultConstructable data; data.a = 1000; RealtimeBoxBestEffort box; - //Assignment operator is always non RT! + // Assignment operator is always non RT! box = data; auto value = box.get(); @@ -124,12 +124,12 @@ TEST(RealtimeBoxBestEffort, typecast_operator) { RealtimeBoxBestEffort box(DefaultConstructable{.a = 100, .str = ""}); - //Use non RT access + // Use non RT access DefaultConstructable data = box; EXPECT_EQ(data.a, 100); - //Use RT access -> returns std::nullopt if the mutex could not be locked + // Use RT access -> returns std::nullopt if the mutex could not be locked std::optional rt_data_access = box; if (rt_data_access) { @@ -143,10 +143,11 @@ TEST(RealtimeBoxBestEffort, pointer_type) int * ptr = &a; RealtimeBoxBestEffort box(ptr); - //This does not and should not compile! - //auto value = box.get(); + // This does not and should not compile! + // auto value = box.get(); - //Instead access it via a passed function. This assues that we access the data within the scope of the lock + // Instead access it via a passed function. + // This assures that we access the data within the scope of the lock box.get([](const auto & i) { EXPECT_EQ(*i, 100); }); box.set([](auto & i) { *i = 200; }); @@ -161,10 +162,11 @@ TEST(RealtimeBoxBestEffort, smart_ptr_type) std::shared_ptr ptr = std::make_shared(100); RealtimeBoxBestEffort box(ptr); - //This does not and should not compile! - //auto value = box.get(); + // This does not and should not compile! + // auto value = box.get(); - //Instead access it via a passed function. This assues that we access the data within the scope of the lock + // Instead access it via a passed function. + // This assures that we access the data within the scope of the lock box.get([](const auto & i) { EXPECT_EQ(*i, 100); }); box.set([](auto & i) { *i = 200; }); From a8b3f8a276b0ffe1c55076300a8d25e11bcaff95 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Thu, 25 Jan 2024 11:58:09 +0100 Subject: [PATCH 09/13] fixed last remaining cpplint issue --- include/realtime_tools/realtime_box_best_effort.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 7934bb62..8254c583 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -33,8 +33,10 @@ #include #include #include -#include #include + +#include + namespace realtime_tools { From 69b224c91c5adeba910e5d894fcc265e65361acf Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Thu, 25 Jan 2024 14:32:41 +0100 Subject: [PATCH 10/13] suppress cppcheck missingReturn --- include/realtime_tools/realtime_box_best_effort.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 8254c583..5e91c80d 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -141,6 +141,7 @@ class RealtimeBoxBestEffort typename std::enable_if_t, void> set(const T & value) { std::lock_guard guard(lock_); + // cppcheck-suppress missingReturn value_ = value; } /** @@ -170,6 +171,7 @@ class RealtimeBoxBestEffort typename std::enable_if_t, void> get(T & in) const { std::lock_guard guard(lock_); + // cppcheck-suppress missingReturn in = value_; } /** From 220111a4155e7327fcb353bccf5ad570add29a90 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Wed, 28 Feb 2024 10:45:17 +0100 Subject: [PATCH 11/13] try to resolve comments wherever possible --- .../realtime_tools/realtime_box_best_effort.h | 58 +++++++++++-------- 1 file changed, 35 insertions(+), 23 deletions(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 5e91c80d..5a8c7c29 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -28,7 +28,8 @@ // Author: Lennart Nachtigall -#pragma once +#ifndef REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_H_ +#define REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_H_ #include #include @@ -75,10 +76,10 @@ class RealtimeBoxBestEffort } /** - * @brief set a new content with best effort - * @return false if mutex could not be locked - * @note disabled for pointer types - */ + * @brief set a new content with best effort + * @return false if mutex could not be locked + * @note disabled for pointer types + */ template typename std::enable_if_t, bool> trySet(const T & value) { @@ -93,7 +94,7 @@ class RealtimeBoxBestEffort * @brief access the content readable with best effort * @return false if the mutex could not be locked * @note only safe way to access pointer type content (rw) - */ + */ bool trySet(const std::function & func) { std::unique_lock guard(lock_, std::defer_lock); @@ -105,9 +106,9 @@ class RealtimeBoxBestEffort return true; } /** - * @brief get the content with best effort - * @return std::nullopt if content could not be access, otherwise the content is returned - */ + * @brief get the content with best effort + * @return std::nullopt if content could not be access, otherwise the content is returned + */ template [[nodiscard]] typename std::enable_if_t, std::optional> tryGet() const { @@ -121,7 +122,7 @@ class RealtimeBoxBestEffort * @brief access the content (r) with best effort * @return false if the mutex could not be locked * @note only safe way to access pointer type content (r) - */ + */ bool tryGet(const std::function & func) { std::unique_lock guard(lock_, std::defer_lock); @@ -134,9 +135,9 @@ class RealtimeBoxBestEffort } /** - * @brief set the content and wait until the mutex could be locked (RealtimeBox behaviour) - * @return true - */ + * @brief set the content and wait until the mutex could be locked (RealtimeBox behavior) + * @return true + */ template typename std::enable_if_t, void> set(const T & value) { @@ -146,7 +147,7 @@ class RealtimeBoxBestEffort } /** * @brief access the content (rw) and wait until the mutex could locked - */ + */ void set(const std::function & func) { std::lock_guard guard(lock_); @@ -154,9 +155,9 @@ class RealtimeBoxBestEffort } /** - * @brief get the content and wait until the mutex could be locked (RealtimeBox behaviour) - * @return copy of the value - */ + * @brief get the content and wait until the mutex could be locked (RealtimeBox behaviour) + * @return copy of the value + */ template [[nodiscard]] typename std::enable_if_t, U> get() const { @@ -166,7 +167,7 @@ class RealtimeBoxBestEffort /** * @brief get the content and wait until the mutex could be locked * @note same signature as in the existing RealtimeBox - */ + */ template typename std::enable_if_t, void> get(T & in) const { @@ -178,28 +179,37 @@ class RealtimeBoxBestEffort * @brief access the content (r) and wait until the mutex could be locked * @note only safe way to access pointer type content (r) * @note same signature as in the existing RealtimeBox - */ + */ void get(const std::function & func) { std::lock_guard guard(lock_); func(value_); } - // Make the usage easier by providing a custom assignment operator - // and a custom conversion operator - // Only to be used from non-RT! + /** + * @brief provide a custom assignment operator for easier usage + * @note only to be used from non-RT! + */ template typename std::enable_if_t, void> operator=(const T & value) { set(value); } + /** + * @brief provide a custom conversion operator + * @note Can only be used from non-RT! + */ template >> [[nodiscard]] operator T() const { // Only makes sense with the getNonRT method otherwise we would return an std::optional return get(); } + /** + * @brief provide a custom conversion operator + * @note Can be used from non-RT and RT contexts + */ template >> [[nodiscard]] operator std::optional() const { @@ -209,7 +219,7 @@ class RealtimeBoxBestEffort // In case one wants to actually use a pointer // in this implementation we allow accessing the lock directly. // Note: Be careful with lock.unlock(). - // It may only be called from the thread that locked the mutext! + // It may only be called from the thread that locked the mutex! [[nodiscard]] const mutex_t & getMutex() const { return lock_; } [[nodiscard]] mutex_t & getMutex() { return lock_; } @@ -218,3 +228,5 @@ class RealtimeBoxBestEffort mutable mutex_t lock_; }; } // namespace realtime_tools + +#endif //REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_H_ From c2900a3651d212e25ec1f2a4811f1eb9b12bdcb3 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Fri, 1 Mar 2024 10:32:37 +0100 Subject: [PATCH 12/13] Should fix pre-commit formatting warning Should fix pre-commit formatting warning --- include/realtime_tools/realtime_box_best_effort.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index 5a8c7c29..fae1c3c9 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -229,4 +229,4 @@ class RealtimeBoxBestEffort }; } // namespace realtime_tools -#endif //REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_H_ +#endif // REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_H_ From 4fce1842977971ae5a7400f48692c51ed4d42743 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Fri, 22 Mar 2024 08:01:23 +0100 Subject: [PATCH 13/13] Implemented suggestions --- .../realtime_tools/realtime_box_best_effort.h | 18 +++++++++--------- test/realtime_box_best_effort_tests.cpp | 4 ++++ 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/include/realtime_tools/realtime_box_best_effort.h b/include/realtime_tools/realtime_box_best_effort.h index fae1c3c9..4763c5a0 100644 --- a/include/realtime_tools/realtime_box_best_effort.h +++ b/include/realtime_tools/realtime_box_best_effort.h @@ -83,7 +83,7 @@ class RealtimeBoxBestEffort template typename std::enable_if_t, bool> trySet(const T & value) { - std::unique_lock guard(lock_, std::defer_lock); + std::unique_lock guard(lock_, std::defer_lock); if (!guard.try_lock()) { return false; } @@ -97,7 +97,7 @@ class RealtimeBoxBestEffort */ bool trySet(const std::function & func) { - std::unique_lock guard(lock_, std::defer_lock); + std::unique_lock guard(lock_, std::defer_lock); if (!guard.try_lock()) { return false; } @@ -112,7 +112,7 @@ class RealtimeBoxBestEffort template [[nodiscard]] typename std::enable_if_t, std::optional> tryGet() const { - std::unique_lock guard(lock_, std::defer_lock); + std::unique_lock guard(lock_, std::defer_lock); if (!guard.try_lock()) { return std::nullopt; } @@ -125,7 +125,7 @@ class RealtimeBoxBestEffort */ bool tryGet(const std::function & func) { - std::unique_lock guard(lock_, std::defer_lock); + std::unique_lock guard(lock_, std::defer_lock); if (!guard.try_lock()) { return false; } @@ -141,7 +141,7 @@ class RealtimeBoxBestEffort template typename std::enable_if_t, void> set(const T & value) { - std::lock_guard guard(lock_); + std::lock_guard guard(lock_); // cppcheck-suppress missingReturn value_ = value; } @@ -150,7 +150,7 @@ class RealtimeBoxBestEffort */ void set(const std::function & func) { - std::lock_guard guard(lock_); + std::lock_guard guard(lock_); func(value_); } @@ -161,7 +161,7 @@ class RealtimeBoxBestEffort template [[nodiscard]] typename std::enable_if_t, U> get() const { - std::lock_guard guard(lock_); + std::lock_guard guard(lock_); return value_; } /** @@ -171,7 +171,7 @@ class RealtimeBoxBestEffort template typename std::enable_if_t, void> get(T & in) const { - std::lock_guard guard(lock_); + std::lock_guard guard(lock_); // cppcheck-suppress missingReturn in = value_; } @@ -182,7 +182,7 @@ class RealtimeBoxBestEffort */ void get(const std::function & func) { - std::lock_guard guard(lock_); + std::lock_guard guard(lock_); func(value_); } diff --git a/test/realtime_box_best_effort_tests.cpp b/test/realtime_box_best_effort_tests.cpp index 16b869cc..1cda8186 100644 --- a/test/realtime_box_best_effort_tests.cpp +++ b/test/realtime_box_best_effort_tests.cpp @@ -172,4 +172,8 @@ TEST(RealtimeBoxBestEffort, smart_ptr_type) box.set([](auto & i) { *i = 200; }); box.get([](const auto & i) { EXPECT_EQ(*i, 200); }); + + box.trySet([](const auto & p) { *p = 10; }); + + box.tryGet([](const auto & p) { EXPECT_EQ(*p, 10); }); }