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


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