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
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046 #include <new>
00047
00048 #include "ExtrinsicParameterCalculatorCV.h"
00049 #include "Image/PrimitivesDrawerCV.h"
00050 #include "Image/PrimitivesDrawer.h"
00051 #include "Image/ImageProcessor.h"
00052 #include "Image/IplImageAdaptor.h"
00053 #include "Image/ByteImage.h"
00054 #include "Calibration/Calibration.h"
00055 #include "Math/Math3d.h"
00056 #include "Math/Math2d.h"
00057 #include "Helpers/helpers.h"
00058
00059 #include <stdio.h>
00060 #include <opencv2/legacy/compat.hpp>
00061
00062
00063
00064
00065
00066
00067 bool ExtrinsicParameterCalculatorCV::GetPointsAndTranslationAndRotation(const CCalibration *pCalibration,
00068 const CByteImage *pImage, int nColumns, int nRows, float fSquareSize,
00069 Vec2d *pPoints, Mat3d &rotation, Vec3d &translation)
00070 {
00071 CByteImage gray_image(pImage->width, pImage->height, CByteImage::eGrayScale);
00072 CByteImage temp_image(&gray_image);
00073
00074 ImageProcessor::ConvertImage(pImage, &gray_image);
00075
00076 IplImage *pIplImage = IplImageAdaptor::Adapt(&gray_image);
00077 IplImage *pIplTempImage = IplImageAdaptor::Adapt(&temp_image);
00078 CvMemStorage *pStorage = cvCreateMemStorage();
00079
00080 CvPoint2D32f *pIplPoints = new CvPoint2D32f[nColumns * nRows];
00081
00082 int nPoints = 0;
00083
00084 if (cvFindChessBoardCornerGuesses(pIplImage, pIplTempImage, pStorage,
00085 cvSize(nColumns - 1, nRows - 1), pIplPoints, &nPoints) == 0 ||
00086 nPoints != (nRows - 1) * (nColumns - 1))
00087 {
00088
00089 cvReleaseImageHeader(&pIplImage);
00090 cvReleaseImageHeader(&pIplTempImage);
00091 cvReleaseMemStorage(&pStorage);
00092 delete [] pIplPoints;
00093 return false;
00094 }
00095
00096 cvFindCornerSubPix(pIplImage, pIplPoints, nPoints,
00097 cvSize(5, 5), cvSize(-1, -1),
00098 cvTermCriteria(CV_TERMCRIT_ITER |CV_TERMCRIT_EPS, 10, 0.1));
00099
00100 const CCalibration::CCameraParameters &cameraParameters = pCalibration->GetCameraParameters();
00101
00102 float distortion[] = { (float) cameraParameters.distortion[0], (float) cameraParameters.distortion[1], (float) cameraParameters.distortion[2], (float) cameraParameters.distortion[3] };
00103 float focalLength[] = { (float) cameraParameters.focalLength.x, (float) cameraParameters.focalLength.y };
00104 CvPoint2D32f principalPoint;
00105 float rotationVector[3];
00106 float translationVector[3];
00107
00108 principalPoint.x = (float) cameraParameters.principalPoint.x;
00109 principalPoint.y = (float) cameraParameters.principalPoint.y;
00110
00111 CvPoint3D32f *pIplObjectPoints = (CvPoint3D32f *) malloc(nPoints * sizeof(CvPoint3D32f));
00112
00113 int i = 0;
00114 for (int y = 0; y < nRows - 1; y++)
00115 for (int x = 0; x < nColumns - 1; x++, i++)
00116 {
00117 pIplObjectPoints[i].x = fSquareSize * x;
00118 pIplObjectPoints[i].y = fSquareSize * y;
00119 pIplObjectPoints[i].z = 0;
00120 }
00121
00122 cvFindExtrinsicCameraParams(nPoints,
00123 cvSize(pImage->width, pImage->height),
00124 pIplPoints,
00125 pIplObjectPoints,
00126 focalLength,
00127 principalPoint,
00128 distortion,
00129 rotationVector,
00130 translationVector);
00131
00132 float rotationMatrix[9];
00133
00134 CvMat rmat = cvMat(3, 3, CV_32FC1, rotationMatrix);
00135 CvMat rvec = cvMat(3, 1, CV_32FC1, rotationVector);
00136 cvRodrigues(&rmat, &rvec, 0, CV_RODRIGUES_V2M);
00137
00138
00139
00140
00141 Math3d::SetVec(translation, translationVector[0], translationVector[1], translationVector[2]);
00142
00143
00144 rotation.r1 = rotationMatrix[0];
00145 rotation.r2 = rotationMatrix[1];
00146 rotation.r3 = rotationMatrix[2];
00147 rotation.r4 = rotationMatrix[3];
00148 rotation.r5 = rotationMatrix[4];
00149 rotation.r6 = rotationMatrix[5];
00150 rotation.r7 = rotationMatrix[6];
00151 rotation.r8 = rotationMatrix[7];
00152 rotation.r9 = rotationMatrix[8];
00153
00154
00155 for (i = 0; i < nPoints; i++)
00156 Math2d::SetVec(pPoints[i], pIplPoints[i].x, pIplPoints[i].y);
00157
00158
00159 cvReleaseImageHeader(&pIplImage);
00160 cvReleaseImageHeader(&pIplTempImage);
00161 cvReleaseMemStorage(&pStorage);
00162 free(pIplObjectPoints);
00163 delete [] pIplPoints;
00164
00165 return true;
00166 }
00167
00168
00169 void ExtrinsicParameterCalculatorCV::DrawExtrinsic(CByteImage *pResultImage, const CCalibration *pCalibration, const Vec2d *pPoints, int nPoints, float fSquareSize)
00170 {
00171 Vec3d worldPoint0 = { 0, 0, 0 };
00172 Vec3d worldPointX = { 2 * fSquareSize, 0, 0 };
00173 Vec3d worldPointY = { 0, 2 * fSquareSize, 0 };
00174 Vec2d imagePoint0, imagePointX, imagePointY;
00175 pCalibration->WorldToImageCoordinates(worldPoint0, imagePoint0);
00176 pCalibration->WorldToImageCoordinates(worldPointX, imagePointX);
00177 pCalibration->WorldToImageCoordinates(worldPointY, imagePointY);
00178
00179 PrimitivesDrawer::DrawLine(pResultImage, imagePoint0, imagePointX, 0, 0, 0, 2);
00180 PrimitivesDrawer::DrawLine(pResultImage, imagePoint0, imagePointY, 0, 0, 0, 2);
00181 PrimitivesDrawer::DrawCircle(pResultImage, imagePoint0, 5, 0, 0, 0, -1);
00182 PrimitivesDrawerCV::PutText(pResultImage, "x", imagePointX.x, imagePointX.y, 0.75, 0.75, 0, 0, 0, 2);
00183 PrimitivesDrawerCV::PutText(pResultImage, "y", imagePointY.x, imagePointY.y, 0.75, 0.75, 0, 0, 0, 2);
00184
00185 if (pPoints && nPoints > 0)
00186 {
00187 Vec2d last_point;
00188 Math2d::SetVec(last_point, pPoints[0]);
00189
00190 for (int i = 0; i < nPoints; i++)
00191 {
00192 int r, g, b;
00193 hsv2rgb(int(float(i) / (nPoints - 1) * 240), 255, 255, r, g, b);
00194 PrimitivesDrawer::DrawCircle(pResultImage, pPoints[i], 3, r, g, b, -1);
00195 PrimitivesDrawer::DrawLine(pResultImage, last_point, pPoints[i], r, g, b, 1);
00196 Math2d::SetVec(last_point, pPoints[i]);
00197 }
00198 }
00199 }