Corrected notes
authorIlya Krylov <ilya.krylov@itseez.com>
Tue, 29 Apr 2014 06:24:39 +0000 (10:24 +0400)
committerIlya Krylov <ilya.krylov@itseez.com>
Tue, 29 Apr 2014 06:24:39 +0000 (10:24 +0400)
modules/calib3d/doc/camera_calibration_and_3d_reconstruction.rst
modules/calib3d/include/opencv2/calib3d/calib3d.hpp
modules/calib3d/src/fisheye.cpp
modules/calib3d/src/fisheye.hpp [new file with mode: 0644]
modules/calib3d/test/test_fisheye.cpp

index 3d19b72..710672c 100644 (file)
@@ -1702,12 +1702,6 @@ Estimates new camera matrix for undistortion or rectification.
 
     :param P: New camera matrix (3x3) or new projection matrix (3x4)
 
-    :param new_size: New size
-
-    :param balance: Balance.
-
-    :param fov_scale: Field of View scale.
-
 Fisheye::stereoRectify
 ------------------------------
 Stereo rectification for fisheye camera model
index 816ed76..8caebd3 100644 (file)
@@ -745,32 +745,10 @@ CV_EXPORTS_W  int estimateAffine3D(InputArray src, InputArray dst,
                                    OutputArray out, OutputArray inliers,
                                    double ransacThreshold=3, double confidence=0.99);
 
-
 class Fisheye
 {
 public:
 
-    //Definitions:
-    //  Let P be a point in 3D of coordinates X in the world reference frame (stored in the matrix X)
-    //  The coordinate vector of P in the camera reference frame is: Xc = R*X + T
-    //  where R is the rotation matrix corresponding to the rotation vector om: R = rodrigues(om);
-    //  call x, y and z the 3 coordinates of Xc: x = Xc(1); y = Xc(2); z = Xc(3);
-    //  The pinehole projection coordinates of P is [a;b] where a=x/z and b=y/z.
-    //    call r^2 = a^2 + b^2,
-    //    call theta = atan(r),
-    //
-    //  Fisheye distortion -> theta_d = theta * (1 + k(1)*theta^2 + k(2)*theta^4 + k(3)*theta^6 + k(4)*theta^8)
-    //
-    //  The distorted point coordinates are: xd = [xx;yy] where:
-    //
-    //    xx = (theta_d / r) * x
-    //    yy = (theta_d / r) * y
-    //
-    //  Finally, convertion into pixel coordinates: The final pixel coordinates vector xp=[xxp;yyp] where:
-    //
-    //    xxp = f(1)*(xx + alpha*yy) + c(1)
-    //    yyp = f(2)*yy + c(2)
-
     enum{
         CALIB_USE_INTRINSIC_GUESS   = 1,
         CALIB_RECOMPUTE_EXTRINSIC   = 2,
@@ -826,53 +804,7 @@ public:
         double balance = 0.0, double fov_scale = 1.0);
 };
 
-
-
-namespace internal {
-
-struct IntrinsicParams
-{
-    Vec2d f;
-    Vec2d c;
-    Vec4d k;
-    double alpha;
-    std::vector<int> isEstimate;
-
-    IntrinsicParams();
-    IntrinsicParams(Vec2d f, Vec2d c, Vec4d k, double alpha = 0);
-    IntrinsicParams operator+(const Mat& a);
-    IntrinsicParams& operator =(const Mat& a);
-    void Init(const cv::Vec2d& f, const cv::Vec2d& c, const cv::Vec4d& k = Vec4d(0,0,0,0), const double& alpha = 0);
-};
-
-void projectPoints(cv::InputArray objectPoints, cv::OutputArray imagePoints,
-                   cv::InputArray _rvec,cv::InputArray _tvec,
-                   const IntrinsicParams& param, cv::OutputArray jacobian);
-
-void ComputeExtrinsicRefine(const Mat& imagePoints, const Mat& objectPoints, Mat& rvec,
-                            Mat&  tvec, Mat& J, const int MaxIter,
-                            const IntrinsicParams& param, const double thresh_cond);
-Mat ComputeHomography(Mat m, Mat M);
-
-Mat NormalizePixels(const Mat& imagePoints, const IntrinsicParams& param);
-
-void InitExtrinsics(const Mat& _imagePoints, const Mat& _objectPoints, const IntrinsicParams& param, Mat& omckk, Mat& Tckk);
-
-void CalibrateExtrinsics(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints,
-                         const IntrinsicParams& param, const int check_cond,
-                         const double thresh_cond, InputOutputArray omc, InputOutputArray Tc);
-
-void ComputeJacobians(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints,
-                      const IntrinsicParams& param,  InputArray omc, InputArray Tc,
-                      const int& check_cond, const double& thresh_cond, Mat& JJ2_inv, Mat& ex3);
-
-void EstimateUncertainties(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints,
-                           const IntrinsicParams& params, InputArray omc, InputArray Tc,
-                           IntrinsicParams& errors, Vec2d& std_err, double thresh_cond, int check_cond, double& rms);
-
-}
 }
 
 #endif
