Skip to content

Commit

Permalink
SQLite storage optimized by default (#568)
Browse files Browse the repository at this point in the history
* Use optimized pragmas by default in sqlite storage. Added option to use former behavior

Signed-off-by: Adam Dabrowski <[email protected]>
  • Loading branch information
adamdbrw authored and Emerson Knapp committed Feb 2, 2021
1 parent e0925e8 commit d4e2c77
Show file tree
Hide file tree
Showing 11 changed files with 163 additions and 14 deletions.
8 changes: 7 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -125,8 +125,14 @@ read:
write:
pragmas: <list of pragma settings for read/write>
```
Please refer to [documentation of pragmas](https://www.sqlite.org/pragma.html).

By default, SQLite settings are significantly optimized for performance.
This might have consequences of bag data being corrupted after an application or system-level crash.
This consideration only applies to current bagfile in case bag splitting is on (through `--max-bag-*` parameters).
If increased crash-caused corruption resistance is necessary, use `resilient` option for `--storage-preset-profile` setting.

Settings are fully exposed to the user and should be applied with understanding.
Please refer to [documentation of pragmas](https://www.sqlite.org/pragma.html).

An example configuration file could look like this:

Expand Down
10 changes: 10 additions & 0 deletions ros2bag/ros2bag/verb/record.py
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,15 @@ def add_arguments(self, parser, cli_name): # noqa: D102
'--qos-profile-overrides-path', type=FileType('r'),
help='Path to a yaml file defining overrides of the QoS profile for specific topics.'
)
parser.add_argument(
'--storage-preset-profile', type=str, default='none', choices=['none', 'resilient'],
help='Select a configuration preset for storage.'
'resilient (sqlite3):'
'indicate preference for avoiding data corruption in case of crashes,'
'at the cost of performance. Setting this flag disables optimization settings '
'for storage (the defaut). This flag settings can still be overriden by '
'corresponding settings in the config passed with --storage-config-file.'
)
parser.add_argument(
'--storage-config-file', type=FileType('r'),
help='Path to a yaml file defining storage specific configurations. '
Expand Down Expand Up @@ -171,6 +180,7 @@ def main(self, *, args): # noqa: D102
topics=args.topics,
include_hidden_topics=args.include_hidden_topics,
qos_profile_overrides=qos_profile_overrides,
storage_preset_profile=args.storage_preset_profile,
storage_config_file=storage_config_file)

if os.path.isdir(uri) and not os.listdir(uri):
Expand Down
4 changes: 4 additions & 0 deletions rosbag2_storage/include/rosbag2_storage/storage_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,10 @@ struct StorageOptions
// A value of 0 disables caching and every write happens directly to disk.
uint64_t max_cache_size = 0;

// Preset storage configuration. Preset settings can be overriden with
// corresponding settings specified through storage_config_uri file
std::string storage_preset_profile = "";

// Storage specific configuration file.
// Defaults to empty string.
std::string storage_config_uri = "";
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
// Copyright 2020, Robotec.ai sp. z o.o.
//
// 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_DEFAULT_PLUGINS__SQLITE__SQLITE_PRAGMAS_HPP_
#define ROSBAG2_STORAGE_DEFAULT_PLUGINS__SQLITE__SQLITE_PRAGMAS_HPP_

#include <memory>
#include <string>
#include <unordered_map>
#include <vector>


namespace rosbag2_storage_plugins
{

class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqlitePragmas
{
public:
using pragmas_map_t = std::unordered_map<std::string, std::string>;

static pragmas_map_t default_pragmas()
{
static pragmas_map_t p = {{"schema_version", "PRAGMA schema_version;"}};
return p;
}

// more robust storage settings will cause performace hit on writing,
// but increase resistance to bagfile data corruption in case of crashes
static pragmas_map_t robust_writing_pragmas()
{
static pragmas_map_t p = {
{"journal_mode", "PRAGMA journal_mode=WAL;"},
{"synchronous", "PRAGMA synchronous=NORMAL;"}
};
return p;
}

static pragmas_map_t optimized_writing_pragmas()
{
static pragmas_map_t p = {
{"journal_mode", "PRAGMA journal_mode=MEMORY;"},
{"synchronous", "PRAGMA synchronous=OFF;"}
};
return p;
}
};

} // namespace rosbag2_storage_plugins

#endif // ROSBAG2_STORAGE_DEFAULT_PLUGINS__SQLITE__SQLITE_PRAGMAS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,8 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage

void reset_filter() override;

std::string get_storage_setting(const std::string & key);

private:
void initialize();
void prepare_for_writing();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteWrapper
~SqliteWrapper();

SqliteStatement prepare_statement(const std::string & query);
std::string query_pragma_value(const std::string & key);

size_t get_last_insert_id();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,9 @@

#include "rosbag2_storage/metadata_io.hpp"
#include "rosbag2_storage/serialized_bag_message.hpp"
#include "rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp"
#include "rosbag2_storage_default_plugins/sqlite/sqlite_exception.hpp"
#include "rosbag2_storage_default_plugins/sqlite/sqlite_pragmas.hpp"
#include "rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp"

#ifdef _WIN32
// This is necessary because of a bug in yaml-cpp's cmake
Expand Down Expand Up @@ -142,6 +143,17 @@ inline std::unordered_map<std::string, std::string> parse_pragmas(
return pragmas;
}

void apply_resilient_storage_settings(std::unordered_map<std::string, std::string> & pragmas)
{
auto robust_pragmas = rosbag2_storage_plugins::SqlitePragmas::robust_writing_pragmas();
for (const auto & kv : robust_pragmas) {
// do not override settings from configuration file, otherwise apply
if (pragmas.count(kv.first) == 0) {
pragmas[kv.first] = kv.second;
}
}
}

constexpr const auto FILE_EXTENSION = ".db3";

// Minimum size of a sqlite3 database file in bytes (84 kiB).
Expand All @@ -161,7 +173,11 @@ void SqliteStorage::open(
const rosbag2_storage::StorageOptions & storage_options,
rosbag2_storage::storage_interfaces::IOFlag io_flag)
{
const bool resilient_preset = "resilient" == storage_options.storage_preset_profile;
auto pragmas = parse_pragmas(storage_options.storage_config_uri, io_flag);
if (resilient_preset && is_read_write(io_flag)) {
apply_resilient_storage_settings(pragmas);
}

if (is_read_write(io_flag)) {
relative_path_ = storage_options.uri + FILE_EXTENSION;
Expand Down Expand Up @@ -459,6 +475,11 @@ void SqliteStorage::reset_filter()
storage_filter_ = rosbag2_storage::StorageFilter();
}

std::string SqliteStorage::get_storage_setting(const std::string & key)
{
return database_->query_pragma_value(key);
}

} // namespace rosbag2_storage_plugins

#include "pluginlib/class_list_macros.hpp" // NOLINT
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "rosbag2_storage/serialized_bag_message.hpp"

#include "rosbag2_storage_default_plugins/sqlite/sqlite_exception.hpp"
#include "rosbag2_storage_default_plugins/sqlite/sqlite_pragmas.hpp"

#include "../logging.hpp"

Expand Down Expand Up @@ -83,16 +84,9 @@ void SqliteWrapper::apply_pragma_settings(
{
// Add default pragmas if not overridden by user setting
{
typedef std::unordered_map<std::string, std::string> pragmas_map_t;
pragmas_map_t default_pragmas = {
// Used to check whether db is readable
{"schema_version", "PRAGMA schema_version;"}
};
auto default_pragmas = SqlitePragmas::default_pragmas();
if (io_flag == rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE) {
const pragmas_map_t write_default_pragmas = {
{"journal_mode", "PRAGMA journal_mode=WAL;"},
{"synchronous", "PRAGMA synchronous=NORMAL;"}
};
const auto write_default_pragmas = SqlitePragmas::optimized_writing_pragmas();
default_pragmas.insert(write_default_pragmas.begin(), write_default_pragmas.end());
}
for (const auto & kv : default_pragmas) {
Expand All @@ -117,6 +111,13 @@ void SqliteWrapper::apply_pragma_settings(
}
}

std::string SqliteWrapper::query_pragma_value(const std::string & key)
{
auto query = "PRAGMA " + key + ";";
auto pragma_value = prepare_statement(query)->execute_query<std::string>().get_single_line();
return std::get<0>(pragma_value);
}

SqliteStatement SqliteWrapper::prepare_statement(const std::string & query)
{
return std::make_shared<SqliteStatementWrapper>(db_ptr, query);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ class StorageTestFixture : public TemporaryDirectoryFixture
}

rosbag2_storage::StorageOptions storage_options{storage_uri, plugin_id, 0, 0, 0,
yaml_config};
"", yaml_config};
return storage_options;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -322,6 +322,46 @@ TEST_F(StorageTestFixture, loads_config_file) {
rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE));
}

TEST_F(StorageTestFixture, storage_configuration_file_applies_over_storage_preset_profile) {
// Check that "resilient" values are overriden
const auto journal_setting = "\"journal_mode = OFF\"";
const auto synchronous_setting = "\"synchronous = OFF\"";
const auto not_overriden_setting = "\"cache_size = 1337\"";
const auto overriding_yaml = std::string("write:\n pragmas: [") +
journal_setting + ", " + synchronous_setting + ", " + not_overriden_setting + "]\n";
const auto writable_storage = std::make_unique<rosbag2_storage_plugins::SqliteStorage>();
auto options = make_storage_options_with_config(overriding_yaml, kPluginID);
options.storage_preset_profile = "resilient";
writable_storage->open(options, rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE);

// configuration should replace preset "wal" with "off"
EXPECT_EQ(writable_storage->get_storage_setting("journal_mode"), "off");

// configuration should replace preset setting of 1 with 0
EXPECT_EQ(writable_storage->get_storage_setting("synchronous"), "0");

// configuration of non-conflicting setting schema.cache_size should be unaffected
EXPECT_EQ(writable_storage->get_storage_setting("cache_size"), "1337");
}

TEST_F(StorageTestFixture, storage_preset_profile_applies_over_defaults) {
// Check that "resilient" values override default optimized ones
const auto writable_storage = std::make_unique<rosbag2_storage_plugins::SqliteStorage>();

auto temp_dir = rcpputils::fs::path(temporary_dir_path_);
const auto storage_uri = (temp_dir / "rosbag").string();
rosbag2_storage::StorageOptions options{storage_uri, kPluginID, 0, 0, 0, "", ""};

options.storage_preset_profile = "resilient";
writable_storage->open(options, rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE);

// resilient preset should replace default "memory" with "wal"
EXPECT_EQ(writable_storage->get_storage_setting("journal_mode"), "wal");

// resilient preset should replace default of 0 with 1
EXPECT_EQ(writable_storage->get_storage_setting("synchronous"), "1");
}

TEST_F(StorageTestFixture, throws_on_invalid_pragma_in_config_file) {
// Check that storage throws on invalid pragma statement in sqlite config
const auto invalid_yaml = "write:\n pragmas: [\"unrecognized_pragma_name = 2\"]\n";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#include <chrono>
#include <memory>
#include <string>
#include <thread>
#include <unordered_map>
#include <utility>
#include <vector>
Expand Down Expand Up @@ -106,6 +105,7 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject *
"topics",
"include_hidden_topics",
"qos_profile_overrides",
"storage_preset_profile",
"storage_config_file",
nullptr};

Expand All @@ -126,10 +126,11 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject *
uint64_t max_cache_size = 0u;
PyObject * topics = nullptr;
bool include_hidden_topics = false;
char * storage_preset_profile = nullptr;
char * storage_config_file = nullptr;
if (
!PyArg_ParseTupleAndKeywords(
args, kwargs, "ssssss|KKbbKKKKObOs", const_cast<char **>(kwlist),
args, kwargs, "ssssss|KKbbKKKKObOss", const_cast<char **>(kwlist),
&uri,
&storage_id,
&serilization_format,
Expand All @@ -147,6 +148,7 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject *
&topics,
&include_hidden_topics,
&qos_profile_overrides,
&storage_preset_profile,
&storage_config_file
))
{
Expand All @@ -159,6 +161,7 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject *
storage_options.max_bagfile_size = (uint64_t) max_bagfile_size;
storage_options.max_bagfile_duration = static_cast<uint64_t>(max_bagfile_duration);
storage_options.max_cache_size = max_cache_size;
storage_options.storage_preset_profile = storage_preset_profile;
record_options.all = all;
record_options.is_discovery_disabled = no_discovery;
record_options.topic_polling_interval = std::chrono::milliseconds(polling_interval_ms);
Expand Down

0 comments on commit d4e2c77

Please sign in to comment.