getModelInfo.cpp
Go to the documentation of this file.
00001 
00040 #include "ros/ros.h"
00041 
00042 #include <iostream>
00043 #include <iomanip>
00044 #include <vector>
00045 #include <string>
00046 #include <sstream>
00047 
00048 #include <opencv/cv.h>
00049 #include <opencv/highgui.h>
00050 
00051 #include "../MetaFile.h"
00052 #include "../ObjectModel.h"
00053 
00054 #include "DUtils.h"
00055 #include "DUtilsCV.h"
00056 #include "DVision.h"
00057 
00058 typedef DVision::PMVS::PLYFile PLYFile;
00059 typedef DVision::PMVS::PLYFile::PLYPoint PLYPoint;
00060 typedef DVision::SurfSet SurfSet;
00061 
00062 using namespace std;
00063 
00064 // ---------------------------------------------------------------------------
00065 
00071 double getMinHessian(const SurfSet &surf);
00072 
00080 void calculatePointCloudDimensions(const std::vector<PLYPoint> &plypoints, 
00081   float &dx, float &dy, float &dz);
00082 
00083 // ---------------------------------------------------------------------------
00084 
00085 int main(int argc, char **argv)
00086 {
00087   ros::init(argc, argv, "getModelInfo");
00088  
00089   if(argc < 2)
00090   {
00091     ROS_WARN("Usage: %s <model dir>", argv[0]);
00092     return 1;
00093   }
00094   
00095   string model_dir = argv[1];
00096   
00097   if(!ObjectModel::checkDirectory(model_dir))
00098   {
00099     ROS_ERROR("Directory %s does not seem to contain a valid object model",
00100       model_dir.c_str());
00101     return 2;
00102   }
00103   
00104   string meta_file = model_dir + "/meta.xml";
00105   ROS_DEBUG("Reading meta file %s...", meta_file.c_str());
00106   MetaFile::MetaData meta;
00107   MetaFile::readFile(meta_file, meta);
00108   
00109   ROS_INFO("Retrieving object info from %s...", model_dir.c_str());
00110   ROS_INFO("Object name: %s", meta.Name.c_str());
00111   ROS_INFO("Type: %s", meta.Type.c_str());
00112   
00113   if(meta.Type == "planar")
00114   {
00115     ROS_INFO("Dimensions (width x height x depth, metres): %f x %f x %f", 
00116       meta.Dimensions.Planar.Width, meta.Dimensions.Planar.Height,
00117       meta.Dimensions.Planar.Depth);
00118   }
00119   else if(meta.Type == "3D")
00120   {
00121     ROS_INFO("Scale factor: %f", meta.Dimensions.Volume.Scale);
00122     
00123     string drawing_model_file = model_dir + "/drawing_model.ply";
00124     vector<PLYPoint> drawing_plypoints;
00125     PLYFile::readFile(drawing_model_file, drawing_plypoints);
00126     
00127     float dx, dy, dz;
00128     calculatePointCloudDimensions(drawing_plypoints, dx, dy, dz);
00129     
00130     ROS_INFO("Dimensions (X, Y, Z axes): %f x %f x %f", dx, dy, dz);
00131   }
00132   else
00133   {
00134     ROS_INFO("(Unknown dimensions)");
00135   }
00136 
00137   ROS_INFO("Faces: %d", meta.NFaces);
00138   
00139   // get info from each face
00140   for(int i = 0; i < meta.NFaces; ++i)
00141   {
00142     //stringstream ply_file;
00143     //ply_file << model_dir << "/face_" << setw(3) << setfill('0') << i
00144     //  << ".ply";
00145     stringstream surf_file;
00146     surf_file << model_dir << "/face_" << setw(3) << setfill('0') << i
00147       << ".key.gz";
00148     
00149     DVision::SurfSet surf;
00150     surf.Load(surf_file.str());
00151     double min_hessian = getMinHessian(surf);
00152     
00153     if(meta.Type == "planar")
00154     {
00155       ROS_INFO("- Face %d: %d points (min hessian: %f), %f x %f metres", i, 
00156         surf.size(), min_hessian,
00157         //PLYFile::getNumberOfPoints(ply_file.str()),
00158         meta.Dimensions.Planar.Faces[i].Width,
00159         meta.Dimensions.Planar.Faces[i].Height);
00160     }
00161     else
00162     {
00163       ROS_INFO("- Face %d: %d points (min hessian: %f)", i, 
00164         surf.size(), min_hessian);
00165         //PLYFile::getNumberOfPoints(ply_file.str()));
00166     }
00167     
00168   }
00169   
00170   return 0;
00171 }
00172         
00173 // ---------------------------------------------------------------------------
00174 
00175 double getMinHessian(const SurfSet &surf)
00176 {
00177   if(surf.keys.empty()) return 0;
00178   
00179   double min = 1e9;
00180   vector<cv::KeyPoint>::const_iterator kit;
00181   for(kit = surf.keys.begin(); kit != surf.keys.end(); ++kit)
00182   {
00183     if(kit->response < min) min = kit->response;
00184   }
00185   return min;
00186 }
00187 
00188 // ---------------------------------------------------------------------------
00189 
00190 void calculatePointCloudDimensions(const std::vector<PLYPoint> &plypoints, 
00191   float &dx, float &dy, float &dz)
00192 {
00193   float xmin, xmax, ymin, ymax, zmin, zmax;
00194   
00195   if(plypoints.empty())
00196   {
00197     dx = dy = dz = 0;
00198   }
00199   else
00200   {
00201     vector<PLYPoint>::const_iterator it = plypoints.begin();
00202     xmin = xmax = it->x;
00203     ymin = ymax = it->y;
00204     zmin = zmax = it->z;
00205     
00206     for(++it; it != plypoints.end(); ++it)
00207     {
00208       if(it->x < xmin) xmin = it->x;
00209       else if(it->x > xmax) xmax = it->x;
00210 
00211       if(it->y < ymin) ymin = it->y;
00212       else if(it->y > ymax) ymax = it->y;
00213       
00214       if(it->z < zmin) zmin = it->z;
00215       else if(it->z > zmax) zmax = it->z;
00216     }
00217     
00218     dx = xmax - xmin;
00219     dy = ymax - ymin;
00220     dz = zmax - zmin;
00221   }
00222 }
00223 
00224 // ---------------------------------------------------------------------------
00225 


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:31:16