Skip to content

Commit 62b4b31

Browse files
Janosch MachowinskiJanosch Machowinski
Janosch Machowinski
authored and
Janosch Machowinski
committed
feat(SequentialCompressionWriter): Added option to set compression thread nice value
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent a48001a commit 62b4b31

File tree

2 files changed

+52
-0
lines changed

2 files changed

+52
-0
lines changed

rosbag2_compression/include/rosbag2_compression/compression_options.hpp

+4
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

@@ -61,6 +62,9 @@ struct CompressionOptions
6162
CompressionMode compression_mode;
6263
uint64_t compression_queue_size;
6364
uint64_t compression_threads;
65+
/// if set, the compression thread will try to set
66+
/// the given nice value for itself
67+
std::optional<int8_t> thread_nice_value;
6468
};
6569

6670
} // namespace rosbag2_compression

rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp

+48
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,47 @@ SequentialCompressionWriter::~SequentialCompressionWriter()
6269

6370
void SequentialCompressionWriter::compression_thread_fn()
6471
{
72+
if (compression_options_.thread_nice_value) {
73+
74+
#ifdef _WIN32
75+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
76+
"Lowering of process priority is not implemented for windows");
77+
78+
/**
79+
* The implementation should look something like this
80+
81+
uint8_t nice_value = *compression_options_.thread_nice_value;
82+
83+
// this must match THREAD_PRIORITY_IDLE, THREAD_PRIORITY_LOWEST...
84+
DWORD dwThreadPri = *compression_options_.thread_nice_value;
85+
86+
if(!SetThreadPriority(GetCurrentThread(), dwThreadPri))
87+
{
88+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
89+
"Could not set nice value of compression thread to " << nice_value << " : " << std::strerror(GetLastError()));
90+
}
91+
*/
92+
93+
#else
94+
int wanted_nice_value = *compression_options_.thread_nice_value;
95+
96+
errno = 0;
97+
int cur_nice_value = getpriority(PRIO_PROCESS, 0);
98+
if (cur_nice_value != -1 && errno != 0) {
99+
int new_nice_value = nice(wanted_nice_value - cur_nice_value);
100+
if ((new_nice_value == -1 && errno != 0) || new_nice_value != wanted_nice_value) {
101+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
102+
"Could not set nice value of compression thread to " << wanted_nice_value << " : " << std::strerror(
103+
errno));
104+
}
105+
} else {
106+
ROSBAG2_COMPRESSION_LOG_WARN_STREAM(
107+
"Could not set nice value of compression thread to " << wanted_nice_value <<
108+
" : Could not determine cur nice value");
109+
}
110+
#endif
111+
}
112+
65113
// Every thread needs to have its own compression context for thread safety.
66114
auto compressor = compression_factory_->create_compressor(
67115
compression_options_.compression_format);

0 commit comments

Comments
 (0)