postgresql_database.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
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 the 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(s): Matei Ciocarlie
00036 
00037 #ifndef _POSTGRESQL_DATABASE_H_
00038 #define _POSTGRESQL_DATABASE_H_
00039 
00040 #include <vector>
00041 #include <string>
00042 #include <boost/shared_ptr.hpp>
00043 
00044 //for ROS error messages
00045 #include <ros/ros.h>
00046 #include <yaml-cpp/yaml.h>
00047 
00048 #include "database_interface/db_class.h"
00049 #include "database_interface/db_filters.h"
00050 
00051 //A bit of an involved way to forward declare PGconn, which is a typedef
00052 struct pg_conn;
00053 typedef struct pg_conn PGconn;
00054 
00055 namespace database_interface {
00056 
00057 //this is used to pass the information stored in a received notification event
00058 struct Notification {
00059   std::string channel;
00060   int sending_pid;
00061   std::string payload;
00062 };
00063   
00064 class PostgresqlDatabaseConfig
00065 {
00066 private:
00067   std::string password_;
00068   std::string user_;
00069   std::string host_;
00070   std::string port_;
00071   std::string dbname_;
00072 
00073 public:
00074   PostgresqlDatabaseConfig() {  }
00075 
00076   std::string getPassword() const { return password_; }
00077   std::string getUser() const { return user_; }
00078   std::string getHost() const { return host_; }
00079   std::string getPort() const { return port_; }
00080   std::string getDBname() const { return dbname_; }
00081 
00082   friend void operator>>(const YAML::Node &node, PostgresqlDatabaseConfig &options);
00083 };
00084 
00088 void operator>>(const YAML::Node& node, PostgresqlDatabaseConfig &options);
00089 
00090 class PostgresqlDatabase
00091 {
00092  protected:
00093   void pgMDBconstruct(std::string host, std::string port, std::string user,
00094                       std::string password, std::string dbname );
00095 
00097   PGconn* connection_;
00098 
00100   class PGresultAutoPtr;
00101 
00102   // beginTransaction sets this flag. endTransaction clears it.
00103   bool in_transaction_;
00104 
00106   bool getVariable(std::string name, std::string &value) const;
00107   
00109   bool rollback();
00110 
00112   bool begin();
00113 
00115   bool commit();
00116 
00118   template <class T>
00119     bool getList(std::vector< boost::shared_ptr<T> > &vec, const T& example, std::string where_clause) const;
00120 
00122   bool getListRawResult(const DBClass *example, std::vector<const DBFieldBase*> &fields, 
00123                         std::vector<int> &column_ids, std::string where_clause,
00124                         boost::shared_ptr<PGresultAutoPtr> &result, int &num_tuples) const;
00125 
00127   bool populateListEntry(DBClass *entry, boost::shared_ptr<PGresultAutoPtr> result, int row_num,
00128                          const std::vector<const DBFieldBase*> &fields,
00129                          const std::vector<int> &column_ids) const;
00130 
00132   bool getSequence(std::string name, std::string &value);
00133 
00135   bool insertIntoTable(std::string table_name, const std::vector<const DBFieldBase*> &fields);
00136 
00138   bool deleteFromTable(std::string table_name, const DBFieldBase *key_field);
00139 
00140  public:
00142   PostgresqlDatabase(std::string host, std::string port, std::string user,
00143                      std::string password, std::string dbname);
00144 
00146   PostgresqlDatabase(const PostgresqlDatabaseConfig &config);
00147 
00148 
00150   ~PostgresqlDatabase();
00151 
00153   bool isConnected() const;
00154 
00155   //------- general queries that should work regardless of the datatypes actually being used ------
00156 
00157   //------- retrieval without examples ------- 
00158   template <class T>
00159   bool getList(std::vector< boost::shared_ptr<T> > &vec) const
00160   {
00161     T example;
00162     return getList<T>(vec, example, "");
00163   }
00164   template <class T>
00165   bool getList(std::vector< boost::shared_ptr<T> > &vec, const FilterClause clause) const
00166   {
00167     T example;
00168     return getList<T>(vec, example, clause.clause_);
00169   }
00170   template <class T>
00171   bool getList(std::vector< boost::shared_ptr<T> > &vec, std::string where_clause) const
00172   {
00173     T example;
00174     return getList<T>(vec, example, where_clause);
00175   }
00176 
00177   //------- retrieval with examples ------- 
00178   template <class T>
00179   bool getList(std::vector< boost::shared_ptr<T> > &vec, const T &example) const
00180   {
00181     return getList<T>(vec, example, "");
00182   }
00183   template <class T>
00184   bool getList(std::vector< boost::shared_ptr<T> > &vec, const T &example, const FilterClause clause) const
00185   {
00186     return getList<T>(vec, example, clause.clause_);
00187   }
00188 
00190   bool countList(const DBClass *example, int &count, std::string where_clause) const;
00191 
00193   template <typename T>
00194   bool countList(int &count, const FilterClause clause=FilterClause()) const
00195   {
00196     T example;
00197     return countList(&example, count, clause.clause_);
00198   }
00199 
00201   bool saveToDatabase(const DBFieldBase* field);
00202 
00204   bool loadFromDatabase(DBFieldBase* field) const;
00205 
00207   bool insertIntoDatabase(DBClass* instance);
00208 
00210   bool deleteFromDatabase(DBClass* instance);
00211   
00213   bool listenToChannel(std::string channel);
00214 
00216   bool unlistenToChannel(std::string channel);
00217 
00219   bool checkNotify(Notification &no);
00220 
00222   bool waitForNotify(Notification &no);
00223 
00224 };
00225 
00246 template <class T>
00247 bool PostgresqlDatabase::getList(std::vector< boost::shared_ptr<T> > &vec, 
00248                                  const T &example, std::string where_clause) const
00249 {
00250   //we will store here the fields to be retrieved retrieve from the database
00251   std::vector<const DBFieldBase*> fields;
00252   //we will store here their index in the result returned from the database
00253   std::vector<int> column_ids;
00254   boost::shared_ptr<PGresultAutoPtr> result;
00255 
00256   int num_tuples;
00257   //do all the heavy lifting of querying the database and getting the raw result
00258   if (!getListRawResult(&example, fields, column_ids, where_clause, result, num_tuples))
00259   {
00260     return false;
00261   }
00262 
00263   vec.clear();
00264   if (!num_tuples)
00265   {
00266     return true;
00267   }
00268 
00269   //parse the raw result and populate the list 
00270   for (int i=0; i<num_tuples; i++)
00271   {
00272     boost::shared_ptr<T> entry(new T);
00273     if (populateListEntry(entry.get(), result, i, fields, column_ids))
00274     {
00275       vec.push_back(entry);
00276     }
00277   }
00278   return true;
00279 }
00280 
00281 
00282 }//namespace
00283 
00284 #endif


sql_database
Author(s): Matei Ciocarlie and Lorenz Mosenlechner
autogenerated on Fri Aug 28 2015 13:11:16