Client.h
Go to the documentation of this file.
00001 
00011 #ifndef RAIL_PICK_AND_PLACE_GRASPDB_CLIENT_H_
00012 #define RAIL_PICK_AND_PLACE_GRASPDB_CLIENT_H_
00013 
00014 // graspdb
00015 #include "GraspDemonstration.h"
00016 #include "GraspModel.h"
00017 
00018 // ROS
00019 #include <sensor_msgs/PointCloud2.h>
00020 
00021 // PostgreSQL
00022 #include <pqxx/pqxx>
00023 
00024 // C++ Standard Library
00025 #include <string>
00026 
00027 namespace rail
00028 {
00029 namespace pick_and_place
00030 {
00031 namespace graspdb
00032 {
00033 
00040 class Client
00041 {
00042 public:
00044   static const unsigned int DEFAULT_PORT = 5432;
00045 
00053   Client(const Client &c);
00054 
00066   Client(const std::string &host, const uint16_t port, const std::string &user, const std::string &password,
00067          const std::string &db);
00068 
00074   virtual ~Client();
00075 
00083   uint16_t getPort() const;
00084 
00092   const std::string &getHost() const;
00093 
00101   const std::string &getUser() const;
00102 
00110   const std::string &getPassword() const;
00111 
00119   const std::string &getDatabase() const;
00120 
00127   bool connected() const;
00128 
00135   bool connect();
00136 
00142   void disconnect();
00143 
00153   bool loadGraspDemonstration(uint32_t id, GraspDemonstration &gd) const;
00154 
00163   bool loadGraspDemonstrations(std::vector<GraspDemonstration> &gds) const;
00164 
00175   bool loadGraspDemonstrationsByObjectName(const std::string &object_name, std::vector<GraspDemonstration> &gds) const;
00176 
00186   bool loadGrasp(uint32_t id, Grasp &grasp) const;
00187 
00197   bool loadGraspByGraspModelID(const uint32_t grasp_model_id, std::vector<Grasp> &grasps) const;
00198 
00209   bool loadGraspModel(uint32_t id, GraspModel &gm) const;
00210 
00219   bool loadGraspModels(std::vector<GraspModel> &gms) const;
00220 
00230   bool loadGraspModelsByObjectName(const std::string &object_name, std::vector<GraspModel> &gms) const;
00231 
00240   bool getUniqueGraspDemonstrationObjectNames(std::vector<std::string> &names) const;
00241 
00250   bool getUniqueGraspModelObjectNames(std::vector<std::string> &names) const;
00251 
00261   bool addGrasp(Grasp &graps) const;
00262 
00272   bool addGraspDemonstration(GraspDemonstration &gd) const;
00273 
00283   bool addGraspModel(GraspModel &gm) const;
00284 
00292   void deleteGrasp(uint32_t id) const;
00293 
00301   void deleteGraspDemonstration(uint32_t id) const;
00302 
00310   void deleteGraspModel(uint32_t id) const;
00311 
00312 private:
00319   void checkAPIVersion() const;
00320 
00327   void createTables() const;
00328 
00337   bool doesTypeExist(const std::string &type) const;
00338 
00351   bool getStringArrayFromPrepared(const std::string &prepared_name, const std::string &column_name,
00352                                   std::vector<std::string> &strings) const;
00353 
00362   std::string toSQL(const Pose &p) const;
00363 
00372   std::string toSQL(const Position &p) const;
00373 
00382   std::string toSQL(const Orientation &o) const;
00383 
00393   sensor_msgs::PointCloud2 extractPointCloud2FromBinaryString(const pqxx::binarystring &bs) const;
00394 
00403   sensor_msgs::Image extractImageFromBinaryString(const pqxx::binarystring &bs) const;
00404 
00413   std::vector<double> extractArrayFromString(std::string &array) const;
00414 
00423   GraspDemonstration extractGraspDemonstrationFromTuple(const pqxx::result::tuple &tuple) const;
00424 
00433   Grasp extractGraspFromTuple(const pqxx::result::tuple &tuple) const;
00434 
00443   GraspModel extractGraspModelFromTuple(const pqxx::result::tuple &tuple) const;
00444 
00453   time_t extractTimeFromString(const std::string &str) const;
00454 
00455 // check API versions
00456 #if PQXX_VERSION_MAJOR >= 4
00457 /* Only pqxx 4.0.0 or greater support insert with binary strings */
00458 
00466   pqxx::binarystring toBinaryString(const sensor_msgs::PointCloud2 &pc) const;
00467 
00475   pqxx::binarystring toBinaryString(const sensor_msgs::Image &image) const;
00476 
00477 #endif
00478 
00480   std::string host_, user_, password_, db_;
00482   uint16_t port_;
00484   pqxx::connection *connection_;
00485 };
00486 
00487 }
00488 }
00489 }
00490 
00491 #endif


graspdb
Author(s): Russell Toris
autogenerated on Thu Jun 6 2019 19:44:01