$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2009, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 00034 # Author: Bhaskara Marthi 00035 # 00036 # 1 00037 00038 ## %Tag(PYTHON_CLIENT)% 00039 00040 import roslib; roslib.load_manifest('mongo_ros') 00041 import rospy 00042 import mongo_ros as mr 00043 import unittest 00044 import math 00045 import geometry_msgs.msg as gm 00046 00047 def make_pose(x, y, th): 00048 return gm.Pose(gm.Point(x, y, 0), 00049 gm.Quaternion(0, 0, math.sin(th/2), math.cos(th/2))) 00050 00051 def make_metadata(p, str): 00052 return {'x': p.position.x, 'y': p.position.y, 'name': str} 00053 00054 def to_tuple(p): 00055 return (p.position.x, p.position.y, p.position.z, p.orientation.x, 00056 p.orientation.y, p.orientation.z, p.orientation.w) 00057 00058 def eq_poses(p1, p2): 00059 return to_tuple(p1)==to_tuple(p2) 00060 00061 00062 class TestMongoRospy(unittest.TestCase): 00063 00064 def test_basic(self): 00065 00066 # Set up collection 00067 coll = mr.MessageCollection("my_db", "poses", gm.Pose) 00068 p1 = make_pose(24, 42, 0) 00069 p2 = make_pose(10, 532, 3) 00070 p3 = make_pose(53, 22, 5) 00071 p4 = make_pose(22, -5, 33) 00072 00073 # Insert pose objects with accompanying string metadata 00074 coll.insert(p1, make_metadata(p1, "bar")) 00075 coll.insert(p2, make_metadata(p2, "baz")) 00076 coll.insert(p3, make_metadata(p3, "qux")) 00077 coll.insert(p1, make_metadata(p1, "oof")) 00078 coll.insert(p4, make_metadata(p4, "ooof")) 00079 00080 # Query poses s.t x < 40, y > ), in descending order of name 00081 results = coll.query({'x': {'$lt': 40}, 'y': {'$gt': 0}},\ 00082 sort_by='name', ascending=False) 00083 00084 # Turn list of pairs into pair of lists 00085 poses, metadata = zip(*list(results)) 00086 00087 self.assertEqual(len(poses), 3) 00088 self.assertTrue(eq_poses(p1, poses[0])) 00089 self.assertTrue(eq_poses(p2, poses[1])) 00090 self.assertTrue(eq_poses(p1, poses[2])) 00091 00092 self.assertEqual(metadata[0]['name'], 'oof') 00093 self.assertEqual(metadata[1]['name'], 'baz') 00094 self.assertEqual(metadata[2]['name'], 'bar') 00095 00096 # Update some messages 00097 coll.update(metadata[0], metadata={'name': 'bat'}) 00098 coll.update(metadata[2], msg=p2) 00099 res2 = coll.query({'y': {'$gt': 40}}, sort_by='name') 00100 poses, metadata = zip(*list(res2)) 00101 00102 self.assertEqual(metadata[0]['name'], 'bar') 00103 self.assertEqual(metadata[1]['name'], 'bat') 00104 self.assertEqual(metadata[2]['name'], 'baz') 00105 self.assertTrue(eq_poses(p2, poses[0])) 00106 self.assertTrue(eq_poses(p1, poses[1])) 00107 self.assertTrue(eq_poses(p2, poses[2])) 00108 00109 00110 # Remove entries s.t. y<30 00111 self.assertEqual(5, coll.count()) 00112 self.assertEqual(2, coll.remove({'y': {'$lt': 30}})) 00113 self.assertEqual(3, coll.count()) 00114 00115 # Test find_one 00116 self.assertTrue(coll.find_one({'y': {'$gt': 30}})) 00117 self.assertFalse(coll.find_one({'y': {'$lt': 30}})) 00118 00119 00120 if __name__ == "__main__": 00121 rospy.init_node('test_mongo_rospy') 00122 import rostest 00123 rostest.rosrun('mongo_ros', 'test_mongo_rospy', TestMongoRospy) 00124 00125 ## %EndTag(PYTHON_CLIENT)%