Skip to content

Commit 194c5b6

Browse files
bjin2364mergify[bot]
authored andcommitted
Update ThreadSafeBox Tests (#459)
(cherry picked from commit 534bfab)
1 parent 803e40b commit 194c5b6

File tree

1 file changed

+61
-37
lines changed

1 file changed

+61
-37
lines changed

realtime_tools/test/realtime_thread_safe_box_tests.cpp

Lines changed: 61 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -28,8 +28,15 @@
2828
// POSSIBILITY OF SUCH DAMAGE.
2929

3030
#include <gmock/gmock.h>
31+
#include <gtest/gtest.h>
3132

3233
#include <array>
34+
#include <mutex>
35+
36+
// Priority mutexes are not available on Windows platforms
37+
#if defined(__linux__)
38+
#include "realtime_tools/mutex.hpp"
39+
#endif
3340

3441
#include "realtime_tools/realtime_thread_safe_box.hpp"
3542

@@ -55,40 +62,57 @@ struct FromInitializerList
5562
std::array<int, 3> data;
5663
};
5764

65+
// Dummy test fixture to enable parameterized template types
66+
template <typename T>
67+
class TypedRealtimeThreadSafeBox : public testing::Test
68+
{
69+
};
70+
71+
// Priority mutexes are not available on Windows platforms
72+
#ifdef _WIN32
73+
using TestTypes = ::testing::Types<std::mutex>;
74+
#else
75+
using TestTypes = ::testing::Types<
76+
std::mutex, realtime_tools::prio_inherit_mutex, realtime_tools::prio_inherit_recursive_mutex>;
77+
#endif
78+
79+
TYPED_TEST_SUITE(TypedRealtimeThreadSafeBox, TestTypes);
80+
5881
using realtime_tools::RealtimeThreadSafeBox;
5982

60-
TEST(RealtimeThreadSafeBox, empty_construct)
83+
TYPED_TEST(TypedRealtimeThreadSafeBox, empty_construct)
6184
{
62-
RealtimeThreadSafeBox<DefaultConstructable> box;
85+
RealtimeThreadSafeBox<DefaultConstructable, TypeParam> box;
6386

6487
auto value = box.get();
6588
EXPECT_EQ(value.a, 10);
6689
EXPECT_EQ(value.str, "hallo");
6790
}
6891

69-
TEST(RealtimeThreadSafeBox, default_construct)
92+
TYPED_TEST(TypedRealtimeThreadSafeBox, default_construct)
7093
{
7194
DefaultConstructable data;
7295
data.a = 100;
7396

74-
RealtimeThreadSafeBox<DefaultConstructable> box(data);
97+
RealtimeThreadSafeBox<DefaultConstructable, TypeParam> box(data);
7598

7699
auto value = box.get();
77100
EXPECT_EQ(value.a, 100);
78101
EXPECT_EQ(value.str, "hallo");
79102
}
80103

81-
TEST(RealtimeThreadSafeBox, non_default_constructable)
104+
TYPED_TEST(TypedRealtimeThreadSafeBox, non_default_constructable)
82105
{
83-
RealtimeThreadSafeBox<NonDefaultConstructable> box(NonDefaultConstructable(-10, "hello"));
106+
RealtimeThreadSafeBox<NonDefaultConstructable, TypeParam> box(
107+
NonDefaultConstructable(-10, "hello"));
84108

85109
auto value = box.get();
86110
EXPECT_EQ(value.a, -10);
87111
EXPECT_EQ(value.str, "hello");
88112
}
89-
TEST(RealtimeThreadSafeBox, standard_get)
113+
TYPED_TEST(TypedRealtimeThreadSafeBox, standard_get)
90114
{
91-
RealtimeThreadSafeBox<DefaultConstructable> box(DefaultConstructable{1000});
115+
RealtimeThreadSafeBox<DefaultConstructable, TypeParam> box(DefaultConstructable{1000});
92116

93117
DefaultConstructable data;
94118
box.get(data);
@@ -101,30 +125,30 @@ TEST(RealtimeThreadSafeBox, standard_get)
101125
EXPECT_EQ(value.a, 10000);
102126
}
103127

