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
00031
00032
00033
00034
00035
00036
00037 #include <moveit/warehouse/moveit_message_storage.h>
00038 #include <boost/regex.hpp>
00039 #include <ros/ros.h>
00040
00041 moveit_warehouse::MoveItMessageStorage::MoveItMessageStorage(const std::string& host, const unsigned int port,
00042 double wait_seconds)
00043 : db_host_(host), db_port_(port), timeout_(wait_seconds)
00044 {
00045
00046 if (db_host_.empty() || db_port_ == 0)
00047 {
00048 ros::NodeHandle nh("~");
00049
00050
00051
00052 if (db_port_ == 0)
00053 {
00054 std::string paramName;
00055 if (!nh.searchParam("warehouse_port", paramName))
00056 paramName = "warehouse_port";
00057 int param_port;
00058 if (nh.getParam(paramName, param_port))
00059 db_port_ = param_port;
00060 }
00061 if (db_host_.empty())
00062 {
00063 std::string paramName;
00064 if (!nh.searchParam("warehouse_host", paramName))
00065 paramName = "warehouse_host";
00066 std::string param_host;
00067 if (nh.getParam(paramName, param_host))
00068 db_host_ = param_host;
00069 }
00070 }
00071 ROS_DEBUG("Connecting to MongoDB on host '%s' port '%u'...", db_host_.c_str(), db_port_);
00072 }
00073
00074 moveit_warehouse::MoveItMessageStorage::~MoveItMessageStorage()
00075 {
00076 }
00077
00078 void moveit_warehouse::MoveItMessageStorage::drop(const std::string& db)
00079 {
00080 mongo_ros::dropDatabase(db, db_host_, db_port_, timeout_);
00081 ROS_DEBUG("Dropped database '%s'", db.c_str());
00082 }
00083
00084 void moveit_warehouse::MoveItMessageStorage::filterNames(const std::string& regex,
00085 std::vector<std::string>& names) const
00086 {
00087 if (!regex.empty())
00088 {
00089 std::vector<std::string> fnames;
00090 boost::regex r(regex);
00091 for (std::size_t i = 0; i < names.size(); ++i)
00092 {
00093 boost::cmatch match;
00094 if (boost::regex_match(names[i].c_str(), match, r))
00095 fnames.push_back(names[i]);
00096 }
00097 names.swap(fnames);
00098 }
00099 }