Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added a new implementation of the RealtimeBox with added best effort behaviour #139

Merged
merged 19 commits into from
Apr 4, 2024
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
rclcpp
rclcpp_action
Threads
rcpputils
)

find_package(ament_cmake REQUIRED)
Expand Down
135 changes: 120 additions & 15 deletions include/realtime_tools/realtime_box_best_effort.h
Original file line number Diff line number Diff line change
@@ -1,18 +1,52 @@
#pragma once
// 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.

#include <mutex>
// Author: Lennart Nachtigall

#pragma once
firesurfer marked this conversation as resolved.
Show resolved Hide resolved

#include <initializer_list>
#include <mutex>
#include <optional>
#include <rcpputils/pointer_traits.hpp>
namespace realtime_tools
{

template <typename T>
constexpr auto is_ptr_or_smart_ptr = rcpputils::is_pointer<T>::value;
christophfroehlich marked this conversation as resolved.
Show resolved Hide resolved

/*!
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 T, typename mutex_type = std::mutex>
class RealtimeBoxBestEffort
Expand All @@ -25,7 +59,6 @@ class RealtimeBoxBestEffort
using mutex_t = mutex_type;
using type = T;
saikishor marked this conversation as resolved.
Show resolved Hide resolved
//Provide various constructors

constexpr explicit RealtimeBoxBestEffort(const T & init = T{}) : value_(init) {}
constexpr explicit RealtimeBoxBestEffort(const T && init) : value_(std::move(init)) {}

Expand All @@ -41,8 +74,10 @@ class RealtimeBoxBestEffort
/**
* @brief set a new content with best effort
* @return false if mutex could not be locked
* @note disabled for pointer types
*/
bool set(const T & value)
template <typename U = T>
typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, bool> trySet(const T & value)
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
{
std::unique_lock<std::mutex> guard(lock_, std::defer_lock);
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
if (!guard.try_lock()) {
Expand All @@ -51,49 +86,119 @@ 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<void(T &)> & func)
{
std::unique_lock<std::mutex> guard(lock_, std::defer_lock);
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
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<T> get() const
template <typename U = T>
[[nodiscard]] typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, std::optional<U>> tryGet() const
saikishor marked this conversation as resolved.
Show resolved Hide resolved
{
std::unique_lock<std::mutex> guard(lock_, std::defer_lock);
saikishor marked this conversation as resolved.
Show resolved Hide resolved
if (!guard.try_lock()) {
return std::nullopt;
}
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::function<void(const T &)> & func)
{
std::unique_lock<std::mutex> guard(lock_, std::defer_lock);
saikishor marked this conversation as resolved.
Show resolved Hide resolved
if (!guard.try_lock()) {
return false;
}

func(value_);
return true;
}

/**
* @brief set the content and wait until the mutex could be locked (RealtimeBox behaviour)
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
* @return true
*/
bool setNonRT(const T & value)
template <typename U = T>
typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> set(const T & value)
saikishor marked this conversation as resolved.
Show resolved Hide resolved
{
std::lock_guard<std::mutex> guard(lock_);
saikishor marked this conversation as resolved.
Show resolved Hide resolved
value_ = value;
//Also return a bool in order to mimic the behaviour from 'set'
return true;
}
/**
* @brief access the content (rw) and wait until the mutex could locked
*/
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
void set(const std::function<void(T &)> & func)
{
std::lock_guard<std::mutex> guard(lock_);
saikishor marked this conversation as resolved.
Show resolved Hide resolved
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 <typename U = T>
[[nodiscard]] typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, U> get() const
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
{
std::lock_guard<std::mutex> guard(lock_);
saikishor marked this conversation as resolved.
Show resolved Hide resolved
return value_;
}
/**
* @brief get the content and wait until the mutex could be locked
* @note same signature as in the existing RealtimeBox<T>
*/
template <typename U = T>
typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> get(T & in) const
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
{
std::lock_guard<std::mutex> guard(lock_);
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
in = 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<T>
*/
void get(const std::function<void(const T &)> & func)
{
std::lock_guard<std::mutex> guard(lock_);
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
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 U = T>
typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> operator=(const T & value)
firesurfer marked this conversation as resolved.
Show resolved Hide resolved
{
set(value);
}

template <typename U = T, typename = typename std::enable_if_t<!is_ptr_or_smart_ptr<U>>>
[[nodiscard]] operator T() const
{
//Only makes sense with the getNonRT method otherwise we would return an std::optional
return getNonRT();
return get();
}
template <typename U = T, typename = typename std::enable_if_t<!is_ptr_or_smart_ptr<U>>>
[[nodiscard]] operator std::optional<T>() const
{
return tryGet();
}
[[nodiscard]] operator std::optional<T>() 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!
Expand All @@ -104,4 +209,4 @@ class RealtimeBoxBestEffort
T value_;
mutable mutex_t lock_;
};
} // namespace realtime_tools
} // namespace realtime_tools
85 changes: 75 additions & 10 deletions test/realtime_box_best_effort_tests.cpp
Original file line number Diff line number Diff line change
@@ -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 <gmock/gmock.h>
#include <realtime_tools/realtime_box_best_effort.h>

Expand Down Expand Up @@ -29,7 +59,7 @@ TEST(RealtimeBoxBestEffort, empty_construct)
{
RealtimeBoxBestEffort<DefaultConstructable> box;

auto value = box.getNonRT();
auto value = box.get();
EXPECT_EQ(value.a, 10);
EXPECT_EQ(value.str, "hallo");
}
Expand All @@ -41,7 +71,7 @@ TEST(RealtimeBoxBestEffort, default_construct)

RealtimeBoxBestEffort<DefaultConstructable> box(data);

auto value = box.getNonRT();
auto value = box.get();
EXPECT_EQ(value.a, 100);
EXPECT_EQ(value.str, "hallo");
}
Expand All @@ -50,16 +80,30 @@ TEST(RealtimeBoxBestEffort, non_default_constructable)
{
RealtimeBoxBestEffort<NonDefaultConstructable> box(NonDefaultConstructable(-10, "hello"));

auto value = box.getNonRT();
auto value = box.get();
EXPECT_EQ(value.a, -10);
EXPECT_EQ(value.str, "hello");
}
TEST(RealtimeBoxBestEffort, standard_get)
{
RealtimeBoxBestEffort<DefaultConstructable> 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)
{
RealtimeBoxBestEffort<FromInitializerList> 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);
Expand All @@ -73,7 +117,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)
Expand All @@ -99,10 +143,31 @@ TEST(RealtimeBoxBestEffort, pointer_type)
int * ptr = &a;

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; });
firesurfer marked this conversation as resolved.
Show resolved Hide resolved

box.get([](const auto & i) { EXPECT_EQ(*i, 200); });

box.tryGet([](const auto & i) { EXPECT_EQ(*i, 200); });
}

TEST(RealtimeBoxBestEffort, smart_ptr_type)
{
std::shared_ptr<int> ptr = std::make_shared<int>(100);

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<decltype(box)::mutex_t> guard(box.getMutex());
EXPECT_EQ(*value, 100);
}
box.set([](auto & i) { *i = 200; });

box.get([](const auto & i) { EXPECT_EQ(*i, 200); });
}