Skip to content

Commit

Permalink
added gtest for sqlite3_sequential
Browse files Browse the repository at this point in the history
Signed-off-by: Joshua Hampp <j.hampp@denso-adas.de>
  • Loading branch information
Joshua Hampp committed Aug 12, 2019
1 parent 92a8981 commit 07044e5
Show file tree
Hide file tree
Showing 3 changed files with 194 additions and 4 deletions.
8 changes: 8 additions & 0 deletions rosbag2_storage_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,14 @@ if(BUILD_TESTING)
target_link_libraries(test_sqlite_storage ${TEST_LINK_LIBRARIES})
ament_target_dependencies(test_sqlite_storage rosbag2_test_common)
endif()

ament_add_gmock(test_sqlite_sequential_storage
test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET test_sqlite_sequential_storage)
target_link_libraries(test_sqlite_sequential_storage ${TEST_LINK_LIBRARIES})
ament_target_dependencies(test_sqlite_sequential_storage rosbag2_test_common)
endif()
endif()

ament_package()
Original file line number Diff line number Diff line change
@@ -0,0 +1,184 @@
// Copyright 2019, Denso ADAS Engineering Services GmbH.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gmock/gmock.h>

#include <memory>
#include <string>
#include <tuple>
#include <utility>
#include <vector>

#include "rcutils/snprintf.h"

#include "rosbag2_storage/filesystem_helper.hpp"
#include "storage_test_fixture.hpp"

using namespace ::testing; // NOLINT

namespace rosbag2_storage
{

bool operator!=(const TopicMetadata & lhs, const TopicMetadata & rhs)
{
return !(lhs == rhs);
}

bool operator==(const TopicInformation & lhs, const TopicInformation & rhs)
{
return lhs.topic_metadata == rhs.topic_metadata &&
lhs.message_count == rhs.message_count;
}

bool operator!=(const TopicInformation & lhs, const TopicInformation & rhs)
{
return !(lhs == rhs);
}

} // namespace rosbag2_storage

TEST_F(StorageTestFixture, string_messages_are_written_and_read_to_and_from_sqlite3_storage) {
std::vector<std::string> string_messages = {"first message", "second message", "third message"};
std::vector<std::string> topics = {"topic1", "topic2", "topic3"};
std::vector<std::string> rmw_formats = {"rmw1", "rmw2", "rmw3"};
std::vector<std::tuple<std::string, int64_t, std::string, std::string, std::string>> messages =
{std::make_tuple(string_messages[0], 1, topics[0], "type1", rmw_formats[0]),
std::make_tuple(string_messages[1], 2, topics[1], "type2", rmw_formats[1]),
std::make_tuple(string_messages[2], 3, topics[2], "type3", rmw_formats[2])};

write_messages_to_sqlite(messages);
auto read_messages = read_all_messages_from_sqlite();

ASSERT_THAT(read_messages, SizeIs(3));
for (size_t i = 0; i < 3; i++) {
EXPECT_THAT(deserialize_message(read_messages[i]->serialized_data), Eq(string_messages[i]));
EXPECT_THAT(read_messages[i]->time_stamp, Eq(std::get<1>(messages[i])));
EXPECT_THAT(read_messages[i]->topic_name, Eq(topics[i]));
}
}

TEST_F(StorageTestFixture, has_next_return_false_if_there_are_no_more_messages) {
std::vector<std::tuple<std::string, int64_t, std::string, std::string, std::string>>
string_messages =
{std::make_tuple("first message", 1, "", "", ""),
std::make_tuple("second message", 2, "", "", "")};

write_messages_to_sqlite(string_messages);
std::unique_ptr<rosbag2_storage::storage_interfaces::ReadOnlyInterface> readable_storage =
std::make_unique<rosbag2_storage_plugins::SqliteSequentialStorage>();
readable_storage->open(temporary_dir_path_);

EXPECT_TRUE(readable_storage->has_next());
readable_storage->read_next();
EXPECT_TRUE(readable_storage->has_next());
readable_storage->read_next();
EXPECT_FALSE(readable_storage->has_next());
}

