BusyHandler.cpp
Go to the documentation of this file.
1 // SPDX-License-Identifier: BSD-3-Clause
2 
3 /*
4  * Copyright (c) 2020, Bjarne von Horn
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  * * Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  * * Neither the name of the copyright holder nor the names of its contributors
15  * may be used to endorse or promote products derived from this software
16  * without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
20  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL BJARNE VON HORN BE LIABLE FOR ANY DIRECT,
22  * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
23  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
24  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
25  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <gtest/gtest.h>
31 #include <boost/filesystem.hpp>
35 #include <geometry_msgs/Vector3.h>
36 #include <sqlite3.h>
37 #include <thread>
38 #include <mutex>
39 #include <condition_variable>
40 #include <atomic>
41 
42 namespace bf = boost::filesystem;
43 using V = geometry_msgs::Vector3;
44 
45 struct BusyHandler : ::testing::Test
46 {
47  void SetUp() override
48  {
49  tmp_dir_ = boost::filesystem::temp_directory_path() / boost::filesystem::unique_path();
50  if (!bf::create_directory(tmp_dir_))
51  {
52  // clear tmp_dir so that it's not removed in TearDown()
53  tmp_dir_ = "";
54  FAIL() << "could not create temporary dir";
55  }
56  tmp_file_ = tmp_dir_ / "db.sqlite";
58  db_conn_->setParams(tmp_file_.string(), 0);
59  ASSERT_TRUE(db_conn_->connect());
60  coll_ = db_conn_->openCollectionPtr<V>("main", "coll");
61  ASSERT_TRUE(coll_->md5SumMatches());
62  }
63 
64  void TearDown() override
65  {
66  bf::remove_all(tmp_dir_);
67  coll_.reset();
68  db_conn_.reset();
69  }
70 
71  static bf::path tmp_dir_;
72  static bf::path tmp_file_;
73  static std::unique_ptr<warehouse_ros_sqlite::DatabaseConnection> db_conn_;
75  static sqlite3* startSecondInsert() noexcept;
76 };
77 
78 bf::path BusyHandler::tmp_dir_;
79 bf::path BusyHandler::tmp_file_;
80 warehouse_ros::MessageCollection<V>::Ptr BusyHandler::coll_;
81 std::unique_ptr<warehouse_ros_sqlite::DatabaseConnection> BusyHandler::db_conn_;
82 
83 sqlite3* BusyHandler::startSecondInsert() noexcept
84 {
85  sqlite3* raw_db = nullptr;
86  if (sqlite3_open(tmp_file_.c_str(), &raw_db) != SQLITE_OK)
87  return nullptr;
88  const char* query = "BEGIN TRANSACTION; INSERT INTO \"T_main@coll\" ( \"Data\" ) VALUES (x'DEADBEEF');";
89  if (sqlite3_exec(raw_db, query, nullptr, nullptr, nullptr) != SQLITE_OK)
90  {
91  sqlite3_close(raw_db);
92  return nullptr;
93  }
94  return raw_db;
95 }
96 
97 TEST_F(BusyHandler, TimeoutFires)
98 {
99  auto meta = coll_->createMetadata();
100  // prepare second database accessor
102  ASSERT_TRUE(static_cast<bool>(second_db));
103  EXPECT_THROW(coll_->insert(V(), meta), warehouse_ros_sqlite::InternalError);
104 }
105 
106 TEST_F(BusyHandler, HandlerWorks)
107 {
108  std::mutex m;
109  std::condition_variable cv;
110  std::atomic_bool second_db_setup{ false };
111  auto meta = coll_->createMetadata();
112 
113  std::unique_lock<std::mutex> lk1(m);
114 
115  // start second thread, protected by mutex
116  std::thread worker([&cv, &m, &second_db_setup]() {
117  std::unique_lock<std::mutex> lk2(m);
118  // block the database, protected under the mutex
120 
121  // tell main thread if blocking the db was successul and wake it up
122  second_db_setup.store(static_cast<bool>(second_db));
123  lk2.unlock();
124  cv.notify_one();
125 
126  if (second_db_setup)
127  {
128  // wait for some time and unblock the db afterwards
129  constexpr auto wait_interval =
130  3 * std::chrono::milliseconds{ warehouse_ros_sqlite::DatabaseConnection::BUSY_WAIT_MILLISECS };
131  std::this_thread::sleep_for(wait_interval);
132  second_db.reset();
133  }
134  });
135 
136  // wait for the second thread to block the db
137  cv.wait(lk1);
138  if (!second_db_setup)
139  {
140  ADD_FAILURE() << "Second db setup failed";
141  }
142  else
143  {
144  // inserting data should work after second thread unblocks in the background
145  EXPECT_NO_THROW(coll_->insert(V(), meta));
146  }
147  // join second thread
148  worker.join();
149 }
150 
151 int main(int argc, char** argv)
152 {
153  ros::Time::init();
154  ::testing::InitGoogleTest(&argc, argv);
155  return RUN_ALL_TESTS();
156 }
warehouse_ros_sqlite
Definition: database_connection.h:36
BusyHandler::startSecondInsert
static sqlite3 * startSecondInsert() noexcept
Definition: BusyHandler.cpp:83
BusyHandler::coll_
static warehouse_ros::MessageCollection< V >::Ptr coll_
Definition: BusyHandler.cpp:74
BusyHandler::db_conn_
static std::unique_ptr< warehouse_ros_sqlite::DatabaseConnection > db_conn_
Definition: BusyHandler.cpp:73
exceptions.h
boost::shared_ptr
warehouse_ros_sqlite::DatabaseConnection::BUSY_WAIT_MILLISECS
static const int BUSY_WAIT_MILLISECS
Definition: database_connection.h:75
BusyHandler::tmp_dir_
static bf::path tmp_dir_
Definition: BusyHandler.cpp:71
warehouse_ros::MessageCollection::insert
void insert(const M &msg, Metadata::Ptr metadata)
utils.h
warehouse_ros::MessageCollection::createMetadata
Metadata::Ptr createMetadata() const
warehouse_ros_sqlite::sqlite3_ptr
std::shared_ptr< sqlite3 > sqlite3_ptr
Definition: utils.h:51
warehouse_ros_sqlite::sqlite3_delete
WAREHOUSE_ROS_SQLITE_EXPORT void sqlite3_delete(sqlite3 *db)
Definition: database_connection.cpp:228
warehouse_ros_sqlite::DatabaseConnection
Definition: database_connection.h:38
warehouse_ros::MessageCollection::md5SumMatches
bool md5SumMatches() const
warehouse_ros_sqlite::InternalError
Definition: exceptions.h:42
V
geometry_msgs::Vector3 V
Definition: BusyHandler.cpp:43
BusyHandler::SetUp
void SetUp() override
Definition: BusyHandler.cpp:47
BusyHandler::TearDown
void TearDown() override
Definition: BusyHandler.cpp:64
main
int main(int argc, char **argv)
Definition: BusyHandler.cpp:151
database_connection.h
ros::Time::init
static void init()
BusyHandler
Definition: BusyHandler.cpp:45
std
warehouse_ros
TEST_F
TEST_F(BusyHandler, TimeoutFires)
Definition: BusyHandler.cpp:97
BusyHandler::tmp_file_
static bf::path tmp_file_
Definition: BusyHandler.cpp:72


warehouse_ros_sqlite
Author(s): Bjarne von Horn
autogenerated on Mon Oct 14 2024 02:16:58