Skip to content

Commit

Permalink
feat(SequentialCompressionWriter): Added option to set compression th…
Browse files Browse the repository at this point in the history
…read nice value

Signed-off-by: Janosch Machowinski <[email protected]>
  • Loading branch information
Janosch Machowinski authored and Janosch Machowinski committed Sep 5, 2023
1 parent a48001a commit 77ce698
Show file tree
Hide file tree
Showing 2 changed files with 47 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <cstdint>
#include <string>
#include <optional>

#include "visibility_control.hpp"

Expand Down Expand Up @@ -61,6 +62,9 @@ struct CompressionOptions
CompressionMode compression_mode;
uint64_t compression_queue_size;
uint64_t compression_threads;
/// if set, the compression thread will try to set
/// the given nice value for itself
std::optional<int8_t> thread_nice_value;
};

} // namespace rosbag2_compression
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <algorithm>
#include <chrono>
#include <cstring>
#include <functional>
#include <memory>
#include <stdexcept>
Expand All @@ -33,6 +34,12 @@
#include "rosbag2_storage/storage_interfaces/read_write_interface.hpp"

#include "logging.hpp"
#ifdef _WIN32
#include <windows.h>
#else
#include <unistd.h>
#include <sys/resource.h>
#endif

namespace rosbag2_compression
{
Expand Down Expand Up @@ -62,6 +69,42 @@ SequentialCompressionWriter::~SequentialCompressionWriter()

void SequentialCompressionWriter::compression_thread_fn()
{
if (compression_options_.thread_nice_value) {

#ifdef _WIN32
ROSBAG2_COMPRESSION_LOG_WARN_STREAM("Lowering of process priority is not implemented for windows");

/**
* The implementation should look something like this
uint8_t nice_value = *compression_options_.thread_nice_value;
// this must match THREAD_PRIORITY_IDLE, THREAD_PRIORITY_LOWEST...
DWORD dwThreadPri = *compression_options_.thread_nice_value;
if(!SetThreadPriority(GetCurrentThread(), dwThreadPri))
{
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
"Could not set nice value of compression thread to " << nice_value << " : " << std::strerror(
errno));
}
*/

#else
int wanted_nice_value = *compression_options_.thread_nice_value;

int cur_nice_value = getpriority(PRIO_PROCESS, 0);

int new_nice_value = nice(wanted_nice_value - cur_nice_value);
if(new_nice_value == -1 || new_nice_value != wanted_nice_value)
{
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
"Could not set nice value of compression thread to " << wanted_nice_value << " : " << std::strerror(
errno));
}
#endif
}

// Every thread needs to have its own compression context for thread safety.
auto compressor = compression_factory_->create_compressor(
compression_options_.compression_format);
Expand Down

0 comments on commit 77ce698

Please sign in to comment.