From edf7c396b7d6f9518dbd990dc6178884e63e67b6 Mon Sep 17 00:00:00 2001 From: Zachary Michaels Date: Mon, 7 Oct 2019 14:26:40 -0700 Subject: [PATCH 1/8] Change writer to support bagfile split feature Signed-off-by: Prajakta Gokhale --- rosbag2/include/rosbag2/writer.hpp | 5 +++++ rosbag2/src/rosbag2/writer.cpp | 6 ++++++ 2 files changed, 11 insertions(+) diff --git a/rosbag2/include/rosbag2/writer.hpp b/rosbag2/include/rosbag2/writer.hpp index f3e0a88e4..ab131e057 100644 --- a/rosbag2/include/rosbag2/writer.hpp +++ b/rosbag2/include/rosbag2/writer.hpp @@ -92,6 +92,11 @@ class ROSBAG2_PUBLIC Writer final return *writer_impl_; } + /** + * Check if the current recording database file needs to be split and rolled over to new file. + */ + virtual bool should_split_database() const; + private: std::unique_ptr writer_impl_; }; diff --git a/rosbag2/src/rosbag2/writer.cpp b/rosbag2/src/rosbag2/writer.cpp index 9898adf5c..7f9446d3b 100644 --- a/rosbag2/src/rosbag2/writer.cpp +++ b/rosbag2/src/rosbag2/writer.cpp @@ -60,4 +60,10 @@ void Writer::write(std::shared_ptr message) writer_impl_->write(message); } +bool Writer::should_split_database() const +{ + return (max_bagfile_size_ != rosbag2_storage::storage_interfaces::MAX_BAGFILE_SIZE_NO_SPLIT) && + (storage_->get_bagfile_size() > max_bagfile_size_); +} + } // namespace rosbag2 From ee6fa2ba50ed49a0ea0bacb9930a26a2eea5cc2a Mon Sep 17 00:00:00 2001 From: Zachary Michaels Date: Tue, 8 Oct 2019 10:08:54 -0700 Subject: [PATCH 2/8] Change sqlite_storage to support bagfile splitting Signed-off-by: Prajakta Gokhale --- rosbag2/src/rosbag2/writer.cpp | 2 +- .../base_write_interface.hpp | 2 ++ .../test/rosbag2_storage/test_plugin.cpp | 3 +-- .../rosbag2_storage/test_read_only_plugin.cpp | 2 +- .../sqlite/sqlite_storage.hpp | 2 ++ .../sqlite/sqlite_storage.cpp | 20 ++++++++++++++++--- 6 files changed, 24 insertions(+), 7 deletions(-) diff --git a/rosbag2/src/rosbag2/writer.cpp b/rosbag2/src/rosbag2/writer.cpp index 7f9446d3b..88601ad3c 100644 --- a/rosbag2/src/rosbag2/writer.cpp +++ b/rosbag2/src/rosbag2/writer.cpp @@ -63,7 +63,7 @@ void Writer::write(std::shared_ptr message) bool Writer::should_split_database() const { return (max_bagfile_size_ != rosbag2_storage::storage_interfaces::MAX_BAGFILE_SIZE_NO_SPLIT) && - (storage_->get_bagfile_size() > max_bagfile_size_); + (storage_->get_current_bagfile_size() > max_bagfile_size_); } } // namespace rosbag2 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 b5ad6117d..0a60ec860 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 @@ -38,6 +38,8 @@ class ROSBAG2_STORAGE_PUBLIC BaseWriteInterface virtual void create_topic(const TopicMetadata & topic) = 0; virtual void remove_topic(const TopicMetadata & topic) = 0; + + virtual void split_database() = 0; }; } // namespace storage_interfaces diff --git a/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp b/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp index 294ef3973..13eefda80 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp @@ -30,8 +30,7 @@ TestPlugin::~TestPlugin() std::cout << "\nclosing.\n"; } -void TestPlugin::open( - const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) +void TestPlugin::open(const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) { if (flag == rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY) { std::cout << "opening testplugin read only: "; 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 9345be50e..5f0f3ab58 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.cpp @@ -67,7 +67,7 @@ rosbag2_storage::BagMetadata TestReadOnlyPlugin::get_metadata() return rosbag2_storage::BagMetadata(); } -uint64_t TestReadOnlyPlugin::get_bagfile_size() const +uint64_t TestReadOnlyPlugin::get_current_bagfile_size() const { std::cout << "\nreturning bagfile size\n"; return test_constants::MAX_BAGFILE_SIZE; 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 9fac1a998..06aa10abb 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 @@ -75,6 +75,8 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage void prepare_for_writing(); void prepare_for_reading(); void fill_topics_and_types(); + std::string get_current_database_file_name() const; + std::string get_current_database_file_path() const; using ReadQueryResult = SqliteStatementWrapper::QueryResult< std::shared_ptr, rcutils_time_point_value_t, std::string>; 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 a79e8df8f..c8d808b3f 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 @@ -22,6 +22,7 @@ #include #include #include +#include #include #include @@ -59,7 +60,6 @@ constexpr const auto FILE_EXTENSION = ".db3"; namespace rosbag2_storage_plugins { - void SqliteStorage::open( const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag io_flag) { @@ -116,6 +116,20 @@ void SqliteStorage::write(std::shared_ptrexecute_and_reset(); } +uint64_t SqliteStorage::get_current_bagfile_size() const +{ + return rosbag2_storage::FilesystemHelper::get_file_size(get_current_database_file_path()); +} + +void SqliteStorage::split_database() +{ + database_file_counter_++; + read_statement_.reset(); + write_statement_.reset(); + database_.reset(); + open(uri_, io_flag_); +} + bool SqliteStorage::has_next() { if (!read_statement_) { @@ -245,7 +259,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata() metadata.message_count = 0; metadata.topics_with_message_count = {}; - auto statement = database_->prepare_statement( + const auto & statement = database_->prepare_statement( "SELECT name, type, serialization_format, COUNT(messages.id), MIN(messages.timestamp), " "MAX(messages.timestamp) " "FROM messages JOIN topics on topics.id = messages.topic_id " @@ -256,7 +270,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata() rcutils_time_point_value_t min_time = INT64_MAX; rcutils_time_point_value_t max_time = 0; - for (auto result : query_results) { + for (const auto & result : query_results) { metadata.topics_with_message_count.push_back( { {std::get<0>(result), std::get<1>(result), std::get<2>(result)}, From a7357506d18be973480160ce4c9ce3836a41a98b Mon Sep 17 00:00:00 2001 From: Zachary Michaels Date: Tue, 8 Oct 2019 10:18:15 -0700 Subject: [PATCH 3/8] Change Writer to support changes to sqlite_storage bagfile splitting Signed-off-by: Prajakta Gokhale --- rosbag2/src/rosbag2/writer.cpp | 32 ++++++++++++++++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/rosbag2/src/rosbag2/writer.cpp b/rosbag2/src/rosbag2/writer.cpp index 88601ad3c..edc8af13e 100644 --- a/rosbag2/src/rosbag2/writer.cpp +++ b/rosbag2/src/rosbag2/writer.cpp @@ -66,4 +66,36 @@ bool Writer::should_split_database() const (storage_->get_current_bagfile_size() > max_bagfile_size_); } +void Writer::initialize_metadata_() +{ + metadata_.message_count = 0; + metadata_.topics_with_message_count = {}; + metadata_.starting_time = + std::chrono::time_point( + std::chrono::nanoseconds(INT64_MAX)); + metadata_.duration = std::chrono::nanoseconds(0); + metadata_.bag_size = 0; +} + +void Writer::aggregate_metadata_(rosbag2_storage::BagMetadata metadata) +{ + metadata_.storage_identifier = metadata.storage_identifier; + metadata_.relative_file_paths.swap(metadata.relative_file_paths); + metadata_.message_count += metadata.message_count; + + if (metadata_.starting_time > metadata.starting_time && + metadata.starting_time != + std::chrono::time_point(std::chrono::nanoseconds(0))) + { + metadata_.starting_time = metadata.starting_time; + } + + metadata_.duration += metadata.duration; + metadata_.bag_size = metadata.bag_size; + metadata_.topics_with_message_count.insert( + metadata_.topics_with_message_count.end(), + metadata.topics_with_message_count.begin(), + metadata.topics_with_message_count.end()); +} + } // namespace rosbag2 From f9441cfc18027e8fcb2c86678746d45c68096880 Mon Sep 17 00:00:00 2001 From: Prajakta Gokhale Date: Tue, 1 Oct 2019 09:19:12 -0700 Subject: [PATCH 4/8] Add CLI option to split recording into multiple files Signed-off-by: Prajakta Gokhale --- ros2bag/ros2bag/verb/record.py | 11 ++++++++++- .../rosbag2_transport/rosbag2_transport_python.cpp | 6 +++++- 2 files changed, 15 insertions(+), 2 deletions(-) diff --git a/ros2bag/ros2bag/verb/record.py b/ros2bag/ros2bag/verb/record.py index b7cd65173..eb3360b62 100644 --- a/ros2bag/ros2bag/verb/record.py +++ b/ros2bag/ros2bag/verb/record.py @@ -49,6 +49,13 @@ def add_arguments(self, parser, cli_name): # noqa: D102 help='time in ms to wait between querying available topics for recording. It has no ' 'effect if --no-discovery is enabled.' ) + parser.add_argument( + '-b', '--bag-size', type=int, default=0, + help='provides a threshold for recording bagfile size in bytes, before the recording is split and ' + 'rolled over to a new bagfile. This value is only used as a guideline because actually enforcing a ' + 'maximum file size is difficult. The actual bagfile size may be a little over this value. ' + 'By default it is zero, all recording data is written to single bagfile and this feature is disabled.' + ) self._subparser = parser def create_bag_directory(self, uri): @@ -83,7 +90,8 @@ def main(self, *, args): # noqa: D102 node_prefix=NODE_NAME_PREFIX, all=True, no_discovery=args.no_discovery, - polling_interval=args.polling_interval) + polling_interval=args.polling_interval, + max_bagfile_size=args.bag_size) elif args.topics and len(args.topics) > 0: # NOTE(hidmic): in merged install workspaces on Windows, Python entrypoint lookups # combined with constrained environments (as imposed by colcon test) @@ -99,6 +107,7 @@ def main(self, *, args): # noqa: D102 node_prefix=NODE_NAME_PREFIX, no_discovery=args.no_discovery, polling_interval=args.polling_interval, + max_bagfile_size=args.bag_size, topics=args.topics) else: self._subparser.print_help() diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp index ca0f0a3c4..ae601f745 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp @@ -36,6 +36,7 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject * "all", "no_discovery", "polling_interval", + "max_bagfile_size", "topics", nullptr}; @@ -46,8 +47,9 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject * bool all = false; bool no_discovery = false; uint64_t polling_interval_ms = 100; + unsigned long long max_bagfile_size = 0; // NOLINT PyObject * topics = nullptr; - if (!PyArg_ParseTupleAndKeywords(args, kwargs, "ssss|bbKO", const_cast(kwlist), + if (!PyArg_ParseTupleAndKeywords(args, kwargs, "ssss|bbKKO", const_cast(kwlist), &uri, &storage_id, &serilization_format, @@ -55,6 +57,7 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject * &all, &no_discovery, &polling_interval_ms, + &max_bagfile_size, &topics)) { return nullptr; @@ -62,6 +65,7 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject * storage_options.uri = std::string(uri); storage_options.storage_id = std::string(storage_id); + storage_options.max_bagfile_size = (uint64_t) max_bagfile_size; record_options.all = all; record_options.is_discovery_disabled = no_discovery; record_options.topic_polling_interval = std::chrono::milliseconds(polling_interval_ms); From 8e087feeaa9e7623b6e31db6d1821eff06adc3b1 Mon Sep 17 00:00:00 2001 From: Prajakta Gokhale Date: Wed, 13 Nov 2019 16:56:57 -0800 Subject: [PATCH 5/8] Merge rosbag2/master Signed-off-by: Prajakta Gokhale --- rosbag2/include/rosbag2/writer.hpp | 5 ----- .../base_write_interface.hpp | 2 -- .../test/rosbag2_storage/test_plugin.cpp | 3 ++- .../sqlite/sqlite_storage.hpp | 2 -- .../sqlite/sqlite_storage.cpp | 19 ++----------------- 5 files changed, 4 insertions(+), 27 deletions(-) diff --git a/rosbag2/include/rosbag2/writer.hpp b/rosbag2/include/rosbag2/writer.hpp index ab131e057..f3e0a88e4 100644 --- a/rosbag2/include/rosbag2/writer.hpp +++ b/rosbag2/include/rosbag2/writer.hpp @@ -92,11 +92,6 @@ class ROSBAG2_PUBLIC Writer final return *writer_impl_; } - /** - * Check if the current recording database file needs to be split and rolled over to new file. - */ - virtual bool should_split_database() const; - private: std::unique_ptr writer_impl_; }; 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 0a60ec860..b5ad6117d 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 @@ -38,8 +38,6 @@ class ROSBAG2_STORAGE_PUBLIC BaseWriteInterface virtual void create_topic(const TopicMetadata & topic) = 0; virtual void remove_topic(const TopicMetadata & topic) = 0; - - virtual void split_database() = 0; }; } // namespace storage_interfaces diff --git a/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp b/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp index 13eefda80..294ef3973 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_plugin.cpp @@ -30,7 +30,8 @@ TestPlugin::~TestPlugin() std::cout << "\nclosing.\n"; } -void TestPlugin::open(const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) +void TestPlugin::open( + const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) { if (flag == rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY) { std::cout << "opening testplugin read only: "; 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 06aa10abb..9fac1a998 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 @@ -75,8 +75,6 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage void prepare_for_writing(); void prepare_for_reading(); void fill_topics_and_types(); - std::string get_current_database_file_name() const; - std::string get_current_database_file_path() const; using ReadQueryResult = SqliteStatementWrapper::QueryResult< std::shared_ptr, rcutils_time_point_value_t, std::string>; 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 c8d808b3f..9a7ccadcc 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 @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -116,20 +115,6 @@ void SqliteStorage::write(std::shared_ptrexecute_and_reset(); } -uint64_t SqliteStorage::get_current_bagfile_size() const -{ - return rosbag2_storage::FilesystemHelper::get_file_size(get_current_database_file_path()); -} - -void SqliteStorage::split_database() -{ - database_file_counter_++; - read_statement_.reset(); - write_statement_.reset(); - database_.reset(); - open(uri_, io_flag_); -} - bool SqliteStorage::has_next() { if (!read_statement_) { @@ -259,7 +244,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata() metadata.message_count = 0; metadata.topics_with_message_count = {}; - const auto & statement = database_->prepare_statement( + auto statement = database_->prepare_statement( "SELECT name, type, serialization_format, COUNT(messages.id), MIN(messages.timestamp), " "MAX(messages.timestamp) " "FROM messages JOIN topics on topics.id = messages.topic_id " @@ -270,7 +255,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata() rcutils_time_point_value_t min_time = INT64_MAX; rcutils_time_point_value_t max_time = 0; - for (const auto & result : query_results) { + for (auto result : query_results) { metadata.topics_with_message_count.push_back( { {std::get<0>(result), std::get<1>(result), std::get<2>(result)}, From 665bb0a486f2727696c26825e31b924aef132ab3 Mon Sep 17 00:00:00 2001 From: Prajakta Gokhale Date: Wed, 13 Nov 2019 17:08:53 -0800 Subject: [PATCH 6/8] Make help text short and succinct Signed-off-by: Prajakta Gokhale --- ros2bag/ros2bag/verb/record.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/ros2bag/ros2bag/verb/record.py b/ros2bag/ros2bag/verb/record.py index eb3360b62..910e57824 100644 --- a/ros2bag/ros2bag/verb/record.py +++ b/ros2bag/ros2bag/verb/record.py @@ -50,11 +50,9 @@ def add_arguments(self, parser, cli_name): # noqa: D102 'effect if --no-discovery is enabled.' ) parser.add_argument( - '-b', '--bag-size', type=int, default=0, - help='provides a threshold for recording bagfile size in bytes, before the recording is split and ' - 'rolled over to a new bagfile. This value is only used as a guideline because actually enforcing a ' - 'maximum file size is difficult. The actual bagfile size may be a little over this value. ' - 'By default it is zero, all recording data is written to single bagfile and this feature is disabled.' + '-b', '--max-bag-size', type=int, default=0, + help='maximum size in bytes before the bagfile will be split.' + 'Default it is zero, recording written in single bagfile and splitting is disabled.' ) self._subparser = parser From 59cf85b1347a8f84ba5749f394a2f05aeffd82d0 Mon Sep 17 00:00:00 2001 From: Prajakta Gokhale Date: Wed, 13 Nov 2019 17:54:07 -0800 Subject: [PATCH 7/8] Fix flake8 errors Signed-off-by: Prajakta Gokhale --- ros2bag/ros2bag/verb/record.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/ros2bag/ros2bag/verb/record.py b/ros2bag/ros2bag/verb/record.py index 910e57824..6582ef172 100644 --- a/ros2bag/ros2bag/verb/record.py +++ b/ros2bag/ros2bag/verb/record.py @@ -46,13 +46,14 @@ def add_arguments(self, parser, cli_name): # noqa: D102 'startup will be recorded') parser.add_argument( '-p', '--polling-interval', type=int, default=100, - help='time in ms to wait between querying available topics for recording. It has no ' - 'effect if --no-discovery is enabled.' + help='time in ms to wait between querying available topics for recording. ' + 'It has no effect if --no-discovery is enabled.' ) parser.add_argument( '-b', '--max-bag-size', type=int, default=0, - help='maximum size in bytes before the bagfile will be split.' - 'Default it is zero, recording written in single bagfile and splitting is disabled.' + help='maximum size in bytes before the bagfile will be split. ' + 'Default it is zero, recording written in single bagfile and splitting ' + 'is disabled.' ) self._subparser = parser @@ -89,7 +90,7 @@ def main(self, *, args): # noqa: D102 all=True, no_discovery=args.no_discovery, polling_interval=args.polling_interval, - max_bagfile_size=args.bag_size) + max_bagfile_size=args.max_bag_size) elif args.topics and len(args.topics) > 0: # NOTE(hidmic): in merged install workspaces on Windows, Python entrypoint lookups # combined with constrained environments (as imposed by colcon test) @@ -105,7 +106,7 @@ def main(self, *, args): # noqa: D102 node_prefix=NODE_NAME_PREFIX, no_discovery=args.no_discovery, polling_interval=args.polling_interval, - max_bagfile_size=args.bag_size, + max_bagfile_size=args.max_bag_size, topics=args.topics) else: self._subparser.print_help() From ae9796baba6fd917e8a7dd1d6c7af892d4087358 Mon Sep 17 00:00:00 2001 From: Prajakta Gokhale Date: Mon, 18 Nov 2019 10:31:48 -0800 Subject: [PATCH 8/8] Rebase on master Signed-off-by: Prajakta Gokhale --- rosbag2/src/rosbag2/writer.cpp | 38 ------------------- .../rosbag2_storage/test_read_only_plugin.cpp | 2 +- .../sqlite/sqlite_storage.cpp | 1 + 3 files changed, 2 insertions(+), 39 deletions(-) diff --git a/rosbag2/src/rosbag2/writer.cpp b/rosbag2/src/rosbag2/writer.cpp index edc8af13e..9898adf5c 100644 --- a/rosbag2/src/rosbag2/writer.cpp +++ b/rosbag2/src/rosbag2/writer.cpp @@ -60,42 +60,4 @@ void Writer::write(std::shared_ptr message) writer_impl_->write(message); } -bool Writer::should_split_database() const -{ - return (max_bagfile_size_ != rosbag2_storage::storage_interfaces::MAX_BAGFILE_SIZE_NO_SPLIT) && - (storage_->get_current_bagfile_size() > max_bagfile_size_); -} - -void Writer::initialize_metadata_() -{ - metadata_.message_count = 0; - metadata_.topics_with_message_count = {}; - metadata_.starting_time = - std::chrono::time_point( - std::chrono::nanoseconds(INT64_MAX)); - metadata_.duration = std::chrono::nanoseconds(0); - metadata_.bag_size = 0; -} - -void Writer::aggregate_metadata_(rosbag2_storage::BagMetadata metadata) -{ - metadata_.storage_identifier = metadata.storage_identifier; - metadata_.relative_file_paths.swap(metadata.relative_file_paths); - metadata_.message_count += metadata.message_count; - - if (metadata_.starting_time > metadata.starting_time && - metadata.starting_time != - std::chrono::time_point(std::chrono::nanoseconds(0))) - { - metadata_.starting_time = metadata.starting_time; - } - - metadata_.duration += metadata.duration; - metadata_.bag_size = metadata.bag_size; - metadata_.topics_with_message_count.insert( - metadata_.topics_with_message_count.end(), - metadata.topics_with_message_count.begin(), - metadata.topics_with_message_count.end()); -} - } // namespace rosbag2 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 5f0f3ab58..9345be50e 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_read_only_plugin.cpp @@ -67,7 +67,7 @@ rosbag2_storage::BagMetadata TestReadOnlyPlugin::get_metadata() return rosbag2_storage::BagMetadata(); } -uint64_t TestReadOnlyPlugin::get_current_bagfile_size() const +uint64_t TestReadOnlyPlugin::get_bagfile_size() const { std::cout << "\nreturning bagfile size\n"; return test_constants::MAX_BAGFILE_SIZE; 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 9a7ccadcc..a79e8df8f 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 @@ -59,6 +59,7 @@ constexpr const auto FILE_EXTENSION = ".db3"; namespace rosbag2_storage_plugins { + void SqliteStorage::open( const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag io_flag) {