31 #include <opencv2/core/core.hpp> 32 #include <opencv2/calib3d/calib3d.hpp> 37 CameraParameters::CameraParameters() {
38 CameraMatrix = cv::Mat();
39 Distorsion = cv::Mat();
40 CamSize = cv::Size(-1, -1);
47 CameraParameters::CameraParameters(cv::Mat cameraMatrix, cv::Mat distorsionCoeff, cv::Size size)
throw(cv::Exception) {
48 setParams(cameraMatrix, distorsionCoeff, size);
68 void CameraParameters::setParams(cv::Mat cameraMatrix, cv::Mat distorsionCoeff, cv::Size size)
throw(cv::Exception) {
69 if (cameraMatrix.rows != 3 || cameraMatrix.cols != 3)
70 throw cv::Exception(9000,
"invalid input cameraMatrix",
"CameraParameters::setParams", __FILE__, __LINE__);
71 cameraMatrix.convertTo(CameraMatrix, CV_32FC1);
72 if (distorsionCoeff.total() < 4 || distorsionCoeff.total() >= 7)
73 throw cv::Exception(9000,
"invalid input distorsionCoeff",
"CameraParameters::setParams", __FILE__, __LINE__);
76 distorsionCoeff.convertTo(Distorsion, CV_32FC1);
87 cv::Point3f CameraParameters::getCameraLocation(cv::Mat Rvec, cv::Mat Tvec) {
88 cv::Mat m33(3, 3, CV_32FC1);
89 cv::Rodrigues(Rvec, m33);
91 cv::Mat m44 = cv::Mat::eye(4, 4, CV_32FC1);
92 for (
int i = 0; i < 3; i++)
93 for (
int j = 0; j < 3; j++)
94 m44.at<
float >(i, j) = m33.at<
float >(i, j);
97 for (
int i = 0; i < 3; i++)
98 m44.at<
float >(i, 3) = Tvec.at<
float >(0, i);
101 return cv::Point3f(m44.at<
float >(0, 0), m44.at<
float >(0, 1), m44.at<
float >(0, 2));
107 void CameraParameters::saveToFile(
string path,
bool inXML)
throw(cv::Exception) {
109 throw cv::Exception(9006,
"invalid object",
"CameraParameters::saveToFile", __FILE__, __LINE__);
111 ofstream file(path.c_str());
113 throw cv::Exception(9006,
"could not open file:" + path,
"CameraParameters::saveToFile", __FILE__, __LINE__);
114 file <<
"# Aruco 1.0 CameraParameters" << endl;
115 file <<
"fx = " << CameraMatrix.at<
float >(0, 0) << endl;
116 file <<
"cx = " << CameraMatrix.at<
float >(0, 2) << endl;
117 file <<
"fy = " << CameraMatrix.at<
float >(1, 1) << endl;
118 file <<
"cy = " << CameraMatrix.at<
float >(1, 2) << endl;
119 file <<
"k1 = " << Distorsion.at<
float >(0, 0) << endl;
120 file <<
"k2 = " << Distorsion.at<
float >(1, 0) << endl;
121 file <<
"p1 = " << Distorsion.at<
float >(2, 0) << endl;
122 file <<
"p2 = " << Distorsion.at<
float >(3, 0) << endl;
123 file <<
"width = " << CamSize.width << endl;
124 file <<
"height = " << CamSize.height << endl;
126 cv::FileStorage fs(path, cv::FileStorage::WRITE);
127 fs <<
"image_width" << CamSize.width;
128 fs <<
"image_height" << CamSize.height;
129 fs <<
"camera_matrix" << CameraMatrix;
130 fs <<
"distortion_coefficients" << Distorsion;
136 void CameraParameters::resize(cv::Size size)
throw(cv::Exception) {
138 throw cv::Exception(9007,
"invalid object",
"CameraParameters::resize", __FILE__, __LINE__);
143 float AxFactor = float(size.width) / float(CamSize.width);
144 float AyFactor = float(size.height) / float(CamSize.height);
145 CameraMatrix.at<
float >(0, 0) *= AxFactor;
146 CameraMatrix.at<
float >(0, 2) *= AxFactor;
147 CameraMatrix.at<
float >(1, 1) *= AyFactor;
148 CameraMatrix.at<
float >(1, 2) *= AyFactor;
157 void CameraParameters::readFromXMLFile(
string filePath)
throw(cv::Exception) {
158 cv::FileStorage fs(filePath, cv::FileStorage::READ);
160 cv::Mat MCamera, MDist;
162 fs[
"image_width"] >> w;
163 fs[
"image_height"] >> h;
164 fs[
"distortion_coefficients"] >> MDist;
165 fs[
"camera_matrix"] >> MCamera;
167 if (MCamera.cols == 0 || MCamera.rows == 0)
168 throw cv::Exception(9007,
"File :" + filePath +
" does not contains valid camera matrix",
"CameraParameters::readFromXML", __FILE__, __LINE__);
169 if (w == -1 || h == 0)
170 throw cv::Exception(9007,
"File :" + filePath +
" does not contains valid camera dimensions",
"CameraParameters::readFromXML", __FILE__, __LINE__);
172 if (MCamera.type() != CV_32FC1)
173 MCamera.convertTo(CameraMatrix, CV_32FC1);
175 CameraMatrix = MCamera;
177 if (MDist.total() < 4)
178 throw cv::Exception(9007,
"File :" + filePath +
" does not contains valid distortion_coefficients",
"CameraParameters::readFromXML", __FILE__,
182 MDist.convertTo(mdist32, CV_32FC1);
187 Distorsion.create(1, 5, CV_32FC1);
188 for (
int i = 0; i < 5; i++)
189 Distorsion.ptr<
float >(0)[i] = mdist32.ptr<
float >(0)[i];
196 void CameraParameters::glGetProjectionMatrix(cv::Size orgImgSize, cv::Size size,
double proj_matrix[16],
double gnear,
double gfar,
197 bool invert)
throw(cv::Exception) {
199 if (cv::countNonZero(Distorsion) != 0)
200 std::cerr <<
"CameraParameters::glGetProjectionMatrix :: The camera has distortion coefficients " << __FILE__ <<
" " << __LINE__ << endl;
201 if (isValid() ==
false)
202 throw cv::Exception(9100,
"invalid camera parameters",
"CameraParameters::glGetProjectionMatrix", __FILE__, __LINE__);
205 double Ax = double(size.width) / double(orgImgSize.width);
206 double Ay = double(size.height) / double(orgImgSize.height);
207 double _fx = CameraMatrix.at<
float >(0, 0) * Ax;
208 double _cx = CameraMatrix.at<
float >(0, 2) * Ax;
209 double _fy = CameraMatrix.at<
float >(1, 1) * Ay;
210 double _cy = CameraMatrix.at<
float >(1, 2) * Ay;
211 double cparam[3][4] = {{_fx, 0, _cx, 0}, {0, _fy, _cy, 0}, {0, 0, 1, 0}};
213 argConvGLcpara2(cparam, size.width, size.height, gnear, gfar, proj_matrix, invert);
220 double CameraParameters::norm(
double a,
double b,
double c) {
return (
sqrt(a * a + b * b + c * c)); }
227 double CameraParameters::dot(
double a1,
double a2,
double a3,
double b1,
double b2,
double b3) {
return (a1 * b1 + a2 * b2 + a3 * b3); }
234 void CameraParameters::argConvGLcpara2(
double cparam[3][4],
int width,
int height,
double gnear,
double gfar,
double m[16],
bool invert)
throw(cv::Exception) {
238 double p[3][3], q[4][4];
241 cparam[0][2] *= -1.0;
242 cparam[1][2] *= -1.0;
243 cparam[2][2] *= -1.0;
245 if (arParamDecompMat(cparam, icpara, trans) < 0)
246 throw cv::Exception(9002,
"parameter error",
"MarkerDetector::argConvGLcpara2", __FILE__, __LINE__);
248 for (i = 0; i < 3; i++) {
249 for (j = 0; j < 3; j++) {
250 p[i][j] = icpara[i][j] / icpara[2][2];
253 q[0][0] = (2.0 * p[0][0] / width);
254 q[0][1] = (2.0 * p[0][1] / width);
255 q[0][2] = ((2.0 * p[0][2] / width) - 1.0);
259 q[1][1] = (2.0 * p[1][1] / height);
260 q[1][2] = ((2.0 * p[1][2] / height) - 1.0);
265 q[2][2] = (gfar + gnear) / (gfar - gnear);
266 q[2][3] = -2.0 * gfar * gnear / (gfar - gnear);
273 for (i = 0; i < 4; i++) {
274 for (j = 0; j < 3; j++) {
275 m[i + j * 4] = q[i][0] * trans[0][j] + q[i][1] * trans[1][j] + q[i][2] * trans[2][j];
277 m[i + 3 * 4] = q[i][0] * trans[0][3] + q[i][1] * trans[1][3] + q[i][2] * trans[2][3] + q[i][3];
292 int CameraParameters::arParamDecompMat(
double source[3][4],
double cpara[3][4],
double trans[3][4])
throw(cv::Exception) {
295 double rem1, rem2, rem3;
297 if (source[2][3] >= 0) {
298 for (r = 0; r < 3; r++) {
299 for (c = 0; c < 4; c++) {
300 Cpara[r][c] = source[r][c];
304 for (r = 0; r < 3; r++) {
305 for (c = 0; c < 4; c++) {
306 Cpara[r][c] = -(source[r][c]);
311 for (r = 0; r < 3; r++) {
312 for (c = 0; c < 4; c++) {
316 cpara[2][2] = norm(Cpara[2][0], Cpara[2][1], Cpara[2][2]);
317 trans[2][0] = Cpara[2][0] / cpara[2][2];
318 trans[2][1] = Cpara[2][1] / cpara[2][2];
319 trans[2][2] = Cpara[2][2] / cpara[2][2];
320 trans[2][3] = Cpara[2][3] / cpara[2][2];
322 cpara[1][2] =
dot(trans[2][0], trans[2][1], trans[2][2], Cpara[1][0], Cpara[1][1], Cpara[1][2]);
323 rem1 = Cpara[1][0] - cpara[1][2] * trans[2][0];
324 rem2 = Cpara[1][1] - cpara[1][2] * trans[2][1];
325 rem3 = Cpara[1][2] - cpara[1][2] * trans[2][2];
326 cpara[1][1] = norm(rem1, rem2, rem3);
327 trans[1][0] = rem1 / cpara[1][1];
328 trans[1][1] = rem2 / cpara[1][1];
329 trans[1][2] = rem3 / cpara[1][1];
331 cpara[0][2] =
dot(trans[2][0], trans[2][1], trans[2][2], Cpara[0][0], Cpara[0][1], Cpara[0][2]);
332 cpara[0][1] =
dot(trans[1][0], trans[1][1], trans[1][2], Cpara[0][0], Cpara[0][1], Cpara[0][2]);
333 rem1 = Cpara[0][0] - cpara[0][1] * trans[1][0] - cpara[0][2] * trans[2][0];
334 rem2 = Cpara[0][1] - cpara[0][1] * trans[1][1] - cpara[0][2] * trans[2][1];
335 rem3 = Cpara[0][2] - cpara[0][1] * trans[1][2] - cpara[0][2] * trans[2][2];
336 cpara[0][0] = norm(rem1, rem2, rem3);
337 trans[0][0] = rem1 / cpara[0][0];
338 trans[0][1] = rem2 / cpara[0][0];
339 trans[0][2] = rem3 / cpara[0][0];
341 trans[1][3] = (Cpara[1][3] - cpara[1][2] * trans[2][3]) / cpara[1][1];
342 trans[0][3] = (Cpara[0][3] - cpara[0][1] * trans[1][3] - cpara[0][2] * trans[2][3]) / cpara[0][0];
344 for (r = 0; r < 3; r++) {
345 for (c = 0; c < 3; c++) {
346 cpara[r][c] /= cpara[2][2];
357 void CameraParameters::OgreGetProjectionMatrix(cv::Size orgImgSize, cv::Size size,
double proj_matrix[16],
double gnear,
double gfar,
358 bool invert)
throw(cv::Exception) {
359 double temp_matrix[16];
360 (*this).glGetProjectionMatrix(orgImgSize, size, temp_matrix, gnear, gfar, invert);
361 proj_matrix[0] = -temp_matrix[0];
362 proj_matrix[1] = -temp_matrix[4];
363 proj_matrix[2] = -temp_matrix[8];
364 proj_matrix[3] = temp_matrix[12];
366 proj_matrix[4] = -temp_matrix[1];
367 proj_matrix[5] = -temp_matrix[5];
368 proj_matrix[6] = -temp_matrix[9];
369 proj_matrix[7] = temp_matrix[13];
371 proj_matrix[8] = -temp_matrix[2];
372 proj_matrix[9] = -temp_matrix[6];
373 proj_matrix[10] = -temp_matrix[10];
374 proj_matrix[11] = temp_matrix[14];
376 proj_matrix[12] = -temp_matrix[3];
377 proj_matrix[13] = -temp_matrix[7];
378 proj_matrix[14] = -temp_matrix[11];
379 proj_matrix[15] = temp_matrix[15];
390 if (R.type() == CV_64F) {
391 assert(T.type() == CV_64F);
392 cv::Mat Matrix = cv::Mat::eye(4, 4, CV_64FC1);
394 cv::Mat R33 = cv::Mat(Matrix, cv::Rect(0, 0, 3, 3));
395 if (R.total() == 3) {
396 cv::Rodrigues(R, R33);
397 }
else if (R.total() == 9) {
399 R.convertTo(R64, CV_64F);
402 for (
int i = 0; i < 3; i++)
403 Matrix.at<
double >(i, 3) = T.ptr<
double >(0)[i];
405 }
else if (R.depth() == CV_32F) {
406 cv::Mat Matrix = cv::Mat::eye(4, 4, CV_32FC1);
407 cv::Mat R33 = cv::Mat(Matrix, cv::Rect(0, 0, 3, 3));
408 if (R.total() == 3) {
409 cv::Rodrigues(R, R33);
410 }
else if (R.total() == 9) {
412 R.convertTo(R32, CV_32F);
416 for (
int i = 0; i < 3; i++)
417 Matrix.at<
float >(i, 3) = T.ptr<
float >(0)[i];
425 M.convertTo(MTyped, forceType);
cv::Mat getRTMatrix(const cv::Mat &R_, const cv::Mat &T_, int forceType)
Parameters of the camera.
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
const CwiseUnaryOp< internal::scalar_sqrt_op< Scalar >, const Derived > sqrt() const