computePixelPoints.cpp
Go to the documentation of this file.
00001 
00034 #include <iostream>
00035 #include <opencv/cv.h>
00036 #include <opencv/highgui.h>
00037 #include <string>
00038 #include <vector>
00039 
00040 #include "Mask.h"
00041 
00042 #include "DUtils.h"
00043 #include "DUtilsCV.h"
00044 #include "DVision.h"
00045 
00046 using namespace std;
00047 
00048 typedef DVision::PMVS::PatchFile PatchFile;
00049 typedef DVision::PMVS::PatchFile::Patch Patch;
00050 
00051 typedef DVision::PMVS::PLYFile PLYFile;
00052 typedef DVision::PMVS::PLYFile::PLYPoint PLYPoint;
00053 
00054 typedef DVision::PMVS::CameraFile CameraFile;
00055 typedef DVision::PMVS::CameraFile::Camera Camera;
00056 
00057 // ----------------------------------------------------------------------------
00058 
00059 struct PixelPoint
00060 {
00061   float x, y; // coords
00062   int idx3d; // index of its plypoint
00063 };
00064 
00065 void getPixelsFromImage(const std::string &img_file, 
00066   const std::string &mask_file, 
00067   const Camera& camera,
00068   const std::vector<PLYPoint> &plypoints, 
00069   const std::vector<int> &visible_points,
00070   vector<PixelPoint> &pixelpoints);
00071 
00072 void savePixelPoints(const std::string &save_file, 
00073   const vector<PixelPoint> &pixel_points,
00074   const vector<PLYPoint> &plypoints);
00075 
00076 // ----------------------------------------------------------------------------
00077 
00078 int main(int argc, char *argv[])
00079 {
00080 
00081   if(argc < 5)
00082   {
00083     cout << "Usage: " << argv[0] << " <ply file> <patch file> <img dir> <camera dir>"
00084       << endl;
00085     return 1;
00086   }
00087 
00088   string ply_file = argv[1];
00089   string patch_file = argv[2];
00090   string img_dir = argv[3];
00091   string camera_dir = argv[4];
00092   
00093   cout << "Loading input files... " << flush;
00094   
00095   vector<PLYPoint> plypoints;
00096   PLYFile::readFile(ply_file, plypoints);  
00097   cout << "(ply ok) " << flush;
00098   
00099   vector<vector<int> > visibility;
00100   PatchFile::readFile(patch_file, visibility);
00101   cout << "(patch ok) " << flush;
00102 
00103   vector<Camera> cameras;
00104   CameraFile::readFile(camera_dir, cameras);
00105   cout << "(cameras ok) " << flush;
00106   
00107   cout << endl;
00108   
00109   vector<string> mask_files =
00110     DUtils::FileFunctions::Dir(img_dir.c_str(), "_mask.png", true);
00111   
00112   if(mask_files.size() != cameras.size())
00113   {
00114     cout << "Error: there are " << cameras.size() << " cameras, but "
00115       << mask_files.size() << " images" << endl;
00116     return 1;
00117   }
00118   
00119   for(unsigned int i = 0; i < mask_files.size(); ++i)
00120   {
00121     string path, name, ext;
00122     DUtils::FileFunctions::FileParts(mask_files[i], path, name, ext);
00123     
00124     string img_name = name.substr(0, name.size() - string("_mask").length());
00125     string img_file = path + "/" + img_name + ".jpg";
00126     
00127     cout << img_file << "..." << endl;
00128 
00129     // projection
00130     vector<PixelPoint> pixelpoints;
00131     getPixelsFromImage(img_file, mask_files[i], cameras[i],
00132       plypoints, visibility[i], pixelpoints);
00133 
00134     // save
00135     string save_file = path + "/" + img_name + "_points.txt";
00136     savePixelPoints(save_file, pixelpoints, plypoints);
00137   }
00138   
00139   // save (rename) the cameras
00140   if(!mask_files.empty())
00141   {
00142     string path, name, ext;
00143     DUtils::FileFunctions::FileParts(mask_files[0], path, name, ext);    
00144     CameraFile::saveFile(path, cameras, "im%02d_cam.txt");
00145   }
00146 
00147   return 0;
00148 }
00149 
00150 // ----------------------------------------------------------------------------
00151 
00152 void getPixelsFromImage(const std::string &img_file, 
00153   const std::string &mask_file, 
00154   const Camera &camera,
00155   const std::vector<PLYPoint> &plypoints, 
00156   const std::vector<int> &visible_points,
00157   vector<PixelPoint> &pixelpoints)
00158 {
00159   const int MARGIN = 5;
00160   
00161   cv::Mat im = cv::imread(img_file.c_str(), 0);
00162   Mask mask(mask_file.c_str());
00163   mask.shrink(MARGIN);
00164   
00165   pixelpoints.resize(0);
00166   pixelpoints.reserve(visible_points.size());
00167   
00168   std::vector<int>::const_iterator vit;
00169   for(vit = visible_points.begin(); vit != visible_points.end(); ++vit)
00170   {
00171     const PLYPoint& p3d = plypoints[*vit];
00172     
00173     cv::Mat X = (cv::Mat_<double>(4, 1) << 
00174       p3d.x, p3d.y, p3d.z, 1.);
00175     
00176     cv::Mat p = camera.P * X;
00177 
00178     PixelPoint pp;
00179     pp.x = float(p.at<double>(0,0) / p.at<double>(2,0));
00180     pp.y = float(p.at<double>(1,0) / p.at<double>(2,0));
00181     pp.idx3d = *vit;
00182 
00183     // add if it is inside the mask
00184     if(mask.test((int)pp.x, (int)pp.y))
00185     {
00186       pixelpoints.push_back(pp);
00187     }
00188   }
00189   
00190 }
00191 
00192 // ----------------------------------------------------------------------------
00193 
00194 void savePixelPoints(const std::string &save_file, 
00195   const vector<PixelPoint> &pixel_points, const vector<PLYPoint> &plypoints)
00196 {
00197   // Format:
00198   // N
00199   // u v x y z idx3d
00200   // ...
00201   
00202   fstream f(save_file.c_str(), ios::out);
00203   
00204   f << pixel_points.size() << endl;
00205   
00206   vector<PixelPoint>::const_iterator pit;
00207   for(pit = pixel_points.begin(); pit != pixel_points.end(); ++pit)
00208   {
00209     f << pit->x << " "
00210       << pit->y << " "
00211       << plypoints[pit->idx3d].x << " "
00212       << plypoints[pit->idx3d].y << " "
00213       << plypoints[pit->idx3d].z << " "
00214       << pit->idx3d << endl;
00215   }
00216 
00217   f.close();
00218 }
00219 
00220 // ----------------------------------------------------------------------------
00221 
00222 


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