104-
TEST(RealtimeThreadSafeBox, initializer_list)
128+
TYPED_TEST(TypedRealtimeThreadSafeBox, initializer_list)
105129
{
106-
RealtimeThreadSafeBox<FromInitializerList> box({1, 2, 3});
130+
RealtimeThreadSafeBox<FromInitializerList, TypeParam> box({1, 2, 3});
107131

108132
auto value = box.get();
109133
EXPECT_EQ(value.data[0], 1);
110134
EXPECT_EQ(value.data[1], 2);
111135
EXPECT_EQ(value.data[2], 3);
112136
}
113137

114-
TEST(RealtimeThreadSafeBox, assignment_operator)
138+
TYPED_TEST(TypedRealtimeThreadSafeBox, assignment_operator)
115139
{
116140
DefaultConstructable data;
117141
data.a = 1000;
118-
RealtimeThreadSafeBox<DefaultConstructable> box;
142+
RealtimeThreadSafeBox<DefaultConstructable, TypeParam> box;
119143
// Assignment operator is always non RT!
120144
box = data;
121145

122146
auto value = box.get();
123147
EXPECT_EQ(value.a, 1000);
124148
}
125-
TEST(RealtimeThreadSafeBox, typecast_operator)
149+
TYPED_TEST(TypedRealtimeThreadSafeBox, typecast_operator)
126150
{
127-
RealtimeThreadSafeBox<DefaultConstructable> box(DefaultConstructable{100, ""});
151+
RealtimeThreadSafeBox<DefaultConstructable, TypeParam> box(DefaultConstructable{100, ""});
128152

129153
// Use non RT access
130154
DefaultConstructable data = box;
@@ -139,12 +163,12 @@ TEST(RealtimeThreadSafeBox, typecast_operator)
139163
}
140164
}
141165

142-
TEST(RealtimeThreadSafeBox, pointer_type)
166+
TYPED_TEST(TypedRealtimeThreadSafeBox, pointer_type)
143167
{
144168
int a = 100;
145169
int * ptr = &a;
146170

147-
RealtimeThreadSafeBox<int *> box(ptr);
171+
RealtimeThreadSafeBox<int *, TypeParam> box(ptr);
148172
// This does not and should not compile!
149173
// auto value = box.get();
150174

@@ -159,11 +183,11 @@ TEST(RealtimeThreadSafeBox, pointer_type)
159183
box.try_get([](const auto & i) { EXPECT_EQ(*i, 200); });
160184
}
161185

162-
TEST(RealtimeThreadSafeBox, smart_ptr_type)
186+
TYPED_TEST(TypedRealtimeThreadSafeBox, smart_ptr_type)
163187
{
164188
std::shared_ptr<int> ptr = std::make_shared<int>(100);
165189

166-
RealtimeThreadSafeBox<std::shared_ptr<int>> box(ptr);
190+
RealtimeThreadSafeBox<std::shared_ptr<int>, TypeParam> box(ptr);
167191

168192
// Instead access it via a passed function.
169193
// This assures that we access the data within the scope of the lock
@@ -181,7 +205,7 @@ TEST(RealtimeThreadSafeBox, smart_ptr_type)
181205
box.try_get([](const auto & p) { EXPECT_EQ(*p, 10); });
182206

183207
// Test that we are able to set the nullptr for pointer types
184-
RealtimeThreadSafeBox<std::shared_ptr<int>> box2;
208+
RealtimeThreadSafeBox<std::shared_ptr<int>, TypeParam> box2;
185209
box2.set(nullptr);
186210
}
187211

@@ -196,28 +220,28 @@ class DefaultConstructable_existing
196220
int number_;
197221
};
198222

