Add option to set compression threads priority#1457
Add option to set compression threads priority#1457MichaelOrlov merged 10 commits intoros2:rollingfrom
Conversation
|
@emersonknapp Could you review this (or find someone to to it)? This is an important feature that enables us to use rosbag2 in production environments without grinding the whole system to a halt when writing large bag files. |
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
fbe7081 to
77ce698
Compare
MichaelOrlov
left a comment
There was a problem hiding this comment.
@jmachowinski Thank you for your contribution.
I think we can move forward with this PR and the proposed approach but need to address some minor issues and add missing parts in the dependent rosbag2 packages.
In particular, will need to:
- update
rosbag2_pypackage with the new data structure field. - update
rosbag2_transport::RecordOptionspackage with the new data structure field. - update
ros2bag/verb/record.pywith a new command line option for compression threads priority value. - Consider if it will be possible to add some unit tests to check if threads priority sets up as expected.
I will doublecheck yet Windows implementation and let you know if changes are needed.
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Show resolved
Hide resolved
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
77ce698 to
62b4b31
Compare
The python stuff is nothing, were a commit from ME would meet any quality standards... @kohrt can you have a look at this ? |
fujitatomoya
left a comment
There was a problem hiding this comment.
besides all comments, and
Manual page getpriority(2)
...
BUGS
According to POSIX, the nice value is a per-process setting. However, under the current Linux/NPTL implementation of
POSIX threads, the nice value is a per-thread attribute: different threads in the same process can have different nice
values. Portable applications should avoid relying on the Linux behavior, which may be made standards conformant in
the future.
IMO, i am not inclined to take this fix.
related REP(ROS Enhancement Proposal): ros-infrastructure/rep#385
rosbag2_compression/include/rosbag2_compression/compression_options.hpp
Outdated
Show resolved
Hide resolved
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Show resolved
Hide resolved
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Show resolved
Hide resolved
62b4b31 to
35c8cdb
Compare
Done
Added a test case |
|
@jmachowinski Could you please rename |
rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
MichaelOrlov
left a comment
There was a problem hiding this comment.
@jmachowinski The selected approach for tests is not going to work. The test shall be rewritten.
See my comments in code.
I would propose creating a regular non-fake sequential_compression_writer and capture std::err output to verify logged error messages.
Something like
auto writer = ReaderWriterFactory::make_writer(record_options);
testing::internal::CaptureStderr();
writer->open(zero_cache_storage_options);
std::string test_output = testing::internal::GetCapturedStderr();
EXPECT_TRUE(
test_output.find(
"Could not set priority for compression thread to'") == std::string::npos);
and make two test cases with valid thread priority and invalid thread priority values.
Also please rename compression_threads_nice_value and thread_nice_value parameters to the compression_threads_priority and thread_priority respectively.
rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp
Outdated
Show resolved
Hide resolved
A priority is something special in the linux world, therefore I would not name it that. |
|
@jmachowinski As regards
The |
072ef7e to
c8cdcba
Compare
|
@MichaelOrlov I suggest we move the check back into a class inside of the test function. |
Done |
Hold on let me double-check. We didn't change the way how the library was linked. |
You added test/rosbag2_compression/fake_compressor.cpp to test_sequential_compression_writer this, triggers the warning |
|
@jmachowinski You can disregard this warning. If this warning is really bothering you and you want to get rid of it you can fix it by specifying But in this case, will need to add rosbag2_compression_zstd as a runtime dependenises for the tests in the package.xml file
|
MichaelOrlov
left a comment
There was a problem hiding this comment.
@jmachowinski Thanks for the renames and fixes.
We do have currently uint8_t for thread_priority and it is totally aligned with the range of the nice value on Linux/POSIX since it varies from -19 to 20.
Although it doesn't align with the possible thread's priority values on Windows.
According to the https://learn.microsoft.com/en-us/windows/win32/api/processthreadsapi/nf-processthreadsapi-setthreadpriority one of the biggest values could be settled up is
THREAD_MODE_BACKGROUND_END 0x00020000
In decimal, this is 131 072. On Windows, the type is int but this is not good to use int type in data structures since not strictly defined length of the integer type. i.e. it could vary from different platforms and compilators.
I think we need to change the type for the thread's priority at least to the int32_t or even better int64_t to accommodate all possible values.
We can use a static cast to int when passing it to set priority functions.
|
@jmachowinski Could you please fix DCO and cpplint warnings? |
|
@jmachowinski I am sorry, but we just merged another big PR and this branch has to be rebased and conflicts shall be resolved. |
…read priority Signed-off-by: Janosch Machowinski <J.Machowinski@cellumation.com>
Signed-off-by: Janosch Machowinski <J.Machowinski@cellumation.com>
Signed-off-by: Janosch Machowinski <J.Machowinski@cellumation.com>
Co-authored-by: Janosch Machowinski <J.Machowinski@cellumation.com> Signed-off-by: Michael Orlov <michael.orlov@apex.ai>
Signed-off-by: Janosch Machowinski <J.Machowinski@cellumation.com>
Signed-off-by: Janosch Machowinski <J.Machowinski@cellumation.com>
Signed-off-by: Michael Orlov <michael.orlov@apex.ai>
Signed-off-by: Michael Orlov <michael.orlov@apex.ai>
c16ea98 to
ed3d4e4
Compare
|
rebased |
|
@jmachowinski since we added recently a feature for composable recorder. This is when Could you please add to the |
|
@jmachowinski I've made the requested change in the node params parser and relevant test for the |
|
Looks good to me, another try to merge it ? |
|
Re-run CI after an attempt to fix Windows build errors and rebase. |
|
@jmachowinski Unfortunately Windows build still fails with the following error messages |
|
I just set up a windows machine.... |
Signed-off-by: Janosch Machowinski <J.Machowinski@cellumation.com>
Signed-off-by: Michael Orlov <michael.orlov@apex.ai>
b0f0aa2 to
2f58113
Compare
|
Compiles and tests now fine under windows. |
|
This pull request has been mentioned on ROS Discourse. There might be relevant details there: https://discourse.ros.org/t/ros-2-tsc-meeting-minutes-for-2023-12-14/35153/1 |
|
This pull request has been mentioned on ROS Discourse. There might be relevant details there: https://discourse.ros.org/t/ros-2-tsc-meeting-minutes-for-2024-01-18/35779/1 |
Added option to the the nice value of the compression thread.