TEST_F(StorageTestFixture, get_next_returns_messages_in_timestamp_order) {
std::vector<std::tuple<std::string, int64_t, std::string, std::string, std::string>>
string_messages =
{std::make_tuple("first message", 2, "", "", ""),
std::make_tuple("second message", 6, "", "", "")};

write_messages_to_sqlite(string_messages);
std::unique_ptr<rosbag2_storage::storage_interfaces::ReadOnlyInterface> readable_storage =
std::make_unique<rosbag2_storage_plugins::SqliteSequentialStorage>();
readable_storage->open(temporary_dir_path_);

EXPECT_TRUE(readable_storage->has_next());
auto first_message = readable_storage->read_next();
EXPECT_THAT(first_message->time_stamp, Eq(2));
EXPECT_TRUE(readable_storage->has_next());
auto second_message = readable_storage->read_next();
EXPECT_THAT(second_message->time_stamp, Eq(6));
EXPECT_FALSE(readable_storage->has_next());
}

TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector) {
std::unique_ptr<rosbag2_storage::storage_interfaces::ReadWriteInterface> writable_storage =
std::make_unique<rosbag2_storage_plugins::SqliteSequentialStorage>();
writable_storage->open(temporary_dir_path_);
writable_storage->create_topic({"topic1", "type1", "rmw1"});
writable_storage->create_topic({"topic2", "type2", "rmw2"});
metadata_io_.write_metadata(temporary_dir_path_, writable_storage->get_metadata());
writable_storage.reset();

auto readable_storage = std::make_unique<rosbag2_storage_plugins::SqliteSequentialStorage>();
readable_storage->open(
temporary_dir_path_, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY);
auto topics_and_types = readable_storage->get_all_topics_and_types();

EXPECT_THAT(topics_and_types, ElementsAreArray({
rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1"},
rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2"}
}));
}

TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) {
std::vector<std::string> string_messages = {"first message", "second message", "third message"};
std::vector<std::string> topics = {"topic1", "topic2"};
std::vector<std::tuple<std::string, int64_t, std::string, std::string, std::string>> messages =
{std::make_tuple(
string_messages[0], static_cast<int64_t>(1e9), topics[0], "type1", "rmw_format"),
std::make_tuple(
string_messages[1], static_cast<int64_t>(2e9), topics[0], "type1", "rmw_format"),
std::make_tuple(
string_messages[2], static_cast<int64_t>(3e9), topics[1], "type2", "rmw_format")};

write_messages_to_sqlite(messages);

auto readable_storage = std::make_unique<rosbag2_storage_plugins::SqliteSequentialStorage>();
readable_storage->open(
temporary_dir_path_, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY);
auto metadata = readable_storage->get_metadata();

EXPECT_THAT(metadata.storage_identifier, Eq("sqlite3"));
EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3",
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3.extra"
}));
EXPECT_THAT(metadata.topics_with_message_count, ElementsAreArray({
rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{
"topic1", "type1", "rmw_format"}, 2u},
rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{
"topic2", "type2", "rmw_format"}, 1u}
}));
EXPECT_THAT(metadata.message_count, Eq(3u));
EXPECT_THAT(metadata.starting_time, Eq(
std::chrono::time_point<std::chrono::high_resolution_clock>(std::chrono::seconds(1))
));
EXPECT_THAT(metadata.duration, Eq(std::chrono::seconds(2)));
}

TEST_F(StorageTestFixture, get_metadata_returns_correct_struct_if_no_messages) {
write_messages_to_sqlite({});

auto readable_storage = std::make_unique<rosbag2_storage_plugins::SqliteSequentialStorage>();
readable_storage->open(
temporary_dir_path_, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY);
auto metadata = readable_storage->get_metadata();

EXPECT_THAT(metadata.storage_identifier, Eq("sqlite3"));
EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3",
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3.extra"
}));
EXPECT_THAT(metadata.topics_with_message_count, IsEmpty());
EXPECT_THAT(metadata.message_count, Eq(0u));
EXPECT_THAT(metadata.starting_time, Eq(
std::chrono::time_point<std::chrono::high_resolution_clock>(std::chrono::seconds(0))
));
EXPECT_THAT(metadata.duration, Eq(std::chrono::seconds(0)));
}
Original file line number Diff line number Diff line change
Expand Up @@ -146,8 +146,7 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) {

EXPECT_THAT(metadata.storage_identifier, Eq("sqlite3"));
EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3",
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3.extra"
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3"
}));
EXPECT_THAT(metadata.topics_with_message_count, ElementsAreArray({
rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{
Expand All @@ -172,8 +171,7 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct_if_no_messages) {

EXPECT_THAT(metadata.storage_identifier, Eq("sqlite3"));
EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3",
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3.extra"
rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3"
}));
EXPECT_THAT(metadata.topics_with_message_count, IsEmpty());
EXPECT_THAT(metadata.message_count, Eq(0u));
Expand Down

0 comments on commit 07044e5

Please sign in to comment.