diff --git a/ros2bag/ros2bag/verb/info.py b/ros2bag/ros2bag/verb/info.py index 9926414c5..15715091e 100644 --- a/ros2bag/ros2bag/verb/info.py +++ b/ros2bag/ros2bag/verb/info.py @@ -12,18 +12,24 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os import sys from ros2bag.verb import VerbExtension +from rosbag2_transport import rosbag2_transport_py + class InfoVerb(VerbExtension): """ros2 bag info.""" def add_arguments(self, parser, cli_name): # noqa: D102 - arg = parser.add_argument( + parser.add_argument( 'bag_file', help='bag file to introspect') def main(self, *, args): # noqa: D102 bag_file = args.bag_file - print('calling ros2 bag info on', bag_file) + if not os.path.exists(bag_file): + return "Error: bag file '{}' does not exist!".format(bag_file) + + rosbag2_transport_py.info(uri=bag_file) diff --git a/rosbag2/CMakeLists.txt b/rosbag2/CMakeLists.txt index c06a080b3..03507eede 100644 --- a/rosbag2/CMakeLists.txt +++ b/rosbag2/CMakeLists.txt @@ -24,6 +24,7 @@ find_package(rosbag2_storage REQUIRED) find_package(rosidl_generator_cpp REQUIRED) add_library(${PROJECT_NAME} SHARED + src/rosbag2/info.cpp src/rosbag2/sequential_reader.cpp src/rosbag2/typesupport_helpers.cpp src/rosbag2/writer.cpp) @@ -71,6 +72,15 @@ if(BUILD_TESTING) if(TARGET rosbag2_typesupport_helpers_test) target_link_libraries(rosbag2_typesupport_helpers_test rosbag2) endif() + + ament_add_gmock(test_info + test/rosbag2/test_info.cpp + test/rosbag2/mock_metadata_io.hpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) + if(TARGET test_info) + target_link_libraries(test_info rosbag2) + ament_target_dependencies(test_info rosbag2_test_common) + endif() endif() ament_package() diff --git a/rosbag2_storage/include/rosbag2_storage/bag_info.hpp b/rosbag2/include/rosbag2/info.hpp similarity index 66% rename from rosbag2_storage/include/rosbag2_storage/bag_info.hpp rename to rosbag2/include/rosbag2/info.hpp index db68786c7..3b020830a 100644 --- a/rosbag2_storage/include/rosbag2_storage/bag_info.hpp +++ b/rosbag2/include/rosbag2/info.hpp @@ -12,23 +12,25 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROSBAG2_STORAGE__BAG_INFO_HPP_ -#define ROSBAG2_STORAGE__BAG_INFO_HPP_ +#ifndef ROSBAG2__INFO_HPP_ +#define ROSBAG2__INFO_HPP_ #include -namespace rosbag2_storage +#include "rosbag2/types.hpp" +#include "visibility_control.hpp" + +namespace rosbag2 { -/** - * Struct to hold the storage information. - */ -struct BagInfo +class ROSBAG2_PUBLIC Info { - std::string uri; - // TODO(greimela-si/botteroa-si): Add remaining info fields. +public: + virtual ~Info() = default; + + virtual rosbag2::BagMetadata read_metadata(const std::string & uri); }; -} // namespace rosbag2_storage +} // namespace rosbag2 -#endif // ROSBAG2_STORAGE__BAG_INFO_HPP_ +#endif // ROSBAG2__INFO_HPP_ diff --git a/rosbag2/include/rosbag2/types.hpp b/rosbag2/include/rosbag2/types.hpp index 71371b0f9..b3fa15ff0 100644 --- a/rosbag2/include/rosbag2/types.hpp +++ b/rosbag2/include/rosbag2/types.hpp @@ -15,12 +15,15 @@ #ifndef ROSBAG2__TYPES_HPP_ #define ROSBAG2__TYPES_HPP_ +#include "rosbag2_storage/bag_metadata.hpp" #include "rosbag2_storage/serialized_bag_message.hpp" #include "rosbag2_storage/topic_with_type.hpp" namespace rosbag2 { +using BagMetadata = rosbag2_storage::BagMetadata; using SerializedBagMessage = rosbag2_storage::SerializedBagMessage; +using TopicMetadata = rosbag2_storage::TopicMetadata; using TopicWithType = rosbag2_storage::TopicWithType; } // namespace rosbag2 diff --git a/rosbag2/include/rosbag2/writer.hpp b/rosbag2/include/rosbag2/writer.hpp index 8f7e9f1c4..ee4283ff2 100644 --- a/rosbag2/include/rosbag2/writer.hpp +++ b/rosbag2/include/rosbag2/writer.hpp @@ -70,6 +70,7 @@ class ROSBAG2_PUBLIC Writer virtual void write(std::shared_ptr message); private: + std::string uri_; rosbag2_storage::StorageFactory factory_; std::shared_ptr storage_; }; diff --git a/rosbag2/package.xml b/rosbag2/package.xml index 0c591259c..bb79acf36 100644 --- a/rosbag2/package.xml +++ b/rosbag2/package.xml @@ -20,6 +20,7 @@ ament_lint_auto ament_lint_common test_msgs + rosbag2_test_common ament_cmake diff --git a/rosbag2/src/rosbag2/info.cpp b/rosbag2/src/rosbag2/info.cpp new file mode 100644 index 000000000..a8d7bcb5a --- /dev/null +++ b/rosbag2/src/rosbag2/info.cpp @@ -0,0 +1,30 @@ +// Copyright 2018, Bosch Software Innovations 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 "rosbag2/info.hpp" + +#include + +#include "rosbag2_storage/metadata_io.hpp" + +namespace rosbag2 +{ + +rosbag2::BagMetadata Info::read_metadata(const std::string & uri) +{ + rosbag2_storage::MetadataIo metadata_io; + return metadata_io.read_metadata(uri); +} + +} // namespace rosbag2 diff --git a/rosbag2/src/rosbag2/writer.cpp b/rosbag2/src/rosbag2/writer.cpp index b5af1c1f6..ec8e8786a 100644 --- a/rosbag2/src/rosbag2/writer.cpp +++ b/rosbag2/src/rosbag2/writer.cpp @@ -16,7 +16,10 @@ #include #include +#include +#include "rosbag2_storage/metadata_io.hpp" +#include "rosbag2/info.hpp" #include "rosbag2/storage_options.hpp" namespace rosbag2 @@ -24,6 +27,11 @@ namespace rosbag2 Writer::~Writer() { + if (!uri_.empty()) { + rosbag2_storage::MetadataIo metadata_io; + metadata_io.write_metadata(uri_, storage_->get_metadata()); + } + storage_.reset(); // Necessary to ensure that the writer is destroyed before the factory } @@ -33,6 +41,7 @@ void Writer::open(const StorageOptions & options) if (!storage_) { throw std::runtime_error("No storage could be initialized. Abort"); } + uri_ = options.uri; } void Writer::create_topic(const TopicWithType & topic_with_type) diff --git a/rosbag2/test/rosbag2/mock_metadata_io.hpp b/rosbag2/test/rosbag2/mock_metadata_io.hpp new file mode 100644 index 000000000..0c473cda4 --- /dev/null +++ b/rosbag2/test/rosbag2/mock_metadata_io.hpp @@ -0,0 +1,34 @@ +// Copyright 2018, Bosch Software Innovations 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. + +#ifndef ROSBAG2__MOCK_METADATA_IO_HPP_ +#define ROSBAG2__MOCK_METADATA_IO_HPP_ + +#include + +#include +#include +#include + +#include "rosbag2_storage/bag_metadata.hpp" +#include "rosbag2_storage/metadata_io.hpp" + +class MockMetadataIo : public rosbag2_storage::MetadataIo +{ +public: + MOCK_METHOD2(write_metadata, void(const std::string &, rosbag2_storage::BagMetadata)); + MOCK_METHOD1(read_metadata, rosbag2_storage::BagMetadata(const std::string &)); +}; + +#endif // ROSBAG2__MOCK_METADATA_IO_HPP_ diff --git a/rosbag2/test/rosbag2/mock_storage.hpp b/rosbag2/test/rosbag2/mock_storage.hpp new file mode 100644 index 000000000..b92c6ba7b --- /dev/null +++ b/rosbag2/test/rosbag2/mock_storage.hpp @@ -0,0 +1,63 @@ +// Copyright 2018, Bosch Software Innovations 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. + +#ifndef ROSBAG2__MOCK_STORAGE_HPP_ +#define ROSBAG2__MOCK_STORAGE_HPP_ + +#include +#include +#include + +#include "rosbag2_storage/bag_metadata.hpp" +#include "rosbag2_storage/serialized_bag_message.hpp" +#include "rosbag2_storage/topic_with_type.hpp" +#include "rosbag2_storage/storage_interfaces/read_write_interface.hpp" + +class MockStorage : public rosbag2_storage::storage_interfaces::ReadWriteInterface +{ +public: + ~MockStorage() override = default; + + void open(const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) override + { + (void) uri; + (void) flag; + } + + void create_topic(const rosbag2_storage::TopicWithType & topic) override + { + (void) topic; + } + + bool has_next() override {return true;} + + std::shared_ptr read_next() override {return nullptr;} + + void write(std::shared_ptr msg) override + { + (void) msg; + } + + std::vector get_all_topics_and_types() override + { + return std::vector(); + } + + rosbag2_storage::BagMetadata get_metadata() override + { + return rosbag2_storage::BagMetadata(); + } +}; + +#endif // ROSBAG2__MOCK_STORAGE_HPP_ diff --git a/rosbag2/test/rosbag2/test_info.cpp b/rosbag2/test/rosbag2/test_info.cpp new file mode 100644 index 000000000..e6841819b --- /dev/null +++ b/rosbag2/test/rosbag2/test_info.cpp @@ -0,0 +1,91 @@ +// Copyright 2018, Bosch Software Innovations 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 + +#include +#include +#include +#include + +#include "mock_metadata_io.hpp" +#include "rosbag2/info.hpp" +#include "rosbag2_storage/bag_metadata.hpp" +#include "rosbag2_storage/filesystem_helper.hpp" +#include "rosbag2_test_common/temporary_directory_fixture.hpp" + +using namespace ::testing; // NOLINT +using namespace rosbag2_test_common; // NOLINT + +TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metadata_io_method) { + std::string bagfile( + "rosbag2_bagfile_information:\n" + " version: 1\n" + " storage_identifier: sqlite3\n" + " storage_format: cdr\n" + " relative_file_paths:\n" + " - some_relative_path\n" + " - some_other_relative_path\n" + " combined_bag_size: 10\n" + " duration:\n" + " nanoseconds: 100\n" + " starting_time:\n" + " nanoseconds_since_epoch: 1000000\n" + " message_count: 50\n" + " topics_with_message_count:\n" + " - topic_and_type:\n" + " name: topic1\n" + " type: type1\n" + " message_count: 100\n" + " - topic_and_type:\n" + " name: topic2\n" + " type: type2\n" + " message_count: 200"); + + std::ofstream fout( + rosbag2_storage::FilesystemHelper::concat({ + temporary_dir_path_, rosbag2_storage::MetadataIo::metadata_filename + })); + fout << bagfile; + fout.close(); + + rosbag2::Info info; + auto read_metadata = info.read_metadata(temporary_dir_path_); + + EXPECT_THAT(read_metadata.storage_identifier, Eq("sqlite3")); + EXPECT_THAT(read_metadata.storage_format, Eq("cdr")); + EXPECT_THAT(read_metadata.relative_file_paths, + Eq(std::vector({"some_relative_path", "some_other_relative_path"}))); + EXPECT_THAT(read_metadata.duration, Eq(std::chrono::nanoseconds(100))); + EXPECT_THAT(read_metadata.starting_time, + Eq(std::chrono::time_point( + std::chrono::nanoseconds(1000000)))); + EXPECT_THAT(read_metadata.message_count, Eq(50u)); + EXPECT_THAT(read_metadata.topics_with_message_count, + SizeIs(2u)); + auto actual_first_topic = read_metadata.topics_with_message_count[0]; + rosbag2_storage::TopicMetadata expected_first_topic = {{"topic1", "type1"}, 100}; + EXPECT_THAT(actual_first_topic.topic_with_type.name, + Eq(expected_first_topic.topic_with_type.name)); + EXPECT_THAT(actual_first_topic.topic_with_type.type, + Eq(expected_first_topic.topic_with_type.type)); + EXPECT_THAT(actual_first_topic.message_count, Eq(expected_first_topic.message_count)); + auto actual_second_topic = read_metadata.topics_with_message_count[1]; + rosbag2_storage::TopicMetadata expected_second_topic = {{"topic2", "type2"}, 200}; + EXPECT_THAT(actual_second_topic.topic_with_type.name, + Eq(expected_second_topic.topic_with_type.name)); + EXPECT_THAT(actual_second_topic.topic_with_type.type, + Eq(expected_second_topic.topic_with_type.type)); + EXPECT_THAT(actual_second_topic.message_count, Eq(expected_second_topic.message_count)); +} diff --git a/rosbag2_storage/CMakeLists.txt b/rosbag2_storage/CMakeLists.txt index 7769bfa98..032ebaba4 100644 --- a/rosbag2_storage/CMakeLists.txt +++ b/rosbag2_storage/CMakeLists.txt @@ -18,17 +18,20 @@ endif() find_package(ament_cmake REQUIRED) find_package(pluginlib REQUIRED) find_package(rcutils REQUIRED) +find_package(rviz_yaml_cpp_vendor REQUIRED) add_library( rosbag2_storage SHARED + src/rosbag2_storage/metadata_io.cpp src/rosbag2_storage/ros_helper.cpp src/rosbag2_storage/storage_factory.cpp) target_include_directories(rosbag2_storage PUBLIC include) ament_target_dependencies( rosbag2_storage pluginlib - rcutils) + rcutils + rviz_yaml_cpp_vendor) # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. @@ -88,6 +91,14 @@ if(BUILD_TESTING) target_link_libraries(test_ros_helper rosbag2_storage) endif() + ament_add_gmock(test_metadata_serialization + test/rosbag2_storage/test_metadata_serialization.cpp) + if(TARGET test_metadata_serialization) + target_include_directories(test_metadata_serialization PRIVATE include) + target_link_libraries(test_metadata_serialization rosbag2_storage) + ament_target_dependencies(test_metadata_serialization rosbag2_test_common) + endif() + ament_add_gmock(test_filesystem_helper test/rosbag2_storage/test_filesystem_helper.cpp) if(TARGET test_filesystem_helper) diff --git a/rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp b/rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp new file mode 100644 index 000000000..bcecd3720 --- /dev/null +++ b/rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp @@ -0,0 +1,50 @@ +// Copyright 2018, Bosch Software Innovations 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. + +#ifndef ROSBAG2_STORAGE__BAG_METADATA_HPP_ +#define ROSBAG2_STORAGE__BAG_METADATA_HPP_ + +#include +#include +#include +#include +#include + +#include "rosbag2_storage/topic_with_type.hpp" + +namespace rosbag2_storage +{ + +struct TopicMetadata +{ + TopicWithType topic_with_type; + size_t message_count; +}; + +struct BagMetadata +{ + int version = 1; + size_t bag_size = 0; // Will not be serialized + std::string storage_identifier; + std::string storage_format; + std::vector relative_file_paths; + std::chrono::nanoseconds duration; + std::chrono::time_point starting_time; + size_t message_count; + std::vector topics_with_message_count; +}; + +} // namespace rosbag2_storage + +#endif // ROSBAG2_STORAGE__BAG_METADATA_HPP_ diff --git a/rosbag2_storage/include/rosbag2_storage/storage_interfaces/base_info_interface.hpp b/rosbag2_storage/include/rosbag2_storage/metadata_io.hpp similarity index 52% rename from rosbag2_storage/include/rosbag2_storage/storage_interfaces/base_info_interface.hpp rename to rosbag2_storage/include/rosbag2_storage/metadata_io.hpp index f8991d142..cdb9c9d8e 100644 --- a/rosbag2_storage/include/rosbag2_storage/storage_interfaces/base_info_interface.hpp +++ b/rosbag2_storage/include/rosbag2_storage/metadata_io.hpp @@ -1,4 +1,4 @@ -// Copyright 2018 Open Source Robotics Foundation, Inc. +// Copyright 2018, Bosch Software Innovations GmbH. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,25 +12,30 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROSBAG2_STORAGE__STORAGE_INTERFACES__BASE_INFO_INTERFACE_HPP_ -#define ROSBAG2_STORAGE__STORAGE_INTERFACES__BASE_INFO_INTERFACE_HPP_ +#ifndef ROSBAG2_STORAGE__METADATA_IO_HPP_ +#define ROSBAG2_STORAGE__METADATA_IO_HPP_ -#include "rosbag2_storage/bag_info.hpp" +#include + +#include "rosbag2_storage/bag_metadata.hpp" +#include "rosbag2_storage/topic_with_type.hpp" #include "rosbag2_storage/visibility_control.hpp" namespace rosbag2_storage { -namespace storage_interfaces -{ -class ROSBAG2_STORAGE_PUBLIC BaseInfoInterface +class MetadataIo { public: - virtual ~BaseInfoInterface() = default; - virtual BagInfo info() = 0; + static constexpr const char * const metadata_filename = "metadata.yaml"; + + ROSBAG2_STORAGE_PUBLIC void write_metadata(const std::string & uri, BagMetadata metadata); + ROSBAG2_STORAGE_PUBLIC BagMetadata read_metadata(const std::string & uri); + +private: + std::string get_metadata_file_name(const std::string & uri); }; -} // namespace storage_interfaces } // namespace rosbag2_storage -#endif // ROSBAG2_STORAGE__STORAGE_INTERFACES__BASE_INFO_INTERFACE_HPP_ +#endif // ROSBAG2_STORAGE__METADATA_IO_HPP_ diff --git a/rosbag2_storage/include/rosbag2_storage/storage_interfaces/base_write_interface.hpp b/rosbag2_storage/include/rosbag2_storage/storage_interfaces/base_write_interface.hpp index e6125ff71..99f6a09c8 100644 --- a/rosbag2_storage/include/rosbag2_storage/storage_interfaces/base_write_interface.hpp +++ b/rosbag2_storage/include/rosbag2_storage/storage_interfaces/base_write_interface.hpp @@ -19,7 +19,7 @@ #include #include "rosbag2_storage/serialized_bag_message.hpp" -#include "rosbag2_storage/bag_info.hpp" +#include "rosbag2_storage/bag_metadata.hpp" #include "rosbag2_storage/topic_with_type.hpp" #include "rosbag2_storage/visibility_control.hpp" @@ -36,6 +36,8 @@ class ROSBAG2_STORAGE_PUBLIC BaseWriteInterface virtual void write(std::shared_ptr msg) = 0; virtual void create_topic(const TopicWithType & topic) = 0; + + virtual BagMetadata get_metadata() = 0; }; } // namespace storage_interfaces diff --git a/rosbag2_storage/include/rosbag2_storage/storage_interfaces/read_only_interface.hpp b/rosbag2_storage/include/rosbag2_storage/storage_interfaces/read_only_interface.hpp index de2f71239..9096bc407 100644 --- a/rosbag2_storage/include/rosbag2_storage/storage_interfaces/read_only_interface.hpp +++ b/rosbag2_storage/include/rosbag2_storage/storage_interfaces/read_only_interface.hpp @@ -17,7 +17,6 @@ #include -#include "rosbag2_storage/storage_interfaces/base_info_interface.hpp" #include "rosbag2_storage/storage_interfaces/base_io_interface.hpp" #include "rosbag2_storage/storage_interfaces/base_read_interface.hpp" #include "rosbag2_storage/visibility_control.hpp" @@ -28,7 +27,7 @@ namespace storage_interfaces { class ROSBAG2_STORAGE_PUBLIC ReadOnlyInterface - : public BaseInfoInterface, public BaseIOInterface, public BaseReadInterface + : public BaseIOInterface, public BaseReadInterface { public: virtual ~ReadOnlyInterface() = default; diff --git a/rosbag2_storage/package.xml b/rosbag2_storage/package.xml index 3f51e7d1d..4fbaa2017 100644 --- a/rosbag2_storage/package.xml +++ b/rosbag2_storage/package.xml @@ -10,6 +10,7 @@ pluginlib rcutils + rviz_yaml_cpp_vendor ament_cmake_gtest ament_cmake_gmock diff --git a/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp b/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp new file mode 100644 index 000000000..f77129489 --- /dev/null +++ b/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp @@ -0,0 +1,177 @@ +// Copyright 2018, Bosch Software Innovations 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 "rosbag2_storage/metadata_io.hpp" + +#include +#include +#include + +#include "rosbag2_storage/filesystem_helper.hpp" + +#ifdef _WIN32 +// This is necessary because of a bug in yaml-cpp's cmake +#define YAML_CPP_DLL +// This is necessary because yaml-cpp does not always use dllimport/dllexport consistently +# pragma warning(push) +# pragma warning(disable:4251) +# pragma warning(disable:4275) +#endif +#include "yaml-cpp/yaml.h" +#ifdef _WIN32 +# pragma warning(pop) +#endif + +namespace YAML +{ +template<> +struct convert +{ + static Node encode(const rosbag2_storage::TopicWithType & topic) + { + Node node; + node["name"] = topic.name; + node["type"] = topic.type; + return node; + } + + static bool decode(const Node & node, rosbag2_storage::TopicWithType & topic) + { + topic.name = node["name"].as(); + topic.type = node["type"].as(); + return true; + } +}; + +template<> +struct convert +{ + static Node encode(const rosbag2_storage::TopicMetadata & metadata) + { + Node node; + node["topic_and_type"] = metadata.topic_with_type; + node["message_count"] = metadata.message_count; + return node; + } + + static bool decode(const Node & node, rosbag2_storage::TopicMetadata & metadata) + { + metadata.topic_with_type = node["topic_and_type"].as(); + metadata.message_count = node["message_count"].as(); + return true; + } +}; + +template<> +struct convert +{ + static Node encode(const std::chrono::nanoseconds & time_in_ns) + { + Node node; + node["nanoseconds"] = time_in_ns.count(); + return node; + } + + static bool decode(const Node & node, std::chrono::nanoseconds & time_in_ns) + { + time_in_ns = std::chrono::nanoseconds(node["nanoseconds"].as()); + return true; + } +}; + +template<> +struct convert> +{ + static Node encode(const std::chrono::time_point & start_time) + { + Node node; + node["nanoseconds_since_epoch"] = start_time.time_since_epoch().count(); + return node; + } + + static bool decode( + const Node & node, std::chrono::time_point & start_time) + { + start_time = std::chrono::time_point( + std::chrono::nanoseconds(node["nanoseconds_since_epoch"].as())); + return true; + } +}; + +template<> +struct convert +{ + static Node encode(const rosbag2_storage::BagMetadata & metadata) + { + Node node; + node["version"] = metadata.version; + node["storage_identifier"] = metadata.storage_identifier; + node["storage_format"] = metadata.storage_format; + node["relative_file_paths"] = metadata.relative_file_paths; + node["duration"] = metadata.duration; + node["starting_time"] = metadata.starting_time; + node["message_count"] = metadata.message_count; + node["topics_with_message_count"] = metadata.topics_with_message_count; + return node; + } + + static bool decode(const Node & node, rosbag2_storage::BagMetadata & metadata) + { + metadata.version = node["version"].as(); + metadata.storage_identifier = node["storage_identifier"].as(); + metadata.storage_format = node["storage_format"].as(); + metadata.relative_file_paths = node["relative_file_paths"].as>(); + metadata.duration = node["duration"].as(); + metadata.starting_time = node["starting_time"] + .as>(); + metadata.message_count = node["message_count"].as(); + metadata.topics_with_message_count = + node["topics_with_message_count"].as>(); + return true; + } +}; + +} // namespace YAML + +namespace rosbag2_storage +{ + +void MetadataIo::write_metadata(const std::string & uri, BagMetadata metadata) +{ + YAML::Node metadata_node; + metadata_node["rosbag2_bagfile_information"] = metadata; + std::ofstream fout(get_metadata_file_name(uri)); + fout << metadata_node; +} + +BagMetadata MetadataIo::read_metadata(const std::string & uri) +{ + try { + YAML::Node yaml_file = YAML::LoadFile(get_metadata_file_name(uri)); + auto metadata = yaml_file["rosbag2_bagfile_information"].as(); + metadata.bag_size = FilesystemHelper::calculate_directory_size(uri); + return metadata; + } catch (const YAML::Exception & ex) { + throw std::runtime_error(std::string("Exception on parsing info file: ") + ex.what()); + } +} + +std::string MetadataIo::get_metadata_file_name(const std::string & uri) +{ + std::string metadata_file = rosbag2_storage::FilesystemHelper::concat({uri, metadata_filename}); + + return metadata_file; +} + +} // namespace rosbag2_storage diff --git a/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp b/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp new file mode 100644 index 000000000..10fb87ee6 --- /dev/null +++ b/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp @@ -0,0 +1,87 @@ +// Copyright 2018, Bosch Software Innovations 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 + +#include +#include +#include +#include +#include + +#ifdef _WIN32 +# include +# include +#endif + +#include "rosbag2_storage/bag_metadata.hpp" +#include "rosbag2_storage/metadata_io.hpp" +#include "rosbag2_storage/filesystem_helper.hpp" +#include "rosbag2_test_common/temporary_directory_fixture.hpp" + +using namespace ::testing; // NOLINT +using namespace rosbag2_storage; // NOLINT +using namespace rosbag2_test_common; // NOLINT + +class MetadataFixture : public TemporaryDirectoryFixture +{ +public: + MetadataFixture() + : metadata_io_(std::make_shared()) {} + + std::shared_ptr metadata_io_; +}; + +TEST_F(MetadataFixture, test_writing_and_reading_yaml) +{ + BagMetadata metadata{}; + metadata.version = 1; + metadata.storage_identifier = "sqlite3"; + metadata.storage_format = "cdr"; + metadata.relative_file_paths.emplace_back("some_relative_path"); + metadata.relative_file_paths.emplace_back("some_other_relative_path"); + metadata.duration = std::chrono::nanoseconds(100); + metadata.starting_time = + std::chrono::time_point(std::chrono::nanoseconds(1000000)); + metadata.message_count = 50; + metadata.topics_with_message_count.push_back({{"topic1", "type1"}, 100}); + metadata.topics_with_message_count.push_back({{"topic2", "type2"}, 200}); + + metadata_io_->write_metadata(temporary_dir_path_, metadata); + auto read_metadata = metadata_io_->read_metadata(temporary_dir_path_); + + EXPECT_THAT(read_metadata.version, Eq(metadata.version)); + EXPECT_THAT(read_metadata.storage_identifier, Eq(metadata.storage_identifier)); + EXPECT_THAT(read_metadata.storage_format, Eq(metadata.storage_format)); + EXPECT_THAT(read_metadata.relative_file_paths, Eq(metadata.relative_file_paths)); + EXPECT_THAT(read_metadata.duration, Eq(metadata.duration)); + EXPECT_THAT(read_metadata.starting_time, Eq(metadata.starting_time)); + EXPECT_THAT(read_metadata.message_count, Eq(metadata.message_count)); + EXPECT_THAT(read_metadata.topics_with_message_count, + SizeIs(metadata.topics_with_message_count.size())); + auto actual_first_topic = read_metadata.topics_with_message_count[0]; + auto expected_first_topic = metadata.topics_with_message_count[0]; + EXPECT_THAT(actual_first_topic.topic_with_type.name, + Eq(expected_first_topic.topic_with_type.name)); + EXPECT_THAT(actual_first_topic.topic_with_type.type, + Eq(expected_first_topic.topic_with_type.type)); + EXPECT_THAT(actual_first_topic.message_count, Eq(expected_first_topic.message_count)); + auto actual_second_topic = read_metadata.topics_with_message_count[1]; + auto expected_second_topic = metadata.topics_with_message_count[1]; + EXPECT_THAT(actual_second_topic.topic_with_type.name, + Eq(expected_second_topic.topic_with_type.name)); + EXPECT_THAT(actual_second_topic.topic_with_type.type, + Eq(expected_second_topic.topic_with_type.type)); + EXPECT_THAT(actual_second_topic.message_count, Eq(expected_second_topic.message_count)); +} diff --git a/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp b/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp index f21d155e4..4855d102a 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp @@ -21,7 +21,6 @@ #include "pluginlib/class_list_macros.hpp" -#include "rosbag2_storage/bag_info.hpp" #include "rosbag2_storage/serialized_bag_message.hpp" #include "test_plugin.hpp" @@ -42,11 +41,6 @@ void TestPlugin::open( std::cout << uri << ".\n"; } -rosbag2_storage::BagInfo TestPlugin::info() -{ - return rosbag2_storage::BagInfo(); -} - bool TestPlugin::has_next() { return true; @@ -75,4 +69,10 @@ std::vector TestPlugin::get_all_topics_and_types return std::vector(); } +rosbag2_storage::BagMetadata TestPlugin::get_metadata() +{ + std::cout << "\nreturning metadata\n"; + return rosbag2_storage::BagMetadata(); +} + PLUGINLIB_EXPORT_CLASS(TestPlugin, rosbag2_storage::storage_interfaces::ReadWriteInterface) diff --git a/rosbag2_storage/test/rosbag2_storage/test_plugin.hpp b/rosbag2_storage/test/rosbag2_storage/test_plugin.hpp index dbc1bc5d3..77d2c5ceb 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_plugin.hpp +++ b/rosbag2_storage/test/rosbag2_storage/test_plugin.hpp @@ -21,7 +21,6 @@ #include #include -#include "rosbag2_storage/bag_info.hpp" #include "rosbag2_storage/serialized_bag_message.hpp" #include "rosbag2_storage/topic_with_type.hpp" #include "rosbag2_storage/storage_interfaces/read_write_interface.hpp" @@ -33,8 +32,6 @@ class TestPlugin : public rosbag2_storage::storage_interfaces::ReadWriteInterfac void open(const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) override; - rosbag2_storage::BagInfo info() override; - void create_topic(const rosbag2_storage::TopicWithType & topic) override; bool has_next() override; @@ -44,6 +41,8 @@ class TestPlugin : public rosbag2_storage::storage_interfaces::ReadWriteInterfac void write(std::shared_ptr msg) override; std::vector get_all_topics_and_types() override; + + rosbag2_storage::BagMetadata get_metadata() override; }; #endif // ROSBAG2_STORAGE__TEST_PLUGIN_HPP_ diff --git a/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.cpp b/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.cpp index a8f818aba..6bbd1ddec 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.cpp @@ -38,11 +38,6 @@ void TestReadOnlyPlugin::open( std::cout << uri << ".\n"; } -rosbag2_storage::BagInfo TestReadOnlyPlugin::info() -{ - return rosbag2_storage::BagInfo(); -} - bool TestReadOnlyPlugin::has_next() { return true; diff --git a/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.hpp b/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.hpp index c0a5ab958..aabe2c329 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.hpp +++ b/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.hpp @@ -29,8 +29,6 @@ class TestReadOnlyPlugin : public rosbag2_storage::storage_interfaces::ReadOnlyI void open(const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) override; - rosbag2_storage::BagInfo info() override; - bool has_next() override; std::shared_ptr read_next() override; diff --git a/rosbag2_storage_default_plugins/include/rosbag2_storage_default_plugins/sqlite/sqlite_storage.hpp b/rosbag2_storage_default_plugins/include/rosbag2_storage_default_plugins/sqlite/sqlite_storage.hpp index d0eec3818..9a10585ba 100644 --- a/rosbag2_storage_default_plugins/include/rosbag2_storage_default_plugins/sqlite/sqlite_storage.hpp +++ b/rosbag2_storage_default_plugins/include/rosbag2_storage_default_plugins/sqlite/sqlite_storage.hpp @@ -60,7 +60,7 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage std::vector get_all_topics_and_types() override; - rosbag2_storage::BagInfo info() override; + rosbag2_storage::BagMetadata get_metadata() override; private: void initialize(); @@ -74,7 +74,7 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage std::shared_ptr, rcutils_time_point_value_t, std::string>; std::shared_ptr database_; - rosbag2_storage::BagInfo bag_info_; + rosbag2_storage::BagMetadata metadata_; SqliteStatement write_statement_; SqliteStatement read_statement_; ReadQueryResult message_result_; diff --git a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp index 8a851f7e2..d7a7a9ee1 100644 --- a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp +++ b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp @@ -15,6 +15,8 @@ #include "rosbag2_storage_default_plugins/sqlite/sqlite_storage.hpp" #include + +#include #include #include #include @@ -36,12 +38,15 @@ namespace rosbag2_storage_plugins SqliteStorage::SqliteStorage() : database_(), - bag_info_(), + metadata_(), write_statement_(nullptr), read_statement_(nullptr), message_result_(nullptr), current_message_row_(nullptr, SqliteStatementWrapper::QueryResult<>::Iterator::POSITION_END) -{} +{ + metadata_.storage_identifier = "sqlite3"; + metadata_.storage_format = "cdr"; // TODO(greimela) Determine format (i.e. data encoding) +} void SqliteStorage::open( const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag io_flag) @@ -57,7 +62,7 @@ void SqliteStorage::open( try { database_ = std::make_unique(database_path, io_flag); - bag_info_.uri = database_name; + metadata_.relative_file_paths = {database_name}; } catch (const SqliteException & e) { throw std::runtime_error("Failed to setup storage. Error: " + std::string(e.what())); } @@ -132,11 +137,6 @@ void SqliteStorage::initialize() database_->prepare_statement(create_table)->execute_and_reset(); } -rosbag2_storage::BagInfo SqliteStorage::info() -{ - return bag_info_; -} - void SqliteStorage::create_topic(const rosbag2_storage::TopicWithType & topic) { if (topics_.find(topic.name) == std::end(topics_)) { @@ -186,8 +186,44 @@ bool SqliteStorage::database_exists(const std::string & uri) return database.good(); } -} // namespace rosbag2_storage_plugins +rosbag2_storage::BagMetadata SqliteStorage::get_metadata() +{ + metadata_.message_count = 0; + metadata_.topics_with_message_count = {}; + + auto statement = database_->prepare_statement( + "SELECT name, type, COUNT(messages.id), MIN(messages.timestamp), MAX(messages.timestamp) " + "FROM messages JOIN topics on topics.id = messages.topic_id " + "GROUP BY topics.name;"); + auto query_results = statement->execute_query< + std::string, std::string, int, rcutils_time_point_value_t, rcutils_time_point_value_t>(); + + rcutils_time_point_value_t min_time = INT64_MAX; + rcutils_time_point_value_t max_time = 0; + for (auto result : query_results) { + metadata_.topics_with_message_count.push_back( + { + {std::get<0>(result), std::get<1>(result)}, + static_cast(std::get<2>(result)) + }); + metadata_.message_count += std::get<2>(result); + min_time = std::get<3>(result) < min_time ? std::get<3>(result) : min_time; + max_time = std::get<4>(result) > max_time ? std::get<4>(result) : max_time; + } + + if (metadata_.message_count == 0) { + min_time = 0; + max_time = 0; + } + metadata_.starting_time = + std::chrono::time_point(std::chrono::nanoseconds(min_time)); + metadata_.duration = std::chrono::nanoseconds(max_time) - std::chrono::nanoseconds(min_time); + + return metadata_; +} + +} // namespace rosbag2_storage_plugins #include "pluginlib/class_list_macros.hpp" // NOLINT PLUGINLIB_EXPORT_CLASS(rosbag2_storage_plugins::SqliteStorage, diff --git a/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp b/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp index bfd2c576b..490d5ca25 100644 --- a/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp +++ b/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp @@ -40,6 +40,17 @@ bool operator!=(const TopicWithType & lhs, const TopicWithType & rhs) return !(lhs == rhs); } +bool operator==(const TopicMetadata & lhs, const TopicMetadata & rhs) +{ + return lhs.topic_with_type == rhs.topic_with_type && + lhs.message_count == rhs.message_count; +} + +bool operator!=(const TopicMetadata & lhs, const TopicMetadata & rhs) +{ + return !(lhs == rhs); +} + } // namespace rosbag2_storage TEST_F(StorageTestFixture, string_messages_are_written_and_read_to_and_from_sqlite3_storage) { @@ -113,3 +124,55 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector) rosbag2_storage::TopicWithType{"topic2", "type2"} })); } + +TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) { + std::vector string_messages = {"first message", "second message", "third message"}; + std::vector topics = {"topic1", "topic2"}; + std::vector> messages = + {std::make_tuple(string_messages[0], static_cast(1e9), topics[0], "type1"), + std::make_tuple(string_messages[1], static_cast(2e9), topics[0], "type1"), + std::make_tuple(string_messages[2], static_cast(3e9), topics[1], "type2")}; + + write_messages_to_sqlite(messages); + + auto readable_storage = std::make_unique(); + 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.storage_format, Eq("cdr")); + EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({ + rosbag2_storage::FilesystemHelper::get_folder_name(temporary_dir_path_) + ".db3" + })); + EXPECT_THAT(metadata.topics_with_message_count, ElementsAreArray({ + rosbag2_storage::TopicMetadata{rosbag2_storage::TopicWithType{"topic1", "type1"}, 2u}, + rosbag2_storage::TopicMetadata{rosbag2_storage::TopicWithType{"topic2", "type2"}, 1u} + })); + EXPECT_THAT(metadata.message_count, Eq(3u)); + EXPECT_THAT(metadata.starting_time, Eq( + std::chrono::time_point(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(); + 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.storage_format, Eq("cdr")); + EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({ + 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)); + EXPECT_THAT(metadata.starting_time, Eq( + std::chrono::time_point(std::chrono::seconds(0)) + )); + EXPECT_THAT(metadata.duration, Eq(std::chrono::seconds(0))); +} diff --git a/rosbag2_tests/CMakeLists.txt b/rosbag2_tests/CMakeLists.txt index 22c13af8e..7317d2ed8 100644 --- a/rosbag2_tests/CMakeLists.txt +++ b/rosbag2_tests/CMakeLists.txt @@ -55,6 +55,14 @@ if(BUILD_TESTING) test_msgs) endif() + ament_add_gmock(test_rosbag2_info_end_to_end + test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) + if(TARGET test_rosbag2_info_end_to_end) + ament_target_dependencies(test_rosbag2_info_end_to_end + rosbag2_storage) + endif() + endif() ament_package() diff --git a/rosbag2_tests/resources/test/metadata.yaml b/rosbag2_tests/resources/test/metadata.yaml new file mode 100644 index 000000000..157490cfc --- /dev/null +++ b/rosbag2_tests/resources/test/metadata.yaml @@ -0,0 +1,20 @@ +rosbag2_bagfile_information: + version: 1 + storage_identifier: sqlite3 + storage_format: cdr + relative_file_paths: + - test.db3 + duration: + nanoseconds: 155979811 + starting_time: + nanoseconds_since_epoch: 1537282604241440135 + message_count: 7 + topics_with_message_count: + - topic_and_type: + name: /test_topic + type: test_msgs/Primitives + message_count: 3 + - topic_and_type: + name: /array_topic + type: test_msgs/StaticArrayPrimitives + message_count: 4 diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp new file mode 100644 index 000000000..25f0143aa --- /dev/null +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp @@ -0,0 +1,63 @@ +// Copyright 2018, Bosch Software Innovations 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 + +#include +#include +#include + +#include "process_execution_helpers.hpp" + +using namespace ::testing; // NOLINT + +class InfoEndToEndTestFixture : public Test +{ +public: + InfoEndToEndTestFixture() + { + database_path_ = _SRC_RESOURCES_DIR_PATH; // variable defined in CMakeLists.txt + } + + std::string database_path_; +}; + +TEST_F(InfoEndToEndTestFixture, info_end_to_end_test) { + internal::CaptureStdout(); + auto exit_code = execute_and_wait_until_completion("ros2 bag info test", database_path_); + std::string output = internal::GetCapturedStdout(); + + EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS)); + // We have two asserts because the bag size depends on the os and, therefore, cannot be asserted. + EXPECT_THAT(output, HasSubstr("\nFiles: test.db3\n")); + EXPECT_THAT(output, HasSubstr( + "\nStorage id: sqlite3" + "\nStorage format: cdr" + "\nDuration: 0.155s" + "\nStart: Sep 18 2018 16:56:44.241 (1537282604.241)" + "\nEnd Sep 18 2018 16:56:44.397 (1537282604.397)" + "\nMessages: 7" + "\nTopics with Type: /test_topic; test_msgs/Primitives; 3 msgs" + "\n /array_topic; test_msgs/StaticArrayPrimitives; 4 msgs")); +} + +TEST_F(InfoEndToEndTestFixture, info_fails_gracefully_if_bag_does_not_exist) { + internal::CaptureStderr(); + auto exit_code = + execute_and_wait_until_completion("ros2 bag info does_not_exist", database_path_); + auto error_output = internal::GetCapturedStderr(); + + EXPECT_THAT(exit_code, Eq(EXIT_FAILURE)); + EXPECT_THAT(error_output, HasSubstr("'does_not_exist' does not exist")); +} diff --git a/rosbag2_transport/CMakeLists.txt b/rosbag2_transport/CMakeLists.txt index 5931e872d..b3296f370 100644 --- a/rosbag2_transport/CMakeLists.txt +++ b/rosbag2_transport/CMakeLists.txt @@ -12,7 +12,7 @@ if(NOT CMAKE_CXX_STANDARD) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) + add_compile_options(-Wall -Wextra -Wpedantic -Werror) endif() find_package(ament_cmake REQUIRED) @@ -25,6 +25,7 @@ find_package(shared_queues_vendor REQUIRED) add_library(${PROJECT_NAME} SHARED src/rosbag2_transport/player.cpp + src/rosbag2_transport/formatter.cpp src/rosbag2_transport/generic_publisher.cpp src/rosbag2_transport/generic_subscription.cpp src/rosbag2_transport/rosbag2_node.cpp @@ -78,6 +79,14 @@ if(BUILD_TESTING) find_package(rosbag2_test_common REQUIRED) ament_lint_auto_find_test_dependencies() + ament_add_gmock(test_info + test/rosbag2_transport/test_info.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) + if(TARGET test_info) + target_link_libraries(test_info rosbag2_transport) + ament_target_dependencies(test_info rosbag2_test_common) + endif() + ament_add_gmock(test_record test/rosbag2_transport/test_record.cpp WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) @@ -128,6 +137,14 @@ if(BUILD_TESTING) test_msgs rosbag2_test_common) endif() + + ament_add_gmock(test_formatter + test/rosbag2_transport/test_formatter.cpp + src/rosbag2_transport/formatter.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) + if(TARGET test_formatter) + target_link_libraries(test_formatter rosbag2_transport) + endif() endif() ament_package() diff --git a/rosbag2_transport/include/rosbag2_transport/rosbag2_transport.hpp b/rosbag2_transport/include/rosbag2_transport/rosbag2_transport.hpp index 7b13894d9..b841b25bc 100644 --- a/rosbag2_transport/include/rosbag2_transport/rosbag2_transport.hpp +++ b/rosbag2_transport/include/rosbag2_transport/rosbag2_transport.hpp @@ -21,6 +21,7 @@ #include #include +#include "rosbag2/info.hpp" #include "rosbag2/sequential_reader.hpp" #include "rosbag2/writer.hpp" #include "rosbag2_transport/play_options.hpp" @@ -46,7 +47,9 @@ class Rosbag2Transport /// Constructor for testing, allows to set the reader and writer to use ROSBAG2_TRANSPORT_PUBLIC Rosbag2Transport( - std::shared_ptr reader, std::shared_ptr writer); + std::shared_ptr reader, + std::shared_ptr writer, + std::shared_ptr info); ROSBAG2_TRANSPORT_PUBLIC void init(); @@ -73,6 +76,14 @@ class Rosbag2Transport ROSBAG2_TRANSPORT_PUBLIC void play(const StorageOptions & storage_options, const PlayOptions & play_options); + /** + * Print the bag info contained in the metadata yaml file. + * + * \param uri path to the metadata yaml file. + */ + ROSBAG2_TRANSPORT_PUBLIC + void print_bag_info(const std::string & uri); + private: std::shared_ptr create_subscription( @@ -81,6 +92,7 @@ class Rosbag2Transport std::shared_ptr reader_; std::shared_ptr writer_; + std::shared_ptr info_; std::shared_ptr transport_node_; diff --git a/rosbag2_transport/src/rosbag2_transport/formatter.cpp b/rosbag2_transport/src/rosbag2_transport/formatter.cpp new file mode 100644 index 000000000..f2cb53ce2 --- /dev/null +++ b/rosbag2_transport/src/rosbag2_transport/formatter.cpp @@ -0,0 +1,131 @@ +// Copyright 2018, Bosch Software Innovations 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 "formatter.hpp" + +#include +#include +#include +#include +#include +#include + +#ifdef _WIN32 +#include +#endif + +namespace rosbag2_transport +{ + +std::map Formatter::format_duration( + std::chrono::high_resolution_clock::duration duration) +{ + std::map formatted_duration; + auto m_seconds = std::chrono::duration_cast(duration); + auto seconds = std::chrono::duration_cast(m_seconds); + std::string fractional_seconds = std::to_string(m_seconds.count() % 1000); + std::time_t std_time_point = seconds.count(); + tm time; +#ifdef _WIN32 + localtime_s(&time, &std_time_point); +#else + localtime_r(&std_time_point, &time); +#endif + + std::stringstream formatted_date; + std::stringstream formatted_time; + formatted_date << std::put_time(&time, "%b %e %Y"); + formatted_time << std::put_time(&time, "%H:%M:%S") << "." << fractional_seconds; + formatted_duration["date"] = formatted_date.str(); + formatted_duration["time"] = formatted_time.str(); + formatted_duration["time_in_sec"] = std::to_string(seconds.count()) + "." + fractional_seconds; + + return formatted_duration; +} + +std::string Formatter::format_time_point( + std::chrono::high_resolution_clock::duration duration) +{ + auto formatted_duration = format_duration(duration); + return formatted_duration["date"] + " " + formatted_duration["time"] + + " (" + formatted_duration["time_in_sec"] + ")"; +} + +std::string Formatter::format_file_size(size_t file_size) +{ + double size = static_cast(file_size); + static const char * units[] = {"B", "KiB", "MiB", "GiB", "TiB"}; + double reference_number_bytes = 1024; + int index = 0; + while (size >= reference_number_bytes && index < 4) { + size /= reference_number_bytes; + index++; + } + + std::stringstream rounded_size; + int size_format_precision = index == 0 ? 0 : 1; + rounded_size << std::setprecision(size_format_precision) << std::fixed << size; + return rounded_size.str() + " " + units[index]; +} + +void Formatter::format_file_paths( + std::vector paths, std::stringstream & info_stream, int indentation_spaces) +{ + if (paths.empty()) { + info_stream << std::endl; + return; + } + + size_t number_of_files = paths.size(); + for (size_t i = 0; i < number_of_files; i++) { + if (i == 0) { + info_stream << paths[i] << std::endl; + } else { + indent(info_stream, indentation_spaces); + info_stream << paths[i] << std::endl; + } + } +} + +void Formatter::format_topics_with_type( + std::vector topics, + std::stringstream & info_stream, + int indentation_spaces) +{ + if (topics.empty()) { + info_stream << std::endl; + return; + } + + size_t number_of_topics = topics.size(); + for (size_t j = 0; j < number_of_topics; ++j) { + std::string topic_with_type = topics[j].topic_with_type.name + "; " + + topics[j].topic_with_type.type + "; " + std::to_string(topics[j].message_count) + " msgs\n"; + if (j == 0) { + info_stream << topic_with_type; + } else { + indent(info_stream, indentation_spaces); + info_stream << topic_with_type; + } + } +} + +void Formatter::indent(std::stringstream & info_stream, int number_of_spaces) +{ + for (int i = 0; i < number_of_spaces; i++) { + info_stream << " "; + } +} + +} // namespace rosbag2_transport diff --git a/rosbag2_transport/src/rosbag2_transport/formatter.hpp b/rosbag2_transport/src/rosbag2_transport/formatter.hpp new file mode 100644 index 000000000..cf477ae55 --- /dev/null +++ b/rosbag2_transport/src/rosbag2_transport/formatter.hpp @@ -0,0 +1,47 @@ +// Copyright 2018, Bosch Software Innovations 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. + +#ifndef ROSBAG2_TRANSPORT__FORMATTER_HPP_ +#define ROSBAG2_TRANSPORT__FORMATTER_HPP_ + +#include +#include +#include +#include +#include + +#include "rosbag2/types.hpp" + +namespace rosbag2_transport +{ + +class Formatter +{ +public: + static std::map format_duration( + std::chrono::high_resolution_clock::duration duration); + static std::string format_time_point(std::chrono::high_resolution_clock::duration time_point); + static std::string format_file_size(size_t file_size); + static void format_file_paths( + std::vector paths, std::stringstream & info_stream, int indentation_spaces); + static void format_topics_with_type( + std::vector, std::stringstream & info_stream, int indentation_spaces); + +private: + static void indent(std::stringstream & info_stream, int number_of_spaces); +}; + +} // namespace rosbag2_transport + +#endif // ROSBAG2_TRANSPORT__FORMATTER_HPP_ diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp index fc1d59e20..3f8701727 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp @@ -14,7 +14,6 @@ #include "rosbag2_transport/rosbag2_transport.hpp" -#include #include #include #include @@ -22,7 +21,6 @@ #include #include -#include "rcl/graph.h" #include "rclcpp/rclcpp.hpp" #include "rcutils/time.h" @@ -32,6 +30,7 @@ #include "rosbag2/typesupport_helpers.hpp" #include "rosbag2/writer.hpp" +#include "formatter.hpp" #include "generic_subscription.hpp" #include "player.hpp" #include "replayable_message.hpp" @@ -42,12 +41,15 @@ namespace rosbag2_transport Rosbag2Transport::Rosbag2Transport() : reader_(std::make_shared()), - writer_(std::make_shared()) + writer_(std::make_shared()), + info_(std::make_shared()) {} Rosbag2Transport::Rosbag2Transport( - std::shared_ptr reader, std::shared_ptr writer) -: reader_(std::move(reader)), writer_(std::move(writer)) {} + std::shared_ptr reader, + std::shared_ptr writer, + std::shared_ptr info) +: reader_(std::move(reader)), writer_(std::move(writer)), info_(std::move(info)) {} void Rosbag2Transport::init() { @@ -139,4 +141,32 @@ void Rosbag2Transport::play( player.play(play_options); } +void Rosbag2Transport::print_bag_info(const std::string & uri) +{ + auto metadata = info_->read_metadata(uri); + auto start_time = metadata.starting_time.time_since_epoch(); + auto end_time = start_time + metadata.duration; + auto formatter = std::make_unique(); + std::stringstream info_stream; + int indentation_spaces = 18; // just the longest info field (Topics with Type:) plus one space. + + info_stream << std::endl; + info_stream << "Files: "; + formatter->format_file_paths(metadata.relative_file_paths, info_stream, indentation_spaces); + info_stream << "Bag size: " << formatter->format_file_size( + metadata.bag_size) << std::endl; + info_stream << "Storage id: " << metadata.storage_identifier << std::endl; + info_stream << "Storage format: " << metadata.storage_format << std::endl; + info_stream << "Duration: " << formatter->format_duration( + metadata.duration)["time_in_sec"] << "s" << std::endl; + info_stream << "Start: " << formatter->format_time_point(start_time) << std::endl; + info_stream << "End " << formatter->format_time_point(end_time) << std::endl; + info_stream << "Messages: " << metadata.message_count << std::endl; + info_stream << "Topics with Type: "; + formatter->format_topics_with_type( + metadata.topics_with_message_count, info_stream, indentation_spaces); + + std::cout << info_stream.str() << std::endl; +} + } // namespace rosbag2_transport diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp index 438c3d460..69022dc92 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp @@ -98,6 +98,24 @@ rosbag2_transport_play(PyObject * Py_UNUSED(self), PyObject * args, PyObject * k Py_RETURN_NONE; } +static PyObject * +rosbag2_transport_info(PyObject * Py_UNUSED(self), PyObject * args, PyObject * kwargs) +{ + static const char * kwlist[] = {"uri", nullptr}; + + char * char_uri; + if (!PyArg_ParseTupleAndKeywords(args, kwargs, "s", const_cast(kwlist), &char_uri)) { + return nullptr; + } + + std::string uri = std::string(char_uri); + + rosbag2_transport::Rosbag2Transport transport; + transport.print_bag_info(uri); + + Py_RETURN_NONE; +} + /// Define the public methods of this module static PyMethodDef rosbag2_transport_methods[] = { { @@ -108,6 +126,10 @@ static PyMethodDef rosbag2_transport_methods[] = { "play", reinterpret_cast(rosbag2_transport_play), METH_VARARGS | METH_KEYWORDS, "Play bag" }, + { + "info", reinterpret_cast(rosbag2_transport_info), METH_VARARGS | METH_KEYWORDS, + "Print bag info" + }, {nullptr, nullptr, 0, nullptr} /* sentinel */ }; diff --git a/rosbag2_transport/test/rosbag2_transport/mock_info.hpp b/rosbag2_transport/test/rosbag2_transport/mock_info.hpp new file mode 100644 index 000000000..42e082594 --- /dev/null +++ b/rosbag2_transport/test/rosbag2_transport/mock_info.hpp @@ -0,0 +1,31 @@ +// Copyright 2018, Bosch Software Innovations 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. + +#ifndef ROSBAG2_TRANSPORT__MOCK_INFO_HPP_ +#define ROSBAG2_TRANSPORT__MOCK_INFO_HPP_ + +#include + +#include + +#include "rosbag2/info.hpp" +#include "rosbag2/types.hpp" + +class MockInfo : public rosbag2::Info +{ +public: + MOCK_METHOD1(read_metadata, rosbag2::BagMetadata(const std::string &)); +}; + +#endif // ROSBAG2_TRANSPORT__MOCK_INFO_HPP_ diff --git a/rosbag2_transport/test/rosbag2_transport/record_integration_fixture.hpp b/rosbag2_transport/test/rosbag2_transport/record_integration_fixture.hpp index 1c4069439..a64a93133 100644 --- a/rosbag2_transport/test/rosbag2_transport/record_integration_fixture.hpp +++ b/rosbag2_transport/test/rosbag2_transport/record_integration_fixture.hpp @@ -51,7 +51,7 @@ class RecordIntegrationTestFixture : public Rosbag2TransportTestFixture // the future object returned from std::async needs to be stored not to block the execution future_ = std::async( std::launch::async, [this, options]() { - rosbag2_transport::Rosbag2Transport rosbag2_transport(reader_, writer_); + rosbag2_transport::Rosbag2Transport rosbag2_transport(reader_, writer_, info_); rosbag2_transport.record(storage_options_, options); }); } diff --git a/rosbag2_transport/test/rosbag2_transport/rosbag2_transport_test_fixture.hpp b/rosbag2_transport/test/rosbag2_transport/rosbag2_transport_test_fixture.hpp index 58f52deb2..ff1750c14 100644 --- a/rosbag2_transport/test/rosbag2_transport/rosbag2_transport_test_fixture.hpp +++ b/rosbag2_transport/test/rosbag2_transport/rosbag2_transport_test_fixture.hpp @@ -36,6 +36,8 @@ #include "rosbag2/types.hpp" #include "rosbag2/writer.hpp" #include "rosbag2_test_common/memory_management.hpp" + +#include "mock_info.hpp" #include "mock_sequential_reader.hpp" #include "mock_writer.hpp" @@ -57,7 +59,8 @@ class Rosbag2TransportTestFixture : public Test Rosbag2TransportTestFixture() : storage_options_({"uri", "storage_id"}), play_options_({1000}), reader_(std::make_shared()), - writer_(std::make_shared()) {} + writer_(std::make_shared()), + info_(std::make_shared()) {} template std::shared_ptr @@ -81,6 +84,7 @@ class Rosbag2TransportTestFixture : public Test std::shared_ptr reader_; std::shared_ptr writer_; + std::shared_ptr info_; }; #endif // ROSBAG2_TRANSPORT__ROSBAG2_TRANSPORT_TEST_FIXTURE_HPP_ diff --git a/rosbag2_transport/test/rosbag2_transport/test_formatter.cpp b/rosbag2_transport/test/rosbag2_transport/test_formatter.cpp new file mode 100644 index 000000000..f7e3c9f9a --- /dev/null +++ b/rosbag2_transport/test/rosbag2_transport/test_formatter.cpp @@ -0,0 +1,92 @@ +// Copyright 2018, Bosch Software Innovations 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 + +#include +#include +#include +#include +#include + +#include "../../src/rosbag2_transport/formatter.hpp" + +using namespace ::testing; // NOLINT +using namespace std::chrono_literals; // NOLINT + +class FormatterTestFixture : public Test +{ +public: + FormatterTestFixture() + : formatter_(std::make_unique()), indentation_spaces_(18) {} + + std::unique_ptr formatter_; + int indentation_spaces_; +}; + +TEST_F(FormatterTestFixture, format_file_size_returns_correct_format) { + size_t zero_bytes = 0; + size_t thirty_bytes = 30; + size_t two_kibibytes = 2048; + size_t two_point_twelve_kibibytes = 3195; + size_t one_and_a_half_mebibytes = 1536 * 1024; + size_t one_tebibite = static_cast(pow(1024, 4)); + size_t one_pebibyte = static_cast(pow(1024, 5)); + + EXPECT_THAT(formatter_->format_file_size(zero_bytes), Eq("0 B")); + EXPECT_THAT(formatter_->format_file_size(thirty_bytes), Eq("30 B")); + EXPECT_THAT(formatter_->format_file_size(two_kibibytes), Eq("2.0 KiB")); + EXPECT_THAT(formatter_->format_file_size(two_point_twelve_kibibytes), Eq("3.1 KiB")); + EXPECT_THAT(formatter_->format_file_size(one_and_a_half_mebibytes), Eq("1.5 MiB")); + EXPECT_THAT(formatter_->format_file_size(one_tebibite), Eq("1.0 TiB")); + EXPECT_THAT(formatter_->format_file_size(one_pebibyte), Eq("1024.0 TiB")); +} + +TEST_F(FormatterTestFixture, format_files_correctly_layouts_more_paths) { + std::vector paths = {"first/file/path", "second/file", "third/path/"}; + std::stringstream formatted_output; + + formatter_->format_file_paths(paths, formatted_output, indentation_spaces_); + EXPECT_THAT(formatted_output.str(), Eq( + "first/file/path\n" + " second/file\n" + " third/path/\n")); +} + +TEST_F(FormatterTestFixture, format_files_prints_newline_if_there_are_no_paths) { + std::vector paths = {}; + std::stringstream formatted_output; + + formatter_->format_file_paths(paths, formatted_output, 0); + EXPECT_THAT(formatted_output.str(), Eq("\n")); +} + +TEST_F(FormatterTestFixture, format_topics_with_type_correctly_layouts_more_topics) { + std::vector topics; + topics.push_back({{"topic1", "type1"}, 100}); + topics.push_back({{"topic2", "type2"}, 200}); + std::stringstream formatted_output; + + formatter_->format_topics_with_type(topics, formatted_output, indentation_spaces_); + EXPECT_THAT(formatted_output.str(), Eq("topic1; type1; 100 msgs\n" + " topic2; type2; 200 msgs\n")); +} + +TEST_F(FormatterTestFixture, format_topics_with_type_prints_newline_if_there_are_no_topics) { + std::vector topics = {}; + std::stringstream formatted_output; + + formatter_->format_topics_with_type(topics, formatted_output, 0); + EXPECT_THAT(formatted_output.str(), Eq("\n")); +} diff --git a/rosbag2_transport/test/rosbag2_transport/test_info.cpp b/rosbag2_transport/test/rosbag2_transport/test_info.cpp new file mode 100644 index 000000000..fd85ae2c0 --- /dev/null +++ b/rosbag2_transport/test/rosbag2_transport/test_info.cpp @@ -0,0 +1,63 @@ +// Copyright 2018, Bosch Software Innovations 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 + +#include +#include +#include +#include +#include + +#include "rosbag2/types.hpp" +#include "rosbag2_transport/rosbag2_transport.hpp" +#include "rosbag2_transport_test_fixture.hpp" + +using namespace ::testing; // NOLINT + +TEST_F(Rosbag2TransportTestFixture, info_pretty_prints_information_from_bagfile) +{ + internal::CaptureStdout(); + + rosbag2::BagMetadata bagfile; + bagfile.storage_identifier = "sqlite3"; + bagfile.storage_format = "cdr"; + bagfile.relative_file_paths.emplace_back("some_relative_path"); + bagfile.relative_file_paths.emplace_back("some_other_relative_path"); + bagfile.starting_time = std::chrono::time_point( + std::chrono::nanoseconds(1538051985348887471)); // corresponds to Sept 27 14:39:45.348 + bagfile.duration = std::chrono::nanoseconds(50000000); + bagfile.message_count = 50; + bagfile.topics_with_message_count.push_back({{"topic1", "type1"}, 100}); + bagfile.topics_with_message_count.push_back({{"topic2", "type2"}, 200}); + EXPECT_CALL(*info_, read_metadata(_)).WillOnce(Return(bagfile)); + + rosbag2_transport::Rosbag2Transport transport(reader_, writer_, info_); + transport.print_bag_info("test"); + std::string expected_output( + "\nFiles: some_relative_path\n" + " some_other_relative_path\n" + "Bag size: 0 B\n" + "Storage id: sqlite3\n" + "Storage format: cdr\n" + "Duration: 0.50s\n" + "Start: Sep 27 2018 14:39:45.348 (1538051985.348)\n" + "End Sep 27 2018 14:39:45.398 (1538051985.398)\n" + "Messages: 50\n" + "Topics with Type: topic1; type1; 100 msgs\n" + " topic2; type2; 200 msgs\n\n"); + + std::string output = internal::GetCapturedStdout(); + EXPECT_THAT(output, HasSubstr(expected_output)); +} diff --git a/rosbag2_transport/test/rosbag2_transport/test_play.cpp b/rosbag2_transport/test/rosbag2_transport/test_play.cpp index 0e16bb559..0faea8079 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play.cpp @@ -85,7 +85,7 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_all_topics) auto await_received_messages = sub_->spin_subscriptions(); - Rosbag2Transport rosbag2_transport(reader_, writer_); + Rosbag2Transport rosbag2_transport(reader_, writer_, info_); rosbag2_transport.play(storage_options_, play_options_); await_received_messages.get(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp index 862bc2d4e..cf752dc9e 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp @@ -54,7 +54,7 @@ TEST_F(Rosbag2TransportTestFixture, playing_respects_relative_timing_of_stored_m // we check that time elapsed during playing is at least the time difference between the two // messages auto start = std::chrono::steady_clock::now(); - Rosbag2Transport rosbag2_transport(reader_, writer_); + Rosbag2Transport rosbag2_transport(reader_, writer_, info_); rosbag2_transport.play(storage_options_, play_options_); auto replay_time = std::chrono::steady_clock::now() - start;