00001
00002
00003
00004
00005
00006
00007
00008 #include "pano_core/ImageAtom.h"
00009 #include "pano_core/feature_utils.h"
00010 #include "pano_core/QuadTree.h"
00011
00012 #include <opencv2/core/core.hpp>
00013 #include <opencv2/highgui/highgui.hpp>
00014 #include <opencv2/features2d/features2d.hpp>
00015 #include <opencv2/imgproc/imgproc.hpp>
00016 #include <iostream>
00017 #include <fstream>
00018 #include <list>
00019 #include <string>
00020
00021 using namespace std;
00022 using namespace cv;
00023 using namespace pano;
00024
00025 list<string> getImageList(istream& input)
00026 {
00027 list<string> imlist;
00028 while (!input.eof() && input.good())
00029 {
00030 string imname;
00031 input >> imname;
00032 if (!input.eof() && input.good())
00033 imlist.push_back(imname);
00034 }
00035 return imlist;
00036 }
00037
00038
00039
00040 void estimateH(const cv::Mat& w, const cv::Mat& R, const cv::Mat& K, const cv::Mat& Kinv, cv::Mat& R_w,
00041 cv::Mat & R_new, cv::Mat& H)
00042 {
00043 Rodrigues(w, R_w);
00044 R_new = R_w * R;
00045 H = K * R_new * Kinv;
00046 }
00047
00048 void getSmallImage(const cv::Mat& src, cv::Mat& dest, float factor = 10.0f)
00049 {
00050 resize(src, dest, Size(src.size().width / factor, src.size().height / factor), 0, 0, CV_INTER_AREA);
00051 }
00052
00053 void getGradientImage(const cv::Mat& src, cv::Mat&dest)
00054 {
00055 Sobel(src, dest, CV_32F, 1, 1);
00056 }
00057
00058
00059 class ESM_data
00060 {
00061 public:
00062
00063 ESM_data(const Mat&ref, const Mat& live, const Mat& K, const Mat& Kinv) :
00064 w_(Mat::zeros(3, 1, CV_32F)), R_(Mat::eye(3, 3, CV_32F)), R_new_(Mat::eye(3, 3, CV_32F)),
00065 H_(Mat::eye(3, 3, CV_32F)), grad_norm_(10.0e6), ref_(ref), live_(live), K_(K), Kinv_(Kinv)
00066 {
00067 getGradientImage(ref, grad_ref_);
00068 }
00069
00070 void estimageRandH(Mat& R, Mat& H, int iters)
00071 {
00072
00073 }
00074 private:
00075 void updateW()
00076 {
00077
00078 }
00079 void updateWarp()
00080 {
00081 Rodrigues(w_, R_w_,w_jacobian_);
00082 R_new_ = R_w_ * R_;
00083 H_ = K_ * R_new_ * Kinv_;
00084 warpPerspective(live_, warped_, H_, live_.size());
00085 }
00086 void updateGradient()
00087 {
00088 grad_diff_ = grad_ref_ - grad_live_;
00089 multiply(grad_diff_, grad_diff_, grad_diff_);
00090 grad_norm_ = sum(grad_diff_)[0];
00091 }
00092
00093 Mat w_;
00094 Mat w_jacobian_;
00095 Mat R_w_;
00096 Mat R_;
00097 Mat R_new_;
00098 Mat H_;
00099
00100 Mat grad_diff_;
00101 Mat grad_ref_;
00102 Mat grad_live_;
00103 Mat warped_;
00104
00105 float grad_norm_;
00106
00107 static const Mat EYE;
00108 const Mat ref_;
00109 const Mat live_;
00110 const Mat K_;
00111 const Mat Kinv_;
00112
00113 };
00114
00115 const Mat ESM_data::EYE = Mat::eye(3, 3, CV_32F);
00116
00117 int main(int ac, char ** av)
00118 {
00119
00120 if (ac != 3)
00121 {
00122 cerr << "usage : " << av[0] << " directory imagelist.txt" << endl;
00123 return 1;
00124 }
00125
00126 std::ifstream input(av[2]);
00127 std::string directory = av[1];
00128
00129 cout << "directory " << directory << endl;
00130 std::list<string> img_names = getImageList(input);
00131
00132 if (img_names.empty())
00133 {
00134 cerr << av[2] << "does not contain a list of images" << endl;
00135 return 1;
00136 }
00137 ImageAtom atom;
00138
00139 atom.camera().setCameraIntrinsics("data/camera.yml");
00140 atom.images().load(img_names.back(), directory);
00141 img_names.pop_back();
00142
00143 BriefDescriptorExtractor brief(32);
00144
00145 Ptr<cv::AdjusterAdapter> adapter = new FastAdjuster();
00146 Ptr<FeatureDetector> detector(new DynamicAdaptedFeatureDetector( adapter, 400, 800, 20) );
00147
00148 BruteForceMatcher<HammingLUT> matcher;
00149 atom.detect( *detector );
00150 atom.extract(brief,matcher);
00151
00152
00153 Mat frame;
00154
00155 vector<DMatch> matches;
00156
00157
00158
00159
00160
00161 Features train = atom.features();
00162
00163
00164 atom.draw(&frame, ImageAtom::DRAW_FEATURES);
00165 imshow("frame", frame);
00166 waitKey();
00167
00168 BruteForceMatcher<HammingLUT> desc_matcher;
00169
00170 Mat ref, live;
00171
00172 getSmallImage(atom.images().src(), ref);
00173
00174 while (!img_names.empty())
00175 {
00176
00177 string image_name = img_names.back();
00178 img_names.pop_back();
00179
00180 atom.images().load(image_name, directory);
00181 getSmallImage(atom.images().grey(), live);
00182
00183 ESM_data esm(ref, live, atom.camera().K(), atom.camera().Kinv());
00184
00185
00186 waitKey(1000);
00187
00188 }
00189 return 0;
00190 }