ImageAtom.cpp
Go to the documentation of this file.
00001 #include "pano_core/ImageAtom.h"
00002 #include <opencv2/core/core.hpp>
00003 #include <opencv2/highgui/highgui.hpp>
00004 
00005 #include "pano_core/feature_utils.h"
00006 
00007 #include <iomanip>
00008 #include <sstream>
00009 
00010 #include <pano_core/ModelFitter.h>
00011 using namespace cv;
00012 using namespace std;
00013 namespace pano
00014 {
00015 static int uid_gen = 0;
00016 int getUID()
00017 {
00018   return uid_gen++;
00019 }
00020 ImageAtom::ImageAtom() :
00021   extrinsics_(cv::Mat::eye(3, 3, CV_32FC1), 0), uid_(-1)
00022 {
00023 
00024 }
00025 ImageAtom::~ImageAtom()
00026 {
00027 
00028 }
00029 
00030 ImageAtom::ImageAtom(const Camera& camera, const Images& images) :
00031   images_(images), camera_(camera), uid_(-1)
00032 {
00033 
00034 }
00035 //cv::Mat ImageAtom::undistortPoints(){
00036 //  vector<Point2f> points(features_.pts().size());
00038 //  Mat nK;
00039 //  cv::undistortPoints(Mat(features_.pts()),points,camera_.K(),camera_.D());
00040 //  features_.pts() = points;
00041 //  for(size_t i = 0; i < features_.kpts().size();i++){
00042 //    features_.kpts()[i] = features_.pts()[i];
00043 //  }
00044 //  camera_.setCameraIntrinsics(nK,Mat(),camera_.img_size());
00045 //  return nK;
00046 //}
00047 void ImageAtom::detect(const cv::FeatureDetector& detector)
00048 {
00049   features_.detect(detector, images_.grey());
00050 }
00051 
00052 #define MATCH_DEBUG 0
00053 
00054 void ImageAtom::descriptorMatchMask(const ImageAtom& query, cv::Mat& mask, const cv::Mat& H, float uncertainty) const
00055 {
00056   const ImageAtom* prior = this;
00057   Mat _H = H;
00058 
00059   if (_H.empty() && query.extrinsics().flag(Extrinsics::ESTIMATED) && prior->extrinsics().flag(Extrinsics::ESTIMATED))
00060   {
00061     if(angularDist(query.extrinsics(),prior->extrinsics()) > camera().fov_max()){
00062       mask = Mat::zeros(query.features().kpts().size(),prior->features().kpts().size(),CV_8UC1);
00063       return;
00064     }
00065     Mat R21 = prior->extrinsics().relativeToOther(query.extrinsics(), Extrinsics::R);
00066     _H = query.camera().K() * R21 * prior->camera().Kinv();
00067     uncertainty += query.extrinsics().val(Extrinsics::CONFIDENCE) + prior->extrinsics().val(Extrinsics::CONFIDENCE);
00068   }
00069   if (!_H.empty())
00070   {
00071     vector<Point2f> pts(query.features().pts().size());
00072     Mat m_pts(pts);
00073     Mat src(query.features().pts());
00074     perspectiveTransform(src, m_pts, _H);
00075     vector<KeyPoint> kpts;
00076     PointsToKeyPoints(pts, kpts);
00077 #if MATCH_DEBUG
00078     {
00079       Mat hypo;
00080       drawKeypoints(query.images().grey(), kpts, hypo, Scalar(255, 255, 255));
00081       //drawKeypoints(hypo, query.features().kpts(), hypo, Scalar(0, 255, 0), DrawMatchesFlags::DRAW_OVER_OUTIMG);
00082       drawKeypoints(hypo, prior->features().kpts(), hypo, Scalar(0, 0, 255), DrawMatchesFlags::DRAW_OVER_OUTIMG);
00083       imshow("hypo", hypo);
00084       waitKey(10);
00085     }
00086 #endif
00087     mask = windowedMatchingMask(kpts, prior->features().kpts(), uncertainty, uncertainty);
00088   }
00089 }
00090 
00091 void ImageAtom::match(const ImageAtom& query, std::vector<cv::DMatch>& matches, const Mat& H, float uncertainty) const
00092 {
00093   Mat mask;
00094   const ImageAtom* prior = this;
00095   if(uncertainty >0){
00096     descriptorMatchMask(query, mask, H, uncertainty);
00097   }
00098   prior->features().match(query.features(), mask, matches);
00099   std::sort(matches.begin(), matches.end());
00100   DMatch match(0, 0, 80);
00101   size_t i;
00102   for (i = 0; i < matches.size(); i++)
00103   {
00104     if (match < matches[i])
00105       break;
00106   }
00107   //vector<DMatch>::iterator it = find(matches.begin(),matches.end(),match);
00108   if (i != matches.size())
00109     matches.resize(i);
00110 #if MATCH_DEBUG
00111   Mat m_img; //= query.images().grey().clone();
00112   //drawMatchesRelative(prior->features(),query.features(),matches,m_img,vector<uchar>());
00113   drawMatches(query.images().src(), query.features().kpts(), images().src(), prior->features().kpts(), matches, m_img);
00114   imshow("matches", m_img);
00115   waitKey(30);
00116 #endif
00117 
00118 }
00119 
00120 /*
00121  * drawable functions
00122  */
00123 
00124 void ImageAtom::draw(cv::Mat* out, int flags)
00125 {
00126   Mat tout;
00127   if (flags & DRAW_FEATURES)
00128   {
00129     cv::drawKeypoints(images_.grey(), features_.kpts(), tout);
00130   }
00131   *out = tout;
00132 
00133 }
00134 
00135 void ImageAtom::setUid(int id)
00136 {
00137   uid_ = id;
00138   if (images().fname().empty())
00139   {
00140     std::stringstream ss;
00141 
00142     ss << "img" << std::setfill('0') << std::setw(5) << uid_ << ".jpg";
00143     images().fname() = ss.str();
00144   }
00145 
00146 }
00147 
00148 void ImageAtom::serialize(cv::FileStorage& fs) const
00149 {
00150   fs << "{";
00151   fs << "features";
00152   features_.serialize(fs);
00153   fs << "images";
00154   images_.serialize(fs);
00155   fs << "extrinsics";
00156   extrinsics_.serialize(fs);
00157   fs << "camera";
00158   camera_.serialize(fs);
00159   fs << "uid" << uid_;
00160   fs << "}";
00161 }
00162 
00163 void ImageAtom::deserialize(const cv::FileNode& fn)
00164 {
00165   features_.deserialize(fn["features"]);
00166   images_.deserialize(fn["images"]);
00167   extrinsics_.deserialize(fn["extrinsics"]);
00168   camera_.deserialize(fn["camera"]);
00169   uid_ = (int)fn["uid"];
00170 }
00171 
00172 }


pano_core
Author(s): Ethan Rublee
autogenerated on Mon Mar 14 2016 10:56:54