BlenderMultiband.cpp
Go to the documentation of this file.
00001 #include "pano_core/Blender.h"
00002 #include "pano_core/Projector.h"
00003 #include <opencv2/core/core.hpp>
00004 #include <opencv2/highgui/highgui.hpp>
00005 
00006 #include "pano_core/panoutils.h"
00007 #include "pano_core/BlurDetector.h"
00008 
00009 //#include <wavelet2d/wavelet2d.h>
00010 
00011 #include <opencv2/core/core.hpp>
00012 #include <opencv2/highgui/highgui.hpp>
00013 
00014 //using namespace wavelet2d;
00015 using namespace cv;
00016 using namespace std;
00017 
00018 namespace pano
00019 {
00020 
00021 BlenderMultiband::BlenderMultiband() :
00022   cbe(NULL)
00023 {
00024 
00025 }
00026 
00027 BlenderMultiband::~BlenderMultiband()
00028 {
00029 
00030 }
00031 
00032  
00033 
00034 void BlenderMultiband::blendIncremental(const ImageAtom& atom, cv::Mat& outimage)
00035 {
00036   CV_Assert((outimage.empty() && output_prefix.size() ) || outimage.type() == CV_64FC3)
00037     ;
00038   Mat img;
00039   if (atom.images().src().empty())
00040   {
00041     Images images = atom.images();
00042     images.restore();
00043     img = images.src();
00044   }
00045   else
00046     img = atom.images().src();
00047 
00048   if (cbe)
00049   {
00050     cbe->callBack(atom, 0);
00051   }
00052 
00053   Mat _img = img;
00054   Mat _R = atom.extrinsics().mat(Extrinsics::R);
00055   std::vector<int> roi_ids;
00056   cv::Size inputSize = _img.size();
00057 
00058   //setup the projector
00059   projector.setSRandK(inputSize, _R, atom.camera().K(), roi_ids);
00060 
00061   std::string roi_name;
00062   for (int i = 0; i < (int)roi_ids.size(); i++)
00063   {
00064     int roi_id = roi_ids[i];
00065     Rect roi = projector.getRoi(roi_id);
00066     Mat roi_out;
00067     if (outimage.empty())
00068     {
00069       roi_name = huge_image_.addName(roi_id, output_prefix);
00070       huge_image_.addRoi(roi_id, roi);
00071       roi_out = imread(roi_name);
00072       if (roi_out.empty())
00073         roi_out = cv::Mat::zeros(roi.size(), CV_8UC3);
00074     }
00075     else
00076       roi_out = outimage(roi);
00077 
00078     //project the image onto a clean slate
00079     projector.projectMat(roi_id, _img, in_img, cv::BORDER_CONSTANT);
00080 
00081     // compose:
00082 
00083     if (outimage.empty())
00084     {
00085       imwrite(roi_name, roi_out);
00086     }
00087 
00088   }
00089 
00090 }
00091 
00092 void BlenderMultiband::BlendMolecule(const ImageMolecule& molecule, cv::Mat& outimage_)
00093 {
00094   Mat outimage = cv::Mat::zeros(outimage_.size(), CV_64FC3);
00095   if (!molecule.getAtoms().size())
00096   {
00097     cerr << "bad: empty molecule" << endl;
00098     return;
00099   }
00100   SparseProjector sprojector(outimage.size(), Size(10, 5));
00101   Mat wsum(Mat::zeros(outimage.size(), CV_64F)); // sum of all images' weights
00102   outimage = Scalar(0); // float32 version of final image
00103 
00104   Mat Ib,  Ib_32; // map atom's image to projection
00105   Mat img, img_32;
00106   Mat wb,  wb_32;
00107 
00108   set<Ptr<ImageAtom> >::const_iterator atom = molecule.getAtoms().begin();
00109 
00110   std::vector<cv::Mat> img_channels_cache(3);
00111   Size input_size;
00112   if ((*atom)->images().src().empty())
00113   {
00114     Images images = (*atom)->images();
00115     images.restore();
00116     input_size = images.src().size();
00117 
00118   }
00119   else
00120     input_size = (*atom)->images().src().size();
00121 
00122   Mat weights   = Mat(input_size, CV_64F);
00123   Mat cweights, cw_32;
00124   Blender::fillWeightsGaussian64(weights);
00125 
00126   double confidence_min = 1e-3;
00127 
00128   ofstream matlab_file;
00129   matlab_file.open("omega_blend_out.m");
00130 
00131   int img_idx = 0;
00132   for (; atom != molecule.getAtoms().end(); ++atom)
00133   {
00134     double confidence = ((*atom)->extrinsics().val(Extrinsics::CONFIDENCE));
00135 
00136    // cout << "% atom confidence: " << confidence << endl;
00137     if (cbe) {
00138       cbe->callBack(**atom, 0);
00139     }
00140 
00141     { // dump final image name <=> rotation
00142       matlab_file << "images_all{1+" << img_idx << "}='"
00143            << (*atom)->images().fname() << "';" << endl;
00144 
00145       matlab_file << "omega_all{1+" << img_idx << "}="
00146            << (*atom)->extrinsics().mat(Extrinsics::W) << ";" << endl;
00147       img_idx += 1;
00148     }
00149 
00150     if (confidence < confidence_min)  {
00151       cout << "not blending, confidence is too low: " << confidence << endl;
00152       continue;
00153     }
00154 
00155     if ((*atom)->images().src().empty())
00156     {
00157       Images images = (*atom)->images();
00158       images.restore();
00159       images.src().convertTo(img, CV_64FC3);
00160     }
00161     else
00162       (*atom)->images().src().convertTo(img, CV_64FC3);
00163 
00164     sharpen_backwards_heat_equation( img.clone(), img, .05);
00165 
00166     Mat R = (*atom)->extrinsics().mat(Extrinsics::R);
00167     Mat T = (*atom)->extrinsics().mat(Extrinsics::T);
00168 
00169     cv::sqrt( confidence * weights, cweights );
00170 
00171     cweights.convertTo(cw_32, CV_32F);
00172 
00173     std::vector<int> roi_ids;
00174 
00175     //get all the chips for this atom, given R and K
00176     sprojector.setSRandK(img.size(), R, (*atom)->camera().K(), roi_ids);
00177 
00178     //multiply the image by the weigths
00179     multiplyImageByDoubleWeights(img, cweights, img, &img_channels_cache);
00180     img.convertTo( img_32, CV_32FC3 );
00181 
00182     assert( !cw_32.empty() && !img_32.empty() );
00183     for (int i = 0; i < (int)roi_ids.size(); i++)
00184     {
00185       int roi_id = roi_ids[i];
00186       Rect roi = sprojector.getRoi(roi_id);
00187       Mat out_chip = outimage(roi);
00188       Mat wsum_chip = wsum(roi);
00189 
00190 
00191       sprojector.projectMat(roi_id, cw_32, wb_32, INTER_LINEAR);   // project MS-bits
00192       sprojector.projectMat(roi_id, img_32, Ib_32, INTER_LINEAR);  // project MS-bits
00193 
00194       wb_32.convertTo(wb,CV_64F);
00195       Ib_32.convertTo(Ib,CV_64FC3);
00196 
00197       wsum_chip += wb;
00198       out_chip += Ib;
00199     }
00200   }
00201   matlab_file.close();
00202 
00203   divideImageByDoubleWeights(outimage, wsum, outimage);
00204 
00205   outimage.convertTo(outimage_, outimage_.type());
00206  
00207 }
00208 
00209 } // end namespace vrcl
00210 
00211 


pano_core
Author(s): Ethan Rublee
autogenerated on Mon Oct 6 2014 08:04:38