DatabaseConnection.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>
33 #include <geometry_msgs/Point.h>
34 #include <geometry_msgs/Pose.h>
35 #include <geometry_msgs/Vector3.h>
36 #include <ros/ros.h>
37 
38 class ConnectionTest : public ::testing::Test
39 {
40 protected:
41  void SetUp() override
42  {
44  conn_->setParams(":memory:", 0);
45  ASSERT_TRUE(conn_->connect());
46  }
47 
48  static std::unique_ptr<warehouse_ros_sqlite::DatabaseConnection> conn_;
49 };
50 std::unique_ptr<warehouse_ros_sqlite::DatabaseConnection> ConnectionTest::conn_;
51 
52 TEST_F(ConnectionTest, CreateCollection)
53 {
54  using V = geometry_msgs::Vector3;
55  auto coll = conn_->openCollection<V>("main", "coll");
56 
57  EXPECT_STREQ(conn_->messageType("main", "coll").c_str(), ros::message_traits::DataType<V>::value());
58 
59  EXPECT_EQ(coll.count(), 0U);
60 }
61 
62 TEST_F(ConnectionTest, InsertQueryAndDeleteMessage)
63 {
64  using V = geometry_msgs::Vector3;
65  auto coll = conn_->openCollection<V>("main", "coll");
66  auto meta1 = coll.createMetadata();
67  meta1->append("x", 3);
68 
69  V v1, v2;
70  v1.x = 3.0;
71  v1.y = 1.0;
72 
73  coll.insert(v1, meta1);
74 
75  EXPECT_EQ(coll.count(), 1U);
76 
77  v2.x = 5.0;
78  v2.y = 7.0;
79 
80  auto meta2 = coll.createMetadata();
81  meta2->append("x", 5);
82 
83  coll.insert(v2, meta2);
84 
85  EXPECT_EQ(coll.count(), 2U);
86 
87  auto query = coll.createQuery();
88  query->append("x", 3);
89 
90  const auto list = coll.queryList(query);
91 
92  ASSERT_EQ(list.size(), size_t(1));
93  ASSERT_EQ(list[0]->y, 1.0);
94 
95  EXPECT_EQ(coll.removeMessages(query), 1U);
96  EXPECT_EQ(coll.count(), 1U);
97 }
98 
99 TEST_F(ConnectionTest, MD5Validation)
100 {
101  auto coll1 = conn_->openCollection<geometry_msgs::Vector3>("main", "coll");
102  ASSERT_TRUE(coll1.md5SumMatches());
103  auto coll2 = conn_->openCollection<geometry_msgs::Pose>("main", "coll");
104  ASSERT_FALSE(coll2.md5SumMatches());
105  auto coll3 = conn_->openCollection<geometry_msgs::Vector3>("main", "coll");
106  ASSERT_TRUE(coll3.md5SumMatches());
107 }
108 
109 TEST_F(ConnectionTest, MetadataNullValue)
110 {
111  using V = geometry_msgs::Vector3;
112  auto coll = conn_->openCollection<V>("main", "coll");
113  auto meta1 = coll.createMetadata();
114  meta1->append("x", 3);
115 
116  V v1, v2;
117  v1.x = 3.0;
118  v1.y = 1.0;
119  v2.x = 5.0;
120  v2.y = 7.0;
121 
122  coll.insert(v1, meta1);
123  meta1->append("y", 8);
124  coll.insert(v2, meta1);
125 
126  auto query = coll.createQuery();
127  query->append("x", 3);
128 
129  const auto list = coll.queryList(query);
130  ASSERT_EQ(list.size(), size_t(2));
131  EXPECT_EQ(list[0]->lookupInt("x"), 3);
132  EXPECT_EQ(list[1]->lookupInt("x"), 3);
133 
134  EXPECT_TRUE(((list[0]->lookupInt("y") == 0 && list[1]->lookupInt("y") == 8) ||
135  (list[1]->lookupInt("y") == 0 && list[0]->lookupInt("y") == 8)));
136 }
137 
139 {
140  using V = geometry_msgs::Vector3;
141  auto coll = conn_->openCollection<V>("main", "coll");
142  auto meta1 = coll.createMetadata();
143  meta1->append("x", 3);
144 
145  coll.insert(V(), meta1);
146  coll.insert(V(), meta1);
147 
148  auto query = coll.createQuery();
149  query->append("x", 3);
150 
151  const auto list = coll.queryList(query);
152  ASSERT_EQ(list.size(), size_t(2));
153  ASSERT_NE(list[0]->lookupInt("id"), list[1]->lookupInt("id"));
154 }
155 
156 TEST_F(ConnectionTest, OverwriteMetadata)
157 {
158  using V = geometry_msgs::Vector3;
159  auto coll = conn_->openCollection<V>("main", "coll");
160  auto meta1 = coll.createMetadata();
161  meta1->append("x", 3);
162 
163  const int y1 = 8;
164  meta1->append("y", y1);
165 
166  V v1, v2;
167  v1.x = 3.0;
168  v1.y = 9.0;
169  v2.x = 5.0;
170  v2.y = 7.0;
171 
172  coll.insert(v1, meta1);
173  meta1->append("y", 6);
174  coll.insert(v2, meta1);
175 
176  auto query = coll.createQuery();
177  query->append("y", y1);
178 
179  const auto list = coll.queryList(query);
180  ASSERT_EQ(list.size(), size_t(1));
181  EXPECT_EQ(list[0]->lookupInt("x"), 3);
182  EXPECT_EQ(list[0]->lookupInt("y"), y1);
183  EXPECT_EQ(list[0]->y, 9.0);
184 }
185 
186 TEST_F(ConnectionTest, ModifyMetadata)
187 {
188  using V = geometry_msgs::Vector3;
189  auto coll = conn_->openCollection<V>("main", "coll");
190  auto meta1 = coll.createMetadata();
191 
192  V v1, v2;
193  v1.x = 3.0;
194  v2.x = 5.0;
195  const int x1 = 8;
196 
197  meta1->append("x", x1);
198  meta1->append("y", "one");
199  coll.insert(v1, meta1);
200 
201  auto meta2 = coll.createMetadata();
202  meta2->append("x", 2);
203  meta2->append("y", "one");
204  coll.insert(v2, meta2);
205 
206  auto modify_query = coll.createQuery();
207  modify_query->append("x", x1);
208  auto meta_modify = coll.createMetadata();
209  meta_modify->append("y", "two");
210  coll.modifyMetadata(modify_query, meta_modify);
211 
212  auto query = coll.createQuery();
213  query->append("y", "two");
214  const auto list = coll.queryList(query);
215 
216  ASSERT_EQ(list.size(), size_t(1));
217  EXPECT_EQ(list[0]->lookupInt("x"), x1);
218  EXPECT_EQ(list[0]->lookupString("y"), "two");
219  EXPECT_EQ(list[0]->x, 3.0);
220 }
221 
223 {
224  using V = geometry_msgs::Vector3;
225  auto coll = conn_->openCollection<V>("main", "coll");
226  auto meta1 = coll.createMetadata();
227 
228  auto keys = meta1->lookupFieldNames();
229  EXPECT_TRUE(keys.empty());
230  meta1->append("x", false);
231 
232  keys = meta1->lookupFieldNames();
233  EXPECT_NE(keys.find("x"), keys.end());
234  EXPECT_EQ(keys.size(), 1U);
235  EXPECT_TRUE(meta1->lookupField("x"));
236  EXPECT_FALSE(meta1->lookupField("z"));
237 }
238 
239 TEST_F(ConnectionTest, ComplexQuery)
240 {
241  using V = geometry_msgs::Vector3;
242  auto coll = conn_->openCollection<V>("main", "coll");
243  auto meta1 = coll.createMetadata();
244  meta1->append("x", 3);
245 
246  const int y1 = 8;
247  meta1->append("y", y1);
248 
249  V v1, v2;
250  v1.x = 3.0;
251  v1.y = 9.0;
252  v2.x = 5.0;
253  v2.y = 7.0;
254 
255  coll.insert(v1, meta1);
256  meta1->append("y", 6);
257  coll.insert(v2, meta1);
258 
259  auto query = coll.createQuery();
260  query->append("x", 3);
261  query->append("y", y1);
262 
263  const auto list = coll.queryList(query);
264  ASSERT_EQ(list.size(), size_t(1));
265  EXPECT_EQ(list[0]->lookupInt("x"), 3);
266  EXPECT_EQ(list[0]->lookupInt("y"), y1);
267  EXPECT_EQ(list[0]->y, 9.0);
268 }
269 
270 TEST_F(ConnectionTest, EmptyQuery)
271 {
272  using V = geometry_msgs::Vector3;
273  auto coll = conn_->openCollection<V>("main", "coll");
274  auto meta1 = coll.createMetadata();
275  meta1->append("x", 7);
276  coll.insert(V(), meta1);
277 
278  // known column, but wrong value
279  auto query = coll.createQuery();
280  query->append("x", 3);
281 
282  auto it_pair = coll.query(query);
283  EXPECT_EQ(std::get<0>(it_pair), std::get<1>(it_pair));
284 
285  auto list = coll.queryList(query);
286  EXPECT_EQ(list.size(), size_t(0));
287 
288  // unknown column
289  query->append("y", 3);
290 
291  it_pair = coll.query(query);
292  EXPECT_EQ(std::get<0>(it_pair), std::get<1>(it_pair));
293 
294  list = coll.queryList(query);
295  EXPECT_EQ(list.size(), size_t(0));
296 }
297 
298 TEST_F(ConnectionTest, DifferentDatabases)
299 {
300  using V = geometry_msgs::Vector3;
301  auto coll1 = conn_->openCollection<V>("main1", "coll");
302  auto meta1 = coll1.createMetadata();
303  meta1->append("x", 7);
304  coll1.insert(V(), meta1);
305 
306  auto coll2 = conn_->openCollection<V>("main2", "coll");
307  {
308  auto query2 = coll2.createQuery();
309  query2->append("x", 7);
310  const auto list2 = coll2.queryList(query2);
311  EXPECT_EQ(list2.size(), size_t(0));
312  }
313  {
314  auto meta2 = coll2.createMetadata();
315  meta2->append("x", 7);
316  coll2.insert(V(), meta2);
317  }
318  {
319  auto query1 = coll1.createQuery();
320  query1->append("x", 7);
321  const auto list1 = coll1.queryList(query1);
322  EXPECT_EQ(list1.size(), size_t(1));
323  }
324 }
325 
326 TEST_F(ConnectionTest, DropDatabase)
327 {
328  using V = geometry_msgs::Vector3;
329  // create two independent databases
330  {
331  auto coll = conn_->openCollection<V>("main", "coll");
332  auto meta1 = coll.createMetadata();
333  meta1->append("x", 7);
334  coll.insert(V(), meta1);
335  }
336  {
337  auto coll = conn_->openCollection<V>("main2", "coll");
338  auto meta1 = coll.createMetadata();
339  meta1->append("x", 7);
340  coll.insert(V(), meta1);
341  }
342  // delete first one
343  conn_->dropDatabase("main");
344  // second one still there?
345  {
346  auto coll1 = conn_->openCollection<V>("main2", "coll");
347  auto query1 = coll1.createQuery();
348  query1->append("x", 7);
349  const auto list1 = coll1.queryList(query1);
350  EXPECT_EQ(list1.size(), size_t(1));
351  }
352  // first one gone?
353  {
354  auto coll1 = conn_->openCollection<V>("main", "coll");
355  auto query1 = coll1.createQuery();
356  query1->append("x", 7);
357  const auto list1 = coll1.queryList(query1);
358  EXPECT_EQ(list1.size(), size_t(0));
359  }
360 }
361 
363 {
364  using V = geometry_msgs::Vector3;
365  auto coll = conn_->openCollection<V>("main", "coll");
366  auto meta1 = coll.createMetadata();
367  meta1->append("x", 7);
368  coll.insert(V(), meta1);
369 
370  auto query = coll.createQuery();
371  query->append("x", 9);
372  EXPECT_THROW(coll.findOne(query), warehouse_ros::NoMatchingMessageException);
373 }
374 
376 {
377  using V = geometry_msgs::Vector3;
378  auto coll = conn_->openCollection<V>("main", "coll");
379  auto meta1 = coll.createMetadata();
380  meta1->append("x", 71);
381  coll.insert(V(), meta1);
382  meta1->append("x", 10);
383  coll.insert(V(), meta1);
384 
385  {
386  // ascending
387  auto query = coll.createQuery();
388  const auto list1 = coll.queryList(query, false, "x", true);
389  ASSERT_EQ(list1.size(), size_t(2));
390  EXPECT_EQ(list1[0]->lookupInt("x"), 10);
391  EXPECT_EQ(list1[1]->lookupInt("x"), 71);
392  }
393  {
394  // descending
395  auto query = coll.createQuery();
396  const auto list1 = coll.queryList(query, false, "x", false);
397  ASSERT_EQ(list1.size(), size_t(2));
398  EXPECT_EQ(list1[0]->lookupInt("x"), 71);
399  EXPECT_EQ(list1[1]->lookupInt("x"), 10);
400  }
401 }
402 
404 {
405  auto coll = conn_->openCollection<geometry_msgs::Point>("test_db", "test_collection");
406 
407  auto metadata = coll.createMetadata();
408  metadata->append("test_metadata", 5.0);
409 
410  geometry_msgs::Point msg = {};
411  coll.insert(msg, metadata);
412 
413  {
414  auto query = coll.createQuery();
415  query->appendGTE("unrelated", 4.0);
416  EXPECT_TRUE(coll.queryList(query).empty());
417  }
418 
419  {
420  auto query = coll.createQuery();
421  query->appendGT("unrelated", 4.0);
422  EXPECT_TRUE(coll.queryList(query).empty());
423  }
424 
425  {
426  auto query = coll.createQuery();
427  query->appendLTE("unrelated", 6.0);
428  EXPECT_TRUE(coll.queryList(query).empty());
429  }
430 
431  {
432  auto query = coll.createQuery();
433  query->appendLT("unrelated", 6.0);
434  EXPECT_TRUE(coll.queryList(query).empty());
435  }
436 }
437 
438 TEST_F(ConnectionTest, BacktickInMeta)
439 {
440  auto coll = conn_->openCollection<geometry_msgs::Point>("test_db", "test_backtick");
441 
442  auto metadata = coll.createMetadata();
443  metadata->append("test_`metadata", 5.0);
444 
445  geometry_msgs::Point msg = {};
446  coll.insert(msg, metadata);
447 
448  {
449  auto query = coll.createQuery();
450  query->appendGTE("test_`metadata", 4.0);
451  EXPECT_EQ(coll.queryList(query).size(), 1);
452  }
453 }
454 
455 TEST(Utils, Md5Validation)
456 {
457  const char* a = "4a842b65f413084dc2b10fb484ea7f17";
458  const std::array<unsigned char, 16> b{
459  0x4a, 0x84, 0x2b, 0x65, 0xf4, 0x13, 0x08, 0x4d, 0xc2, 0xb1, 0x0f, 0xb4, 0x84, 0xea, 0x7f, 0x17,
460  };
461 
463 
464  EXPECT_THROW(warehouse_ros_sqlite::parse_md5_hexstring("123abc"), std::invalid_argument);
465  const char* c = "Za842b65f413084dc2b10fb484ea7f17";
466  const char* d = "aZ842b65f413084dc2b10fb484ea7f17";
467  EXPECT_THROW(warehouse_ros_sqlite::parse_md5_hexstring(c), std::invalid_argument);
468  EXPECT_THROW(warehouse_ros_sqlite::parse_md5_hexstring(d), std::invalid_argument);
469 }
470 
471 int main(int argc, char** argv)
472 {
473  ros::Time::init();
474  ::testing::InitGoogleTest(&argc, argv);
475  return RUN_ALL_TESTS();
476 }
ros.h
TEST_F
TEST_F(ConnectionTest, CreateCollection)
Definition: DatabaseConnection.cpp:52
ros::message_traits::DataType
utils.h
warehouse_ros_sqlite::parse_md5_hexstring
WAREHOUSE_ROS_SQLITE_EXPORT std::array< unsigned char, 16 > parse_md5_hexstring(const std::string &md5)
Definition: utils.h:127
TEST
TEST(Utils, Md5Validation)
Definition: DatabaseConnection.cpp:455
ConnectionTest::conn_
static std::unique_ptr< warehouse_ros_sqlite::DatabaseConnection > conn_
Definition: DatabaseConnection.cpp:48
main
int main(int argc, char **argv)
Definition: DatabaseConnection.cpp:471
d
d
warehouse_ros_sqlite::DatabaseConnection
Definition: database_connection.h:38
V
geometry_msgs::Vector3 V
Definition: BusyHandler.cpp:43
database_connection.h
ros::Time::init
static void init()
ConnectionTest
Definition: DatabaseConnection.cpp:38
warehouse_ros::NoMatchingMessageException
ConnectionTest::SetUp
void SetUp() override
Definition: DatabaseConnection.cpp:41


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