-
 #endif
index 0dcc5e7..a9172c9 100644 (file)
@@ -1,9 +1,7 @@
 #include "opencv2/opencv.hpp"
 #include "opencv2/core/affine.hpp"
 #include "opencv2/core/affine.hpp"
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////
-/// cv::Fisheye::projectPoints
+#include "fisheye.hpp"
 
 namespace cv { namespace
 {
@@ -16,6 +14,9 @@ namespace cv { namespace
     };
 }}
 
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////
+/// cv::Fisheye::projectPoints
+
 void cv::Fisheye::projectPoints(InputArray objectPoints, OutputArray imagePoints, const Affine3d& affine,
     InputArray K, InputArray D, double alpha, OutputArray jacobian)
 {
diff --git a/modules/calib3d/src/fisheye.hpp b/modules/calib3d/src/fisheye.hpp
new file mode 100644 (file)
index 0000000..e000e63
--- /dev/null
@@ -0,0 +1,48 @@
+#ifndef FISHEYE_INTERNAL_H
+#define FISHEYE_INTERNAL_H
+
+namespace cv { namespace internal {
+
+struct IntrinsicParams
+{
+    Vec2d f;
+    Vec2d c;
+    Vec4d k;
+    double alpha;
+    std::vector<int> isEstimate;
+
+    IntrinsicParams();
+    IntrinsicParams(Vec2d f, Vec2d c, Vec4d k, double alpha = 0);
+    IntrinsicParams operator+(const Mat& a);
+    IntrinsicParams& operator =(const Mat& a);
+    void Init(const cv::Vec2d& f, const cv::Vec2d& c, const cv::Vec4d& k = Vec4d(0,0,0,0), const double& alpha = 0);
+};
+
+void projectPoints(cv::InputArray objectPoints, cv::OutputArray imagePoints,
+                   cv::InputArray _rvec,cv::InputArray _tvec,
+                   const IntrinsicParams& param, cv::OutputArray jacobian);
+
+void ComputeExtrinsicRefine(const Mat& imagePoints, const Mat& objectPoints, Mat& rvec,
+                            Mat&  tvec, Mat& J, const int MaxIter,
+                            const IntrinsicParams& param, const double thresh_cond);
+Mat ComputeHomography(Mat m, Mat M);
+
+Mat NormalizePixels(const Mat& imagePoints, const IntrinsicParams& param);
+
+void InitExtrinsics(const Mat& _imagePoints, const Mat& _objectPoints, const IntrinsicParams& param, Mat& omckk, Mat& Tckk);
+
+void CalibrateExtrinsics(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints,
+                         const IntrinsicParams& param, const int check_cond,
+                         const double thresh_cond, InputOutputArray omc, InputOutputArray Tc);
+
+void ComputeJacobians(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints,
+                      const IntrinsicParams& param,  InputArray omc, InputArray Tc,
+                      const int& check_cond, const double& thresh_cond, Mat& JJ2_inv, Mat& ex3);
+
+void EstimateUncertainties(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints,
+                           const IntrinsicParams& params, InputArray omc, InputArray Tc,
+                           IntrinsicParams& errors, Vec2d& std_err, double thresh_cond, int check_cond, double& rms);
+
+}}
+
+#endif
index e7d4b31..41bbfea 100644 (file)
@@ -1,6 +1,7 @@
 #include "test_precomp.hpp"
-#include<fstream>
+#include <fstream>
 #include <opencv2/ts/gpu_test.hpp>
+#include "../src/fisheye.hpp"
 
 class FisheyeTest : public ::testing::Test {
 
@@ -21,9 +22,9 @@ protected:
 
     std::string combine_format(const std::string& item1, const std::string& item2, ...);
 
-    void readPoins(std::vector<std::vector<cv::Point3d> >& objectPoints,
+    void readPoints(std::vector<std::vector<cv::Point3d> >& objectPoints,
                    std::vector<std::vector<cv::Point2d> >& imagePoints,
-                   const std::string& path, const int n_images, const int n_points);
+                   const std::string& path, const int n_images);
 
     void readExtrinsics(const std::string& file, cv::OutputArray _R, cv::OutputArray _T, cv::OutputArray _R1, cv::OutputArray _R2,
                         cv::OutputArray _P1, cv::OutputArray _P2, cv::OutputArray _Q);
@@ -104,8 +105,6 @@ TEST_F(FisheyeTest, undistortImage)
         else
             EXPECT_MAT_NEAR(correct, undistorted, 1e-10);
     }
-
-    cv::waitKey();
 }
 
 TEST_F(FisheyeTest, jacobians)
