test_mongo_ros.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 
00039 // %Tag(CPP_CLIENT)%
00040 
00041 #include "test_mongo_helpers.h"
00042 #include <mongo_ros/message_collection.h>
00043 #include <mongo_ros/exceptions.h>
00044 #include <ros/ros.h>
00045 #include <boost/foreach.hpp>
00046 #include <gtest/gtest.h>
00047 
00048 namespace mr=mongo_ros;
00049 namespace gm=geometry_msgs;
00050 using std::vector;
00051 using std::string;
00052 using std::cout;
00053 
00054 typedef mr::MessageWithMetadata<gm::Pose> PoseWithMetadata;
00055 typedef PoseWithMetadata::ConstPtr PoseMetaPtr;
00056 
00057 // Helper function that creates metadata for a message.
00058 // Here we'll use the x and y position, as well as a 'name'
00059 // field that isn't part of the original message.
00060 mr::Metadata makeMetadata (const gm::Pose& p, const string& v)
00061 {
00062   return mr::Metadata("x", p.position.x, "y", p.position.y, "name", v);
00063 }
00064 
00065 TEST(MongoRos, MongoRos)
00066 {
00067   // Symbols used in queries to denote binary predicates for < and >
00068   // Note that equality is the default, so we don't need a symbol for it
00069   using mr::LT;
00070   using mr::GT;
00071 
00072   // Clear existing data if any
00073   mr::dropDatabase("my_db", "localhost", 27019, 60.0);
00074   
00075   // Set up db
00076   mr::MessageCollection<gm::Pose> coll("my_db", "poses", "localhost",
00077                                        27019, 60.0);
00078 
00079   // Arrange to index on metadata fields 'x' and 'name'
00080   coll.ensureIndex("name");
00081   coll.ensureIndex("x");
00082 
00083   // Add some poses and metadata
00084   const gm::Pose p1 = makePose(24, 42, 0);
00085   const gm::Pose p2 = makePose(10, 532, 3);
00086   const gm::Pose p3 = makePose(53, 22, 5);
00087   const gm::Pose p4 = makePose(22, -5, 33);
00088   coll.insert(p1, makeMetadata(p1, "bar"));
00089   coll.insert(p2, makeMetadata(p2, "baz"));
00090   coll.insert(p3, makeMetadata(p3, "qux"));
00091   coll.insert(p1, makeMetadata(p1, "oof"));
00092   coll.insert(p4, makeMetadata(p4, "ooof"));
00093   EXPECT_EQ(5u, coll.count());
00094 
00095   // Simple query: find the pose with name 'qux' and return just its metadata
00096   // Since we're doing an equality check, we don't explicitly specify a predicate
00097   vector<PoseMetaPtr> res = coll.pullAllResults(mr::Query("name", "qux"), true);
00098   EXPECT_EQ(1u, res.size());
00099   EXPECT_EQ("qux", res[0]->lookupString("name"));
00100   EXPECT_DOUBLE_EQ(53, res[0]->lookupDouble("x"));
00101   
00102   // Set up query: position.x < 40 and position.y > 0.  Reverse order
00103   // by the "name" metadata field.  Also, here we pull the message itself, not
00104   // just the metadata.  Finally, we can't use the simplified construction
00105   // syntax here because it's too long
00106   mr::Query q = mr::Query().append("x", mr::LT, 40).append("y", mr::GT, 0);
00107   vector<PoseMetaPtr> poses = coll.pullAllResults(q, false, "name", false);
00108   
00109   // Verify poses. 
00110   EXPECT_EQ(3u, poses.size());
00111   EXPECT_EQ(p1, *poses[0]);
00112   EXPECT_EQ(p2, *poses[1]);
00113   EXPECT_EQ(p1, *poses[2]);
00114 
00115   EXPECT_EQ("oof", poses[0]->lookupString("name"));
00116   EXPECT_EQ("baz", poses[1]->lookupString("name"));
00117   EXPECT_EQ("bar", poses[2]->lookupString("name"));
00118 
00119   // Set up query to delete some poses.
00120   mr::Query q2 ("y", mr::LT, 30);
00121 
00122   EXPECT_EQ(5u, coll.count());
00123   EXPECT_EQ(2u, coll.removeMessages(q2));
00124   EXPECT_EQ(3u, coll.count());
00125 
00126   // Test findOne
00127   mr::Query q4("name", "bar");
00128   EXPECT_EQ(p1, *coll.findOne(q4, false));
00129   EXPECT_DOUBLE_EQ(24, coll.findOne(q4, true)->lookupDouble("x"));
00130 
00131   mr::Query q5("name", "barbar");
00132   EXPECT_THROW(coll.findOne(q5, true), mr::NoMatchingMessageException);
00133   EXPECT_THROW(coll.findOne(q5, false), mr::NoMatchingMessageException);
00134   
00135   // Test update
00136   coll.modifyMetadata(q4, mr::Metadata("name", "barbar"));
00137   EXPECT_EQ(3u, coll.count());
00138   EXPECT_THROW(coll.findOne(q4, false), mr::NoMatchingMessageException);
00139   ROS_INFO("here");
00140   EXPECT_EQ(p1, *coll.findOne(q5, false));
00141 
00142   // Check stored metadata
00143   boost::shared_ptr<mongo::DBClientConnection> conn =
00144     mr::makeDbConnection(ros::NodeHandle());
00145   EXPECT_EQ("geometry_msgs/Pose", mr::messageType(*conn, "my_db", "poses"));
00146 }
00147 
00148 
00149 int main (int argc, char** argv)
00150 {
00151   ros::init(argc, argv, "client_test");
00152   ros::NodeHandle nh;
00153   testing::InitGoogleTest(&argc, argv);
00154   return RUN_ALL_TESTS();
00155 }
00156  
00157 // %EndTag(CPP_CLIENT)%


warehouse_ros
Author(s): Bhaskara Marthi
autogenerated on Mon Oct 6 2014 08:51:55