00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #include <opencv2/core/core.hpp>
00036 #include <posest/test/simulated.h>
00037 #include <posest/planarSFM.h>
00038 #include <iostream>
00039 #include <stdio.h>
00040 
00041 using namespace pe;
00042 using namespace cv;
00043 
00044 int main(int argc, char** argv)
00045 {
00046     Mat intrinsics, R0, T0;
00047     vector<Point3f> points;
00048     vector<KeyPoint> points1, points2;
00049     vector<int> indices;
00050     generateData(intrinsics, R0, T0, points1, points2, indices, points);
00051 
00052     Mat R, T, H;
00053     double error = SFM(intrinsics, points1, points2, indices, R, T);
00054     printf("SFM completed with reprojection error %f\n", error);
00055     T = T*10.0;
00056     dumpFltMat("SFM returned R", R);
00057     dumpFltMat("SFM return T", T);
00058 
00059     vector<Point2f> _points1, _points2;
00060     matchesFromIndices(points1, points2, indices, _points1, _points2);
00061 
00062     Mat essential = calcEssentialMatrix(intrinsics.inv(), R, T);
00063     vector<bool> inliers;
00064     computeEpipolarInliers(essential, _points1, _points2, inliers, 5.0);
00065     filterVector(_points1, inliers);
00066     filterVector(_points2, inliers);
00067     filterVector(points, inliers);
00068 
00069     vector<Point3f> cloud;
00070     vector<bool> valid;
00071     reprojectPoints(intrinsics, R, T, _points1, _points2, cloud, valid);
00072 
00073     printf("%d points before filtering\n", (int)points.size());
00074     filterVector(_points1, valid);
00075     filterVector(_points2, valid);
00076     filterVector(points, valid);
00077     filterVector(cloud, valid);
00078 
00079     printf("%d points left after filtering\n", (int)points.size());
00080     float error0 = calcScaledPointCloudDistance(cloud, points);
00081 
00082     Mat rvec;
00083     Rodrigues(R, rvec);
00084 
00085     sba(intrinsics, rvec, T, cloud, _points1, _points2);
00086     findNaNPoints(cloud, valid);
00087     filterVector(_points1, valid);
00088     filterVector(_points2, valid);
00089     filterVector(cloud, valid);
00090     filterVector(points, valid);
00091 
00092     float error1 = calcScaledPointCloudDistance(cloud, points);
00093 
00094     dumpFltMat("rvec", rvec);
00095     dumpFltMat("tvec", T);
00096 
00097     printf("%d points left after sba\n3D error after SFM: %f\n 3D error after sba: %f\n",
00098         points.size(), error0, error1);
00099 
00100     FileStorage fs("extrinsics.yml", FileStorage::WRITE);
00101     fs << "rvec" << rvec << "T" << T;
00102 }