objects_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 _OBJECTS_DATABASE_H_
00038 #define _OBJECTS_DATABASE_H_
00039 
00040 #include <boost/algorithm/string.hpp>
00041 #include <boost/foreach.hpp>
00042 #include <boost/lexical_cast.hpp>
00043 
00044 //for ROS error messages
00045 #include <ros/ros.h>
00046 
00047 #include <geometry_msgs/PoseStamped.h>
00048 
00049 #include <shape_msgs/Mesh.h>
00050 
00051 #include <household_objects_database_msgs/DatabaseScan.h>
00052 
00053 #include <database_interface/postgresql_database.h>
00054 
00055 #include "household_objects_database/database_original_model.h"
00056 #include "household_objects_database/database_scaled_model.h"
00057 #include "household_objects_database/database_grasp.h"
00058 #include "household_objects_database/database_mesh.h"
00059 #include "household_objects_database/database_perturbation.h"
00060 #include "household_objects_database/database_scan.h"
00061 #include "household_objects_database/database_view.h"
00062 #include "household_objects_database/database_vfh.h"
00063 #include "household_objects_database/database_vfh_orientation.h"
00064 #include "household_objects_database/database_file_path.h"
00065 #include "household_objects_database/database_task.h"
00066 #include "household_objects_database/database_capture_region.h"
00067 #include "household_objects_database/database_object_paths.h"
00068 
00069 namespace household_objects_database
00070 {
00071 
00072   class DatabaseTask;
00073 
00075   class ObjectsDatabase : public database_interface::PostgresqlDatabase
00076   {
00077   public:
00079     ObjectsDatabase (std::string host, std::string port, std::string user, std::string password, std::string dbname) :
00080       PostgresqlDatabase (host, port, user, password, dbname)
00081     {
00082     }
00083 
00085     ObjectsDatabase (const database_interface::PostgresqlDatabaseConfig &config) :
00086       PostgresqlDatabase (config)
00087     {
00088     }
00089 
00091     ~ObjectsDatabase ()
00092     {
00093     }
00094 
00096 
00099     virtual bool
00100     acquireNextTask (std::vector<boost::shared_ptr<DatabaseTask> > &task, std::vector<std::string> accepted_types);
00101 
00102     //------- helper functions wrapped around the general versions for convenience -------
00103     //----------------- or for cases where where_clauses are needed ----------------------
00104 
00106     bool
00107     getOriginalModelsList (std::vector<boost::shared_ptr<DatabaseOriginalModel> > &models) const
00108     {
00109       DatabaseOriginalModel example;
00110       return getList<DatabaseOriginalModel> (models, example, "");
00111     }
00112 
00114     bool
00115     getScaledModelsList (std::vector<boost::shared_ptr<DatabaseScaledModel> > &models) const
00116     {
00117       DatabaseScaledModel example;
00118       return getList<DatabaseScaledModel> (models, example, "");
00119     }
00120 
00122     bool
00123     getScaledModelsByAcquisition (std::vector<boost::shared_ptr<DatabaseScaledModel> > &models,
00124                                   std::string acquisition_method) const
00125     {
00126       std::string where_clause ("acquisition_method_name='" + acquisition_method + "'");
00127       DatabaseScaledModel example;
00128       //this should be set by default, but let's make sure again
00129       example.acquisition_method_.setReadFromDatabase (true);
00130       return getList<DatabaseScaledModel> (models, example, where_clause);
00131     }
00132 
00133     virtual bool
00134     getScaledModelsBySet (std::vector<boost::shared_ptr<DatabaseScaledModel> > &models, 
00135                           std::string model_set_name) const
00136     {
00137       if (model_set_name.empty ())
00138         return getScaledModelsList (models);
00139       std::string where_clause = std::string ("original_model_id IN (SELECT original_model_id FROM "
00140         "model_set WHERE model_set_name = '") + model_set_name + std::string ("')");
00141       DatabaseScaledModel example;
00142       return getList<DatabaseScaledModel> (models, example, where_clause);
00143     }
00144 
00146     bool
00147     getNumOriginalModels (int &num_models) const
00148     {
00149       DatabaseOriginalModel example;
00150       return countList (&example, num_models, "");
00151     }
00152 
00153     bool
00154     getScaledModelsByRecognitionId(std::vector<boost::shared_ptr<DatabaseScaledModel> > &models, 
00155                                    std::string recognition_id) const
00156     {
00157       std::string where_clause = 
00158         std::string("original_model_id IN (SELECT original_model_id FROM "
00159                     "original_model WHERE original_model_recognition_id = '")
00160         + recognition_id + std::string("')");
00161       DatabaseScaledModel example;
00162       return getList<DatabaseScaledModel> (models, example, where_clause);
00163     }
00164 
00166     bool
00167     getModelRoot (std::string& root) const
00168     {
00169       return getVariable ("'MODEL_ROOT'", root);
00170     }
00171 
00173     bool
00174     getModelsListByTags (std::vector<boost::shared_ptr<DatabaseOriginalModel> > &models, 
00175                          std::vector<std::string> tags) const
00176     {
00177       DatabaseOriginalModel example;
00178       std::string where_clause ("(");
00179       for (size_t i = 0; i < tags.size (); i++)
00180       {
00181         if (i != 0)
00182           where_clause += "AND ";
00183         where_clause += "'" + tags[i] + "' = ANY (original_model_tags)";
00184       }
00185       where_clause += ")";
00186       return getList<DatabaseOriginalModel> (models, example, where_clause);
00187     }
00188 
00190     bool
00191     getGrasps (int scaled_model_id, std::string hand_name, std::vector<boost::shared_ptr<DatabaseGrasp> > &grasps) const
00192     {
00193       DatabaseGrasp example;
00194       std::stringstream id;
00195       id << scaled_model_id;
00196       std::string where_clause ("scaled_model_id=" + id.str () + " AND hand_name='" + hand_name + "'");
00197       return getList<DatabaseGrasp> (grasps, example, where_clause);
00198     }
00199 
00201     bool
00202     getClusterRepGrasps (int scaled_model_id, std::string hand_name,
00203                          std::vector<boost::shared_ptr<DatabaseGrasp> > &grasps) const
00204     {
00205       DatabaseGrasp example;
00206       std::stringstream id;
00207       id << scaled_model_id;
00208       std::string where_clause ("scaled_model_id=" + id.str () + " AND hand_name='" + hand_name + "'"
00209           + " AND grasp_cluster_rep=true");
00210       return getList<DatabaseGrasp> (grasps, example, where_clause);
00211     }
00212 
00214     bool
00215     getScaledModelMesh (int scaled_model_id, DatabaseMesh &mesh) const
00216     {
00217       //first get the original model id
00218       DatabaseScaledModel scaled_model;
00219       scaled_model.id_.data () = scaled_model_id;
00220       if (!loadFromDatabase (&scaled_model.original_model_id_))
00221       {
00222         ROS_ERROR ("Failed to get original model for scaled model id %d", scaled_model_id);
00223         return false;
00224       }
00225       mesh.id_.data () = scaled_model.original_model_id_.data ();
00226       if (!loadFromDatabase (&mesh.triangles_) || !loadFromDatabase (&mesh.vertices_))
00227       {
00228         ROS_ERROR ("Failed to load mesh from database for scaled model %d, resolved to original model %d",
00229                    scaled_model_id, mesh.id_.data ());
00230         return false;
00231       }
00232       return true;
00233     }
00234 
00236     bool
00237     getScaledModelMesh (int scaled_model_id, shape_msgs::Mesh &ros_mesh) const
00238     {
00239       DatabaseMesh mesh;
00240       if (!getScaledModelMesh (scaled_model_id, mesh))
00241         return false;
00242 
00243       ros_mesh.vertices.clear ();
00244       if (mesh.vertices_.data ().size () % 3 != 0)
00245       {
00246         ROS_ERROR ("Get scaled model mesh: size of vertices vector is not a multiple of 3");
00247         return false;
00248       }
00249       for (size_t i = 0; i < mesh.vertices_.data ().size () / 3; i++)
00250       {
00251         geometry_msgs::Point p;
00252         p.x = mesh.vertices_.data ().at (3 * i + 0);
00253         p.y = mesh.vertices_.data ().at (3 * i + 1);
00254         p.z = mesh.vertices_.data ().at (3 * i + 2);
00255         ros_mesh.vertices.push_back (p);
00256       }
00257 
00258       ros_mesh.triangles.clear ();
00259       if (mesh.triangles_.data ().size () % 3 != 0)
00260       {
00261         ROS_ERROR ("Get scaled model mesh: size of triangles vector is not a multiple of 3");
00262         return false;
00263       }
00264       for (size_t i = 0; i < mesh.triangles_.data ().size () / 3; i++)
00265       {
00266         shape_msgs::MeshTriangle triangle;
00267         triangle.vertex_indices[0] = mesh.triangles_.data ().at (3 * i + 0);
00268         triangle.vertex_indices[1] = mesh.triangles_.data ().at (3 * i + 1);
00269         triangle.vertex_indices[2] = mesh.triangles_.data ().at (3 * i + 2);
00270         ros_mesh.triangles.push_back (triangle);
00271       }
00272       return true;
00273     }
00274 
00275     bool
00276     getModelScans (int scaled_model_id, std::string source,
00277                    std::vector<household_objects_database_msgs::DatabaseScan> &matching_scan_list) const
00278     {
00279       DatabaseScan scan;
00280       std::vector<boost::shared_ptr<DatabaseScan> > matching_scans;
00281       std::string where_clause ("scaled_model_id = " + boost::lexical_cast<std::string> (scaled_model_id) + " AND "
00282           + "scan_source = '" + source + "'");
00283       getList<DatabaseScan> (matching_scans, where_clause);
00284 
00285       BOOST_FOREACH(const boost::shared_ptr<DatabaseScan> &scan, matching_scans)
00286             {
00287               household_objects_database_msgs::DatabaseScan out_scan;
00288               out_scan.model_id = scan->scaled_model_id_.get ();
00289               out_scan.scan_source = scan->scan_source_.get ();
00290               out_scan.bagfile_location = scan->scan_bagfile_location_.get ();
00291 
00292               out_scan.pose.pose = scan->object_pose_.get ().pose_;
00293               out_scan.pose.header.frame_id = scan->frame_id_.get ();
00294               out_scan.cloud_topic = scan->cloud_topic_.get ();
00295               matching_scan_list.push_back (out_scan);
00296             }
00297 
00298       return true;
00299     }
00300 
00305 
00306     bool
00307     getAllPerturbationsForModel (int scaled_model_id, std::vector<DatabasePerturbationPtr> &perturbations)
00308     {
00309       std::string where_clause = std::string ("grasp_id = ANY(ARRAY(SELECT grasp_id FROM grasp WHERE "
00310         "scaled_model_id = " + boost::lexical_cast<std::string> (scaled_model_id) + std::string ("))"));
00311       DatabasePerturbation example;
00312       return getList<DatabasePerturbation> (perturbations, example, where_clause);
00313     }
00314 
00315     bool
00316     getPerturbationsForGrasps (const std::vector<int> &grasp_ids, std::vector<DatabasePerturbationPtr> &perturbations)
00317     {
00318       std::vector<std::string> grasp_id_strs;
00319       grasp_id_strs.reserve (grasp_ids.size ());
00320       BOOST_FOREACH(int id, grasp_ids)
00321             {
00322               grasp_id_strs.push_back (boost::lexical_cast<std::string, int> (id));
00323             }
00324       std::string where_clause = std::string ("grasp_id = ANY(ARRAY[" + boost::algorithm::join (grasp_id_strs, ", ")
00325           + "])");
00326       DatabasePerturbation example;
00327       return getList<DatabasePerturbation> (perturbations, example, where_clause);
00328     }
00329 
00330     bool
00331     getVFHDescriptors (std::vector<boost::shared_ptr<DatabaseVFH> > &vfh)
00332     {
00333       DatabaseVFH example;
00334       if (!getList<DatabaseVFH> (vfh, example, ""))
00335         return false;
00336       for (size_t i = 0; i < vfh.size (); i++)
00337       {
00338         if (!loadFromDatabase (&(vfh[i]->vfh_descriptor_)))
00339         {
00340           ROS_ERROR ("Failed to load descriptor data for vfh id %d", vfh[i]->vfh_id_.data ());
00341         }
00342       }
00343       return true;
00344     }
00345 
00346     bool
00347    getViewFromViewIdNoData (int view_id, boost::shared_ptr<DatabaseView> &view)
00348    {
00349      std::vector<boost::shared_ptr<DatabaseView> > views;
00350      std::stringstream where2;
00351      where2 << "view_id =" << view_id;
00352      std::string where_clause2 (where2.str ());
00353      getList (views, where_clause2);
00354      view = views[0];
00355      return true;
00356    }
00357 
00358     bool
00359     getViewFromVFHId (int vfh_id, boost::shared_ptr<DatabaseView> &view)
00360     {
00361       std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00362       std::stringstream where;
00363       where << "vfh_id =" << vfh_id;
00364       std::string where_clause (where.str ());
00365       if (!getList (vfhs, where_clause)) {
00366         return false;
00367       }
00368 
00369       std::vector<boost::shared_ptr<DatabaseView> > views;
00370       std::stringstream where2;
00371       where2 << "view_id =" << vfhs[0]->view_id_.data ();
00372       std::string where_clause2 (where2.str ());
00373       getList (views, where_clause2);
00374       if (!loadFromDatabase (&views[0]->view_point_cloud_data_)) {
00375         ROS_ERROR ("Failed to load view point cloud data for view id %d", vfhs[0]->view_id_.data ());
00376       }
00377       view = views[0];
00378       return true;
00379     }
00380 
00381     bool
00382     getViewFromVFHIdNoData (int vfh_id, boost::shared_ptr<DatabaseView> &view)
00383     {
00384       std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00385       std::stringstream where;
00386       where << "vfh_id =" << vfh_id;
00387       std::string where_clause (where.str ());
00388       if (!getList (vfhs, where_clause)) {
00389         return false;
00390       }
00391 
00392       std::vector<boost::shared_ptr<DatabaseView> > views;
00393       std::stringstream where2;
00394       where2 << "view_id =" << vfhs[0]->view_id_.data ();
00395       std::string where_clause2 (where2.str ());
00396       getList (views, where_clause2);
00397       view = views[0];
00398       return true;
00399     }
00400 
00401     bool
00402     getVFHFromView (boost::shared_ptr<DatabaseVFH> & vfh, 
00403                     boost::shared_ptr<household_objects_database::DatabaseView> &view)
00404     {
00405       std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00406       std::stringstream where;
00407       where << "view_id =" << view->view_id_.data();
00408       std::string where_clause (where.str ());
00409       if (!getList (vfhs, where_clause)) {
00410         return false;
00411       }
00412 
00413       vfh = vfhs[0];
00414       if (!loadFromDatabase (&vfh->vfh_descriptor_)) {
00415         ROS_ERROR ("Failed to load VFH descriptor for %d", vfh->vfh_id_.data ());
00416       }
00417       return true;
00418     }
00419 
00420     bool
00421     getOrientationRollFromVFHId (int vfh_id, boost::shared_ptr<DatabaseVFHOrientation> &roll_histogram)
00422     {
00423       std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00424       std::stringstream where;
00425       where << "vfh_id =" << vfh_id;
00426       std::string where_clause (where.str ());
00427       if (!getList (vfhs, where_clause)) {
00428         return false;
00429       }
00430 
00431       /*std::vector<boost::shared_ptr<DatabaseView> > views;
00432       std::stringstream where2;
00433       where2 << "view_id =" << vfhs[0]->view_id_.data ();
00434       std::string where_clause2 (where2.str ());
00435       getList (views, where_clause2);*/
00436 
00437       //Once we have the view, load vfh orientation
00438       std::vector<boost::shared_ptr<DatabaseVFHOrientation> > rolls;
00439       std::stringstream where3;
00440       where3 << "vfh_id =" << vfhs[0]->vfh_id_.data ();
00441       std::string where_clause3 (where3.str ());
00442       if (!getList (rolls, where_clause3)) {
00443         return false;
00444       }
00445 
00446       //std::cout << "rolls size:" << rolls.size() << std::endl;
00447       if (rolls.size() == 0) {
00448         return false;
00449       }
00450 
00451       if (!loadFromDatabase (&rolls[0]->vfh_orientation_descriptor_)) {
00452         ROS_ERROR ("Failed to load VFH roll orientation histogram => id %d", rolls[0]->vfh_orientation_id_.data ());
00453       }
00454       roll_histogram = rolls[0];
00455       return true;
00456     }
00457 
00458     bool
00459     getOrientationRollFromVFHThroughViewId (int vfh_id, boost::shared_ptr<DatabaseVFHOrientation> &roll_histogram)
00460     {
00461       std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00462       std::stringstream where;
00463       where << "vfh_id =" << vfh_id;
00464       std::string where_clause (where.str ());
00465       if (!getList (vfhs, where_clause)) {
00466         return false;
00467       }
00468 
00469       std::vector<boost::shared_ptr<DatabaseView> > views;
00470       std::stringstream where2;
00471       where2 << "view_id =" << vfhs[0]->view_id_.data ();
00472       std::string where_clause2 (where2.str ());
00473       getList (views, where_clause2);
00474 
00475       //Once we have the view, load vfh orientation
00476       std::vector<boost::shared_ptr<DatabaseVFHOrientation> > rolls;
00477       std::stringstream where3;
00478       where3 << "view_id =" << views[0]->view_id_.data ();
00479       std::string where_clause3 (where3.str ());
00480       getList (rolls, where_clause3);
00481 
00482       if (!loadFromDatabase (&rolls[0]->vfh_orientation_descriptor_)) {
00483         ROS_ERROR ("Failed to load VFH roll orientation histogram => id %d", rolls[0]->vfh_orientation_id_.data ());
00484       }
00485       roll_histogram = rolls[0];
00486       return true;
00487     }
00488 
00489     bool
00490     getModelScaleFromId (int scaled_model_id, boost::shared_ptr<DatabaseScaledModel> &scale_model)
00491     {
00492       std::vector<boost::shared_ptr<DatabaseScaledModel> > scaled_models;
00493       std::stringstream where;
00494       where << "scaled_model_id =" << scaled_model_id;
00495       std::string where_clause (where.str ());
00496       if (!getList (scaled_models, where_clause))
00497         return false;
00498 
00499       scale_model = scaled_models[0];
00500       return true;
00501     }
00502 
00503     bool
00504     getModelPathFromViewId (boost::shared_ptr<DatabaseView> &view, std::string &path)
00505     {
00506 
00507       boost::shared_ptr<DatabaseScaledModel> scaled_model;
00508       getModelScaleFromId (view->scaled_model_id_.data (), scaled_model);
00509       //get path...
00510       std::vector<boost::shared_ptr<DatabaseFilePath> > file_paths;
00511       std::stringstream where3;
00512       where3 << "original_model_id =" << scaled_model->original_model_id_.data ();
00513       std::string where_clause3 (where3.str ());
00514       if (!getList (file_paths, where_clause3))
00515         return false;
00516 
00517       path = file_paths[0]->file_path_.data ();
00518       return true;
00519     }
00520 
00521     bool
00522     getModelScale (boost::shared_ptr<DatabaseView> &view, double * scale_factor)
00523     {
00524       boost::shared_ptr<DatabaseScaledModel> scaled_model;
00525       getModelScaleFromId (view->scaled_model_id_.data (), scaled_model);
00526       *scale_factor = scaled_model->scale_.data ();
00527       return true;
00528     }
00529 
00530     bool
00531     getViewsFromScaledModelId (int scaled_model_id, int iteration, std::vector<boost::shared_ptr<DatabaseView> > & views)
00532     {
00533       std::stringstream where;
00534       where << "scaled_model_id =" << scaled_model_id << " AND iteration =" << iteration;
00535       std::string where_clause (where.str ());
00536       if (!getList (views, where_clause)) {
00537         return false;
00538       }
00539 
00540       return true;
00541     }
00542 
00544     bool
00545     getCaptureRegions (int scaled_model_id, std::string robot_geometry_hash, std::vector<boost::shared_ptr<DatabaseCaptureRegion> > &capture_regions) const
00546     {
00547       DatabaseCaptureRegion example;
00548       std::stringstream id;
00549       id << scaled_model_id;
00550       std::string where_clause ("scaled_model_id=" + id.str () + " AND robot_geometry_hash='" + robot_geometry_hash + "'" );
00551       return getList<DatabaseCaptureRegion> (capture_regions, example, where_clause);
00552     }
00553 
00555     bool
00556     getObjectPaths (int scaled_model_id, std::string robot_geometry_hash, std::vector<boost::shared_ptr<DatabaseObjectPaths> > &object_paths) const
00557     {
00558       DatabaseObjectPaths example;
00559       std::stringstream id;
00560       id << scaled_model_id;
00561       std::string where_clause ("object_db_id=" + id.str () + " AND robot_geometry_hash='" + robot_geometry_hash + "'" );
00562       return getList<DatabaseObjectPaths> (object_paths, example, where_clause);
00563     }
00564 
00565 
00566   };
00567   typedef boost::shared_ptr<ObjectsDatabase> ObjectsDatabasePtr;
00568 }//namespace
00569 
00570 #endif


household_objects_database
Author(s): Matei Ciocarlie, except for source files individually marked otherwise
autogenerated on Thu Aug 27 2015 13:24:24