@@ -206,13 +205,11 @@ TEST_F(FisheyeTest, jacobians)
 TEST_F(FisheyeTest, Calibration)
 {
     const int n_images = 34;
-    const int n_points = 48;
 
-    cv::Size imageSize = cv::Size(1280, 800);
     std::vector<std::vector<cv::Point2d> > imagePoints;
     std::vector<std::vector<cv::Point3d> > objectPoints;
 
-    readPoins(objectPoints, imagePoints, combine(datasets_repository_path, "calib-3_stereo_from_JY/left"), n_images, n_points);
+    readPoints(objectPoints, imagePoints, combine(datasets_repository_path, "calib-3_stereo_from_JY/left"), n_images);
 
     int flag = 0;
     flag |= cv::Fisheye::CALIB_RECOMPUTE_EXTRINSIC;
@@ -232,13 +229,11 @@ TEST_F(FisheyeTest, Calibration)
 TEST_F(FisheyeTest, Homography)
 {
     const int n_images = 1;
-    const int n_points = 48;
 
-    cv::Size imageSize = cv::Size(1280, 800);
     std::vector<std::vector<cv::Point2d> > imagePoints;
     std::vector<std::vector<cv::Point3d> > objectPoints;
 
-    readPoins(objectPoints, imagePoints, combine(datasets_repository_path, "calib-3_stereo_from_JY/left"), n_images, n_points);
+    readPoints(objectPoints, imagePoints, combine(datasets_repository_path, "calib-3_stereo_from_JY/left"), n_images);
     cv::internal::IntrinsicParams param;
     param.Init(cv::Vec2d(cv::max(imageSize.width, imageSize.height) / CV_PI, cv::max(imageSize.width, imageSize.height) / CV_PI),
                cv::Vec2d(imageSize.width  / 2.0 - 0.5, imageSize.height / 2.0 - 0.5));
@@ -283,13 +278,11 @@ TEST_F(FisheyeTest, Homography)
 TEST_F(FisheyeTest, EtimateUncertainties)
 {
     const int n_images = 34;
-    const int n_points = 48;
 
-    cv::Size imageSize = cv::Size(1280, 800);
     std::vector<std::vector<cv::Point2d> > imagePoints;
     std::vector<std::vector<cv::Point3d> > objectPoints;
 
-    readPoins(objectPoints, imagePoints, combine(datasets_repository_path, "calib-3_stereo_from_JY/left"), n_images, n_points);
+    readPoints(objectPoints, imagePoints, combine(datasets_repository_path, "calib-3_stereo_from_JY/left"), n_images);
 
     int flag = 0;
     flag |= cv::Fisheye::CALIB_RECOMPUTE_EXTRINSIC;
@@ -325,7 +318,7 @@ TEST_F(FisheyeTest, EtimateUncertainties)
     EXPECT_MAT_NEAR(err_std, cv::Vec2d(0.187475975266883, 0.185678953263995), 1e-10);
     CV_Assert(abs(rms - 0.263782587133546) < 1e-10);
     CV_Assert(errors.alpha == 0);
-  }
+}
 
 TEST_F(FisheyeTest, rectify)
 {
@@ -375,7 +368,6 @@ TEST_F(FisheyeTest, rectify)
     }
 }
 
