30 #include <gtest/gtest.h>
31 #include <boost/filesystem.hpp>
35 #include <geometry_msgs/Vector3.h>
39 #include <condition_variable>
42 namespace bf = boost::filesystem;
43 using V = geometry_msgs::Vector3;
49 tmp_dir_ = boost::filesystem::temp_directory_path() / boost::filesystem::unique_path();
54 FAIL() <<
"could not create temporary dir";
73 static std::unique_ptr<warehouse_ros_sqlite::DatabaseConnection>
db_conn_;
85 sqlite3* raw_db =
nullptr;
86 if (sqlite3_open(
tmp_file_.c_str(), &raw_db) != SQLITE_OK)
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)
91 sqlite3_close(raw_db);
102 ASSERT_TRUE(
static_cast<bool>(second_db));
109 std::condition_variable cv;
110 std::atomic_bool second_db_setup{
false };
113 std::unique_lock<std::mutex> lk1(m);
116 std::thread worker([&cv, &m, &second_db_setup]() {
117 std::unique_lock<std::mutex> lk2(m);
122 second_db_setup.store(
static_cast<bool>(second_db));
129 constexpr
auto wait_interval =
131 std::this_thread::sleep_for(wait_interval);
138 if (!second_db_setup)
140 ADD_FAILURE() <<
"Second db setup failed";
151 int main(
int argc,
char** argv)
154 ::testing::InitGoogleTest(&argc, argv);
155 return RUN_ALL_TESTS();