Skip to content

Commit 072ef7e

Browse files
authored
Merge pull request #1 from ros2/morlov/redesign-test-for-writer-thread-priority
Redesign test for the case when compression writer sets threads priority
2 parents 35c8cdb + 2e48487 commit 072ef7e

File tree

5 files changed

+81
-65
lines changed

5 files changed

+81
-65
lines changed

rosbag2_compression/CMakeLists.txt

+2-1
Original file line numberDiff line numberDiff line change
@@ -104,7 +104,8 @@ if(BUILD_TESTING)
104104
)
105105

106106
ament_add_gmock(test_sequential_compression_writer
107-
test/rosbag2_compression/test_sequential_compression_writer.cpp)
107+
test/rosbag2_compression/test_sequential_compression_writer.cpp
108+
test/rosbag2_compression/fake_compressor.cpp)
108109
target_link_libraries(test_sequential_compression_writer
109110
${PROJECT_NAME}
110111
rosbag2_cpp::rosbag2_cpp
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
// Copyright 2023 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef ROSBAG2_COMPRESSION__FAKE_COMPRESSION_FACTORY_HPP_
16+
#define ROSBAG2_COMPRESSION__FAKE_COMPRESSION_FACTORY_HPP_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include "rosbag2_compression/compression_factory.hpp"
22+
#include "fake_compressor.hpp"
23+
24+
class FakeCompressionFactory
25+
: public rosbag2_compression::CompressionFactory
26+
{
27+
public:
28+
FakeCompressionFactory() = delete;
29+
30+
~FakeCompressionFactory() override = default;
31+
32+
explicit FakeCompressionFactory(int & detected_thread_priority)
33+
: detected_thread_priority_(detected_thread_priority) {}
34+
35+
std::shared_ptr<rosbag2_compression::BaseCompressorInterface>
36+
create_compressor(const std::string & /*compression_format*/) override
37+
{
38+
return std::make_shared<FakeCompressor>(detected_thread_priority_);
39+
}
40+
41+
private:
42+
int & detected_thread_priority_;
43+
};
44+
45+
#endif // ROSBAG2_COMPRESSION__FAKE_COMPRESSION_FACTORY_HPP_

rosbag2_compression/test/rosbag2_compression/fake_compressor.cpp

+17-1
Original file line numberDiff line numberDiff line change
@@ -13,11 +13,27 @@
1313
// limitations under the License.
1414

1515
#include <string>
16+
#ifdef _WIN32
17+
#include <windows.h>
18+
#else
19+
#include <sys/resource.h>
20+
#endif
1621

1722
#include "pluginlib/class_list_macros.hpp"
18-
1923
#include "fake_compressor.hpp"
2024

25+
FakeCompressor::FakeCompressor(int & detected_thread_priority)
26+
{
27+
#ifndef _WIN32
28+
int cur_nice_value = getpriority(PRIO_PROCESS, 0);
29+
if (cur_nice_value != -1 && errno == 0) {
30+
detected_thread_priority = cur_nice_value;
31+
}
32+
#else
33+
detected_thread_priority = GetThreadPriority(GetCurrentThread());
34+
#endif
35+
}
36+
2137
std::string FakeCompressor::compress_uri(const std::string & uri)
2238
{
2339
return uri + "." + get_compression_identifier();

rosbag2_compression/test/rosbag2_compression/fake_compressor.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@ class FakeCompressor : public rosbag2_compression::BaseCompressorInterface
2525
public:
2626
FakeCompressor() = default;
2727

28+
explicit FakeCompressor(int & detected_thread_priority);
29+
2830
std::string compress_uri(const std::string & uri) override;
2931

3032
void compress_serialized_bag_message(

rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp

+15-63
Original file line numberDiff line numberDiff line change
@@ -36,12 +36,10 @@
3636
#include "mock_storage_factory.hpp"
3737

3838
#include "mock_compression_factory.hpp"
39+
#include "fake_compression_factory.hpp"
3940

4041
#ifdef _WIN32
4142
#include <windows.h>
42-
#else
43-
#include <unistd.h>
44-
#include <sys/resource.h>
4543
#endif
4644

4745
using namespace testing; // NOLINT
@@ -401,82 +399,37 @@ TEST_P(SequentialCompressionWriterTest, writer_writes_with_compression_queue_siz
401399
EXPECT_EQ(fake_storage_size_, kNumMessagesToWrite);
402400
}
403401

404-
405-
TEST_P(SequentialCompressionWriterTest, writer_sets_nice_value)
402+
TEST_P(SequentialCompressionWriterTest, writer_sets_threads_priority)
406403
{
407404
const std::string test_topic_name = "test_topic";
408405
const std::string test_topic_type = "test_msgs/BasicTypes";
409406
const uint64_t kCompressionQueueSize = GetParam();
410-
const int wanted_nice_value = 10;
411-
412-
class TestCompressor : public rosbag2_compression::BaseCompressorInterface
413-
{
414-
int & detected_nice_value;
415-
416-
public:
417-
TestCompressor(int & detected_nice_value)
418-
: detected_nice_value(detected_nice_value) {}
419-
virtual std::string compress_uri(const std::string & uri)
420-
{
421-
return uri;
422-
}
423-
424-
virtual void compress_serialized_bag_message(
425-
const rosbag2_storage::SerializedBagMessage * bag_message,
426-
rosbag2_storage::SerializedBagMessage * compressed_message)
427-
{
428-
#ifdef _WIN32
429-
int cur_nice_value = getpriority(PRIO_PROCESS, 0);
430-
if (cur_nice_value != -1 && errno == 0) {
431-
432-
detected_nice_value = cur_nice_value;
433-
}
407+
#ifndef _WIN32
408+
const int wanted_thread_priority = 10;
434409
#else
435-
//FIXME implement windows version
410+
const int wanted_thread_priority = THREAD_MODE_BACKGROUND_BEGIN;
436411
#endif
437412

438-
*compressed_message = *bag_message;
439-
}
440-
441-
/**
442-
* Get the identifier of the compression algorithm.
443-
* This is appended to the extension of the compressed file.
444-
*/
445-
virtual std::string get_compression_identifier() const
446-
{
447-
return "niceTest";
448-
}
449-
};
450-
451-
class FakeFactory : public rosbag2_compression::CompressionFactory
452-
{
453-
int & detected_nice_value;
454-
455-
public:
456-
FakeFactory(int & detected_nice_value)
457-
: detected_nice_value(detected_nice_value) {}
458-
459-
virtual std::shared_ptr<rosbag2_compression::BaseCompressorInterface>
460-
create_compressor(const std::string & /*compression_format*/)
461-
{
462-
return std::make_shared<TestCompressor>(detected_nice_value);
463-
}
464-
};
465-
466413
// queue size should be 0 or at least the number of remaining messages to prevent message loss
467414
rosbag2_compression::CompressionOptions compression_options {
468415
DefaultTestCompressor,
469416
rosbag2_compression::CompressionMode::MESSAGE,
470417
kCompressionQueueSize,
471418
kDefaultCompressionQueueThreads,
472-
wanted_nice_value
419+
wanted_thread_priority
473420
};
474421

422+
#ifndef _WIN32
475423
// nice values are in the range from -20 to +19, so this value will never be read
476-
int detected_nice_value = 100;
424+
int detected_thread_priority = 100;
425+
#else
426+
int detected_thread_priority = THREAD_PRIORITY_ERROR_RETURN;
427+
#endif
477428

478429
initializeFakeFileStorage();
479-
initializeWriter(compression_options, std::make_unique<FakeFactory>(detected_nice_value));
430+
initializeWriter(
431+
compression_options,
432+
std::make_unique<FakeCompressionFactory>(detected_thread_priority));
480433

481434
writer_->open(tmp_dir_storage_options_);
482435
writer_->create_topic({test_topic_name, test_topic_type, "", "", ""});
@@ -490,8 +443,7 @@ TEST_P(SequentialCompressionWriterTest, writer_sets_nice_value)
490443
}
491444
writer_.reset(); // reset will call writer destructor
492445

493-
EXPECT_EQ(detected_nice_value, *compression_options.thread_nice_value);
494-
446+
EXPECT_EQ(detected_thread_priority, *compression_options.thread_nice_value);
495447
EXPECT_EQ(fake_storage_size_, kNumMessagesToWrite);
496448
}
497449

0 commit comments

Comments
 (0)