199-
TEST(RealtimeThreadSafeBox, default_construct_existing)
223+
TYPED_TEST(TypedRealtimeThreadSafeBox, default_construct_existing)
200224
{
201225
DefaultConstructable_existing thing;
202226
thing.number_ = 5;
203227

204-
RealtimeThreadSafeBox<DefaultConstructable_existing> box;
228+
RealtimeThreadSafeBox<DefaultConstructable_existing, TypeParam> box;
205229
box.get(thing);
206230

207231
EXPECT_EQ(42, thing.number_);
208232
}
209233

210-
TEST(RealtimeThreadSafeBox, initial_value_existing)
234+
TYPED_TEST(TypedRealtimeThreadSafeBox, initial_value_existing)
211235
{
212-
RealtimeThreadSafeBox<double> box(3.14);
236+
RealtimeThreadSafeBox<double, TypeParam> box(3.14);
213237
double num = 0.0;
214238
box.get(num);
215239
EXPECT_DOUBLE_EQ(3.14, num);
216240
}
217241

218-
TEST(RealtimeThreadSafeBox, set_and_get_existing)
242+
TYPED_TEST(TypedRealtimeThreadSafeBox, set_and_get_existing)
219243
{
220-
RealtimeThreadSafeBox<char> box('a');
244+
RealtimeThreadSafeBox<char, TypeParam> box('a');
221245

222246
{
223247
const char input = 'z';
@@ -229,38 +253,38 @@ TEST(RealtimeThreadSafeBox, set_and_get_existing)
229253
EXPECT_EQ('z', output);
230254
}
231255

232-
TEST(RealtimeThreadSafeBox, copy_assign)
256+
TYPED_TEST(TypedRealtimeThreadSafeBox, copy_assign)
233257
{
234-
RealtimeThreadSafeBox<char> box_a('a');
235-
RealtimeThreadSafeBox<char> box_b('b');
258+
RealtimeThreadSafeBox<char, TypeParam> box_a('a');
259+
RealtimeThreadSafeBox<char, TypeParam> box_b('b');
236260

237261
// Assign b to a -> a should now contain b
238262
box_a = box_b;
239263

240264
EXPECT_EQ('b', box_a.try_get().value());
241265
}
242-
TEST(RealtimeThreadSafeBox, copy)
266+
TYPED_TEST(TypedRealtimeThreadSafeBox, copy)
243267
{
244-
RealtimeThreadSafeBox<char> box_b('b');
245-
RealtimeThreadSafeBox<char> box_a(box_b);
268+
RealtimeThreadSafeBox<char, TypeParam> box_b('b');
269+
RealtimeThreadSafeBox<char, TypeParam> box_a(box_b);
246270

247271
EXPECT_EQ('b', box_a.try_get().value());
248272
}
249273

250-
TEST(RealtimeThreadSafeBox, move_assign)
274+
TYPED_TEST(TypedRealtimeThreadSafeBox, move_assign)
251275
{
252-
RealtimeThreadSafeBox<char> box_a('a');
253-
RealtimeThreadSafeBox<char> box_b('b');
276+
RealtimeThreadSafeBox<char, TypeParam> box_a('a');
277+
RealtimeThreadSafeBox<char, TypeParam> box_b('b');
254278

255279
// Move b to a -> a should now contain b
256280
box_a = std::move(box_b);
257281

258282
EXPECT_EQ('b', box_a.try_get().value());
259283
}
260-
TEST(RealtimeThreadSafeBox, move)
284+
TYPED_TEST(TypedRealtimeThreadSafeBox, move)
261285
{
262-
RealtimeThreadSafeBox<char> box_b('b');
263-
RealtimeThreadSafeBox<char> box_a(std::move(box_b));
286+
RealtimeThreadSafeBox<char, TypeParam> box_b('b');
287+
RealtimeThreadSafeBox<char, TypeParam> box_a(std::move(box_b));
264288

265289
EXPECT_EQ('b', box_a.try_get().value());
266290
}

0 commit comments

Comments
 (0)