Skip to content

Commit c43e37d

Browse files
Janosch MachowinskiJanosch Machowinski
Janosch Machowinski
authored and
Janosch Machowinski
committed
chore: made compression_threads_priority an int32_t
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent 7438b50 commit c43e37d

File tree

5 files changed

+10
-11
lines changed

5 files changed

+10
-11
lines changed

rosbag2_compression/include/rosbag2_compression/compression_options.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ struct CompressionOptions
6464
uint64_t compression_threads;
6565
/// if set, the compression thread(s) will try to set
6666
/// the given priority for itself
67-
std::optional<int8_t> thread_priority;
67+
std::optional<int32_t> thread_priority;
6868
};
6969

7070
} // namespace rosbag2_compression

rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,6 @@ SequentialCompressionWriter::~SequentialCompressionWriter()
7070
void SequentialCompressionWriter::compression_thread_fn()
7171
{
7272
if (compression_options_.thread_priority) {
73-
7473
#ifdef _WIN32
7574
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
7675
"Changing thread priority is not implemented for windows");
@@ -103,8 +102,8 @@ void SequentialCompressionWriter::compression_thread_fn()
103102
int new_nice_value = nice(wanted_nice_value - cur_nice_value);
104103
if ((new_nice_value == -1 && errno != 0)) {
105104
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
106-
"Could not set nice value of compression thread to " << wanted_nice_value << " : " << std::strerror(
107-
errno));
105+
"Could not set nice value of compression thread to " << wanted_nice_value <<
106+
" : " << std::strerror(errno));
108107
}
109108
}
110109
#endif

rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -148,7 +148,7 @@ class SequentialCompressionWriterTest : public TestWithParam<uint64_t>
148148

149149
const uint64_t kDefaultCompressionQueueSize = 1;
150150
const uint64_t kDefaultCompressionQueueThreads = 4;
151-
const std::optional<int8_t> kDefaultCompressionQueueThreadsPriority = std::nullopt;
151+
const std::optional<int32_t> kDefaultCompressionQueueThreadsPriority = std::nullopt;
152152
};
153153

154154
TEST_F(SequentialCompressionWriterTest, open_throws_on_empty_storage_options_uri)
@@ -405,9 +405,9 @@ TEST_P(SequentialCompressionWriterTest, writer_sets_threads_priority)
405405
const std::string test_topic_type = "test_msgs/BasicTypes";
406406
const uint64_t kCompressionQueueSize = GetParam();
407407
#ifndef _WIN32
408-
const int wanted_thread_priority = 10;
408+
const int32_t wanted_thread_priority = 10;
409409
#else
410-
const int wanted_thread_priority = THREAD_MODE_BACKGROUND_BEGIN;
410+
const int32_t wanted_thread_priority = THREAD_MODE_BACKGROUND_BEGIN;
411411
#endif
412412

413413
// queue size should be 0 or at least the number of remaining messages to prevent message loss
@@ -421,9 +421,9 @@ TEST_P(SequentialCompressionWriterTest, writer_sets_threads_priority)
421421

422422
#ifndef _WIN32
423423
// nice values are in the range from -20 to +19, so this value will never be read
424-
int detected_thread_priority = 100;
424+
int32_t detected_thread_priority = 100;
425425
#else
426-
int detected_thread_priority = THREAD_PRIORITY_ERROR_RETURN;
426+
int32_t detected_thread_priority = THREAD_PRIORITY_ERROR_RETURN;
427427
#endif
428428

429429
initializeFakeFileStorage();

rosbag2_transport/include/rosbag2_transport/record_options.hpp

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

rosbag2_transport/src/rosbag2_transport/record_options.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ bool convert<rosbag2_transport::RecordOptions>::decode(
8181
optional_assign<std::string>(node, "compression_format", record_options.compression_format);
8282
optional_assign<uint64_t>(node, "compression_queue_size", record_options.compression_queue_size);
8383
optional_assign<uint64_t>(node, "compression_threads", record_options.compression_threads);
84-
optional_assign<int8_t>(
84+
optional_assign<int32_t>(
8585
node, "compression_threads_priority",
8686
record_options.compression_threads_priority);
8787

0 commit comments

Comments
 (0)