Skip to content

Commit cea3fb0

Browse files
jmachowinskiJanosch Machowinskimorlov-apexai
authored
Add option to set compression threads priority (#1457)
* feat(SequentialCompressionWriter): Added option to set compression thread priority Signed-off-by: Janosch Machowinski <[email protected]> * feat: Added compression_threads_priority option Signed-off-by: Janosch Machowinski <[email protected]> * test: implemented test case for setting priority value Signed-off-by: Janosch Machowinski <[email protected]> * Redesign test for the case when compression writer sets threads priority Co-authored-by: Janosch Machowinski <[email protected]> Signed-off-by: Michael Orlov <[email protected]> * fix: Fixed inverted check Signed-off-by: Janosch Machowinski <[email protected]> * chore: made compression_threads_priority an int32_t Signed-off-by: Janosch Machowinski <[email protected]> * Enable thread priority for Windows Signed-off-by: Michael Orlov <[email protected]> * Address grammar in log messages Signed-off-by: Michael Orlov <[email protected]> * fix: fixed namespace collision warning in test Signed-off-by: Janosch Machowinski <[email protected]> * Add compression_threads_priority to the node params parser Signed-off-by: Michael Orlov <[email protected]> --------- Signed-off-by: Janosch Machowinski <[email protected]> Signed-off-by: Michael Orlov <[email protected]> Co-authored-by: Janosch Machowinski <[email protected]> Co-authored-by: Michael Orlov <[email protected]>
1 parent 95f78b6 commit cea3fb0

File tree

14 files changed

+214
-13
lines changed

14 files changed

+214
-13
lines changed

rosbag2_compression/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -107,6 +107,7 @@ if(BUILD_TESTING)
107107
test/rosbag2_compression/test_sequential_compression_writer.cpp)
108108
target_link_libraries(test_sequential_compression_writer
109109
${PROJECT_NAME}
110+
fake_plugin
110111
rosbag2_cpp::rosbag2_cpp
111112
rosbag2_storage::rosbag2_storage
112113
)

rosbag2_compression/include/rosbag2_compression/compression_options.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <cstdint>
1919
#include <string>
20+
#include <optional>
2021

2122
#include "visibility_control.hpp"
2223

@@ -60,7 +61,12 @@ struct CompressionOptions
6061
std::string compression_format;
6162
CompressionMode compression_mode;
6263
uint64_t compression_queue_size;
64+
/// \brief // The number of compression threads
6365
uint64_t compression_threads;
66+
/// \brief If set, the compression thread(s) will try to set the given priority for itself
67+
/// For Windows the valid values are: THREAD_PRIORITY_LOWEST, THREAD_PRIORITY_BELOW_NORMAL and
68+
/// THREAD_PRIORITY_NORMAL. For POSIX compatible OSes this is the "nice" value.
69+
std::optional<int32_t> thread_priority;
6470
};
6571

6672
} // namespace rosbag2_compression

rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp

+46
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include <algorithm>
1818
#include <chrono>
19+
#include <cstring>
1920
#include <functional>
2021
#include <memory>
2122
#include <stdexcept>
@@ -33,6 +34,12 @@
3334
#include "rosbag2_storage/storage_interfaces/read_write_interface.hpp"
3435

3536
#include "logging.hpp"
37+
#ifdef _WIN32
38+
#include <windows.h>
39+
#else
40+
#include <unistd.h>
41+
#include <sys/resource.h>
42+
#endif
3643

