$search
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 #include <mongo_ros/mongo_ros.h> 00040 #include <mongo_ros/exceptions.h> 00041 00042 namespace mongo_ros 00043 { 00044 00045 using std::string; 00046 00048 template <class P> 00049 P getParam (const ros::NodeHandle& nh, const string& name, const P& default_val) 00050 { 00051 P val; 00052 nh.param(name, val, default_val); 00053 ROS_DEBUG_STREAM_NAMED ("init", "Initialized " << name << " to " << val << 00054 " (default was " << default_val << ")"); 00055 return val; 00056 } 00057 00058 boost::shared_ptr<mongo::DBClientConnection> makeDbConnection (const ros::NodeHandle& nh, 00059 const string& host, 00060 const unsigned& port) 00061 { 00062 // The defaults should match the ones used by mongodb/wrapper.py 00063 const string db_host = 00064 (host=="") ? 00065 getParam<string>(nh, "warehouse_host", "localhost") : 00066 host; 00067 const int db_port = 00068 (port==0) ? 00069 getParam<int>(nh, "warehouse_port", 27017) : 00070 port; 00071 00072 const string db_address = (boost::format("%1%:%2%") % db_host % db_port).str(); 00073 boost::shared_ptr<mongo::DBClientConnection> conn; 00074 while (ros::ok()) 00075 { 00076 conn.reset(new mongo::DBClientConnection()); 00077 try 00078 { 00079 ROS_DEBUG_STREAM_NAMED ("init", "Connecting to db at " << db_address); 00080 conn->connect(db_address); 00081 break; 00082 } 00083 catch (mongo::ConnectException& e) 00084 { 00085 ros::Duration(1.0).sleep(); 00086 } 00087 } 00088 if (conn->isFailed()) 00089 throw DbConnectException(); 00090 00091 return conn; 00092 00093 } 00094 00095 void dropDatabase (const string& db_name) 00096 { 00097 ros::NodeHandle nh; 00098 boost::shared_ptr<mongo::DBClientConnection> c = makeDbConnection(nh); 00099 c->dropDatabase(db_name); 00100 } 00101 00102 string messageType (mongo::DBClientConnection& conn, 00103 const string& db, const string& coll) 00104 { 00105 const string ns = db+".ros_message_collections"; 00106 auto_ptr<mongo::DBClientCursor> cursor = conn.query(ns, BSON("name" << coll)); 00107 mongo::BSONObj obj = cursor->next(); 00108 return obj.getStringField("type"); 00109 } 00110 00111 } // namespace