Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007 #include <pano_py/pano_py.h>
00008
00009 #include <opencv2/highgui/highgui.hpp>
00010 #include <opencv2/core/core.hpp>
00011
00012 #include <pano_core/pano_core.h>
00013 #include <pano_py/opencv.h>
00014
00015
00016 using namespace pano;
00017 using namespace cv;
00018 namespace pano_py{
00019 namespace{
00020 struct CanceledException : public std::exception
00021 {
00022 const char * what() const throw ()
00023 {
00024 return "Canceled!";
00025 }
00026 };
00027
00028
00029 class StitchProgress:public StitchProgressCallable{
00030 public:
00031
00032 void setOnProgressCallback(const bp::object& on_progress){
00033 py_obj_= on_progress;
00034 }
00035 virtual int onProgress(int progress){
00036 return bp::extract<int>(py_obj_(progress));
00037 }
00038 private:
00039 bp::object py_obj_;
00040 };
00041
00042 struct PairFitterCallback
00043 {
00044 int * i;
00045 int total;
00046 int offset;
00047 StitchProgressCallable* callback_;
00048 PairFitterCallback(StitchProgressCallable* callback, int* i, int total, int offset) :
00049 i(i), total(total), offset(offset), callback_(callback)
00050 {
00051 }
00052 template<typename T>
00053 void operator()(const T&)
00054 {
00055 if (callback_)
00056 {
00057 (*i)++;
00058 int progress = (float(*i) / total) * 100 + offset;
00059 callback_->onProgress(progress);
00060 }
00061 }
00062 };
00063
00064 void stitch_py(Options opts, const bp::object& on_progress){
00065 StitchProgress cb;
00066 cb.setOnProgressCallback(on_progress);
00067 stitch(opts,&cb);
00068 }
00069
00070 struct StitchEngine
00071 {
00072 Options opts;
00073 Ptr<cv::AdjusterAdapter> adapter;
00074 Ptr<FeatureDetector> detector;
00075 SVDRSolverParams params;
00076 Camera camera;
00077 Ptr<SVDFitter> svdfitter;
00078 Ptr<ModelFitter> fitter;
00079 MoleculeGlob glob;
00080 vector<ImageAtom> atoms;
00081 vector<Mat> descriptors;
00082 Images images;
00083 int idx;
00084 StitchEngine(Options opts) :
00085 opts(opts), detector(new GriddedDynamicDetectorAdaptor(250, 20, 2, 2, FastAdjuster())), params(opts.fitter_params),
00086 camera(opts.camera),svdfitter(new SVDFitter(params)), fitter(reinterpret_cast<const Ptr<ModelFitter>&> (svdfitter)),idx(0)
00087 {
00088 camera.initUndistort();
00089 }
00090
00091 void addNewImage(const cv::Mat& image){
00092 CV_Assert(image.empty() == false);
00093 Mat uimage;
00094 camera.undistort(image,uimage);
00095 ImageAtom atom(camera,Images(uimage));
00096 atom.setUid(idx++);
00097 Extrinsics ext(Mat::eye(3, 3, CV_32F), 200);
00098 atom.extrinsics() = ext;
00099 atom.extrinsics().flag(Extrinsics::ESTIMATED) = false;
00100 atom.extrinsics().val(Extrinsics::CONFIDENCE) = 200;
00101 atom.detect(*detector);
00102 atom.extract(BriefDescriptorExtractor(), BruteForceMatcher<Hamming> ());
00103 glob.addAtomToGlob(fitter, atom);
00104
00105 }
00106
00107 void stitch(cv::Mat& blended, StitchProgressCallable* callback){
00108 glob.batchFindAndSetTrinsics();
00109 CallbackEngine cbengine;
00110 CV_Assert(blended.type() == CV_8UC3);
00111
00112
00113 Ptr<ImageMolecule> molecule;
00114
00115 molecule = glob.getBiggestMolecule();
00116
00117 int atom_idx = 0;
00118 cbengine.addCallback<ImageAtom> (0, PairFitterCallback(callback, &atom_idx, molecule->getAtoms().size(), 100));
00119
00120 std::cout << ("simple stitching now") << std::endl;
00121 BlenderSimple blender;
00122 blender.cbe = &cbengine;
00123 blender.BlendMolecule(*molecule, blended);
00124
00125 }
00126
00127 };
00128
00129 void stitch_engine_py(StitchEngine& se, cv::Mat image, const bp::object& on_progress){
00130 StitchProgress cb;
00131 cb.setOnProgressCallback(on_progress);
00132 se.stitch(image,&cb);
00133 }
00134
00135 }
00136
00137 bool stitch(Options opts, StitchProgressCallable* callback)
00138 {
00139 try
00140 {
00141
00142 StitchEngine stitcher(opts);
00143
00144 int i = 0;
00145 int t_s = opts.image_names.size();
00146 while (opts.image_names.size())
00147 {
00148 string imagename = opts.image_names.back();
00149 string imagename_full = opts.directory + "/" + imagename;
00150 std::cout << "reading " << imagename_full << std::endl;
00151
00152 Mat img = imread(opts.directory + "/" + imagename);
00153 if(img.empty()){
00154 std::cerr << "image was not read!" << std::endl;
00155 }
00156 stitcher.addNewImage(img);
00157
00158 if (callback)
00159 {
00160 callback->onProgress(int((float(i++) / t_s) * 100));
00161 }
00162 opts.image_names.pop_back();
00163 }
00164 Mat blended(opts.stitch_size,CV_8UC3);
00165 stitcher.stitch(blended,callback);
00166
00167 vector<int> write_params(2);
00168 write_params[0] = CV_IMWRITE_JPEG_QUALITY;
00169 write_params[1] = 85;
00170
00171
00172 imwrite(opts.stitch_output, blended, write_params);
00173 }
00174 catch (CanceledException e)
00175 {
00176 std::cout << ("Canceled");
00177 return true;
00178 }
00179 catch (...)
00180 {
00181 std::cerr << ("Fail stitch!");
00182 return false;
00183 }
00184 return true;
00185
00186 }
00187
00188 void wrap_stitch(){
00189 bp::def("stitch",&stitch_py, "stitch a pano");
00190 bp::class_<StitchEngine>("StitchEngine",bp::init<Options>())
00191 .def("addNewImage",&StitchEngine::addNewImage)
00192 .def("stitch",&stitch_engine_py);
00193 }
00194 }