computePixelPoints2.cpp
Go to the documentation of this file.
00001 
00035 #include <iostream>
00036 #include <opencv/cv.h>
00037 #include <opencv/highgui.h>
00038 #include <string>
00039 #include <sstream>
00040 #include <vector>
00041 #include <iomanip>
00042 
00043 #include "Mask.h"
00044 
00045 #include "DUtils.h"
00046 #include "DUtilsCV.h"
00047 #include "DVision.h"
00048 
00049 using namespace std;
00050 
00051 typedef DVision::PMVS::PatchFile PatchFile;
00052 typedef DVision::PMVS::PatchFile::Patch Patch;
00053 
00054 typedef DVision::PMVS::PLYFile PLYFile;
00055 typedef DVision::PMVS::PLYFile::PLYPoint PLYPoint;
00056 
00057 typedef DVision::PMVS::CameraFile PMVS_CameraFile;
00058 typedef DVision::PMVS::CameraFile::Camera PMVS_Camera;
00059 
00060 typedef DVision::Bundle::CameraFile Bundle_CameraFile;
00061 typedef DVision::Bundle::CameraFile::Camera Bundle_Camera;
00062 
00063 
00064 // ----------------------------------------------------------------------------
00065 
00066 struct PixelPoint
00067 {
00068   float x, y; // coords
00069   int idx3d; // index of its plypoint
00070 };
00071 
00072 void getPixelsFromImage(const std::string &img_file, 
00073   const std::string &mask_file, 
00074   const PMVS_Camera &camera,
00075   const std::vector<PLYPoint> &plypoints, 
00076   const std::vector<int> &visible_points,
00077   vector<PixelPoint> &pixelpoints);
00078 
00079 void savePixelPoints(const std::string &save_file, 
00080   const vector<PixelPoint> &pixel_points,
00081   const vector<PLYPoint> &plypoints);
00082 
00083 void convertCamera(const PMVS_Camera &pmvs_camera, 
00084   Bundle_Camera &bundle_cam);
00085 
00086 // ----------------------------------------------------------------------------
00087 
00088 int main(int argc, char *argv[])
00089 {
00090 
00091   if(argc < 5)
00092   {
00093     cout << "Usage: " << argv[0] << " <ply file> <patch file> <img dir> <camera dir>"
00094       << endl;
00095     return 1;
00096   }
00097 
00098   string ply_file = argv[1];
00099   string patch_file = argv[2];
00100   string img_dir = argv[3];
00101   string camera_dir = argv[4];
00102   
00103   cout << "Loading input files... " << flush;
00104   
00105   vector<PLYPoint> plypoints;
00106   PLYFile::readFile(ply_file, plypoints);  
00107   cout << plypoints.size() << " PLY points read" << endl;
00108   
00109   vector<vector<int> > visibility;
00110   PatchFile::readFile(patch_file, visibility);
00111   cout << "Covisibility values read" << endl;
00112 
00113   vector<PMVS_Camera> cameras;
00114   PMVS_CameraFile::readFile(camera_dir, cameras);
00115   cout << cameras.size() << " cameras read" << endl;
00116   
00117   cout << endl;
00118   
00119   vector<string> mask_files =
00120     DUtils::FileFunctions::Dir(img_dir.c_str(), "_mask.png", true);
00121   
00122   if(mask_files.size() != cameras.size())
00123   {
00124     cout << "Error: there are " << cameras.size() << " cameras, but "
00125       << mask_files.size() << " images" << endl;
00126     return 1;
00127   }
00128   
00129   try
00130   {
00131   
00132     for(unsigned int i = 0; i < mask_files.size(); ++i)
00133     {
00134       string path, name, ext;
00135       DUtils::FileFunctions::FileParts(mask_files[i], path, name, ext);
00136       
00137       string img_name = name.substr(0, name.size() - string("_mask").length());
00138       string img_file = path + "/" + img_name + ".jpg";
00139       
00140       cout << img_file << "..." << endl;
00141 
00142       // projection
00143       vector<PixelPoint> pixelpoints;
00144       getPixelsFromImage(img_file, mask_files[i], cameras[i],
00145         plypoints, visibility[i], pixelpoints);
00146 
00147       // save
00148       string save_file = path + "/" + img_name + "_points.txt";
00149       savePixelPoints(save_file, pixelpoints, plypoints);
00150     }
00151     
00152     // save (rename) the cameras in bundler format
00153     if(!mask_files.empty())
00154     {
00155       cout << "Creating cameras..." << endl;
00156       
00157       string path, name, ext;
00158       DUtils::FileFunctions::FileParts(mask_files[0], path, name, ext);
00159       
00160       vector<Bundle_Camera> bundle_cams(1);
00161       for(unsigned int i = 0; i < cameras.size(); ++i)
00162       {
00163         cout << "... camera " << i << endl;
00164         
00165         convertCamera(cameras[i], bundle_cams[0]);
00166         
00167         cout << "... saving..." << endl;
00168         
00169         stringstream ssfile;
00170         ssfile << path << "/im" << setw(2) << setfill('0') << i << "_cam.txt";
00171         Bundle_CameraFile::saveFile(ssfile.str(), bundle_cams);
00172       }
00173     }
00174   
00175   }catch(std::string ex)
00176   {
00177     cout << ex << endl;
00178   }
00179 
00180   return 0;
00181 }
00182 
00183 // ----------------------------------------------------------------------------
00184 
00185 void getPixelsFromImage(const std::string &img_file, 
00186   const std::string &mask_file, 
00187   const PMVS_Camera &camera,
00188   const std::vector<PLYPoint> &plypoints, 
00189   const std::vector<int> &visible_points,
00190   vector<PixelPoint> &pixelpoints)
00191 {
00192   const int MARGIN = 5;
00193   
00194   cv::Mat im = cv::imread(img_file.c_str(), 0);
00195   
00196   if(im.empty())
00197   {
00198     throw string("Could not open image ") + img_file;
00199   }
00200   
00201   Mask mask(mask_file.c_str());
00202   
00203   if(mask.empty())
00204   {
00205     throw string("Could not open mask ") + mask_file;
00206   }
00207   
00208   mask.shrink(MARGIN);
00209   
00210   pixelpoints.resize(0);
00211   pixelpoints.reserve(visible_points.size());
00212   
00213   std::vector<int>::const_iterator vit;
00214   for(vit = visible_points.begin(); vit != visible_points.end(); ++vit)
00215   {
00216     const PLYPoint& p3d = plypoints[*vit];
00217     
00218     cv::Mat X = (cv::Mat_<double>(4, 1) << 
00219       p3d.x, p3d.y, p3d.z, 1.);
00220     
00221     cv::Mat p = camera.P * X;
00222 
00223     PixelPoint pp;
00224     pp.x = float(p.at<double>(0,0) / p.at<double>(2,0));
00225     pp.y = float(p.at<double>(1,0) / p.at<double>(2,0));
00226     pp.idx3d = *vit;
00227 
00228     // add if it is inside the mask
00229     if(mask.test((int)pp.x, (int)pp.y))
00230     {
00231       pixelpoints.push_back(pp);
00232     }
00233   }
00234   
00235 }
00236 
00237 // ----------------------------------------------------------------------------
00238 
00239 void savePixelPoints(const std::string &save_file, 
00240   const vector<PixelPoint> &pixel_points, const vector<PLYPoint> &plypoints)
00241 {
00242   // Format:
00243   // N
00244   // u v x y z idx3d
00245   // ...
00246   
00247   fstream f(save_file.c_str(), ios::out);
00248   
00249   f << pixel_points.size() << endl;
00250   
00251   vector<PixelPoint>::const_iterator pit;
00252   for(pit = pixel_points.begin(); pit != pixel_points.end(); ++pit)
00253   {
00254     f << pit->x << " "
00255       << pit->y << " "
00256       << plypoints[pit->idx3d].x << " "
00257       << plypoints[pit->idx3d].y << " "
00258       << plypoints[pit->idx3d].z << " "
00259       << pit->idx3d << endl;
00260   }
00261 
00262   f.close();
00263 }
00264 
00265 // ----------------------------------------------------------------------------
00266 
00267 void convertCamera(const PMVS_Camera &pmvs_camera, 
00268   Bundle_Camera &bundle_cam)
00269 {
00270   cv::Mat K, R, t; // 3x3, 3x3, 4x1
00271   cv::decomposeProjectionMatrix(pmvs_camera.P, K, R, t);
00272   // opencv 2.1: t is not correct 
00273 
00274   assert(K.type() == CV_64F);
00275   assert(R.type() == CV_64F);
00276   assert(t.type() == CV_64F);
00277   
00278   cv::Mat Rt = K.inv() * pmvs_camera.P;
00279   
00280   bundle_cam.f = K.at<double>(0,0);
00281   bundle_cam.k1 = bundle_cam.k2 = 0;
00282   
00283   bundle_cam.R = Rt.rowRange(0, 3).colRange(0, 3);
00284   bundle_cam.t = Rt.rowRange(0, 3).colRange(3, 4);
00285   
00286 }
00287 
00288 // ----------------------------------------------------------------------------
00289 


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