00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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
00045 #include <ros/ros.h>
00046
00047 #include <geometry_msgs/PoseStamped.h>
00048
00049 #include <geometric_shapes_msgs/Shape.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
00067 namespace household_objects_database
00068 {
00069
00070 class DatabaseTask;
00071
00073 class ObjectsDatabase : public database_interface::PostgresqlDatabase
00074 {
00075 public:
00077 ObjectsDatabase (std::string host, std::string port, std::string user, std::string password, std::string dbname) :
00078 PostgresqlDatabase (host, port, user, password, dbname)
00079 {
00080 }
00081
00083 ObjectsDatabase (const database_interface::PostgresqlDatabaseConfig &config) :
00084 PostgresqlDatabase (config)
00085 {
00086 }
00087
00089 ~ObjectsDatabase ()
00090 {
00091 }
00092
00094
00096 virtual bool
00097 acquireNextTask (std::vector<boost::shared_ptr<DatabaseTask> > &task);
00098
00099
00100
00101
00103 bool
00104 getOriginalModelsList (std::vector<boost::shared_ptr<DatabaseOriginalModel> > &models) const
00105 {
00106 DatabaseOriginalModel example;
00107 return getList<DatabaseOriginalModel> (models, example, "");
00108 }
00109
00111 bool
00112 getScaledModelsList (std::vector<boost::shared_ptr<DatabaseScaledModel> > &models) const
00113 {
00114 DatabaseScaledModel example;
00115 return getList<DatabaseScaledModel> (models, example, "");
00116 }
00117
00119 bool
00120 getScaledModelsByAcquisition (std::vector<boost::shared_ptr<DatabaseScaledModel> > &models,
00121 std::string acquisition_method) const
00122 {
00123 std::string where_clause ("acquisition_method_name='" + acquisition_method + "'");
00124 DatabaseScaledModel example;
00125
00126 example.acquisition_method_.setReadFromDatabase (true);
00127 return getList<DatabaseScaledModel> (models, example, where_clause);
00128 }
00129
00130 virtual bool
00131 getScaledModelsBySet (std::vector<boost::shared_ptr<DatabaseScaledModel> > &models, std::string model_set_name) const
00132 {
00133 if (model_set_name.empty ())
00134 return getScaledModelsList (models);
00135 std::string where_clause = std::string ("original_model_id IN (SELECT original_model_id FROM "
00136 "model_set WHERE model_set_name = '") + model_set_name + std::string ("')");
00137 DatabaseScaledModel example;
00138 return getList<DatabaseScaledModel> (models, example, where_clause);
00139 }
00140
00142 bool
00143 getNumOriginalModels (int &num_models) const
00144 {
00145 DatabaseOriginalModel example;
00146 return countList (&example, num_models, "");
00147 }
00148
00150 bool
00151 getModelRoot (std::string& root) const
00152 {
00153 return getVariable ("'MODEL_ROOT'", root);
00154 }
00155
00157 bool
00158 getModelsListByTags (std::vector<boost::shared_ptr<DatabaseOriginalModel> > &models, std::vector<std::string> tags) const
00159 {
00160 DatabaseOriginalModel example;
00161 std::string where_clause ("(");
00162 for (size_t i = 0; i < tags.size (); i++)
00163 {
00164 if (i != 0)
00165 where_clause += "AND ";
00166 where_clause += "'" + tags[i] + "' = ANY (original_model_tags)";
00167 }
00168 where_clause += ")";
00169 return getList<DatabaseOriginalModel> (models, example, where_clause);
00170 }
00171
00173 bool
00174 getGrasps (int scaled_model_id, std::string hand_name, std::vector<boost::shared_ptr<DatabaseGrasp> > &grasps) const
00175 {
00176 DatabaseGrasp example;
00177 std::stringstream id;
00178 id << scaled_model_id;
00179 std::string where_clause ("scaled_model_id=" + id.str () + " AND hand_name='" + hand_name + "' AND grasp_energy >= 0 AND grasp_energy < 10" );
00180 return getList<DatabaseGrasp> (grasps, example, where_clause);
00181 }
00182
00184 bool
00185 getClusterRepGrasps (int scaled_model_id, std::string hand_name,
00186 std::vector<boost::shared_ptr<DatabaseGrasp> > &grasps) const
00187 {
00188 DatabaseGrasp example;
00189 std::stringstream id;
00190 id << scaled_model_id;
00191 std::string where_clause ("scaled_model_id=" + id.str () + " AND hand_name='" + hand_name + "'"
00192 + " AND grasp_cluster_rep=true AND grasp_energy >= 0 AND grasp_energy < 10");
00193 return getList<DatabaseGrasp> (grasps, example, where_clause);
00194 }
00195
00197 bool
00198 getScaledModelMesh (int scaled_model_id, DatabaseMesh &mesh) const
00199 {
00200
00201 DatabaseScaledModel scaled_model;
00202 scaled_model.id_.data () = scaled_model_id;
00203 if (!loadFromDatabase (&scaled_model.original_model_id_))
00204 {
00205 ROS_ERROR ("Failed to get original model for scaled model id %d", scaled_model_id);
00206 return false;
00207 }
00208 mesh.id_.data () = scaled_model.original_model_id_.data ();
00209 if (!loadFromDatabase (&mesh.triangles_) || !loadFromDatabase (&mesh.vertices_))
00210 {
00211 ROS_ERROR ("Failed to load mesh from database for scaled model %d, resolved to original model %d",
00212 scaled_model_id, mesh.id_.data ());
00213 return false;
00214 }
00215 return true;
00216 }
00217
00219 bool
00220 getScaledModelMesh (int scaled_model_id, geometric_shapes_msgs::Shape &shape) const
00221 {
00222 DatabaseMesh mesh;
00223 if (!getScaledModelMesh (scaled_model_id, mesh))
00224 return false;
00225 shape.triangles = mesh.triangles_.data ();
00226 shape.vertices.clear ();
00227 if (mesh.vertices_.data ().size () % 3 != 0)
00228 {
00229 ROS_ERROR ("Get scaled model mesh: size of vertices vector is not a multiple of 3");
00230 return false;
00231 }
00232 for (size_t i = 0; i < mesh.vertices_.data ().size () / 3; i++)
00233 {
00234 geometry_msgs::Point p;
00235 p.x = mesh.vertices_.data ().at (3 * i + 0);
00236 p.y = mesh.vertices_.data ().at (3 * i + 1);
00237 p.z = mesh.vertices_.data ().at (3 * i + 2);
00238 shape.vertices.push_back (p);
00239 }
00240 return true;
00241 }
00242
00243 bool
00244 getModelScans (int scaled_model_id, std::string source,
00245 std::vector<household_objects_database_msgs::DatabaseScan> &matching_scan_list) const
00246 {
00247 DatabaseScan scan;
00248 std::vector<boost::shared_ptr<DatabaseScan> > matching_scans;
00249 std::string where_clause ("scaled_model_id = " + boost::lexical_cast<std::string> (scaled_model_id) + " AND "
00250 + "scan_source = '" + source + "'");
00251 getList<DatabaseScan> (matching_scans, where_clause);
00252
00253 BOOST_FOREACH(const boost::shared_ptr<DatabaseScan> &scan, matching_scans)
00254 {
00255 household_objects_database_msgs::DatabaseScan out_scan;
00256 out_scan.model_id = scan->scaled_model_id_.get ();
00257 out_scan.scan_source = scan->scan_source_.get ();
00258 out_scan.bagfile_location = scan->scan_bagfile_location_.get ();
00259
00260 out_scan.pose.pose = scan->object_pose_.get ().pose_;
00261 out_scan.pose.header.frame_id = scan->frame_id_.get ();
00262 out_scan.cloud_topic = scan->cloud_topic_.get ();
00263 matching_scan_list.push_back (out_scan);
00264 }
00265
00266 return true;
00267 }
00268
00273
00274 bool
00275 getAllPerturbationsForModel (int scaled_model_id, std::vector<DatabasePerturbationPtr> &perturbations)
00276 {
00277 std::string where_clause = std::string ("grasp_id = ANY(ARRAY(SELECT grasp_id FROM grasp WHERE "
00278 "scaled_model_id = " + boost::lexical_cast<std::string> (scaled_model_id) + std::string ("))"));
00279 DatabasePerturbation example;
00280 return getList<DatabasePerturbation> (perturbations, example, where_clause);
00281 }
00282
00283 bool
00284 getPerturbationsForGrasps (const std::vector<int> &grasp_ids, std::vector<DatabasePerturbationPtr> &perturbations)
00285 {
00286 std::vector<std::string> grasp_id_strs;
00287 grasp_id_strs.reserve (grasp_ids.size ());
00288 BOOST_FOREACH(int id, grasp_ids)
00289 {
00290 grasp_id_strs.push_back (boost::lexical_cast<std::string, int> (id));
00291 }
00292 std::string where_clause = std::string ("grasp_id = ANY(ARRAY[" + boost::algorithm::join (grasp_id_strs, ", ")
00293 + "])");
00294 DatabasePerturbation example;
00295 return getList<DatabasePerturbation> (perturbations, example, where_clause);
00296 }
00297
00298 bool
00299 getVFHDescriptors (std::vector<boost::shared_ptr<DatabaseVFH> > &vfh)
00300 {
00301 DatabaseVFH example;
00302 if (!getList<DatabaseVFH> (vfh, example, ""))
00303 return false;
00304 for (size_t i = 0; i < vfh.size (); i++)
00305 {
00306 if (!loadFromDatabase (&(vfh[i]->vfh_descriptor_)))
00307 {
00308 ROS_ERROR ("Failed to load descriptor data for vfh id %d", vfh[i]->vfh_id_.data ());
00309 }
00310 }
00311 }
00312
00313 bool
00314 getViewFromViewIdNoData (int view_id, boost::shared_ptr<DatabaseView> &view)
00315 {
00316 std::vector<boost::shared_ptr<DatabaseView> > views;
00317 std::stringstream where2;
00318 where2 << "view_id =" << view_id;
00319 std::string where_clause2 (where2.str ());
00320 getList (views, where_clause2);
00321 view = views[0];
00322 return true;
00323 }
00324
00325 bool
00326 getViewFromVFHId (int vfh_id, boost::shared_ptr<DatabaseView> &view)
00327 {
00328 std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00329 std::stringstream where;
00330 where << "vfh_id =" << vfh_id;
00331 std::string where_clause (where.str ());
00332 if (!getList (vfhs, where_clause)) {
00333 return false;
00334 }
00335
00336 std::vector<boost::shared_ptr<DatabaseView> > views;
00337 std::stringstream where2;
00338 where2 << "view_id =" << vfhs[0]->view_id_.data ();
00339 std::string where_clause2 (where2.str ());
00340 getList (views, where_clause2);
00341 if (!loadFromDatabase (&views[0]->view_point_cloud_data_)) {
00342 ROS_ERROR ("Failed to load view point cloud data for view id %d", vfhs[0]->view_id_.data ());
00343 }
00344 view = views[0];
00345 return true;
00346 }
00347
00348 bool
00349 getViewFromVFHIdNoData (int vfh_id, boost::shared_ptr<DatabaseView> &view)
00350 {
00351 std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00352 std::stringstream where;
00353 where << "vfh_id =" << vfh_id;
00354 std::string where_clause (where.str ());
00355 if (!getList (vfhs, where_clause)) {
00356 return false;
00357 }
00358
00359 std::vector<boost::shared_ptr<DatabaseView> > views;
00360 std::stringstream where2;
00361 where2 << "view_id =" << vfhs[0]->view_id_.data ();
00362 std::string where_clause2 (where2.str ());
00363 getList (views, where_clause2);
00364 view = views[0];
00365 return true;
00366 }
00367
00368 bool
00369 getVFHFromView (boost::shared_ptr<DatabaseVFH> & vfh, boost::shared_ptr<household_objects_database::DatabaseView> &view)
00370 {
00371 std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00372 std::stringstream where;
00373 where << "view_id =" << view->view_id_.data();
00374 std::string where_clause (where.str ());
00375 if (!getList (vfhs, where_clause)) {
00376 return false;
00377 }
00378
00379 vfh = vfhs[0];
00380 if (!loadFromDatabase (&vfh->vfh_descriptor_)) {
00381 ROS_ERROR ("Failed to load VFH descriptor for %d", vfh->vfh_id_.data ());
00382 }
00383 return true;
00384 }
00385
00386 bool
00387 getOrientationRollFromVFHId (int vfh_id, boost::shared_ptr<DatabaseVFHOrientation> &roll_histogram)
00388 {
00389 std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00390 std::stringstream where;
00391 where << "vfh_id =" << vfh_id;
00392 std::string where_clause (where.str ());
00393 if (!getList (vfhs, where_clause)) {
00394 return false;
00395 }
00396
00397
00398
00399
00400
00401
00402
00403
00404 std::vector<boost::shared_ptr<DatabaseVFHOrientation> > rolls;
00405 std::stringstream where3;
00406 where3 << "vfh_id =" << vfhs[0]->vfh_id_.data ();
00407 std::string where_clause3 (where3.str ());
00408 if (!getList (rolls, where_clause3)) {
00409 return false;
00410 }
00411
00412
00413 if (rolls.size() == 0) {
00414 return false;
00415 }
00416
00417 if (!loadFromDatabase (&rolls[0]->vfh_orientation_descriptor_)) {
00418 ROS_ERROR ("Failed to load VFH roll orientation histogram => id %d", rolls[0]->vfh_orientation_id_.data ());
00419 }
00420 roll_histogram = rolls[0];
00421 return true;
00422 }
00423
00424 bool
00425 getOrientationRollFromVFHThroughViewId (int vfh_id, boost::shared_ptr<DatabaseVFHOrientation> &roll_histogram)
00426 {
00427 std::vector<boost::shared_ptr<DatabaseVFH> > vfhs;
00428 std::stringstream where;
00429 where << "vfh_id =" << vfh_id;
00430 std::string where_clause (where.str ());
00431 if (!getList (vfhs, where_clause)) {
00432 return false;
00433 }
00434
00435 std::vector<boost::shared_ptr<DatabaseView> > views;
00436 std::stringstream where2;
00437 where2 << "view_id =" << vfhs[0]->view_id_.data ();
00438 std::string where_clause2 (where2.str ());
00439 getList (views, where_clause2);
00440
00441
00442 std::vector<boost::shared_ptr<DatabaseVFHOrientation> > rolls;
00443 std::stringstream where3;
00444 where3 << "view_id =" << views[0]->view_id_.data ();
00445 std::string where_clause3 (where3.str ());
00446 getList (rolls, where_clause3);
00447
00448 if (!loadFromDatabase (&rolls[0]->vfh_orientation_descriptor_)) {
00449 ROS_ERROR ("Failed to load VFH roll orientation histogram => id %d", rolls[0]->vfh_orientation_id_.data ());
00450 }
00451 roll_histogram = rolls[0];
00452 return true;
00453 }
00454
00455 bool
00456 getModelScaleFromId (int scaled_model_id, boost::shared_ptr<DatabaseScaledModel> &scale_model)
00457 {
00458 std::vector<boost::shared_ptr<DatabaseScaledModel> > scaled_models;
00459 std::stringstream where;
00460 where << "scaled_model_id =" << scaled_model_id;
00461 std::string where_clause (where.str ());
00462 if (!getList (scaled_models, where_clause))
00463 return false;
00464
00465 scale_model = scaled_models[0];
00466 return true;
00467 }
00468
00469 bool
00470 getModelPathFromViewId (boost::shared_ptr<DatabaseView> &view, std::string &path)
00471 {
00472
00473 boost::shared_ptr<DatabaseScaledModel> scaled_model;
00474 getModelScaleFromId (view->scaled_model_id_.data (), scaled_model);
00475
00476 std::vector<boost::shared_ptr<DatabaseFilePath> > file_paths;
00477 std::stringstream where3;
00478 where3 << "original_model_id =" << scaled_model->original_model_id_.data ();
00479 std::string where_clause3 (where3.str ());
00480 if (!getList (file_paths, where_clause3))
00481 return false;
00482
00483 path = file_paths[0]->file_path_.data ();
00484 return true;
00485 }
00486
00487 bool
00488 getModelScale (boost::shared_ptr<DatabaseView> &view, double * scale_factor)
00489 {
00490 boost::shared_ptr<DatabaseScaledModel> scaled_model;
00491 getModelScaleFromId (view->scaled_model_id_.data (), scaled_model);
00492 *scale_factor = scaled_model->scale_.data ();
00493 return true;
00494 }
00495
00496 bool
00497 getViewsFromScaledModelId (int scaled_model_id, int iteration, std::vector<boost::shared_ptr<DatabaseView> > & views)
00498 {
00499 std::stringstream where;
00500 where << "scaled_model_id =" << scaled_model_id << " AND iteration =" << iteration;
00501 std::string where_clause (where.str ());
00502 if (!getList (views, where_clause)) {
00503 return false;
00504 }
00505
00506 return true;
00507 }
00508
00509 };
00510 typedef boost::shared_ptr<ObjectsDatabase> ObjectsDatabasePtr;
00511 }
00512
00513 #endif