Skip to content

Commit

Permalink
chore: made compression_threads_priority an int32_t
Browse files Browse the repository at this point in the history
Signed-off-by: Janosch Machowinski <[email protected]>
  • Loading branch information
Janosch Machowinski authored and Janosch Machowinski committed Oct 6, 2023
1 parent 7438b50 commit c43e37d
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ struct CompressionOptions
uint64_t compression_threads;
/// if set, the compression thread(s) will try to set
/// the given priority for itself
std::optional<int8_t> thread_priority;
std::optional<int32_t> thread_priority;
};

} // namespace rosbag2_compression
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,6 @@ SequentialCompressionWriter::~SequentialCompressionWriter()
void SequentialCompressionWriter::compression_thread_fn()
{
if (compression_options_.thread_priority) {

#ifdef _WIN32
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
"Changing thread priority is not implemented for windows");
Expand Down Expand Up @@ -103,8 +102,8 @@ void SequentialCompressionWriter::compression_thread_fn()
int new_nice_value = nice(wanted_nice_value - cur_nice_value);
if ((new_nice_value == -1 && errno != 0)) {
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
"Could not set nice value of compression thread to " << wanted_nice_value << " : " << std::strerror(
errno));
"Could not set nice value of compression thread to " << wanted_nice_value <<
" : " << std::strerror(errno));
}
}
#endif
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ class SequentialCompressionWriterTest : public TestWithParam<uint64_t>

const uint64_t kDefaultCompressionQueueSize = 1;
const uint64_t kDefaultCompressionQueueThreads = 4;
const std::optional<int8_t> kDefaultCompressionQueueThreadsPriority = std::nullopt;
const std::optional<int32_t> kDefaultCompressionQueueThreadsPriority = std::nullopt;
};

TEST_F(SequentialCompressionWriterTest, open_throws_on_empty_storage_options_uri)
Expand Down Expand Up @@ -405,9 +405,9 @@ TEST_P(SequentialCompressionWriterTest, writer_sets_threads_priority)
const std::string test_topic_type = "test_msgs/BasicTypes";
const uint64_t kCompressionQueueSize = GetParam();
#ifndef _WIN32
const int wanted_thread_priority = 10;
const int32_t wanted_thread_priority = 10;
#else
const int wanted_thread_priority = THREAD_MODE_BACKGROUND_BEGIN;
const int32_t wanted_thread_priority = THREAD_MODE_BACKGROUND_BEGIN;
#endif

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

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

initializeFakeFileStorage();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ struct RecordOptions
std::string compression_format = "";
uint64_t compression_queue_size = 1;
uint64_t compression_threads = 0;
int8_t compression_threads_priority = 0;
int32_t compression_threads_priority = 0;
std::unordered_map<std::string, rclcpp::QoS> topic_qos_profile_overrides{};
bool include_hidden_topics = false;
bool include_unpublished_topics = false;
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_transport/src/rosbag2_transport/record_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ bool convert<rosbag2_transport::RecordOptions>::decode(
optional_assign<std::string>(node, "compression_format", record_options.compression_format);
optional_assign<uint64_t>(node, "compression_queue_size", record_options.compression_queue_size);
optional_assign<uint64_t>(node, "compression_threads", record_options.compression_threads);
optional_assign<int8_t>(
optional_assign<int32_t>(
node, "compression_threads_priority",
record_options.compression_threads_priority);

Expand Down

0 comments on commit c43e37d

Please sign in to comment.