$search
00001 00007 #ifndef P_HOMOGRAPHY_HH 00008 #define P_HOMOGRAPHY_HH 00009 00010 #include <iostream> 00011 #include <float.h> 00012 #include <opencv/cv.h> 00013 #include <opencv/cxcore.h> 00014 #include <blort/Recognizer3D/Vector2.hh> 00015 #include <blort/Recognizer3D/Array.hh> 00016 #include <blort/Recognizer3D/PNamespace.hh> 00017 #include <blort/Recognizer3D/Except.hh> 00018 #include <blort/Recognizer3D/homest.h> 00019 #include <blort/Recognizer3D/Math.hh> 00020 #include <blort/Recognizer3D/SMatrix.hh> 00021 #include <blort/Recognizer3D/PoseCv.hh> 00022 00023 namespace P 00024 { 00025 00026 class Homography 00027 { 00028 private: 00029 Array<Vector2> pts1, pts2; 00030 Array<Vector2> lns1, lns2; 00031 00032 unsigned lastPt; //pointer to the last point 00033 unsigned lastLn; //pointer to the last line 00034 00035 double *T1, *invT; 00036 00037 void NormalizePts(Array<Vector2> &in, unsigned numPts, Array<Vector2> &out, double T[9]); 00038 void NormalizeLns(double T[9], Array<Vector2> &in, unsigned numLns, Array<Vector2> &out); 00039 void SetDataMatrixPts(Array<Vector2> &pts1, Array<Vector2> &pts2, unsigned numPts, unsigned start, CvMat *A); 00040 void SetDataMatrixLns(Array<Vector2> &lns1, Array<Vector2> &lns2, unsigned numLns, unsigned start, CvMat *A); 00041 void NormalizeH(double H[9], double T1[9], double T2[9], double nH[9]); 00042 void DenormalizeH(double nH[9], double T1[9], double T2[9], double H[9]); 00043 void GetRandIdx(unsigned size, unsigned num, P::Array<unsigned> &idx); 00044 bool SolveHomography(CvMat *A, CvMat *W, CvMat *Ut, CvMat *Vt, double H[9]); 00045 void CountInlierPts(double H[9], double thr, int &inl); 00046 void CountInlierLns(double H[9], double thr, double thrAngle, int &inl); 00047 void SetDataMatrix(double *d, double H[9], double thr, double thrAngle, int &numInl); 00048 00049 00050 inline void InsertPointCoeff(Vector2 &pt1, Vector2 &pt2, double *d); 00051 inline void InsertLineCoeff(Vector2 &ln1, Vector2 &ln2, double *d); 00052 00053 00054 00055 public: 00056 Array<int> outl; 00057 Array<int> outlLns; 00058 00059 Homography(); 00060 Homography(unsigned nbPoints, unsigned nbLines=0); 00061 ~Homography(); 00062 00063 bool EstimateHom(double H[9], int &nbOutliers, double inlPcent=.8, bool returnOutl=false, int normalize=1, int NLrefine=HOMEST_SYM_XFER_ERROR, int verbose=1); 00064 bool EstimateAff(double H[9], int &nbOutliers, double inlPcent=.8, bool returnOutl=false, int normalize=1, int verbose=1); 00065 00066 bool ComputeHomLS(double H[9], bool normalize=true); 00067 bool ComputeHomRobustLS(double H[9], bool normalize=true, double thrInlier=1., double thrAngle=1.); 00068 bool ComputeHom(double a1[2], double a2[2], double a3[2], double a4[2], 00069 double b1[2], double b2[2], double b3[2], double b4[2], 00070 double H[9]); 00071 bool ComputeAff(double a1[2], double a2[2], double a3[2], 00072 double b1[2], double b2[2], double b3[2], 00073 double H[9]); 00074 00075 inline void InsertNext(double pt1[2], double pt2[2]); 00076 inline void InsertNextPt(double pt1[2], double pt2[2]); 00077 inline void InsertNextLn(double ln1[2], double ln2[2]); 00078 inline void InsertNextLn(double a1[2], double b1[2], double a2[2], double b2[2]); 00079 inline void SetFirst(); 00080 inline void Resize(unsigned nbPoints, unsigned nbLines=0); 00081 00082 inline void LinePts2Para(double p1[2], double p2[2], double l[3]); 00083 }; 00084 00085 00086 inline void MapPoint(double xin, double yin, double H[9], double &xout, double &yout); 00087 inline void MapPoint(double in[2], double H[9], double out[2]); 00088 inline void GetPosScaleAngle( double x, double y, double H[9], double &xr, double &yr, double &scale, double &angle); 00089 00090 00091 00092 00093 00094 /****************************** INLINE METHODES *********************************/ 00098 inline void Homography::InsertPointCoeff(Vector2 &pt1, Vector2 &pt2, double *d) 00099 { 00100 double t1, t2, t3, t4; 00101 00102 t1 = pt1.x; 00103 t2 = pt1.y; 00104 t3 = pt2.x; 00105 t4 = pt2.y; 00106 00107 d[0] = -t1; 00108 d[1] = -t2; 00109 d[2] = -1.0; 00110 d[3] = 0.0; 00111 d[4] = 0.0; 00112 d[5] = 0.0; 00113 d[6] = t3*t1; 00114 d[7] = t2*t3; 00115 d[8] = t3; 00116 d[9] = 0.0; 00117 d[10] = 0.0; 00118 d[11] = 0.0; 00119 d[12] = d[0]; 00120 d[13] = d[1]; 00121 d[14] = -1.0; 00122 d[15] = t4*t1; 00123 d[16] = t4*t2; 00124 d[17] = t4; 00125 } 00126 00130 inline void Homography::InsertLineCoeff(Vector2 &ln1, Vector2 &ln2, double *d) 00131 { 00132 double t1, t2, t3, t4; 00133 00134 t1 = ln1.x; //x 00135 t2 = ln1.y; //y 00136 t3 = ln2.x; //u 00137 t4 = ln2.y; //v 00138 00139 d[0] = -t3; 00140 d[1] = 0.; 00141 d[2] = t3*t1; 00142 d[3] = -t4; 00143 d[4] = 0.; 00144 d[5] = t4*t1; 00145 d[6] = -1; 00146 d[7] = 0.; 00147 d[8] = t1; 00148 d[9] = 0.; 00149 d[10] = -t3; 00150 d[11] = t3*t2; 00151 d[12] = 0.; 00152 d[13] = -t4; 00153 d[14] = t4*t2; 00154 d[15] = 0.; 00155 d[16] = -1; 00156 d[17] = t2; 00157 } 00158 00162 inline void Homography::Resize(unsigned nbPoints, unsigned nbLines) 00163 { 00164 if (nbPoints>0) 00165 { 00166 pts1.Resize(nbPoints); 00167 pts2.Resize(nbPoints); 00168 } 00169 if (nbLines>0) 00170 { 00171 lns1.Resize(nbLines); 00172 lns2.Resize(nbLines); 00173 } 00174 lastPt=0; 00175 lastLn=0; 00176 } 00177 00181 inline void Homography::SetFirst() 00182 { 00183 lastPt = 0; 00184 lastLn = 0; 00185 } 00186 00190 inline void Homography::InsertNext(double pt1[2], double pt2[2]) 00191 { 00192 if (lastPt<pts1.Size()) 00193 { 00194 pts1[lastPt].x = pt1[0]; 00195 pts1[lastPt].y = pt1[1]; 00196 pts2[lastPt].x = pt2[0]; 00197 pts2[lastPt].y = pt2[1]; 00198 lastPt++; 00199 } 00200 else //fall back solution if anyone did not allocate 00201 { 00202 pts1.PushBack(Vector2(pt1[0],pt1[1])); 00203 pts2.PushBack(Vector2(pt2[0],pt2[1])); 00204 lastPt++; 00205 } 00206 } 00207 00211 inline void Homography::InsertNextPt(double pt1[2], double pt2[2]) 00212 { 00213 if (lastPt<pts1.Size()) 00214 { 00215 pts1[lastPt].x = pt1[0]; 00216 pts1[lastPt].y = pt1[1]; 00217 pts2[lastPt].x = pt2[0]; 00218 pts2[lastPt].y = pt2[1]; 00219 lastPt++; 00220 } 00221 else //fall back solution if anyone did not allocate 00222 { 00223 pts1.PushBack(Vector2(pt1[0],pt1[1])); 00224 pts2.PushBack(Vector2(pt2[0],pt2[1])); 00225 lastPt++; 00226 } 00227 } 00228 00237 inline void Homography::InsertNextLn(double ln1[2], double ln2[2]) 00238 { 00239 if (lastLn<lns1.Size()) 00240 { 00241 lns1[lastLn].x = ln1[0]; 00242 lns1[lastLn].y = ln1[1]; 00243 lns2[lastLn].x = ln2[0]; 00244 lns2[lastLn].y = ln2[1]; 00245 lastLn++; 00246 } 00247 else //fall back solution if anyone did not allocate 00248 { 00249 lns1.PushBack(Vector2(ln1[0],ln1[1])); 00250 lns2.PushBack(Vector2(ln2[0],ln2[1])); 00251 lastLn++; 00252 } 00253 } 00254 00258 inline void Homography::InsertNextLn(double a1[2], double b1[2], double a2[2], double b2[2]) 00259 { 00260 double l[3]; 00261 00262 00263 if (lastLn<lns1.Size()) 00264 { 00265 LinePts2Para(a1,b1,l); 00266 lns1[lastLn].x = l[0]/l[2]; 00267 lns1[lastLn].y = l[1]/l[2]; 00268 LinePts2Para(a2,b2,l); 00269 lns2[lastLn].x = l[0]/l[2]; 00270 lns2[lastLn].y = l[1]/l[2]; 00271 lastLn++; 00272 } 00273 else //fall back solution if anyone did not allocate 00274 { 00275 LinePts2Para(a1,b1,l); 00276 lns1.PushBack(Vector2(l[0]/l[2],l[1]/l[2])); 00277 LinePts2Para(a2,b2,l); 00278 lns2.PushBack(Vector2(l[0]/l[2],l[1]/l[2])); 00279 lastLn++; 00280 } 00281 } 00282 00286 inline void Homography::LinePts2Para(double p1[2], double p2[2], double l[3]) 00287 { 00288 l[0] = p1[1]-p2[1]; 00289 l[1] = p2[0]-p1[0]; 00290 l[2] = p1[0]*p2[1] - p1[1]*p2[0]; 00291 } 00292 00297 inline void MapPoint(double xin, double yin, double H[9], double &xout, double &yout) 00298 { 00299 xout = H[0]*xin + H[1]*yin + H[2]; 00300 yout = H[3]*xin + H[4]*yin + H[5]; 00301 double t = H[6]*xin + H[7]*yin + H[8]; 00302 xout /= t; 00303 yout /= t; 00304 } 00305 00310 inline void MapPoint(double in[2], double H[9], double out[2]) 00311 { 00312 out[0] = H[0]*in[0] + H[1]*in[1] + H[2]; 00313 out[1] = H[3]*in[0] + H[4]*in[1] + H[5]; 00314 double t = H[6]*in[0] + H[7]*in[1] + H[8]; 00315 out[0] /= t; 00316 out[1] /= t; 00317 } 00318 00322 inline void GetPosScaleAngle( double x, double y, double H[9], double &xr, double &yr, double &scale, double &angle) 00323 { 00324 double x2=x+10.; 00325 double y2=y; 00326 double x2H,y2H; 00327 MapPoint(x,y,H,xr,yr); 00328 MapPoint(x2,y2,H,x2H,y2H); 00329 00330 double dxH=x2H-xr; 00331 double dyH=y2H-yr; 00332 scale=((sqrt(dxH*dxH+dyH*dyH))/10.); 00333 angle=atan2(dyH,dxH); 00334 } 00335 00336 00337 00338 } 00339 00340 #endif 00341