36
36
#include " mock_storage_factory.hpp"
37
37
38
38
#include " mock_compression_factory.hpp"
39
+ #include " fake_compression_factory.hpp"
40
+
41
+ #ifdef _WIN32
42
+ #include < windows.h>
43
+ #else
44
+ #include < sys/time.h>
45
+ #include < sys/resource.h>
46
+ #endif
39
47
40
48
using namespace testing ; // NOLINT
41
49
@@ -143,13 +151,15 @@ class SequentialCompressionWriterTest : public TestWithParam<uint64_t>
143
151
144
152
const uint64_t kDefaultCompressionQueueSize = 1 ;
145
153
const uint64_t kDefaultCompressionQueueThreads = 4 ;
154
+ const std::optional<int32_t > kDefaultCompressionQueueThreadsPriority = std::nullopt;
146
155
};
147
156
148
157
TEST_F (SequentialCompressionWriterTest, open_throws_on_empty_storage_options_uri)
149
158
{
150
159
rosbag2_compression::CompressionOptions compression_options{
151
160
DefaultTestCompressor, rosbag2_compression::CompressionMode::FILE,
152
- kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads };
161
+ kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads ,
162
+ kDefaultCompressionQueueThreadsPriority };
153
163
initializeWriter (compression_options);
154
164
155
165
EXPECT_THROW (
@@ -163,7 +173,8 @@ TEST_F(SequentialCompressionWriterTest, open_throws_on_bad_compression_format)
163
173
{
164
174
rosbag2_compression::CompressionOptions compression_options{
165
175
" bad_format" , rosbag2_compression::CompressionMode::FILE,
166
- kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads };
176
+ kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads ,
177
+ kDefaultCompressionQueueThreadsPriority };
167
178
initializeWriter (compression_options);
168
179
169
180
EXPECT_THROW (
@@ -175,7 +186,8 @@ TEST_F(SequentialCompressionWriterTest, open_throws_on_invalid_splitting_size)
175
186
{
176
187
rosbag2_compression::CompressionOptions compression_options{
177
188
DefaultTestCompressor, rosbag2_compression::CompressionMode::FILE,
178
- kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads };
189
+ kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads ,
190
+ kDefaultCompressionQueueThreadsPriority };
179
191
180
192
// Set minimum file size greater than max bagfile size option
181
193
const uint64_t min_split_file_size = 10 ;
@@ -196,7 +208,8 @@ TEST_F(SequentialCompressionWriterTest, open_succeeds_on_supported_compression_f
196
208
{
197
209
rosbag2_compression::CompressionOptions compression_options{
198
210
DefaultTestCompressor, rosbag2_compression::CompressionMode::FILE,
199
- kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads };
211
+ kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads ,
212
+ kDefaultCompressionQueueThreadsPriority };
200
213
initializeWriter (compression_options);
201
214
202
215
auto tmp_dir = rcpputils::fs::temp_directory_path () / " path_not_empty" ;
@@ -211,7 +224,8 @@ TEST_F(SequentialCompressionWriterTest, writer_calls_create_compressor)
211
224
{
212
225
rosbag2_compression::CompressionOptions compression_options{
213
226
DefaultTestCompressor, rosbag2_compression::CompressionMode::FILE,
214
- kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads };
227
+ kDefaultCompressionQueueSize , kDefaultCompressionQueueThreads ,
228
+ kDefaultCompressionQueueThreadsPriority };
215
229
auto compression_factory = std::make_unique<StrictMock<MockCompressionFactory>>();
216
230
EXPECT_CALL (*compression_factory, create_compressor (_)).Times (1 );
217
231
@@ -235,7 +249,8 @@ TEST_F(SequentialCompressionWriterTest, writer_creates_correct_metadata_relative
235
249
DefaultTestCompressor,
236
250
rosbag2_compression::CompressionMode::FILE,
237
251
kDefaultCompressionQueueSize ,
238
- kDefaultCompressionQueueThreads
252
+ kDefaultCompressionQueueThreads ,
253
+ kDefaultCompressionQueueThreadsPriority
239
254
};
240
255
241
256
initializeFakeFileStorage ();
@@ -277,7 +292,8 @@ TEST_F(SequentialCompressionWriterTest, writer_call_metadata_update_on_open_and_
277
292
DefaultTestCompressor,
278
293
rosbag2_compression::CompressionMode::MESSAGE,
279
294
0 ,
280
- kDefaultCompressionQueueThreads
295
+ kDefaultCompressionQueueThreads ,
296
+ kDefaultCompressionQueueThreadsPriority
281
297
};
282
298
283
299
initializeFakeFileStorage ();
@@ -315,7 +331,8 @@ TEST_F(SequentialCompressionWriterTest, writer_call_metadata_update_on_bag_split
315
331
DefaultTestCompressor,
316
332
rosbag2_compression::CompressionMode::MESSAGE,
317
333
0 ,
318
- kDefaultCompressionQueueThreads
334
+ kDefaultCompressionQueueThreads ,
335
+ kDefaultCompressionQueueThreadsPriority
319
336
};
320
337
321
338
initializeFakeFileStorage ();
@@ -363,7 +380,8 @@ TEST_P(SequentialCompressionWriterTest, writer_writes_with_compression_queue_siz
363
380
DefaultTestCompressor,
364
381
rosbag2_compression::CompressionMode::MESSAGE,
365
382
kCompressionQueueSize ,
366
- kDefaultCompressionQueueThreads
383
+ kDefaultCompressionQueueThreads ,
384
+ kDefaultCompressionQueueThreadsPriority
367
385
};
368
386
369
387
initializeFakeFileStorage ();
@@ -384,6 +402,60 @@ TEST_P(SequentialCompressionWriterTest, writer_writes_with_compression_queue_siz
384
402
EXPECT_EQ (fake_storage_size_, kNumMessagesToWrite );
385
403
}
386
404
405
+ TEST_P (SequentialCompressionWriterTest, writer_sets_threads_priority)
406
+ {
407
+ const std::string test_topic_name = " test_topic" ;
408
+ const std::string test_topic_type = " test_msgs/BasicTypes" ;
409
+ const uint64_t kCompressionQueueSize = GetParam ();
410
+ #ifndef _WIN32
411
+ const int32_t wanted_thread_priority = 10 ;
412
+ errno = 0 ;
413
+ int cur_nice_value = getpriority (PRIO_PROCESS, 0 );
414
+ ASSERT_TRUE (!(cur_nice_value == -1 && errno != 0 ));
415
+ #else
416
+ const int32_t wanted_thread_priority = THREAD_PRIORITY_LOWEST;
417
+ auto current_thread_priority = GetThreadPriority (GetCurrentThread ());
418
+ ASSERT_NE (current_thread_priority, THREAD_PRIORITY_ERROR_RETURN);
419
+ ASSERT_NE (current_thread_priority, wanted_thread_priority);
420
+ #endif
421
+
422
+ // queue size should be 0 or at least the number of remaining messages to prevent message loss
423
+ rosbag2_compression::CompressionOptions compression_options {
424
+ DefaultTestCompressor,
425
+ rosbag2_compression::CompressionMode::MESSAGE,
426
+ kCompressionQueueSize ,
427
+ kDefaultCompressionQueueThreads ,
428
+ wanted_thread_priority
429
+ };
430
+
431
+ #ifndef _WIN32
432
+ // nice values are in the range from -20 to +19, so this value will never be read
433
+ int32_t detected_thread_priority = 100 ;
434
+ #else
435
+ int32_t detected_thread_priority = THREAD_PRIORITY_ERROR_RETURN;
436
+ #endif
437
+
438
+ initializeFakeFileStorage ();
439
+ initializeWriter (
440
+ compression_options,
441
+ std::make_unique<FakeCompressionFactory>(detected_thread_priority));
442
+
443
+ writer_->open (tmp_dir_storage_options_);
444
+ writer_->create_topic ({test_topic_name, test_topic_type, " " , {}, " " });
445
+
446
+ auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
447
+ message->topic_name = test_topic_name;
448
+
449
+ const size_t kNumMessagesToWrite = 5 ;
450
+ for (size_t i = 0 ; i < kNumMessagesToWrite ; i++) {
451
+ writer_->write (message);
452
+ }
453
+ writer_.reset (); // reset will call writer destructor
454
+
455
+ EXPECT_EQ (detected_thread_priority, *compression_options.thread_priority );
456
+ EXPECT_EQ (fake_storage_size_, kNumMessagesToWrite );
457
+ }
458
+
387
459
INSTANTIATE_TEST_SUITE_P (
388
460
SequentialCompressionWriterTestQueueSizes,
389
461
SequentialCompressionWriterTest,
0 commit comments