(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using the C++ client library

Description: How to use the C++ client library to talk to the warehouse

Tutorial Level: BEGINNER

Contents

  1. Example code

Example code

The warehouse_ros package provides a C++ ROS client library to the DB. For now, we just have an example of use. Note that this requires the db server to be running, as described in the previous tutorial.

https://raw.githubusercontent.com/ros-planning/warehouse_ros/indigo-devel/test/test_mongo_ros.cpp

   1 #include "test_mongo_helpers.h"
   2 #include <mongo_ros/message_collection.h>
   3 #include <mongo_ros/exceptions.h>
   4 #include <ros/ros.h>
   5 #include <boost/foreach.hpp>
   6 #include <gtest/gtest.h>
   7 
   8 namespace mr=mongo_ros;
   9 namespace gm=geometry_msgs;
  10 using std::vector;
  11 using std::string;
  12 using std::cout;
  13 
  14 typedef mr::MessageWithMetadata<gm::Pose> PoseWithMetadata;
  15 typedef PoseWithMetadata::ConstPtr PoseMetaPtr;
  16 
  17 // Helper function that creates metadata for a message.
  18 // Here we'll use the x and y position, as well as a 'name'
  19 // field that isn't part of the original message.
  20 mr::Metadata makeMetadata (const gm::Pose& p, const string& v)
  21 {
  22   return mr::Metadata("x", p.position.x, "y", p.position.y, "name", v);
  23 }
  24 
  25 TEST(MongoRos, MongoRos)
  26 {
  27   // Symbols used in queries to denote binary predicates for < and >
  28   // Note that equality is the default, so we don't need a symbol for it
  29   using mr::LT;
  30   using mr::GT;
  31 
  32   // Clear existing data if any
  33   mr::dropDatabase("my_db", "localhost", 27019, 60.0);
  34   
  35   // Set up db
  36   mr::MessageCollection<gm::Pose> coll("my_db", "poses", "localhost",
  37                                        27019, 60.0);
  38 
  39   // Arrange to index on metadata fields 'x' and 'name'
  40   coll.ensureIndex("name");
  41   coll.ensureIndex("x");
  42 
  43   // Add some poses and metadata
  44   const gm::Pose p1 = makePose(24, 42, 0);
  45   const gm::Pose p2 = makePose(10, 532, 3);
  46   const gm::Pose p3 = makePose(53, 22, 5);
  47   const gm::Pose p4 = makePose(22, -5, 33);
  48   coll.insert(p1, makeMetadata(p1, "bar"));
  49   coll.insert(p2, makeMetadata(p2, "baz"));
  50   coll.insert(p3, makeMetadata(p3, "qux"));
  51   coll.insert(p1, makeMetadata(p1, "oof"));
  52   coll.insert(p4, makeMetadata(p4, "ooof"));
  53   EXPECT_EQ(5u, coll.count());
  54 
  55   // Simple query: find the pose with name 'qux' and return just its metadata
  56   // Since we're doing an equality check, we don't explicitly specify a predicate
  57   vector<PoseMetaPtr> res = coll.pullAllResults(mr::Query("name", "qux"), true);
  58   EXPECT_EQ(1u, res.size());
  59   EXPECT_EQ("qux", res[0]->lookupString("name"));
  60   EXPECT_DOUBLE_EQ(53, res[0]->lookupDouble("x"));
  61   
  62   // Set up query: position.x < 40 and position.y > 0.  Reverse order
  63   // by the "name" metadata field.  Also, here we pull the message itself, not
  64   // just the metadata.  Finally, we can't use the simplified construction
  65   // syntax here because it's too long
  66   mr::Query q = mr::Query().append("x", mr::LT, 40).append("y", mr::GT, 0);
  67   vector<PoseMetaPtr> poses = coll.pullAllResults(q, false, "name", false);
  68   
  69   // Verify poses. 
  70   EXPECT_EQ(3u, poses.size());
  71   EXPECT_EQ(p1, *poses[0]);
  72   EXPECT_EQ(p2, *poses[1]);
  73   EXPECT_EQ(p1, *poses[2]);
  74 
  75   EXPECT_EQ("oof", poses[0]->lookupString("name"));
  76   EXPECT_EQ("baz", poses[1]->lookupString("name"));
  77   EXPECT_EQ("bar", poses[2]->lookupString("name"));
  78 
  79   // Set up query to delete some poses.
  80   mr::Query q2 ("y", mr::LT, 30);
  81 
  82   EXPECT_EQ(5u, coll.count());
  83   EXPECT_EQ(2u, coll.removeMessages(q2));
  84   EXPECT_EQ(3u, coll.count());
  85 
  86   // Test findOne
  87   mr::Query q4("name", "bar");
  88   EXPECT_EQ(p1, *coll.findOne(q4, false));
  89   EXPECT_DOUBLE_EQ(24, coll.findOne(q4, true)->lookupDouble("x"));
  90 
  91   mr::Query q5("name", "barbar");
  92   EXPECT_THROW(coll.findOne(q5, true), mr::NoMatchingMessageException);
  93   EXPECT_THROW(coll.findOne(q5, false), mr::NoMatchingMessageException);
  94   
  95   // Test update
  96   coll.modifyMetadata(q4, mr::Metadata("name", "barbar"));
  97   EXPECT_EQ(3u, coll.count());
  98   EXPECT_THROW(coll.findOne(q4, false), mr::NoMatchingMessageException);
  99   ROS_INFO("here");
 100   EXPECT_EQ(p1, *coll.findOne(q5, false));
 101 
 102   // Check stored metadata
 103   boost::shared_ptr<mongo::DBClientConnection> conn =
 104     mr::makeDbConnection(ros::NodeHandle());
 105   EXPECT_EQ("geometry_msgs/Pose", mr::messageType(*conn, "my_db", "poses"));
 106 }
 107 
 108 
 109 int main (int argc, char** argv)
 110 {
 111   ros::init(argc, argv, "client_test");
 112   ros::NodeHandle nh;
 113   testing::InitGoogleTest(&argc, argv);
 114   return RUN_ALL_TESTS();
 115 }
 116  

Wiki: warehouse_ros/Tutorials/Using the C++ client library (last edited 2019-07-01 15:56:54 by ZhaoHan)