Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
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 string getHost (ros::NodeHandle nh, const string& host="")
00059 {
00060 const string db_host =
00061 (host=="") ?
00062 getParam<string>(nh, "warehouse_host", "localhost") :
00063 host;
00064 return db_host;
00065 }
00066
00067 int getPort (ros::NodeHandle nh, const int port=0)
00068 {
00069 const int db_port =
00070 (port==0) ?
00071 getParam<int>(nh, "warehouse_port", 27017) :
00072 port;
00073 return db_port;
00074 }
00075
00076 boost::shared_ptr<mongo::DBClientConnection>
00077 makeDbConnection (const ros::NodeHandle& nh, const string& host,
00078 const unsigned& port, const float timeout)
00079 {
00080
00081 const string db_host = getHost(nh, host);
00082 const int db_port = getPort(nh, port);
00083
00084 const string db_address = (boost::format("%1%:%2%") % db_host % db_port).str();
00085 boost::shared_ptr<mongo::DBClientConnection> conn;
00086
00087 const ros::WallTime end = ros::WallTime::now() + ros::WallDuration(timeout);
00088
00089 while (ros::ok() && ros::WallTime::now()<end)
00090 {
00091 conn.reset(new mongo::DBClientConnection());
00092 try
00093 {
00094 ROS_DEBUG_STREAM_NAMED ("init", "Connecting to db at " << db_address);
00095 conn->connect(db_address);
00096 if (!conn->isFailed())
00097 break;
00098 }
00099 catch (mongo::ConnectException& e)
00100 {
00101 ros::Duration(1.0).sleep();
00102 }
00103 }
00104 if (conn->isFailed() || ros::WallTime::now()>end)
00105 throw DbConnectException();
00106
00107 return conn;
00108 }
00109
00110 void dropDatabase (const string& db_name)
00111 {
00112 dropDatabase(db_name, "", 0, 60.0);
00113 }
00114
00115 void dropDatabase (const string& db, const string& host, const unsigned port,
00116 const float timeout)
00117 {
00118 ros::NodeHandle nh;
00119 boost::shared_ptr<mongo::DBClientConnection> c =
00120 makeDbConnection(nh, host, port, timeout);
00121 c->dropDatabase(db);
00122 }
00123
00124 string messageType (mongo::DBClientConnection& conn,
00125 const string& db, const string& coll)
00126 {
00127 const string ns = db+".ros_message_collections";
00128 std::auto_ptr<mongo::DBClientCursor> cursor = conn.query(ns, BSON("name" << coll));
00129 mongo::BSONObj obj = cursor->next();
00130 return obj.getStringField("type");
00131 }
00132
00133 }