3744
namespace rosbag2_compression
3845
{
@@ -62,6 +69,45 @@ SequentialCompressionWriter::~SequentialCompressionWriter()
6269

6370
void SequentialCompressionWriter::compression_thread_fn()
6471
{
72+
if (compression_options_.thread_priority) {
73+
#ifdef _WIN32
74+
// This must match THREAD_PRIORITY_IDLE, THREAD_PRIORITY_LOWEST...
75+
int wanted_thread_priority = *compression_options_.thread_priority;
76+
if (!SetThreadPriority(GetCurrentThread(), wanted_thread_priority)) {
77+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
78+
"Could not set thread priority of compression thread to: " << wanted_thread_priority <<
79+
". Error code: " << GetLastError());
80+
} else {
81+
auto detected_thread_priority = GetThreadPriority(GetCurrentThread());
82+
if (detected_thread_priority == THREAD_PRIORITY_ERROR_RETURN) {
83+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
84+
"Failed to get current thread priority. Error code: " << GetLastError());
85+
} else if (wanted_thread_priority != detected_thread_priority) {
86+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
87+
"Could not set thread priority of compression thread to: " <<
88+
wanted_thread_priority << ". Detected thread priority: " << detected_thread_priority);
89+
}
90+
}
91+
#else
92+
int wanted_nice_value = *compression_options_.thread_priority;
93+
94+
errno = 0;
95+
int cur_nice_value = getpriority(PRIO_PROCESS, 0);
96+
if (cur_nice_value == -1 && errno != 0) {
97+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
98+
"Could not set nice value of compression thread to: " << wanted_nice_value <<
99+
" : Could not determine cur nice value");
100+
} else {
101+
int new_nice_value = nice(wanted_nice_value - cur_nice_value);
102+
if ((new_nice_value == -1 && errno != 0)) {
103+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
104+
"Could not set nice value of compression thread to: " << wanted_nice_value <<
105+
". Error : " << std::strerror(errno));
106+
}
107+
}
108+
#endif
109+
}
110+
65111
// Every thread needs to have its own compression context for thread safety.
66112
auto compressor = compression_factory_->create_compressor(
67113
compression_options_.compression_format);
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
// Copyright 2023 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef ROSBAG2_COMPRESSION__FAKE_COMPRESSION_FACTORY_HPP_
16+
#define ROSBAG2_COMPRESSION__FAKE_COMPRESSION_FACTORY_HPP_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include "rosbag2_compression/compression_factory.hpp"
22+
#include "fake_compressor.hpp"
23+
24+
class ROSBAG2_COMPRESSION_EXPORT FakeCompressionFactory
25+
: public rosbag2_compression::CompressionFactory
26+
{
27+
public:
28+
FakeCompressionFactory() = delete;
29+
30+
~FakeCompressionFactory() override = default;
31+
32+
explicit FakeCompressionFactory(int & detected_thread_priority)
33+
: detected_thread_priority_(detected_thread_priority) {}
34+
35+
std::shared_ptr<rosbag2_compression::BaseCompressorInterface>
36+
create_compressor(const std::string & /*compression_format*/) override
37+
{
38+
return std::make_shared<FakeCompressor>(detected_thread_priority_);
39+
}
40+
41+
private:
42+
int & detected_thread_priority_;
43+
};
44+
45+
#endif // ROSBAG2_COMPRESSION__FAKE_COMPRESSION_FACTORY_HPP_

rosbag2_compression/test/rosbag2_compression/fake_compressor.cpp

+17-1
Original file line numberDiff line numberDiff line change
@@ -13,11 +13,27 @@
1313
// limitations under the License.
1414

1515
#include <string>
16+
#ifdef _WIN32
17+
#include <windows.h>
18+
#else
19+
#include <sys/resource.h>
20+
#endif
1621

1722
#include "pluginlib/class_list_macros.hpp"
18-
1923
#include "fake_compressor.hpp"
2024

