00001
00002
00003
00004
00005
00006
00007 #include <ros/ros.h>
00008 #include <visualization_msgs/Marker.h>
00009 #include <visualization_msgs/MarkerArray.h>
00010 #include <geometry_msgs/Point.h>
00011
00012 #include <vslam_system/vslam.h>
00013 #include <posest/pe3d.h>
00014 #include <posest/peh.h>
00015 #include <sba/sba.h>
00016 #include <sba/sba_file_io.h>
00017 #include <frame_common/frame.h>
00018 #include <boost/shared_ptr.hpp>
00019 #include <cstdio>
00020 #include <fstream>
00021 #include <dirent.h>
00022 #include <fnmatch.h>
00023
00024 #include <opencv/highgui.h>
00025 #include <posest/pe3d.h>
00026 #include "opencv2/contrib/contrib.hpp"
00027
00028 using namespace std;
00029 using namespace sba;
00030 using namespace frame_common;
00031 using namespace cv;
00032 using namespace vslam;
00033
00034
00035 char *lreg, *rreg, *dreg;
00036
00037
00038 int getleft(struct dirent const *entry)
00039 {
00040 if (!fnmatch(lreg, entry->d_name, 0))
00041 return 1;
00042 return 0;
00043 }
00044
00045 int getright(struct dirent const *entry)
00046 {
00047 if (!fnmatch(rreg, entry->d_name, 0))
00048 return 1;
00049 return 0;
00050 }
00051
00052 int getidir(struct dirent const *entry)
00053 {
00054 if (!fnmatch(dreg, entry->d_name, 0))
00055 return 1;
00056 return 0;
00057 }
00058
00059
00060 void project3dPoint(const Point3f& point, const Mat& rvec, const Mat& tvec, Point3f& modif_point)
00061 {
00062 Mat R(3, 3, CV_64FC1);
00063 Rodrigues(rvec, R);
00064 modif_point.x = R.at<double> (0, 0) * point.x + R.at<double> (0, 1) * point.y + R.at<double> (0, 2)
00065 * point.z + tvec.at<double> (0, 0);
00066 modif_point.y = R.at<double> (1, 0) * point.x + R.at<double> (1, 1) * point.y + R.at<double> (1, 2)
00067 * point.z + tvec.at<double> (1, 0);
00068 modif_point.z = R.at<double> (2, 0) * point.x + R.at<double> (2, 1) * point.y + R.at<double> (2, 2)
00069 * point.z + tvec.at<double> (2, 0);
00070 }
00071
00072
00073 void invert(Mat& rvec, Mat& tvec)
00074 {
00075 Mat R, RInv;
00076 Rodrigues(rvec,R);
00077 RInv = R.inv();
00078 Rodrigues(RInv, rvec);
00079 tvec = RInv*tvec;
00080 tvec = tvec*(-1);
00081 }
00082
00083 int main(int argc, char** argv)
00084 {
00085 if (argc < 5)
00086 {
00087 printf("Args are: <param file> <image dir> <left image file template> <right image file template>\n");
00088 exit(0);
00089 }
00090
00091
00092 fstream fstr;
00093 fstr.open(argv[1], fstream::in);
00094 if (!fstr.is_open())
00095 {
00096 printf("Can't open camera file %s\n", argv[1]);
00097 exit(0);
00098 }
00099 CamParams camp;
00100 fstr >> camp.fx;
00101 fstr >> camp.fy;
00102 fstr >> camp.cx;
00103 fstr >> camp.cy;
00104 fstr >> camp.tx;
00105 Mat intrinsic = Mat::zeros(Size(3, 3), CV_64F);
00106 intrinsic.at<double>(0, 0) = camp.fx;
00107 intrinsic.at<double>(0, 2) = camp.cx;
00108 intrinsic.at<double>(1, 1) = camp.fy;
00109 intrinsic.at<double>(1, 2) = camp.cy;
00110 intrinsic.at<double>(2, 2) = 1.0;
00111
00112 cout << "Cam params: " << camp.fx << " " << camp.fy << " " << camp.cx << " " << camp.cy << " " << camp.tx << endl;
00113
00114
00115 struct dirent **lims, **rims, **dirs;
00116 int nlim, nrim, ndirs;
00117 string dname = argv[2];
00118 if (!dname.compare(dname.size() - 1, 1, "/"))
00119 dname.erase(dname.size() - 1);
00120
00121 string dirfn = dname.substr(dname.rfind("/") + 1);
00122 string tdir = dname.substr(0, dname.rfind("/") + 1);
00123 cout << "Top directory is " << tdir << endl;
00124 cout << "Search directory name is " << dirfn << endl;
00125 dreg = (char *)dirfn.c_str();
00126
00127 ndirs = scandir(tdir.c_str(), &dirs, getidir, alphasort);
00128 printf("Found %d directories\n", ndirs);
00129 printf("%s\n", dirs[0]->d_name);
00130
00131 const std::string window_name = "matches";
00132 cv::namedWindow(window_name, 0);
00133 cv::Mat display;
00134
00135 int iter = 0;
00136 lreg = argv[3];
00137 rreg = argv[4];
00138
00139
00140 for (int dd = 0; dd < ndirs; dd++)
00141 {
00142 char dir[2048];
00143 sprintf(dir, "%s%s", tdir.c_str(), dirs[dd]->d_name);
00144 printf("Current directory: %s\n", dir);
00145
00146
00147 nlim = scandir(dir, &lims, getleft, alphasort);
00148 printf("Found %d left images\n", nlim);
00149 printf("%s\n", lims[0]->d_name);
00150
00151 nrim = scandir(dir, &rims, getright, alphasort);
00152 printf("Found %d right images\n", nrim);
00153 printf("%s\n", rims[0]->d_name);
00154
00155 if (nlim != nrim)
00156 {
00157 printf("Number of left/right images does not match: %d vs. %d\n", nlim, nrim);
00158 exit(0);
00159 }
00160
00161 frame_common::Frame prevFrame;
00162 frame_common::FrameProc frameProcessor(5);
00163 typedef cv::CalonderDescriptorExtractor<float> Calonder;
00164 frameProcessor.setFrameDescriptor(new Calonder(argv[7]));
00165
00166 pe::HowardStereoMatcher matcherError(0.01, 17);
00167
00168 pe::PoseEstimator3d po(5000, true, 10.0, 3.0, 3.0);
00169 pe::PoseEstimatorH poh(5000, true, 10.0, 3.0, 3.0, 0.1, 40, 13);
00170
00171 po.wx = poh.wx = 92;
00172 po.wy = poh.wy = 48;
00173
00174 cv::TickMeter poMeter, howMeter;
00175
00176
00177 for (int ii = 0; ii < nlim; iter++, ii++)
00178 {
00179 bool matched = false;
00180
00181 char fn[2048];
00182 sprintf(fn, "%s/%s", dir, lims[ii]->d_name);
00183 printf("%s\n", fn);
00184 cv::Mat image1 = cv::imread(fn, 0);
00185 sprintf(fn, "%s/%s", dir, rims[ii]->d_name);
00186 printf("%s\n", fn);
00187 cv::Mat image1r = cv::imread(fn, 0);
00188 if (image1.rows == 0 || image1r.rows == 0)
00189 exit(0);
00190
00191 Mat im; image1.copyTo(im);
00192
00193 Mat imr; image1r.copyTo(imr);
00194
00195 frame_common::Frame frame;
00196 poMeter.start();
00197 howMeter.start();
00198 frameProcessor.setStereoFrame(frame, image1, image1r, 0, false);
00199 poMeter.stop();
00200 howMeter.stop();
00201 frame.setCamParams(camp);
00202 frame.frameId = ii;
00203
00204 vector<DMatch> matchesError;
00205 vector<Point3f> opointsError;
00206 vector<Point2f> ipointsError;
00207 if (!prevFrame.img.empty())
00208 {
00209 display.create(prevFrame.img.rows, prevFrame.img.cols + frame.img.cols, CV_8UC3);
00210 cv::Mat left = display(cv::Rect(0, 0, prevFrame.img.cols, prevFrame.img.rows));
00211 cvtColor(prevFrame.img, left, CV_GRAY2BGR);
00212 cv::Mat right = display(cv::Rect(prevFrame.img.cols, 0, frame.img.cols, frame.img.rows));
00213 cvtColor(frame.img, right, CV_GRAY2BGR);
00214 for (size_t i = 0; i < prevFrame.kpts.size(); ++i)
00215 {
00216 cv::Point pt1 = prevFrame.kpts[i].pt;
00217 cv::circle(display, pt1, 3, Scalar(255));
00218 }
00219 for (size_t i = 0; i < frame.kpts.size(); ++i)
00220 {
00221 cv::Point pt1(frame.kpts[i].pt.x+prevFrame.img.cols,frame.kpts[i].pt.y);
00222 cv::circle(display, pt1, 3, Scalar(255));
00223 }
00224
00225 howMeter.start();
00226 matched = poh.estimate(prevFrame, frame);
00227 cout << "Inliers = " << poh.inliers.size() << endl;
00228 howMeter.stop();
00229
00230 cout << "Matcher error" << endl;
00231 Mat mask = cv::windowedMatchingMask(prevFrame.kpts, frame.kpts, 92, 48);
00232 vector<int> filteredInidices;
00233 matcherError.match(prevFrame, frame, matchesError, filteredInidices, mask);
00234 cout << "Matches error size = " << filteredInidices.size() << endl;
00235
00236 if (matched)
00237 {
00238 for (size_t i = 0; i < poh.inliers.size(); ++i)
00239 {
00240 if (prevFrame.goodPts[poh.inliers[i].queryIdx] && frame.goodPts[poh.inliers[i].trainIdx])
00241 {
00242 cv::Point pt1(prevFrame.kpts[poh.inliers[i].queryIdx].pt.x,prevFrame.kpts[poh.inliers[i].queryIdx].pt.y);
00243 cv::Point pt2(frame.kpts[poh.inliers[i].trainIdx].pt.x+prevFrame.img.cols,frame.kpts[poh.inliers[i].trainIdx].pt.y);
00244 cv::line(display, pt1, pt2, Scalar(0, 255));
00245 }
00246 }
00247
00248 cout << "Matches Error size = " << filteredInidices.size() << endl;
00249 for (size_t i = 0; i < filteredInidices.size(); ++i)
00250 {
00251 if (prevFrame.goodPts[matchesError[filteredInidices[i]].queryIdx] && frame.goodPts[matchesError[filteredInidices[i]].trainIdx])
00252 {
00253 ipointsError.push_back(frame.kpts[matchesError[filteredInidices[i]].trainIdx].pt);
00254 Eigen::Vector4d vec = prevFrame.pts[matchesError[filteredInidices[i]].queryIdx];
00255 Point3f op(vec(0), vec(1), vec(2));
00256 opointsError.push_back(op);
00257
00258
00259 }
00260 }
00261 }
00262 }
00263
00264 if (matched )
00265 {
00266 Mat R(3,3, CV_64F);
00267 for (int j=0; j<poh.rot.cols(); ++j)
00268 for (int i=0; i<poh.rot.rows(); ++i)
00269 R.at<double>(i, j) = poh.rot(i, j);
00270 Mat tvec(3, 1, CV_64F);
00271 for (int j=0; j<3; ++j)
00272 tvec.at<double>(0,j) = poh.trans(j);
00273 Mat rvec;
00274 Rodrigues(R, rvec);
00275 invert(rvec, tvec);
00276 vector<Point2f> projectedPoints;
00277 Mat distCoeffs = Mat::zeros(Size(1, 5), CV_64F);
00278 projectPoints(Mat(opointsError), rvec, tvec, intrinsic, distCoeffs, projectedPoints);
00279 float reprojectionError = 0;
00280 for (size_t pointInd = 0; pointInd < projectedPoints.size(); pointInd++)
00281 {
00282 float error = norm(projectedPoints[pointInd] - ipointsError[pointInd]);
00283 if (error > reprojectionError)
00284 reprojectionError = error;
00285 }
00286 cout << endl << "Howard pose estimator" << endl;
00287 cout << "Reprojection error = " << reprojectionError << endl;
00288 cout << "Inliers size = " << poh.inliers.size() << endl;
00289 Mat Rinv;
00290 Rodrigues(rvec, Rinv);
00291 cout << Rinv << endl << tvec << endl;
00292
00293
00294 poMeter.start();
00295 po.estimate(prevFrame, frame);
00296 poMeter.stop();
00297
00298
00299
00300
00301
00302
00303
00304
00305
00306 Mat poR;
00307 R.copyTo(poR);
00308 for (int j=0; j<po.rot.cols(); ++j)
00309 for (int i=0; i<po.rot.rows(); ++i)
00310 poR.at<double>(i, j) = po.rot(i, j);
00311 Mat t;
00312 tvec.copyTo(t);
00313 for (int j=0; j<3; ++j)
00314 t.at<double>(0,j) = po.trans(j);
00315 Mat r;
00316 Rodrigues(poR, r);
00317 invert(r, t);
00318 projectPoints(Mat(opointsError), r, t, intrinsic, Mat::zeros(Size(1, 5), CV_64F), projectedPoints);
00319 float reprojectionError3d = 0;
00320 for (size_t pointInd = 0; pointInd < projectedPoints.size(); pointInd++)
00321 {
00322 float error = norm(projectedPoints[pointInd] - ipointsError[pointInd]);
00323 if (error > reprojectionError3d)
00324 reprojectionError3d = error;
00325 }
00326 cout << endl << "3d pose estimator" << endl;
00327 cout << "Reprojection error = " << reprojectionError3d << endl;
00328 cout << "Inliers size = " << po.inliers.size() << ", matches = " << po.matches.size() << endl;
00329 Mat RR;
00330 Rodrigues(r, RR);
00331 cout << RR << endl << t << endl;
00332
00333 cout << "Differences:" << endl;
00334 Mat Rdiff = Rinv - RR;
00335 float rdiff = norm(Rdiff, NORM_INF);
00336 cout << Rdiff << endl;
00337 cout << "R diff = " << rdiff << endl;
00338 cout << "tdiff = " << norm(tvec-t, NORM_INF) << endl;
00339 ofstream f;
00340 f.open("statistic.txt", fstream::app);
00341 f << ii << " " << rdiff << " " << norm(tvec-t, NORM_INF) << " " << reprojectionError << " " << reprojectionError3d << " " << poh.inliers.size() << " " << po.inliers.size() << endl;
00342 f.close();
00343
00344
00345 cv::imshow(window_name, display);
00346 cout << "How time = " << howMeter.getTimeMilli() / (float)(ii+1) << endl;
00347 cout << "Po time = " << poMeter.getTimeMilli() / (float)(ii+1) << endl;
00348 char key;
00349 while (true)
00350 {
00351 key = cv::waitKey(1);
00352 if (key == 32)
00353 {
00354 break;
00355 }
00356 else if (key == 27)
00357 return -1;
00358 }
00359
00360
00361 }
00362 prevFrame = frame;
00363 }
00364 }
00365 return 0;
00366 }
00367
00368