Skip to content

Commit

Permalink
Add topics with zero message counts to the SQLiteStorage::get_metadat…
Browse files Browse the repository at this point in the history
…a(). (#1725) (#1731)

* storage_sqlite3 constructs metadata with topics don't have any messages.

Signed-off-by: Tomoya Fujita <[email protected]>

* Revert "storage_sqlite3 constructs metadata with topics don't have any messages."

This reverts commit a842689.

Signed-off-by: Tomoya Fujita <[email protected]>

* update metadata list topics that does not have any messages.

Signed-off-by: Tomoya Fujita <[email protected]>

* add get_metadata_include_topics_with_zero_messages test

Signed-off-by: Tomoya Fujita <[email protected]>
Co-authored-by: Michael Orlov <[email protected]>

* add std_msgs to rosbag2_cpp for test build.

Signed-off-by: Tomoya Fujita <[email protected]>

* call get_or_generate_extern_topic_id when updating metadata.

Signed-off-by: Tomoya Fujita <[email protected]>

---------

Signed-off-by: Tomoya Fujita <[email protected]>
Co-authored-by: Michael Orlov <[email protected]>
(cherry picked from commit ff829e8)

Co-authored-by: Tomoya Fujita <[email protected]>
(cherry picked from commit 2a627c9)

# Conflicts:
#	rosbag2_cpp/CMakeLists.txt
#	rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp
  • Loading branch information
mergify[bot] committed Aug 9, 2024
1 parent adffc7e commit 6c17288
Show file tree
Hide file tree
Showing 4 changed files with 90 additions and 0 deletions.
11 changes: 11 additions & 0 deletions rosbag2_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,7 @@ if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(test_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(rosbag2_test_msgdefs REQUIRED)
ament_lint_auto_find_test_dependencies()

Expand Down Expand Up @@ -177,8 +178,18 @@ if(BUILD_TESTING)
ament_add_gmock(test_sequential_reader
test/rosbag2_cpp/test_sequential_reader.cpp test/rosbag2_cpp/fake_data.cpp)
if(TARGET test_sequential_reader)
<<<<<<< HEAD
ament_target_dependencies(test_sequential_reader rosbag2_storage rosbag2_test_common test_msgs)
target_link_libraries(test_sequential_reader ${PROJECT_NAME})
=======
target_link_libraries(test_sequential_reader
${PROJECT_NAME}
rosbag2_storage::rosbag2_storage
rosbag2_test_common::rosbag2_test_common
${test_msgs_TARGETS}
${std_msgs_TARGETS}
)
>>>>>>> 2a627c91 (Add topics with zero message counts to the SQLiteStorage::get_metadata(). (#1725) (#1731))
endif()

ament_add_gmock(test_storage_without_metadata_file
Expand Down
1 change: 1 addition & 0 deletions rosbag2_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>test_msgs</test_depend>
<test_depend>std_msgs</test_depend>
<test_depend>rosbag2_test_common</test_depend>
<test_depend>rosbag2_test_msgdefs</test_depend>

Expand Down
33 changes: 33 additions & 0 deletions rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include "rosbag2_test_common/tested_storage_ids.hpp"
#include "rosbag2_test_common/temporary_directory_fixture.hpp"

#include "std_msgs/msg/string.hpp"
#include "test_msgs/msg/basic_types.hpp"

#include "fake_data.hpp"
Expand Down Expand Up @@ -246,6 +247,38 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, reader_accepts_bare_file) {
EXPECT_THAT(reader.get_metadata().topics_with_message_count, SizeIs(1));
}

TEST_P(ParametrizedTemporaryDirectoryFixture, get_metadata_include_topics_with_zero_messages) {
const auto bag_path = rcpputils::fs::path(temporary_dir_path_) / "bag_with_no_msgs";
const std::string topic_name = "topic_with_0_messages";
const auto storage_id = GetParam();
{
rosbag2_storage::TopicMetadata topic_metadata;
topic_metadata.name = topic_name;
topic_metadata.type = "std_msgs/msg/String";

rosbag2_cpp::Writer writer;
rosbag2_storage::StorageOptions options;
options.uri = bag_path.string();
options.storage_id = storage_id;
writer.open(options);
writer.create_topic(topic_metadata);
}

rosbag2_storage::MetadataIo metadata_io;
ASSERT_TRUE(metadata_io.metadata_file_exists(bag_path.string()));
auto metadata_from_yaml = metadata_io.read_metadata(bag_path.string());
auto first_storage = bag_path / metadata_from_yaml.relative_file_paths[0];

rosbag2_storage::StorageFactory factory;
rosbag2_storage::StorageOptions options;
options.uri = first_storage.string();
options.storage_id = storage_id;
auto reader = factory.open_read_only(options);
auto metadata = reader->get_metadata();
ASSERT_THAT(metadata.topics_with_message_count, SizeIs(1));
EXPECT_EQ(metadata.topics_with_message_count[0].message_count, 0U);
}

INSTANTIATE_TEST_SUITE_P(
BareFileTests,
ParametrizedTemporaryDirectoryFixture,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -636,6 +636,42 @@ uint64_t SqliteStorage::get_minimum_split_file_size() const
return MIN_SPLIT_FILE_SIZE;
}

<<<<<<< HEAD
=======
void SqliteStorage::add_topic_to_metadata(
int64_t inner_topic_id, std::string topic_name, std::string topic_type, std::string ser_format,
int64_t msg_count, const std::string & offered_qos_profiles_str, const std::string & type_hash)
{
auto offered_qos_profiles = rosbag2_storage::to_rclcpp_qos_vector(
// Before db_schema_version_ = 3 we didn't store metadata in the database and real
// metadata_.version will be lower than 9
offered_qos_profiles_str, (db_schema_version_ >= 3) ? metadata_.version : 8);
const rosbag2_storage::TopicMetadata topic_metadata {
get_or_generate_extern_topic_id(inner_topic_id), topic_name, topic_type, ser_format,
offered_qos_profiles, type_hash};
auto & topics_list = metadata_.topics_with_message_count;
auto it = std::find_if(
topics_list.begin(), topics_list.end(),
[&](const rosbag2_storage::TopicInformation & topic_info) {
return topic_info.topic_metadata == topic_metadata;
});
if (it != topics_list.end()) {
it->message_count = msg_count;
} else {
metadata_.topics_with_message_count.push_back(
{
{
get_or_generate_extern_topic_id(inner_topic_id), topic_name, topic_type, ser_format,
offered_qos_profiles, type_hash
},
static_cast<size_t>(msg_count)
});
}

metadata_.message_count += msg_count;
}

>>>>>>> 2a627c91 (Add topics with zero message counts to the SQLiteStorage::get_metadata(). (#1725) (#1731))
void SqliteStorage::read_metadata()
{
std::vector<rosbag2_storage::BagMetadata> metadata_from_table;
Expand Down Expand Up @@ -666,6 +702,15 @@ void SqliteStorage::read_metadata()
rcutils_time_point_value_t min_time = INT64_MAX;
rcutils_time_point_value_t max_time = 0;

// fill in all topics and types even those do not have any messages
if (all_topics_and_types_.empty()) {
fill_topics_and_types();
}
metadata_.topics_with_message_count.reserve(all_topics_and_types_.size());
for (const auto & topic_metadata : all_topics_and_types_) {
metadata_.topics_with_message_count.push_back({topic_metadata, 0});
}

if (database_->field_exists("topics", "offered_qos_profiles")) {
if (database_->field_exists("topics", "type_description_hash")) {
std::string query =
Expand Down

0 comments on commit 6c17288

Please sign in to comment.