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


warehouse_ros_sqlite
Author(s): Bjarne von Horn
autogenerated on Fri Nov 11 2022 03:44:33