|
14 | 14 |
|
15 | 15 | #include <gmock/gmock.h> |
16 | 16 |
|
| 17 | +#include <filesystem> |
17 | 18 | #include <memory> |
18 | 19 | #include <string> |
19 | 20 | #include <unordered_map> |
20 | 21 | #include <utility> |
21 | 22 | #include <vector> |
22 | 23 | #include <rosbag2_storage/ros_helper.hpp> |
23 | 24 |
|
| 25 | +#include "mock_recorder.hpp" |
24 | 26 | #include "rclcpp/rclcpp.hpp" |
| 27 | +#include "rcpputils/scope_exit.hpp" |
25 | 28 |
|
26 | 29 | #include "rosbag2_test_common/publication_manager.hpp" |
27 | 30 | #include "rosbag2_test_common/wait_for.hpp" |
| 31 | +#include "rosbag2_test_common/temporary_directory_fixture.hpp" |
28 | 32 |
|
29 | 33 | #include "rosbag2_transport/recorder.hpp" |
30 | 34 |
|
|
34 | 38 |
|
35 | 39 | #include "rosbag2_storage/qos.hpp" |
36 | 40 | #include "record_integration_fixture.hpp" |
| 41 | +#include "rosbag2_transport/reader_writer_factory.hpp" |
| 42 | + |
| 43 | +using namespace ::testing; // NOLINT |
| 44 | +using rosbag2_test_common::TemporaryDirectoryFixture; |
| 45 | +namespace fs = std::filesystem; |
37 | 46 |
|
38 | 47 | TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are_recorded) |
39 | 48 | { |
@@ -126,6 +135,33 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are |
126 | 135 | } |
127 | 136 | } |
128 | 137 |
|
| 138 | +TEST_F(TemporaryDirectoryFixture, can_record_again_after_stop_with_real_storage) { |
| 139 | + rclcpp::init(0, nullptr); |
| 140 | + auto cleanup_process_handle = rcpputils::make_scope_exit([&]() {rclcpp::shutdown();}); |
| 141 | + std::string test_topic = "/can_record_again_after_stop_topic"; |
| 142 | + rosbag2_storage::StorageOptions storage_options{}; |
| 143 | + storage_options.uri = (fs::path(temporary_dir_path_) / "start_stop_again").generic_string(); |
| 144 | + |
| 145 | + rosbag2_transport::RecordOptions record_options{}; |
| 146 | + |
| 147 | + auto writer = rosbag2_transport::ReaderWriterFactory::make_writer(record_options); |
| 148 | + { |
| 149 | + auto recorder = std::make_shared<MockRecorder>( |
| 150 | + std::move(writer), storage_options, record_options); |
| 151 | + |
| 152 | + EXPECT_NO_THROW(recorder->record()); |
| 153 | + fs::path storage_path(storage_options.uri); |
| 154 | + EXPECT_TRUE(fs::is_directory(storage_path)); |
| 155 | + |
| 156 | + EXPECT_NO_THROW(recorder->stop()); |
| 157 | + EXPECT_NO_THROW(recorder->record()); |
| 158 | + storage_path = recorder->get_storage_options().uri; |
| 159 | + EXPECT_TRUE(fs::is_directory(storage_path)); |
| 160 | + std::string expected_path_str = storage_options.uri + "(1)"; |
| 161 | + EXPECT_EQ(storage_path.generic_string(), expected_path_str); |
| 162 | + } |
| 163 | +} |
| 164 | + |
129 | 165 | TEST_F(RecordIntegrationTestFixture, can_record_again_after_stop) |
130 | 166 | { |
131 | 167 | GTEST_SKIP() << "Skipping test `can_record_again_after_stop` in rosbag2_transport, until " |
|
0 commit comments