database_loader.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, Fetch Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Connor Brew */
00036 
00037 #include <warehouse_ros/database_loader.h>
00038 
00039 namespace warehouse_ros
00040 {
00041 
00042 using std::string;
00043 
00044 DatabaseLoader::DatabaseLoader() :
00045     nh_("~")
00046 {
00047   initialize();
00048 }
00049 
00050 DatabaseLoader::~DatabaseLoader()
00051 {
00052 }
00053 
00054 void DatabaseLoader::initialize()
00055 {
00056   // Create the plugin loader.
00057   try
00058   {
00059     db_plugin_loader_.reset(
00060         new pluginlib::ClassLoader<DatabaseConnection>("warehouse_ros", "warehouse_ros::DatabaseConnection"));
00061   }
00062   catch (pluginlib::PluginlibException& ex)
00063   {
00064     ROS_FATAL_STREAM("Exception while creating database_connection plugin loader " << ex.what());
00065   }
00066 }
00067 
00068 typename DatabaseConnection::Ptr DatabaseLoader::loadDatabase()
00069 {
00070   if (!db_plugin_loader_)
00071   {
00072     return typename DatabaseConnection::Ptr(new DBConnectionStub());
00073   }
00074 
00075   // Search for the warehouse_plugin parameter in the local namespace of the node, and up the tree of namespaces.
00076   // If the desired param is not found, make a final attempt to look for the param in the default namespace
00077   string paramName;
00078   if (!nh_.searchParam("warehouse_plugin", paramName))
00079     paramName = "warehouse_plugin";
00080   string db_plugin;
00081   if (!nh_.getParamCached(paramName, db_plugin))
00082   {
00083     ROS_ERROR("Could not find parameter for database plugin name");
00084     return typename DatabaseConnection::Ptr(new DBConnectionStub());
00085   }
00086 
00087   DatabaseConnection::Ptr db;
00088   try
00089   {
00090     db.reset(db_plugin_loader_->createUnmanagedInstance(db_plugin));
00091   }
00092   catch (pluginlib::PluginlibException& ex)
00093   {
00094     ROS_ERROR_STREAM("Exception while loading database plugin '" << db_plugin << "': " << ex.what() << std::endl);
00095     return typename DatabaseConnection::Ptr(new DBConnectionStub());
00096   }
00097 
00098   bool hostFound = false;
00099   bool portFound = false;
00100 
00101   if (!nh_.searchParam("warehouse_host", paramName))
00102     paramName = "warehouse_host";
00103   std::string host;
00104   if (nh_.getParamCached(paramName, host))
00105   {
00106     hostFound = true;
00107   }
00108 
00109   if (!nh_.searchParam("warehouse_port", paramName))
00110     paramName = "warehouse_port";
00111   int port;
00112   if (nh_.getParamCached(paramName, port))
00113   {
00114     portFound = true;
00115   }
00116 
00117   if (hostFound && portFound)
00118   {
00119     db->setParams(host, port);
00120   }
00121 
00122   return db;
00123 }
00124 
00125 }


warehouse_ros
Author(s): Bhaskara Marthi , Connor Brew
autogenerated on Thu Jun 23 2016 05:36:41