Go to the documentation of this file.
58 "DatabaseConnection"));
62 ROS_FATAL_STREAM(
"Exception while creating database_connection plugin loader " << ex.what());
77 paramName =
"warehouse_plugin";
81 ROS_ERROR(
"Could not find parameter for database plugin name");
92 ROS_ERROR_STREAM(
"Exception while loading database plugin '" << db_plugin <<
"': " << ex.what() << std::endl);
96 bool hostFound =
false;
97 bool portFound =
false;
100 paramName =
"warehouse_host";
108 paramName =
"warehouse_port";
115 if (hostFound && portFound)
117 db->setParams(host, port);
boost::scoped_ptr< pluginlib::ClassLoader< warehouse_ros::DatabaseConnection > > db_plugin_loader_
DatabaseLoader()
Takes a warehouse_ros DatabaseConnection. The DatabaseConnection is expected to have already been ini...
#define ROS_ERROR_STREAM(args)
#define ROS_FATAL_STREAM(args)
DatabaseConnection::Ptr loadDatabase()
Load a database connection using pluginlib Looks for ROS params specifying which plugin/host/port to ...
void initialize()
Initialize the DatabaseLoader.
bool searchParam(const std::string &key, std::string &result) const
boost::shared_ptr< DatabaseConnection > Ptr
boost::shared_ptr< MessageCollectionHelper > Ptr
bool getParamCached(const std::string &key, bool &b) const
ROSCONSOLE_DECL void initialize()
MessageCollectionHelper::Ptr openCollectionHelper(const std::string &db_name, const std::string &collection_name) override
warehouse_ros
Author(s): Bhaskara Marthi
, Connor Brew
autogenerated on Wed Oct 16 2024 02:42:07