25+
FakeCompressor::FakeCompressor(int & detected_thread_priority)
26+
{
27+
#ifndef _WIN32
28+
int cur_nice_value = getpriority(PRIO_PROCESS, 0);
29+
if (cur_nice_value != -1 && errno == 0) {
30+
detected_thread_priority = cur_nice_value;
31+
}
32+
#else
33+
detected_thread_priority = GetThreadPriority(GetCurrentThread());
34+
#endif
35+
}
36+
2137
std::string FakeCompressor::compress_uri(const std::string & uri)
2238
{
2339
return uri + "." + get_compression_identifier();

rosbag2_compression/test/rosbag2_compression/fake_compressor.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -20,11 +20,14 @@
2020
#include "rosbag2_compression/base_compressor_interface.hpp"
2121
#include "rosbag2_storage/serialized_bag_message.hpp"
2222

23-
class FakeCompressor : public rosbag2_compression::BaseCompressorInterface
23+
class ROSBAG2_COMPRESSION_EXPORT FakeCompressor : public rosbag2_compression::
24+
BaseCompressorInterface
2425
{
2526
public:
2627
FakeCompressor() = default;
2728

29+
explicit FakeCompressor(int & detected_thread_priority);
30+
2831
std::string compress_uri(const std::string & uri) override;
2932

3033
void compress_serialized_bag_message(

rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp

+81-9
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,14 @@
3636
#include "mock_storage_factory.hpp"
3737

3838
#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
3947

4048
using namespace testing; // NOLINT
4149

@@ -143,13 +151,15 @@ class SequentialCompressionWriterTest : public TestWithParam<uint64_t>
143151

144152
const uint64_t kDefaultCompressionQueueSize = 1;
145153
const uint64_t kDefaultCompressionQueueThreads = 4;
154+
const std::optional<int32_t> kDefaultCompressionQueueThreadsPriority = std::nullopt;
146155
};
147156

148157
TEST_F(SequentialCompressionWriterTest, open_throws_on_empty_storage_options_uri)
149158
{
150159
rosbag2_compression::CompressionOptions compression_options{
151160
DefaultTestCompressor, rosbag2_compression::CompressionMode::FILE,
152-
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads};
161+
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads,
162+
kDefaultCompressionQueueThreadsPriority};
153163
initializeWriter(compression_options);
154164

155165
EXPECT_THROW(
@@ -163,7 +173,8 @@ TEST_F(SequentialCompressionWriterTest, open_throws_on_bad_compression_format)
163173
{
164174
rosbag2_compression::CompressionOptions compression_options{
165175
"bad_format", rosbag2_compression::CompressionMode::FILE,
166-
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads};
176+
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads,
177+
kDefaultCompressionQueueThreadsPriority};
167178
initializeWriter(compression_options);
168179

169180
EXPECT_THROW(
@@ -175,7 +186,8 @@ TEST_F(SequentialCompressionWriterTest, open_throws_on_invalid_splitting_size)
175186
{
176187
rosbag2_compression::CompressionOptions compression_options{
177188
DefaultTestCompressor, rosbag2_compression::CompressionMode::FILE,
178-
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads};
189+
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads,
190+
kDefaultCompressionQueueThreadsPriority};
179191

180192
// Set minimum file size greater than max bagfile size option
181193
const uint64_t min_split_file_size = 10;
@@ -196,7 +208,8 @@ TEST_F(SequentialCompressionWriterTest, open_succeeds_on_supported_compression_f
196208
{
197209
rosbag2_compression::CompressionOptions compression_options{
198210
DefaultTestCompressor, rosbag2_compression::CompressionMode::FILE,
199-
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads};
211+
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads,
212+
kDefaultCompressionQueueThreadsPriority};
200213
initializeWriter(compression_options);
201214

202215
auto tmp_dir = rcpputils::fs::temp_directory_path() / "path_not_empty";
@@ -211,7 +224,8 @@ TEST_F(SequentialCompressionWriterTest, writer_calls_create_compressor)
211224
{
212225
rosbag2_compression::CompressionOptions compression_options{
213226
DefaultTestCompressor, rosbag2_compression::CompressionMode::FILE,
214-
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads};
227+
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads,
228+
kDefaultCompressionQueueThreadsPriority};
215229
auto compression_factory = std::make_unique<StrictMock<MockCompressionFactory>>();
216230
EXPECT_CALL(*compression_factory, create_compressor(_)).Times(1);
217231

@@ -235,7 +249,8 @@ TEST_F(SequentialCompressionWriterTest, writer_creates_correct_metadata_relative
235249
DefaultTestCompressor,
236250
rosbag2_compression::CompressionMode::FILE,
237251
kDefaultCompressionQueueSize,
238-
kDefaultCompressionQueueThreads
252+
kDefaultCompressionQueueThreads,
253+
kDefaultCompressionQueueThreadsPriority
239254
};
240255

241256
initializeFakeFileStorage();
@@ -277,7 +292,8 @@ TEST_F(SequentialCompressionWriterTest, writer_call_metadata_update_on_open_and_
277292
DefaultTestCompressor,
278293
rosbag2_compression::CompressionMode::MESSAGE,
279294
0,
280-
kDefaultCompressionQueueThreads
295+
kDefaultCompressionQueueThreads,
296+
kDefaultCompressionQueueThreadsPriority
281297
};
282298

283299
initializeFakeFileStorage();
@@ -315,7 +331,8 @@ TEST_F(SequentialCompressionWriterTest, writer_call_metadata_update_on_bag_split
315331
DefaultTestCompressor,
316332
rosbag2_compression::CompressionMode::MESSAGE,
317333
0,
318-
kDefaultCompressionQueueThreads
334+
kDefaultCompressionQueueThreads,
335+
kDefaultCompressionQueueThreadsPriority
319336
};
320337

321338
initializeFakeFileStorage();
@@ -363,7 +380,8 @@ TEST_P(SequentialCompressionWriterTest, writer_writes_with_compression_queue_siz
363380
DefaultTestCompressor,
364381
rosbag2_compression::CompressionMode::MESSAGE,
365382
kCompressionQueueSize,
366-
kDefaultCompressionQueueThreads
383+
kDefaultCompressionQueueThreads,
384+
kDefaultCompressionQueueThreadsPriority
367385
};
368386

369387
initializeFakeFileStorage();
@@ -384,6 +402,60 @@ TEST_P(SequentialCompressionWriterTest, writer_writes_with_compression_queue_siz
384402
EXPECT_EQ(fake_storage_size_, kNumMessagesToWrite);
385403
}
386404

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+
387459
INSTANTIATE_TEST_SUITE_P(
388460
SequentialCompressionWriterTestQueueSizes,
389461
SequentialCompressionWriterTest,

rosbag2_performance/rosbag2_performance_benchmarking/src/writer_benchmark.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -178,7 +178,7 @@ void WriterBenchmark::create_writer()
178178
if (!bag_config_.compression_format.empty()) {
179179
rosbag2_compression::CompressionOptions compression_options{
180180
bag_config_.compression_format, rosbag2_compression::CompressionMode::MESSAGE,
181-
bag_config_.compression_queue_size, bag_config_.compression_threads};
181+
bag_config_.compression_queue_size, bag_config_.compression_threads, std::nullopt};
182182

183183
writer_ = std::make_unique<rosbag2_compression::SequentialCompressionWriter>(
184184
compression_options);

rosbag2_transport/include/rosbag2_transport/record_options.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ struct RecordOptions
4242
std::string compression_format = "";
4343
uint64_t compression_queue_size = 1;
4444
uint64_t compression_threads = 0;
45+
int32_t compression_threads_priority = 0;
4546
std::unordered_map<std::string, rclcpp::QoS> topic_qos_profile_overrides{};
4647
bool include_hidden_topics = false;
4748
bool include_unpublished_topics = false;

rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -235,6 +235,10 @@ RecordOptions get_record_options_from_node_params(rclcpp::Node & node)
235235
node, "record.compression_threads", 0, std::numeric_limits<int64_t>::max(),
236236
record_options.compression_threads);
237237

238+
record_options.compression_threads_priority = param_utils::declare_integer_node_params<int32_t>(
239+
node, "record.compression_threads_priority", std::numeric_limits<int32_t>::min(),
240+
std::numeric_limits<int32_t>::max(), record_options.compression_threads_priority);
241+
238242
std::string qos_profile_overrides_path =
239243
node.declare_parameter<std::string>("record.qos_profile_overrides_path", "");
240244

rosbag2_transport/src/rosbag2_transport/reader_writer_factory.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,8 @@ std::unique_ptr<rosbag2_cpp::Writer> ReaderWriterFactory::make_writer(
5353
record_options.compression_format,
5454
rosbag2_compression::compression_mode_from_string(record_options.compression_mode),
5555
record_options.compression_queue_size,
56-
record_options.compression_threads
56+
record_options.compression_threads,
57+
record_options.compression_threads_priority,
5758
};
5859
if (compression_options.compression_threads < 1) {
5960
compression_options.compression_threads = std::thread::hardware_concurrency();

0 commit comments

Comments
 (0)