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