Skip to content

Commit b96a7f8

Browse files
authored
Expand RealtimeBoxBestEffort to use priority mutexes (#454)
1 parent dd0c894 commit b96a7f8

File tree

2 files changed

+33
-20
lines changed

2 files changed

+33
-20
lines changed

include/realtime_tools/realtime_box_best_effort.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -56,8 +56,6 @@ constexpr auto is_ptr_or_smart_ptr = rcpputils::is_pointer<T>::value;
5656
template <class T, typename mutex_type = std::mutex>
5757
class RealtimeBoxBestEffort
5858
{
59-
static_assert(
60-
std::is_same_v<mutex_type, std::mutex> || std::is_same_v<mutex_type, std::recursive_mutex>);
6159
static_assert(std::is_copy_constructible_v<T>, "Passed type must be copy constructible");
6260

6361
public:

test/realtime_box_best_effort_tests.cpp

Lines changed: 33 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,8 @@
2929
// Author: Lennart Nachtigall
3030

3131
#include <gmock/gmock.h>
32+
#include <gtest/gtest.h>
33+
#include <realtime_tools/mutex.hpp>
3234
#include <realtime_tools/realtime_box_best_effort.hpp>
3335

3436
struct DefaultConstructable
@@ -53,40 +55,52 @@ struct FromInitializerList
5355
std::array<int, 3> data;
5456
};
5557

58+
// Dummy test fixture to enable parameterized template types
59+
template <typename T>
60+
class TypedRealtimeBoxBestEffort : public testing::Test
61+
{
62+
};
63+
64+
using TestTypes = ::testing::Types<
65+
std::mutex, realtime_tools::prio_inherit_mutex, realtime_tools::prio_inherit_recursive_mutex>;
66+
67+
TYPED_TEST_SUITE(TypedRealtimeBoxBestEffort, TestTypes);
68+
5669
using realtime_tools::RealtimeBoxBestEffort;
5770

58-
TEST(RealtimeBoxBestEffort, empty_construct)
71+
TYPED_TEST(TypedRealtimeBoxBestEffort, empty_construct)
5972
{
60-
RealtimeBoxBestEffort<DefaultConstructable> box;
73+
RealtimeBoxBestEffort<DefaultConstructable, TypeParam> box;
6174

6275
auto value = box.get();
6376
EXPECT_EQ(value.a, 10);
6477
EXPECT_EQ(value.str, "hallo");
6578
}
6679

67-
TEST(RealtimeBoxBestEffort, default_construct)
80+
TYPED_TEST(TypedRealtimeBoxBestEffort, default_construct)
6881
{
6982
DefaultConstructable data;
7083
data.a = 100;
7184

72-
RealtimeBoxBestEffort<DefaultConstructable> box(data);
85+
RealtimeBoxBestEffort<DefaultConstructable, TypeParam> box(data);
7386

7487
auto value = box.get();
7588
EXPECT_EQ(value.a, 100);
7689
EXPECT_EQ(value.str, "hallo");
7790
}
7891

79-
TEST(RealtimeBoxBestEffort, non_default_constructable)
92+
TYPED_TEST(TypedRealtimeBoxBestEffort, non_default_constructable)
8093
{
81-
RealtimeBoxBestEffort<NonDefaultConstructable> box(NonDefaultConstructable(-10, "hello"));
94+
RealtimeBoxBestEffort<NonDefaultConstructable, TypeParam> box(
95+
NonDefaultConstructable(-10, "hello"));
8296

8397
auto value = box.get();
8498
EXPECT_EQ(value.a, -10);
8599
EXPECT_EQ(value.str, "hello");
86100
}
87-
TEST(RealtimeBoxBestEffort, standard_get)
101+
TYPED_TEST(TypedRealtimeBoxBestEffort, standard_get)
88102
{
89-
RealtimeBoxBestEffort<DefaultConstructable> box(DefaultConstructable{1000});
103+
RealtimeBoxBestEffort<DefaultConstructable, TypeParam> box(DefaultConstructable{1000});
90104

91105
DefaultConstructable data;
92106
box.get(data);
@@ -99,33 +113,34 @@ TEST(RealtimeBoxBestEffort, standard_get)
99113
EXPECT_EQ(value.a, 10000);
100114
}
101115

102-
TEST(RealtimeBoxBestEffort, initializer_list)
116+
TYPED_TEST(TypedRealtimeBoxBestEffort, initializer_list)
103117
{
104-
RealtimeBoxBestEffort<FromInitializerList> box({1, 2, 3});
118+
RealtimeBoxBestEffort<FromInitializerList, TypeParam> box({1, 2, 3});
105119

106120
auto value = box.get();
107121
EXPECT_EQ(value.data[0], 1);
108122
EXPECT_EQ(value.data[1], 2);
109123
EXPECT_EQ(value.data[2], 3);
110124
}
111125

112-
TEST(RealtimeBoxBestEffort, assignment_operator)
126+
TYPED_TEST(TypedRealtimeBoxBestEffort, assignment_operator)
113127
{
114128
DefaultConstructable data;
115129
data.a = 1000;
116-
RealtimeBoxBestEffort<DefaultConstructable> box;
130+
RealtimeBoxBestEffort<DefaultConstructable, TypeParam> box;
117131
// Assignment operator is always non RT!
118132
box = data;
119133

120134
auto value = box.get();
121135
EXPECT_EQ(value.a, 1000);
122136
}
123-
TEST(RealtimeBoxBestEffort, typecast_operator)
137+
138+
TYPED_TEST(TypedRealtimeBoxBestEffort, typecast_operator)
124139
{
125140
DefaultConstructable data_construct;
126141
data_construct.a = 100;
127142
data_construct.str = "";
128-
RealtimeBoxBestEffort box(data_construct);
143+
RealtimeBoxBestEffort<DefaultConstructable, TypeParam> box(data_construct);
129144

130145
// Use non RT access
131146
DefaultConstructable data = box;
@@ -140,12 +155,12 @@ TEST(RealtimeBoxBestEffort, typecast_operator)
140155
}
141156
}
142157

143-
TEST(RealtimeBoxBestEffort, pointer_type)
158+
TYPED_TEST(TypedRealtimeBoxBestEffort, pointer_type)
144159
{
145160
int a = 100;
146161
int * ptr = &a;
147162

148-
RealtimeBoxBestEffort box(ptr);
163+
RealtimeBoxBestEffort<int *, TypeParam> box(ptr);
149164
// This does not and should not compile!
150165
// auto value = box.get();
151166

@@ -160,11 +175,11 @@ TEST(RealtimeBoxBestEffort, pointer_type)
160175
box.tryGet([](const auto & i) { EXPECT_EQ(*i, 200); });
161176
}
162177

163-
TEST(RealtimeBoxBestEffort, smart_ptr_type)
178+
TYPED_TEST(TypedRealtimeBoxBestEffort, smart_ptr_type)
164179
{
165180
std::shared_ptr<int> ptr = std::make_shared<int>(100);
166181

167-
RealtimeBoxBestEffort box(ptr);
182+
RealtimeBoxBestEffort<std::shared_ptr<int>, TypeParam> box(ptr);
168183
// This does not and should not compile!
169184
// auto value = box.get();
170185

0 commit comments

Comments
 (0)