-
 ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 ///  FisheyeTest::
 
@@ -393,7 +385,6 @@ const cv::Matx33d FisheyeTest::R ( 9.9756700084424932e-01, 6.9698277640183867e-0
 
 const cv::Vec3d FisheyeTest::T(-9.9217369356044638e-02, 3.1741831972356663e-03, 1.8551007952921010e-04);
 
-
 std::string FisheyeTest::combine(const std::string& _item1, const std::string& _item2)
 {
     std::string item1 = _item1, item2 = _item2;
@@ -421,44 +412,28 @@ std::string FisheyeTest::combine_format(const std::string& item1, const std::str
     return std::string(buffer);
 }
 
-void FisheyeTest::readPoins(std::vector<std::vector<cv::Point3d> >& objectPoints,
+void FisheyeTest::readPoints(std::vector<std::vector<cv::Point3d> >& objectPoints,
                std::vector<std::vector<cv::Point2d> >& imagePoints,
-               const std::string& path, const int n_images, const int n_points)
+               const std::string& path, const int n_images)
 {
     objectPoints.resize(n_images);
     imagePoints.resize(n_images);
 
-    std::vector<cv::Point2d> image(n_points);
-    std::vector<cv::Point3d> object(n_points);
-
-    std::ifstream ipStream;
-    std::ifstream opStream;
-
-    for (int image_idx = 0; image_idx < n_images; image_idx++)
+    cv::FileStorage fs1(combine(path, "objectPoints.xml"), cv::FileStorage::READ);
+    CV_Assert(fs1.isOpened());
+    for (size_t i = 0; i < objectPoints.size(); ++i)
     {
-        std::stringstream ss;
-        ss << image_idx;
-        std::string idxStr = ss.str();
-
-        ipStream.open(combine(path, std::string(std::string("x_") + idxStr + std::string(".csv"))).c_str(), std::ifstream::in);
-        opStream.open(combine(path, std::string(std::string("X_") + idxStr + std::string(".csv"))).c_str(), std::ifstream::in);
-        CV_Assert(ipStream.is_open() && opStream.is_open());
-
-        for (int point_idx = 0; point_idx < n_points; point_idx++)
-        {
-            double x, y, z;
-            char delim;
-            ipStream >> x >> delim >> y;
-            image[point_idx] = cv::Point2d(x, y);
-            opStream >> x >> delim >> y >> delim >> z;
-            object[point_idx] = cv::Point3d(x, y, z);
-        }
-        ipStream.close();
-        opStream.close();
+        fs1[cv::format("image_%d", i)] >> objectPoints[i];
+    }
+    fs1.release();
 
-        imagePoints[image_idx] = image;
-        objectPoints[image_idx] = object;
+    cv::FileStorage fs2(combine(path, "imagePoints.xml"), cv::FileStorage::READ);
+    CV_Assert(fs2.isOpened());
+    for (size_t i = 0; i < imagePoints.size(); ++i)
+    {
+        fs2[cv::format("image_%d", i)] >> imagePoints[i];
     }
+    fs2.release();
 }
 
 void FisheyeTest::readExtrinsics(const std::string& file, cv::OutputArray _R, cv::OutputArray _T, cv::OutputArray _R1, cv::OutputArray _R2,