Skip to content

Commit

Permalink
Fix test by creating a new bagfile - it seems like it was corrupted i…
Browse files Browse the repository at this point in the history
…n some way

Signed-off-by: Emerson Knapp <[email protected]>
  • Loading branch information
emersonknapp committed Mar 25, 2021
1 parent ee876cd commit fb8c4a5
Show file tree
Hide file tree
Showing 7 changed files with 16 additions and 31 deletions.
4 changes: 1 addition & 3 deletions rosbag2_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -97,9 +97,7 @@ if(BUILD_TESTING)
rosbag2_cpp
rosbag2_storage
rosbag2_storage_default_plugins
rosbag2_test_common
)
# target_link_libraries(test_reindex ${PROJECT_NAME})
rosbag2_test_common)
endif()


Expand Down
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -5,30 +5,17 @@ rosbag2_bagfile_information:
- multiple_files_0.db3
- multiple_files_1.db3
- multiple_files_2.db3
- multiple_files_3.db3
duration:
nanoseconds: 59997863418
nanoseconds: 1616630880179528024
starting_time:
nanoseconds_since_epoch: 1604356847420232242
message_count: 766
nanoseconds_since_epoch: 22460796745086
message_count: 3177
topics_with_message_count:
- topic_metadata:
name: /topic
name: /chatter
type: std_msgs/msg/String
serialization_format: cdr
offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 2\n deadline:\n sec: 2147483647\n nsec: 4294967295\n lifespan:\n sec: 2147483647\n nsec: 4294967295\n liveliness: 1\n liveliness_lease_duration:\n sec: 2147483647\n nsec: 4294967295\n avoid_ros_namespace_conventions: false"
message_count: 378
- topic_metadata:
name: /parameter_events
type: rcl_interfaces/msg/ParameterEvent
serialization_format: cdr
offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 2\n deadline:\n sec: 2147483647\n nsec: 4294967295\n lifespan:\n sec: 2147483647\n nsec: 4294967295\n liveliness: 1\n liveliness_lease_duration:\n sec: 2147483647\n nsec: 4294967295\n avoid_ros_namespace_conventions: false"
message_count: 0
- topic_metadata:
name: /rosout
type: rcl_interfaces/msg/Log
serialization_format: cdr
offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 1\n deadline:\n sec: 2147483647\n nsec: 4294967295\n lifespan:\n sec: 10\n nsec: 0\n liveliness: 1\n liveliness_lease_duration:\n sec: 2147483647\n nsec: 4294967295\n avoid_ros_namespace_conventions: false"
message_count: 388
offered_qos_profiles: "- history: 1\n depth: 1\n reliability: 1\n durability: 2\n deadline:\n sec: 9223372036\n nsec: 854775807\n lifespan:\n sec: 9223372036\n nsec: 854775807\n liveliness: 1\n liveliness_lease_duration:\n sec: 9223372036\n nsec: 854775807\n avoid_ros_namespace_conventions: false"
message_count: 3177
compression_format: ""
compression_mode: ""
18 changes: 9 additions & 9 deletions rosbag2_tests/test/rosbag2_tests/test_reindexer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,31 +45,31 @@ class ReindexTestFixture : public Test
public:
ReindexTestFixture()
{
database_path = std::string(_SRC_RESOURCES_DIR_PATH) + std::string("/reindex_test_bags");
target_dir = database_path + "/target_metadata";
database_path = rcpputils::fs::path(_SRC_RESOURCES_DIR_PATH) / "reindex_test_bags";
target_dir = database_path / "target_metadata";
}

std::string database_path;
std::string target_dir;
rcpputils::fs::path database_path;
rcpputils::fs::path target_dir;
};

TEST_F(ReindexTestFixture, test_multiple_files) {
auto bag_dir = database_path + "/multiple_files";
auto bag_dir = database_path / "multiple_files";
std::unique_ptr<rosbag2_cpp::Reindexer> reindexer =
std::make_unique<rosbag2_cpp::Reindexer>();

rosbag2_storage::StorageOptions so = rosbag2_storage::StorageOptions();
so.uri = bag_dir;
so.uri = bag_dir.string();
so.storage_id = "sqlite3";

reindexer->reindex(so);

auto generated_file = rcpputils::fs::path(bag_dir + "/metadata.yaml");
auto generated_file = rcpputils::fs::path(bag_dir) / "metadata.yaml";
EXPECT_TRUE(generated_file.exists());

auto metadata_io = std::make_unique<rosbag2_storage::MetadataIo>();
auto generated_metadata = metadata_io->read_metadata(bag_dir);
auto target_metadata = metadata_io->read_metadata(target_dir + "/multiple_files");
auto generated_metadata = metadata_io->read_metadata(bag_dir.string());
auto target_metadata = metadata_io->read_metadata((target_dir / "multiple_files").string());

EXPECT_EQ(generated_metadata.version, target_metadata.version);

Expand Down

0 comments on commit fb8c4a5

Please sign in to comment.