From 68e59d6154c6f60cbcb41358b29e42c03d184961 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Mon, 17 Nov 2014 15:02:18 -0500 Subject: [PATCH 01/39] [RHO] Initial commit of RHO algorithm for rapid homography estimation. Implements the RHO algorithm as presented in Paper: Bilaniuk, Olexa, Hamid Bazargani, and Robert Laganiere. "Fast Target Recognition on Mobile Devices: Revisiting Gaussian Elimination for the Estimation of Planar Homographies." In Computer Vision and Pattern Recognition Workshops (CVPRW), 2014 IEEE Conference on, pp. 119-125. IEEE, 2014. - Complete, heavily documented reference C implementation, as well as temporarily disabled dirty SSE2 port. - Enabled tests for RHO in test_homography; Currently these fail presumably due to too-stringent accuracy requirements. - Refinement and final refinement are not yet functional; Do not pass their corresponding flags to RHO. --- modules/calib3d/include/opencv2/calib3d.hpp | 3 +- modules/calib3d/src/fundam.cpp | 77 +- modules/calib3d/src/rhorefc.cpp | 2042 +++++++++++++++++++ modules/calib3d/src/rhorefc.h | 368 ++++ modules/calib3d/src/rhosse2.cpp | 1497 ++++++++++++++ modules/calib3d/src/rhosse2.h | 331 +++ modules/calib3d/test/test_homography.cpp | 26 +- 7 files changed, 4329 insertions(+), 15 deletions(-) create mode 100644 modules/calib3d/src/rhorefc.cpp create mode 100644 modules/calib3d/src/rhorefc.h create mode 100644 modules/calib3d/src/rhosse2.cpp create mode 100644 modules/calib3d/src/rhosse2.h diff --git a/modules/calib3d/include/opencv2/calib3d.hpp b/modules/calib3d/include/opencv2/calib3d.hpp index 4f405afc6..397b87a0e 100644 --- a/modules/calib3d/include/opencv2/calib3d.hpp +++ b/modules/calib3d/include/opencv2/calib3d.hpp @@ -53,7 +53,8 @@ namespace cv //! type of the robust estimation algorithm enum { LMEDS = 4, //!< least-median algorithm - RANSAC = 8 //!< RANSAC algorithm + RANSAC = 8, //!< RANSAC algorithm + RHO = 16 //!< RHO algorithm }; enum { SOLVEPNP_ITERATIVE = 0, diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index c700ece70..07cf68a0f 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -41,6 +41,10 @@ //M*/ #include "precomp.hpp" +#include "rhorefc.h" +#if CV_SSE2 +#include "rhosse2.h" +#endif #include namespace cv @@ -273,6 +277,73 @@ public: } + +namespace cv{ +static bool createAndRunRHORegistrator(double confidence, int maxIters, double ransacReprojThreshold, int npoints, InputArray _src, InputArray _dst, OutputArray _H, OutputArray _tempMask){ + Mat src = _src.getMat(); + Mat dst = _dst.getMat(); + Mat tempMask = _tempMask.getMat(); + bool result; + + /* Run RHO. Needs cleanup or separate function to invoke. */ + Mat tmpH = Mat(3, 3, CV_32FC1); + tempMask = Mat(npoints, 1, CV_8U); + double beta = 0.35;/* 0.35 is a value that often works. */ + +#if CV_SSE2 && 0 + if(useOptimized()){ + RHO_HEST_SSE2 p; + rhoSSE2Init(&p); + rhoSSE2EnsureCapacity(&p, npoints, beta); + result = !!rhoSSE2(&p, + (const float*)src.data, + (const float*)dst.data, + (char*) tempMask.data, + npoints, + ransacReprojThreshold, + maxIters, + maxIters, + confidence, + 4, + beta, + RHO_FLAG_ENABLE_NR, + NULL, + (float*)tmpH.data); + rhoSSE2Fini(&p); + }else +#endif + { + RHO_HEST_REFC p; + rhoRefCInit(&p); + rhoRefCEnsureCapacity(&p, npoints, beta); + result = !!rhoRefC(&p, + (const float*)src.data, + (const float*)dst.data, + (char*) tempMask.data, + npoints, + ransacReprojThreshold, + maxIters, + maxIters, + confidence, + 4, + beta, + RHO_FLAG_ENABLE_NR, + NULL, + (float*)tmpH.data); + rhoRefCFini(&p); + } + tmpH.convertTo(_H, CV_64FC1); + + /* Maps non-zero maks elems to 1, for the sake of the testcase. */ + for(int k=0;krun(src, dst, H, tempMask); else if( method == LMEDS ) result = createLMeDSPointSetRegistrator(cb, 4, confidence, maxIters)->run(src, dst, H, tempMask); - else + else if( method == RHO ){ + result = createAndRunRHORegistrator(confidence, maxIters, ransacReprojThreshold, npoints, src, dst, H, tempMask); + }else CV_Error(Error::StsBadArg, "Unknown estimation method"); - if( result && npoints > 4 ) + if( result && npoints > 4 && method != RHO) { compressPoints( src.ptr(), tempMask.ptr(), 1, npoints ); npoints = compressPoints( dst.ptr(), tempMask.ptr(), 1, npoints ); diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp new file mode 100644 index 000000000..cda70f416 --- /dev/null +++ b/modules/calib3d/src/rhorefc.cpp @@ -0,0 +1,2042 @@ +/* + IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. + + By downloading, copying, installing or using the software you agree to this license. + If you do not agree to this license, do not download, install, + copy or use the software. + + + BSD 3-Clause License + + Copyright (C) 2014, Olexa Bilaniuk, Hamid Bazargani & Robert Laganiere, all rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistribution's of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + * Redistribution's in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * The name of the copyright holders may not be used to endorse or promote products + derived from this software without specific prior written permission. + + This software is provided by the copyright holders and contributors "as is" and + any express or implied warranties, including, but not limited to, the implied + warranties of merchantability and fitness for a particular purpose are disclaimed. + In no event shall the Intel Corporation or contributors be liable for any direct, + indirect, incidental, special, exemplary, or consequential damages + (including, but not limited to, procurement of substitute goods or services; + loss of use, data, or profits; or business interruption) however caused + and on any theory of liability, whether in contract, strict liability, + or tort (including negligence or otherwise) arising in any way out of + the use of this software, even if advised of the possibility of such damage. +*/ + +/** + * Bilaniuk, Olexa, Hamid Bazargani, and Robert Laganiere. "Fast Target + * Recognition on Mobile Devices: Revisiting Gaussian Elimination for the + * Estimation of Planar Homographies." In Computer Vision and Pattern + * Recognition Workshops (CVPRW), 2014 IEEE Conference on, pp. 119-125. + * IEEE, 2014. + */ + +/* Includes */ +#include +#include +#include +#include +#include +#include +#include +#include +#include "rhorefc.h" + + + +/* Defines */ +#define MEM_ALIGN 32 +#define HSIZE (3*3*sizeof(float)) +#define MIN_DELTA_CHNG 0.1 +#define REL_CHNG(a, b) (fabs((a) - (b))/(a)) +#define CHNG_SIGNIFICANT(a, b) (REL_CHNG(a, b) > MIN_DELTA_CHNG) +#define CHI_STAT 2.706 +#define CHI_SQ 1.645 +#define RLO 0.25 +#define RHI 0.75 +#define MAXLEVMARQITERS 10 +#define m 4 /* 4 points required per model */ +#define SPRT_T_M 25 /* Guessing 25 match evlauations / 1 model generation */ +#define SPRT_M_S 1 /* 1 model per sample */ +#define SPRT_EPSILON 0.1 /* No explanation */ +#define SPRT_DELTA 0.01 /* No explanation */ + + + +/* For the sake of cv:: namespace ONLY: */ +#ifdef __cplusplus +namespace cv{/* For C support, replace with extern "C" { */ +#endif + + +/* Data Structures */ + + + +/* Prototypes */ +static inline void* almalloc(size_t nBytes); +static inline void alfree(void* ptr); + +static inline int sacInitRun(RHO_HEST_REFC* p); +static inline void sacFiniRun(RHO_HEST_REFC* p); +static inline int sacHaveExtrinsicGuess(RHO_HEST_REFC* p); +static inline int sacHypothesize(RHO_HEST_REFC* p); +static inline int sacVerify(RHO_HEST_REFC* p); +static inline int sacIsNREnabled(RHO_HEST_REFC* p); +static inline int sacIsRefineEnabled(RHO_HEST_REFC* p); +static inline int sacIsFinalRefineEnabled(RHO_HEST_REFC* p); +static inline int sacPROSACPhaseEndReached(RHO_HEST_REFC* p); +static inline void sacPROSACGoToNextPhase(RHO_HEST_REFC* p); +static inline void sacGetPROSACSample(RHO_HEST_REFC* p); +static inline int sacIsSampleDegenerate(RHO_HEST_REFC* p); +static inline void sacGenerateModel(RHO_HEST_REFC* p); +static inline int sacIsModelDegenerate(RHO_HEST_REFC* p); +static inline void sacEvaluateModelSPRT(RHO_HEST_REFC* p); +static inline void sacUpdateSPRT(RHO_HEST_REFC* p); +static inline void sacDesignSPRTTest(RHO_HEST_REFC* p); +static inline int sacIsBestModel(RHO_HEST_REFC* p); +static inline int sacIsBestModelGoodEnough(RHO_HEST_REFC* p); +static inline void sacSaveBestModel(RHO_HEST_REFC* p); +static inline void sacInitNonRand(double beta, + unsigned start, + unsigned N, + unsigned* nonRandMinInl); +static inline void sacNStarOptimize(RHO_HEST_REFC* p); +static inline void sacUpdateBounds(RHO_HEST_REFC* p); +static inline void sacOutputModel(RHO_HEST_REFC* p); +static inline void sacOutputZeroH(RHO_HEST_REFC* p); + +static inline double sacInitPEndFpI(const unsigned ransacConvg, + const unsigned n, + const unsigned s); +static inline void sacRndSmpl(unsigned sampleSize, + unsigned* currentSample, + unsigned dataSetSize); +static inline double sacRandom(void); +static inline unsigned sacCalcIterBound(double confidence, + double inlierRate, + unsigned sampleSize, + unsigned maxIterBound); +static inline void hFuncRefC(float* packedPoints, float* H); +static inline int sacCanRefine(RHO_HEST_REFC* p); +static inline void sacRefine(RHO_HEST_REFC* p); +static inline void sacCalcJtMats(float (* restrict JtJ)[8], + float* restrict Jte, + float* restrict Sp, + const float* restrict H, + const float* restrict src, + const float* restrict dst, + const char* restrict inl, + unsigned N); +static inline void sacChol8x8 (const float (*A)[8], + float (*L)[8]); +static inline void sacTRInv8x8(const float (*L)[8], + float (*M)[8]); +static inline void sacTRISolve8x8(const float (*L)[8], + const float* Jte, + float* dH); +static inline void sacScaleDiag8x8(const float (*A)[8], + float lambda, + float (*B)[8]); +static inline void sacSub8x1(float* Hout, const float* H, const float* dH); + + + +/* Functions */ + +/** + * Initialize the estimator context, by allocating the aligned buffers + * internally needed. + * + * Currently there are 5 per-estimator buffers: + * - The buffer of m indexes representing a sample + * - The buffer of 16 floats representing m matches (x,y) -> (X,Y). + * - The buffer for the current homography + * - The buffer for the best-so-far homography + * - Optionally, the non-randomness criterion table + * + * @param [in/out] p The uninitialized estimator context to initialize. + * @return 0 if successful; non-zero if an error occured. + */ + +int rhoRefCInit(RHO_HEST_REFC* p){ + memset(p, 0, sizeof(*p)); + + p->ctrl.smpl = (unsigned*)almalloc(m*sizeof(*p->ctrl.smpl)); + + p->curr.pkdPts = (float*) almalloc(m*2*2*sizeof(*p->curr.pkdPts)); + p->curr.H = (float*) almalloc(HSIZE); + p->curr.inl = NULL; + p->curr.numInl = 0; + + p->best.H = (float*) almalloc(HSIZE); + p->best.inl = NULL; + p->best.numInl = 0; + + p->nr.tbl = NULL;/* By default this table is not computed. */ + p->nr.size = 0; + p->nr.beta = 0.0; + + + int areAllAllocsSuccessful = p->ctrl.smpl && + p->curr.H && + p->best.H && + p->curr.pkdPts; + + if(!areAllAllocsSuccessful){ + rhoRefCFini(p); + } + + return areAllAllocsSuccessful; +} + + +/** + * Ensure that the estimator context's internal table for non-randomness + * criterion is at least of the given size, and uses the given beta. The table + * should be larger than the maximum number of matches fed into the estimator. + * + * A value of N of 0 requests deallocation of the table. + * + * @param [in] p The initialized estimator context + * @param [in] N If 0, deallocate internal table. If > 0, ensure that the + * internal table is of at least this size, reallocating if + * necessary. + * @param [in] beta The beta-factor to use within the table. + * @return 1 if successful; 0 if an error occured. + * + * Reads: nr.* + * Writes: nr.* + */ + +int rhoRefCEnsureCapacity(RHO_HEST_REFC* p, unsigned N, double beta){ + unsigned* tmp; + + + if(N == 0){ + /* Deallocate table */ + alfree(p->nr.tbl); + p->nr.tbl = NULL; + p->nr.size = 0; + }else{ + /* Ensure table at least as big as N and made for correct beta. */ + if(p->nr.tbl && p->nr.beta == beta && p->nr.size >= N){ + /* Table already correctly set up */ + }else{ + if(p->nr.size < N){ + /* Reallocate table because it is too small. */ + tmp = (unsigned*)almalloc(N*sizeof(unsigned)); + if(!tmp){ + return 0; + } + + /* Must recalculate in whole or part. */ + if(p->nr.beta != beta){ + /* Beta changed; recalculate in whole. */ + sacInitNonRand(beta, 0, N, tmp); + alfree(p->nr.tbl); + }else{ + /* Beta did not change; Copy over any work already done. */ + memcpy(tmp, p->nr.tbl, p->nr.size*sizeof(unsigned)); + sacInitNonRand(beta, p->nr.size, N, tmp); + alfree(p->nr.tbl); + } + + p->nr.tbl = tmp; + p->nr.size = N; + p->nr.beta = beta; + }else{ + /* Might recalculate in whole, or not at all. */ + if(p->nr.beta != beta){ + /* Beta changed; recalculate in whole. */ + sacInitNonRand(beta, 0, p->nr.size, p->nr.tbl); + p->nr.beta = beta; + }else{ + /* Beta did not change; Table was already big enough. Do nothing. */ + /* Besides, this is unreachable. */ + } + } + } + } + + return 1; +} + + +/** + * Finalize the estimator context, by freeing the aligned buffers used + * internally. + * + * @param [in] p The initialized estimator context to finalize. + */ + +void rhoRefCFini(RHO_HEST_REFC* p){ + alfree(p->ctrl.smpl); + alfree(p->curr.H); + alfree(p->best.H); + alfree(p->curr.pkdPts); + alfree(p->nr.tbl); + + memset(p, 0, sizeof(*p)); +} + + +/** + * Estimates the homography using the given context, matches and parameters to + * PROSAC. + * + * @param [in/out] p The context to use for homography estimation. Must + * be already initialized. Cannot be NULL. + * @param [in] src The pointer to the source points of the matches. + * Must be aligned to 4 bytes. Cannot be NULL. + * @param [in] dst The pointer to the destination points of the matches. + * Must be aligned to 16 bytes. Cannot be NULL. + * @param [out] inl The pointer to the output mask of inlier matches. + * Must be aligned to 16 bytes. May be NULL. + * @param [in] N The number of matches. + * @param [in] maxD The maximum distance. + * @param [in] maxI The maximum number of PROSAC iterations. + * @param [in] rConvg The RANSAC convergence parameter. + * @param [in] cfd The required confidence in the solution. + * @param [in] minInl The minimum required number of inliers. + * @param [in] beta The beta-parameter for the non-randomness criterion. + * @param [in] flags A union of flags to control the estimation. + * @param [in] guessH An extrinsic guess at the solution H, or NULL if + * none provided. + * @param [out] finalH The final estimation of H, or the zero matrix if + * the minimum number of inliers was not met. + * Cannot be NULL. + * @return The number of inliers if the minimum number of + * inliers for acceptance was reached; 0 otherwise. + */ + +unsigned rhoRefC(RHO_HEST_REFC* restrict p, /* Homography estimation context. */ + const float* restrict src, /* Source points */ + const float* restrict dst, /* Destination points */ + char* restrict inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* Works: 3.0 */ + unsigned maxI, /* Works: 2000 */ + unsigned rConvg, /* Works: 2000 */ + double cfd, /* Works: 0.995 */ + unsigned minInl, /* Minimum: 4 */ + double beta, /* Works: 0.35 */ + unsigned flags, /* Works: 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH){ /* Final result. */ + + /** + * Setup + */ + + p->arg.src = src; + p->arg.dst = dst; + p->arg.inl = inl; + p->arg.N = N; + p->arg.maxD = maxD; + p->arg.maxI = maxI; + p->arg.rConvg = rConvg; + p->arg.cfd = cfd; + p->arg.minInl = minInl; + p->arg.beta = beta; + p->arg.flags = flags; + p->arg.guessH = guessH; + p->arg.finalH = finalH; + if(!sacInitRun(p)){ + sacOutputZeroH(p); + sacFiniRun(p); + return 0; + } + + /** + * Extrinsic Guess + */ + + if(sacHaveExtrinsicGuess(p)){ + sacVerify(p); + } + + + /** + * PROSAC Loop + */ + + for(p->ctrl.i=0; p->ctrl.i < p->arg.maxI; p->ctrl.i++){ + sacHypothesize(p) && sacVerify(p); + } + + + /** + * Teardown + */ + + if(sacIsFinalRefineEnabled(p) && sacCanRefine(p)){ + sacRefine(p); + } + + sacOutputModel(p); + sacFiniRun(p); + return sacIsBestModelGoodEnough(p) ? p->best.numInl : 0; +} + + +/** + * Allocate memory aligned to a boundary of MEMALIGN. + */ + +static inline void* almalloc(size_t nBytes){ + if(nBytes){ + unsigned char* ptr = (unsigned char*)malloc(MEM_ALIGN + nBytes); + if(ptr){ + unsigned char* adj = (unsigned char*)(((intptr_t)(ptr+MEM_ALIGN))&((intptr_t)(-MEM_ALIGN))); + ptrdiff_t diff = adj - ptr; + adj[-1] = diff - 1; + return adj; + } + } + + return NULL; +} + +/** + * Free aligned memory. + * + * If argument is NULL, do nothing in accordance with free() semantics. + */ + +static inline void alfree(void* ptr){ + if(ptr){ + unsigned char* cptr = (unsigned char*)ptr; + free(cptr - (ptrdiff_t)cptr[-1] - 1); + } +} + + +/** + * Initialize SAC for a run given its arguments. + * + * Performs sanity-checks and memory allocations. Also initializes the state. + * + * @returns 0 if per-run initialization failed at any point; non-zero + * otherwise. + * + * Reads: arg.*, nr.* + * Writes: curr.*, best.*, ctrl.*, eval.* + */ + +static inline int sacInitRun(RHO_HEST_REFC* p){ + /** + * Sanitize arguments. + * + * Runs zeroth because these are easy-to-check errors and unambiguously + * mean something or other. + */ + + if(!p->arg.src || !p->arg.dst){ + /* Arguments src or dst are insane, must be != NULL */ + return 0; + } + if(p->arg.N < m){ + /* Argument N is insane, must be >= 4. */ + return 0; + } + if(p->arg.maxD < 0){ + /* Argument maxD is insane, must be >= 0. */ + return 0; + } + if(p->arg.cfd < 0 || p->arg.cfd > 1){ + /* Argument cfd is insane, must be in [0, 1]. */ + return 0; + } + /* Clamp minInl to 4 or higher. */ + p->arg.minInl = p->arg.minInl < m ? m : p->arg.minInl; + if(sacIsNREnabled(p) && (p->arg.beta <= 0 || p->arg.beta >= 1)){ + /* Argument beta is insane, must be in (0, 1). */ + return 0; + } + if(!p->arg.finalH){ + /* Argument finalH is insane, must be != NULL */ + return 0; + } + + /** + * Optional NR setup. + * + * Runs first because it is decoupled from most other things (*) and if it + * fails, it is easy to recover from. + * + * (*) The only things this code depends on is the flags argument, the nr.* + * substruct and the sanity-checked N and beta arguments from above. + */ + + if(sacIsNREnabled(p) && !rhoRefCEnsureCapacity(p, p->arg.N, p->arg.beta)){ + return 0; + } + + /** + * Inlier mask alloc. + * + * Runs second because we want to quit as fast as possible if we can't even + * allocate the up tp two masks. + * + * If the calling software wants an output mask, use buffer provided. If + * not, allocate one anyways internally. + */ + + p->best.inl = p->arg.inl ? p->arg.inl : (char*)almalloc(p->arg.N); + p->curr.inl = (char*)almalloc(p->arg.N); + + if(!p->curr.inl || !p->best.inl){ + return 0; + } + + /** + * Reset scalar per-run state. + * + * Runs third because there's no point in resetting/calculating a large + * number of fields if something in the above junk failed. + */ + + p->ctrl.i = 0; + p->ctrl.phNum = m; + p->ctrl.phEndI = 1; + p->ctrl.phEndFpI = sacInitPEndFpI(p->arg.rConvg, p->arg.N, m); + p->ctrl.phMax = p->arg.N; + p->ctrl.phNumInl = 0; + p->ctrl.numModels = 0; + + if(sacHaveExtrinsicGuess(p)){ + memcpy(p->curr.H, p->arg.guessH, HSIZE); + }else{ + memset(p->curr.H, 0, HSIZE); + } + p->curr.numInl = 0; + + memset(p->best.H, 0, HSIZE); + p->best.numInl = 0; + + p->eval.Ntested = 0; + p->eval.Ntestedtotal = 0; + p->eval.good = 1; + p->eval.t_M = SPRT_T_M; + p->eval.m_S = SPRT_M_S; + p->eval.epsilon = SPRT_EPSILON; + p->eval.delta = SPRT_DELTA; + sacDesignSPRTTest(p); + + return 1; +} + +/** + * Finalize SAC run. + * + * Deallocates per-run allocatable resources. Currently this consists only of + * the best and current inlier masks, which are equal in size to p->arg.N + * bytes. + * + * Reads: arg.bestInl, curr.inl, best.inl + * Writes: curr.inl, best.inl + */ + +static inline void sacFiniRun(RHO_HEST_REFC* p){ + /** + * If no output inlier mask was required, free both (internal) masks. + * Else if an (external) mask was provided as argument, find the other + * (the internal one) and free it. + */ + + if(p->arg.inl){ + if(p->arg.inl == p->best.inl){ + alfree(p->curr.inl); + }else{ + alfree(p->best.inl); + } + }else{ + alfree(p->best.inl); + alfree(p->curr.inl); + } + + p->best.inl = NULL; + p->curr.inl = NULL; +} + +/** + * Hypothesize a model. + * + * Selects randomly a sample (within the rules of PROSAC) and generates a + * new current model, and applies degeneracy tests to it. + * + * @returns 0 if hypothesized model could be rejected early as degenerate, and + * non-zero otherwise. + */ + +static inline int sacHypothesize(RHO_HEST_REFC* p){ + if(sacPROSACPhaseEndReached(p)){ + sacPROSACGoToNextPhase(p); + } + + sacGetPROSACSample(p); + if(sacIsSampleDegenerate(p)){ + return 0; + } + + sacGenerateModel(p); + if(sacIsModelDegenerate(p)){ + return 0; + } + + return 1; +} + +/** + * Verify the hypothesized model. + * + * Given the current model, evaluate its quality. If it is better than + * everything before, save as new best model (and possibly refine it). + * + * Returns 1. + */ + +static inline int sacVerify(RHO_HEST_REFC* p){ + sacEvaluateModelSPRT(p); + sacUpdateSPRT(p); + + if(sacIsBestModel(p)){ + sacSaveBestModel(p); + + if(sacIsRefineEnabled(p) && sacCanRefine(p)){ + sacRefine(p); + } + + sacUpdateBounds(p); + + if(sacIsNREnabled(p)){ + sacNStarOptimize(p); + } + } + + return 1; +} + +/** + * Check whether extrinsic guess was provided or not. + * + * @return Zero if no extrinsic guess was provided; non-zero otherwiseEE. + */ + +static inline int sacHaveExtrinsicGuess(RHO_HEST_REFC* p){ + return !!p->arg.guessH; +} + +/** + * Check whether non-randomness criterion is enabled. + * + * @return Zero if non-randomness criterion disabled; non-zero if not. + */ + +static inline int sacIsNREnabled(RHO_HEST_REFC* p){ + return p->arg.flags & RHO_FLAG_ENABLE_NR; +} + +/** + * Check whether best-model-so-far refinement is enabled. + * + * @return Zero if best-model-so-far refinement disabled; non-zero if not. + */ + +static inline int sacIsRefineEnabled(RHO_HEST_REFC* p){ + return p->arg.flags & RHO_FLAG_ENABLE_REFINEMENT; +} + +/** + * Check whether final-model refinement is enabled. + * + * @return Zero if final-model refinement disabled; non-zero if not. + */ + +static inline int sacIsFinalRefineEnabled(RHO_HEST_REFC* p){ + return p->arg.flags & RHO_FLAG_ENABLE_FINAL_REFINEMENT; +} + +/** + * Computes whether the end of the current PROSAC phase has been reached. At + * PROSAC phase phNum, only matches [0, phNum) are sampled from. + * + * Accesses: + * Read: i, phEndI, phNum, phMax. + */ + +static inline int sacPROSACPhaseEndReached(RHO_HEST_REFC* p){ + return p->ctrl.i >= p->ctrl.phEndI && p->ctrl.phNum < p->ctrl.phMax; +} + +/** + * Updates unconditionally the necessary fields to move to the next PROSAC + * stage. + * + * Not idempotent. + * + * Accesses: + * Read: phNum, phEndFpI, phEndI + * Write: phNum, phEndFpI, phEndI + */ + +static inline void sacPROSACGoToNextPhase(RHO_HEST_REFC* p){ + double next; + + p->ctrl.phNum++; + next = (p->ctrl.phEndFpI * p->ctrl.phNum)/(p->ctrl.phNum - m); + p->ctrl.phEndI += ceil(next - p->ctrl.phEndFpI); + p->ctrl.phEndFpI = next; +} + +/** + * Get a sample according to PROSAC rules. Namely: + * - If we're past the phase end interation, select randomly 4 out of the first + * phNum matches. + * - Otherwise, select match phNum-1 and select randomly the 3 others out of + * the first phNum-1 matches. + */ + +static inline void sacGetPROSACSample(RHO_HEST_REFC* p){ + if(p->ctrl.i > p->ctrl.phEndI){ + sacRndSmpl(4, p->ctrl.smpl, p->ctrl.phNum);/* Used to be phMax */ + }else{ + sacRndSmpl(3, p->ctrl.smpl, p->ctrl.phNum-1); + p->ctrl.smpl[3] = p->ctrl.phNum-1; + } +} + +/** + * Checks whether the *sample* is degenerate prior to model generation. + * - First, the extremely cheap numerical degeneracy test is run, which weeds + * out bad samples to the optimized GE implementation. + * - Second, the geometrical degeneracy test is run, which weeds out most other + * bad samples. + */ + +static inline int sacIsSampleDegenerate(RHO_HEST_REFC* p){ + unsigned i0 = p->ctrl.smpl[0], i1 = p->ctrl.smpl[1], i2 = p->ctrl.smpl[2], i3 = p->ctrl.smpl[3]; + typedef struct{float x,y;} MyPt2f; + MyPt2f* pkdPts = (MyPt2f*)p->curr.pkdPts, *src = (MyPt2f*)p->arg.src, *dst = (MyPt2f*)p->arg.dst; + + /** + * Pack the matches selected by the SAC algorithm. + * Must be packed points[0:7] = {srcx0, srcy0, srcx1, srcy1, srcx2, srcy2, srcx3, srcy3} + * points[8:15] = {dstx0, dsty0, dstx1, dsty1, dstx2, dsty2, dstx3, dsty3} + * Gather 4 points into the vector + */ + + pkdPts[0] = src[i0]; + pkdPts[1] = src[i1]; + pkdPts[2] = src[i2]; + pkdPts[3] = src[i3]; + pkdPts[4] = dst[i0]; + pkdPts[5] = dst[i1]; + pkdPts[6] = dst[i2]; + pkdPts[7] = dst[i3]; + + /** + * If the matches' source points have common x and y coordinates, abort. + */ + + if(pkdPts[0].x == pkdPts[1].x || pkdPts[1].x == pkdPts[2].x || + pkdPts[2].x == pkdPts[3].x || pkdPts[0].x == pkdPts[2].x || + pkdPts[1].x == pkdPts[3].x || pkdPts[0].x == pkdPts[3].x || + pkdPts[0].y == pkdPts[1].y || pkdPts[1].y == pkdPts[2].y || + pkdPts[2].y == pkdPts[3].y || pkdPts[0].y == pkdPts[2].y || + pkdPts[1].y == pkdPts[3].y || pkdPts[0].y == pkdPts[3].y){ + return 1; + } + + /* If the matches do not satisfy the strong geometric constraint, abort. */ + /* (0 x 1) * 2 */ + float cross0s0 = pkdPts[0].y-pkdPts[1].y; + float cross0s1 = pkdPts[1].x-pkdPts[0].x; + float cross0s2 = pkdPts[0].x*pkdPts[1].y-pkdPts[0].y*pkdPts[1].x; + float dots0 = cross0s0*pkdPts[2].x + cross0s1*pkdPts[2].y + cross0s2; + float cross0d0 = pkdPts[4].y-pkdPts[5].y; + float cross0d1 = pkdPts[5].x-pkdPts[4].x; + float cross0d2 = pkdPts[4].x*pkdPts[5].y-pkdPts[4].y*pkdPts[5].x; + float dotd0 = cross0d0*pkdPts[6].x + cross0d1*pkdPts[6].y + cross0d2; + if(((int)dots0^(int)dotd0) < 0){ + return 1; + } + /* (0 x 1) * 3 */ + float cross1s0 = cross0s0; + float cross1s1 = cross0s1; + float cross1s2 = cross0s2; + float dots1 = cross1s0*pkdPts[3].x + cross1s1*pkdPts[3].y + cross1s2; + float cross1d0 = cross0d0; + float cross1d1 = cross0d1; + float cross1d2 = cross0d2; + float dotd1 = cross1d0*pkdPts[7].x + cross1d1*pkdPts[7].y + cross1d2; + if(((int)dots1^(int)dotd1) < 0){ + return 1; + } + /* (2 x 3) * 0 */ + float cross2s0 = pkdPts[2].y-pkdPts[3].y; + float cross2s1 = pkdPts[3].x-pkdPts[2].x; + float cross2s2 = pkdPts[2].x*pkdPts[3].y-pkdPts[2].y*pkdPts[3].x; + float dots2 = cross2s0*pkdPts[0].x + cross2s1*pkdPts[0].y + cross2s2; + float cross2d0 = pkdPts[6].y-pkdPts[7].y; + float cross2d1 = pkdPts[7].x-pkdPts[6].x; + float cross2d2 = pkdPts[6].x*pkdPts[7].y-pkdPts[6].y*pkdPts[7].x; + float dotd2 = cross2d0*pkdPts[4].x + cross2d1*pkdPts[4].y + cross2d2; + if(((int)dots2^(int)dotd2) < 0){ + return 1; + } + /* (2 x 3) * 1 */ + float cross3s0 = cross2s0; + float cross3s1 = cross2s1; + float cross3s2 = cross2s2; + float dots3 = cross3s0*pkdPts[1].x + cross3s1*pkdPts[1].y + cross3s2; + float cross3d0 = cross2d0; + float cross3d1 = cross2d1; + float cross3d2 = cross2d2; + float dotd3 = cross3d0*pkdPts[5].x + cross3d1*pkdPts[5].y + cross3d2; + if(((int)dots3^(int)dotd3) < 0){ + return 1; + } + + /* Otherwise, accept */ + return 0; +} + +/** + * Compute homography of matches in gathered, packed sample and output the + * current homography. + */ + +static inline void sacGenerateModel(RHO_HEST_REFC* p){ + hFuncRefC(p->curr.pkdPts, p->curr.H); +} + +/** + * Checks whether the model is itself degenerate. + * - One test: All elements of the homography are added, and if the result is + * NaN the homography is rejected. + */ + +static inline int sacIsModelDegenerate(RHO_HEST_REFC* p){ + int degenerate; + float* H = p->curr.H; + float f=H[0]+H[1]+H[2]+H[3]+H[4]+H[5]+H[6]+H[7]; + + /* degenerate = isnan(f); */ + degenerate = f!=f;/* Only NaN is not equal to itself. */ + /* degenerate = 0; */ + + + return degenerate; +} + +/** + * Evaluates the current model using SPRT for early exiting. + * + * Reads: arg.maxD, arg.src, arg.dst, curr.H, eval.* + * Writes: eval.*, curr.inl, curr.numInl + */ + +static inline void sacEvaluateModelSPRT(RHO_HEST_REFC* p){ + unsigned i; + unsigned isInlier; + double lambda = 1.0; + float distSq = p->arg.maxD*p->arg.maxD; + const float* src = p->arg.src; + const float* dst = p->arg.dst; + char* inl = p->curr.inl; + const float* H = p->curr.H; + + + p->ctrl.numModels++; + + p->curr.numInl = 0; + p->eval.Ntested = 0; + p->eval.good = 1; + + + /* SCALAR */ + for(i=0;iarg.N && p->eval.good;i++){ + /* Backproject */ + float x=src[i*2],y=src[i*2+1]; + float X=dst[i*2],Y=dst[i*2+1]; + + float reprojX=H[0]*x+H[1]*y+H[2]; /* ( X_1 ) ( H_11 H_12 H_13 ) (x_1) */ + float reprojY=H[3]*x+H[4]*y+H[5]; /* ( X_2 ) = ( H_21 H_22 H_23 ) (x_2) */ + float reprojZ=H[6]*x+H[7]*y+1.0; /* ( X_3 ) ( H_31 H_32 H_33=1.0 ) (x_3 = 1.0) */ + + /* reproj is in homogeneous coordinates. To bring back to "regular" coordinates, divide by Z. */ + reprojX/=reprojZ; + reprojY/=reprojZ; + + /* Compute distance */ + reprojX-=X; + reprojY-=Y; + reprojX*=reprojX; + reprojY*=reprojY; + float reprojDist = reprojX+reprojY; + + /* ... */ + isInlier = reprojDist <= distSq; + p->curr.numInl += isInlier; + *inl++ = isInlier; + + + /* SPRT */ + lambda *= isInlier ? p->eval.lambdaAccept : p->eval.lambdaReject; + p->eval.good = lambda <= p->eval.A; + /* If !p->good, the threshold A was exceeded, so we're rejecting */ + } + + + p->eval.Ntested = i; + p->eval.Ntestedtotal += i; +} + +/** + * Update either the delta or epsilon SPRT parameters, depending on the events + * that transpired in the previous evaluation. + * + * If a "good" model that is also the best was encountered, update epsilon, + * since + */ + +static inline void sacUpdateSPRT(RHO_HEST_REFC* p){ + if(p->eval.good){ + if(sacIsBestModel(p)){ + p->eval.epsilon = (double)p->curr.numInl/p->arg.N; + sacDesignSPRTTest(p); + } + }else{ + double newDelta = (double)p->curr.numInl/p->eval.Ntested; + + if(newDelta > 0 && CHNG_SIGNIFICANT(p->eval.delta, newDelta)){ + p->eval.delta = newDelta; + sacDesignSPRTTest(p); + } + } +} + +/** + * Numerically compute threshold A from the estimated delta, epsilon, t_M and + * m_S values. + * + * Epsilon: Denotes the probability that a randomly chosen data point is + * consistent with a good model. + * Delta: Denotes the probability that a randomly chosen data point is + * consistent with a bad model. + * t_M: Time needed to instantiate a model hypotheses given a sample. + * (Computing model parameters from a sample takes the same time + * as verification of t_M data points) + * m_S: The number of models that are verified per sample. + */ + +static inline double designSPRTTest(double delta, double epsilon, double t_M, double m_S){ + double An, C, K, prevAn; + unsigned i; + + /** + * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 + * Eq (2) + */ + + C = (1-delta) * log((1-delta)/(1-epsilon)) + + delta * log( delta / epsilon ); + + /** + * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 + * Eq (6) + * K = K_1/K_2 + 1 = (t_M*C)/m_S + 1 + */ + + K = t_M*C/m_S + 1; + + /** + * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 + * Paragraph below Eq (6) + * + * A* = lim_{n -> infty} A_n, where + * A_0 = K1/K2 + 1 and + * A_{n+1} = K1/K2 + 1 + log(A_n) + * The series converges fast, typically within four iterations. + */ + + An = K; + i = 0; + + do{ + prevAn = An; + An = K + log(An); + }while((An-prevAn > 1.5e-8) && (++i < 10)); + + /** + * Return A = An_stopping, with n_stopping < 10 + */ + + return An; +} + +/** + * Design the SPRT test. Shorthand for + * A = sprt(delta, epsilon, t_M, m_S); + * + * Idempotent, reentrant, thread-safe. + * + * Reads: eval.delta, eval.epsilon, eval.t_M, eval.m_S + * Writes: eval.A, eval.lambdaAccept, eval.lambdaReject + */ + +static inline void sacDesignSPRTTest(RHO_HEST_REFC* p){ + p->eval.A = designSPRTTest(p->eval.delta, p->eval.epsilon, p->eval.t_M, p->eval.m_S); + p->eval.lambdaReject = ((1.0 - p->eval.delta) / (1.0 - p->eval.epsilon)); + p->eval.lambdaAccept = (( p->eval.delta ) / ( p->eval.epsilon )); +} + +/** + * Return whether the current model is the best model so far. + */ + +static inline int sacIsBestModel(RHO_HEST_REFC* p){ + return p->curr.numInl > p->best.numInl; +} + +/** + * Returns whether the current-best model is good enough to be an + * acceptable best model, by checking whether it meets the minimum + * number of inliers. + */ + +static inline int sacIsBestModelGoodEnough(RHO_HEST_REFC* p){ + return p->best.numInl >= p->arg.minInl; +} + +/** + * Make current model new best model by swapping the homography, inlier mask + * and count of inliers between the current and best models. + */ + +static inline void sacSaveBestModel(RHO_HEST_REFC* p){ + float* H = p->curr.H; + char* inl = p->curr.inl; + unsigned numInl = p->curr.numInl; + p->curr.H = p->best.H; + p->curr.inl = p->best.inl; + p->curr.numInl = p->best.numInl; + p->best.H = H; + p->best.inl = inl; + p->best.numInl = numInl; +} + +/** + * Compute NR table entries [start, N) for given beta. + */ + +static inline void sacInitNonRand(double beta, + unsigned start, + unsigned N, + unsigned* nonRandMinInl){ + unsigned n = m+1 > start ? m+1 : start; + double beta_beta1_sq_chi = sqrt(beta*(1.0-beta)) * CHI_SQ; + + for(; n < N; n++){ + double mu = n * beta; + double sigma = sqrt(n)* beta_beta1_sq_chi; + unsigned i_min = ceil(m + mu + sigma); + + nonRandMinInl[n] = i_min; + } +} + +/** + * Optimize the stopping criterion to account for the non-randomness criterion + * of PROSAC. + */ + +static inline void sacNStarOptimize(RHO_HEST_REFC* p){ + unsigned min_sample_length = 10*2; /*(p->N * INLIERS_RATIO) */ + unsigned best_n = p->arg.N; + unsigned test_n = best_n; + unsigned bestNumInl = p->best.numInl; + unsigned testNumInl = bestNumInl; + + for(;test_n > min_sample_length && testNumInl;test_n--){ + if(testNumInl*best_n > bestNumInl*test_n){ + if(testNumInl < p->nr.tbl[test_n]){ + break; + } + best_n = test_n; + bestNumInl = testNumInl; + } + testNumInl -= !!p->arg.inl[test_n-1]; + } + + if(bestNumInl*p->ctrl.phMax > p->ctrl.phNumInl*best_n){ + p->ctrl.phMax = best_n; + p->ctrl.phNumInl = bestNumInl; + p->arg.maxI = sacCalcIterBound(p->arg.cfd, + (double)p->ctrl.phNumInl/p->ctrl.phMax, + m, + p->arg.maxI); + } +} + +/** + * Classic RANSAC iteration bound based on largest # of inliers. + */ + +static inline void sacUpdateBounds(RHO_HEST_REFC* p){ + p->arg.maxI = sacCalcIterBound(p->arg.cfd, + (double)p->best.numInl/p->arg.N, + m, + p->arg.maxI); +} + +/** + * Ouput the best model so far to the output argument. + */ + +static inline void sacOutputModel(RHO_HEST_REFC* p){ + if(sacIsBestModelGoodEnough(p)){ + memcpy(p->arg.finalH, p->best.H, HSIZE); + }else{ + sacOutputZeroH(p); + } +} + +/** + * Ouput a zeroed H to the output argument. + */ + +static inline void sacOutputZeroH(RHO_HEST_REFC* p){ + memset(p->arg.finalH, 0, HSIZE); +} + +/** + * Compute the real-valued number of samples per phase, given the RANSAC convergence speed, + * data set size and sample size. + */ + +static inline double sacInitPEndFpI(const unsigned ransacConvg, + const unsigned n, + const unsigned s){ + double numer=1, denom=1; + + unsigned i; + for(i=0;idataSetSize){ + /** + * Selection Sampling: + * + * Algorithm S (Selection sampling technique). To select n records at random from a set of N, where 0 < n ≤ N. + * S1. [Initialize.] Set t ← 0, m ← 0. (During this algorithm, m represents the number of records selected so far, + * and t is the total number of input records that we have dealt with.) + * S2. [Generate U.] Generate a random number U, uniformly distributed between zero and one. + * S3. [Test.] If (N – t)U ≥ n – m, go to step S5. + * S4. [Select.] Select the next record for the sample, and increase m and t by 1. If m < n, go to step S2; + * otherwise the sample is complete and the algorithm terminates. + * S5. [Skip.] Skip the next record (do not include it in the sample), increase t by 1, and go back to step S2. + * + * Replaced m with i and t with j in the below code. + */ + + unsigned i=0,j=0; + + for(i=0;i=1.){ + /** + * A certainty of picking at least one outlier means that we will need + * an infinite amount of iterations in order to find a correct solution. + */ + + retVal = maxIterBound; + }else if(atLeastOneOutlierProbability<=0.){ + /** + * The certainty of NOT picking an outlier means that only 1 iteration + * is needed to find a solution. + */ + + retVal = 1; + }else{ + /** + * Since 1-confidence (the probability of the model being based on at + * least one outlier in the data) is equal to + * (1-inlierRate**sampleSize)**numIterations (the probability of picking + * at least one outlier in numIterations samples), we can isolate + * numIterations (the return value) into + */ + + retVal = ceil(log(1.-confidence)/log(atLeastOneOutlierProbability)); + } + + /** + * Clamp to maxIterationBound. + */ + + return retVal <= maxIterBound ? retVal : maxIterBound; +} + + +/** + * Given 4 matches, computes the homography that relates them using Gaussian + * Elimination. The row operations are as given in the paper. + * + * TODO: Clean this up. The code is hideous, and might even conceal sign bugs + * (specifically relating to whether the last column should be negated, + * or not). + */ + +static void hFuncRefC(float* packedPoints,/* Source (four x,y float coordinates) points followed by + destination (four x,y float coordinates) points, aligned by 32 bytes */ + float* H){ /* Homography (three 16-byte aligned rows of 3 floats) */ + float x0=*packedPoints++; + float y0=*packedPoints++; + float x1=*packedPoints++; + float y1=*packedPoints++; + float x2=*packedPoints++; + float y2=*packedPoints++; + float x3=*packedPoints++; + float y3=*packedPoints++; + float X0=*packedPoints++; + float Y0=*packedPoints++; + float X1=*packedPoints++; + float Y1=*packedPoints++; + float X2=*packedPoints++; + float Y2=*packedPoints++; + float X3=*packedPoints++; + float Y3=*packedPoints++; + + float x0X0=x0*X0, x1X1=x1*X1, x2X2=x2*X2, x3X3=x3*X3; + float x0Y0=x0*Y0, x1Y1=x1*Y1, x2Y2=x2*Y2, x3Y3=x3*Y3; + float y0X0=y0*X0, y1X1=y1*X1, y2X2=y2*X2, y3X3=y3*X3; + float y0Y0=y0*Y0, y1Y1=y1*Y1, y2Y2=y2*Y2, y3Y3=y3*Y3; + + + /** + * [0] [1] Hidden Prec + * x0 y0 1 x1 + * x1 y1 1 x1 + * x2 y2 1 x1 + * x3 y3 1 x1 + * + * Eliminate ones in column 2 and 5. + * R(0)-=R(2) + * R(1)-=R(2) + * R(3)-=R(2) + * + * [0] [1] Hidden Prec + * x0-x2 y0-y2 0 x1+1 + * x1-x2 y1-y2 0 x1+1 + * x2 y2 1 x1 + * x3-x2 y3-y2 0 x1+1 + * + * Eliminate column 0 of rows 1 and 3 + * R(1)=(x0-x2)*R(1)-(x1-x2)*R(0), y1'=(y1-y2)(x0-x2)-(x1-x2)(y0-y2) + * R(3)=(x0-x2)*R(3)-(x3-x2)*R(0), y3'=(y3-y2)(x0-x2)-(x3-x2)(y0-y2) + * + * [0] [1] Hidden Prec + * x0-x2 y0-y2 0 x1+1 + * 0 y1' 0 x2+3 + * x2 y2 1 x1 + * 0 y3' 0 x2+3 + * + * Eliminate column 1 of rows 0 and 3 + * R(3)=y1'*R(3)-y3'*R(1) + * R(0)=y1'*R(0)-(y0-y2)*R(1) + * + * [0] [1] Hidden Prec + * x0' 0 0 x3+5 + * 0 y1' 0 x2+3 + * x2 y2 1 x1 + * 0 0 0 x4+7 + * + * Eliminate columns 0 and 1 of row 2 + * R(0)/=x0' + * R(1)/=y1' + * R(2)-= (x2*R(0) + y2*R(1)) + * + * [0] [1] Hidden Prec + * 1 0 0 x6+10 + * 0 1 0 x4+6 + * 0 0 1 x4+7 + * 0 0 0 x4+7 + */ + + /** + * Eliminate ones in column 2 and 5. + * R(0)-=R(2) + * R(1)-=R(2) + * R(3)-=R(2) + */ + + /*float minor[4][2] = {{x0-x2,y0-y2}, + {x1-x2,y1-y2}, + {x2 ,y2 }, + {x3-x2,y3-y2}};*/ + /*float major[8][3] = {{x2X2-x0X0,y2X2-y0X0,(X0-X2)}, + {x2X2-x1X1,y2X2-y1X1,(X1-X2)}, + {-x2X2 ,-y2X2 ,(X2 )}, + {x2X2-x3X3,y2X2-y3X3,(X3-X2)}, + {x2Y2-x0Y0,y2Y2-y0Y0,(Y0-Y2)}, + {x2Y2-x1Y1,y2Y2-y1Y1,(Y1-Y2)}, + {-x2Y2 ,-y2Y2 ,(Y2 )}, + {x2Y2-x3Y3,y2Y2-y3Y3,(Y3-Y2)}};*/ + float minor[2][4] = {{x0-x2,x1-x2,x2 ,x3-x2}, + {y0-y2,y1-y2,y2 ,y3-y2}}; + float major[3][8] = {{x2X2-x0X0,x2X2-x1X1,-x2X2 ,x2X2-x3X3,x2Y2-x0Y0,x2Y2-x1Y1,-x2Y2 ,x2Y2-x3Y3}, + {y2X2-y0X0,y2X2-y1X1,-y2X2 ,y2X2-y3X3,y2Y2-y0Y0,y2Y2-y1Y1,-y2Y2 ,y2Y2-y3Y3}, + { (X0-X2) , (X1-X2) , (X2 ) , (X3-X2) , (Y0-Y2) , (Y1-Y2) , (Y2 ) , (Y3-Y2) }}; + + /** + * int i; + * for(i=0;i<8;i++) major[2][i]=-major[2][i]; + * Eliminate column 0 of rows 1 and 3 + * R(1)=(x0-x2)*R(1)-(x1-x2)*R(0), y1'=(y1-y2)(x0-x2)-(x1-x2)(y0-y2) + * R(3)=(x0-x2)*R(3)-(x3-x2)*R(0), y3'=(y3-y2)(x0-x2)-(x3-x2)(y0-y2) + */ + + float scalar1=minor[0][0], scalar2=minor[0][1]; + minor[1][1]=minor[1][1]*scalar1-minor[1][0]*scalar2; + + major[0][1]=major[0][1]*scalar1-major[0][0]*scalar2; + major[1][1]=major[1][1]*scalar1-major[1][0]*scalar2; + major[2][1]=major[2][1]*scalar1-major[2][0]*scalar2; + + major[0][5]=major[0][5]*scalar1-major[0][4]*scalar2; + major[1][5]=major[1][5]*scalar1-major[1][4]*scalar2; + major[2][5]=major[2][5]*scalar1-major[2][4]*scalar2; + + scalar2=minor[0][3]; + minor[1][3]=minor[1][3]*scalar1-minor[1][0]*scalar2; + + major[0][3]=major[0][3]*scalar1-major[0][0]*scalar2; + major[1][3]=major[1][3]*scalar1-major[1][0]*scalar2; + major[2][3]=major[2][3]*scalar1-major[2][0]*scalar2; + + major[0][7]=major[0][7]*scalar1-major[0][4]*scalar2; + major[1][7]=major[1][7]*scalar1-major[1][4]*scalar2; + major[2][7]=major[2][7]*scalar1-major[2][4]*scalar2; + + /** + * Eliminate column 1 of rows 0 and 3 + * R(3)=y1'*R(3)-y3'*R(1) + * R(0)=y1'*R(0)-(y0-y2)*R(1) + */ + + scalar1=minor[1][1];scalar2=minor[1][3]; + major[0][3]=major[0][3]*scalar1-major[0][1]*scalar2; + major[1][3]=major[1][3]*scalar1-major[1][1]*scalar2; + major[2][3]=major[2][3]*scalar1-major[2][1]*scalar2; + + major[0][7]=major[0][7]*scalar1-major[0][5]*scalar2; + major[1][7]=major[1][7]*scalar1-major[1][5]*scalar2; + major[2][7]=major[2][7]*scalar1-major[2][5]*scalar2; + + scalar2=minor[1][0]; + minor[0][0]=minor[0][0]*scalar1-minor[0][1]*scalar2; + + major[0][0]=major[0][0]*scalar1-major[0][1]*scalar2; + major[1][0]=major[1][0]*scalar1-major[1][1]*scalar2; + major[2][0]=major[2][0]*scalar1-major[2][1]*scalar2; + + major[0][4]=major[0][4]*scalar1-major[0][5]*scalar2; + major[1][4]=major[1][4]*scalar1-major[1][5]*scalar2; + major[2][4]=major[2][4]*scalar1-major[2][5]*scalar2; + + /** + * Eliminate columns 0 and 1 of row 2 + * R(0)/=x0' + * R(1)/=y1' + * R(2)-= (x2*R(0) + y2*R(1)) + */ + + scalar1=minor[0][0]; + major[0][0]/=scalar1; + major[1][0]/=scalar1; + major[2][0]/=scalar1; + major[0][4]/=scalar1; + major[1][4]/=scalar1; + major[2][4]/=scalar1; + + scalar1=minor[1][1]; + major[0][1]/=scalar1; + major[1][1]/=scalar1; + major[2][1]/=scalar1; + major[0][5]/=scalar1; + major[1][5]/=scalar1; + major[2][5]/=scalar1; + + + scalar1=minor[0][2];scalar2=minor[1][2]; + major[0][2]-=major[0][0]*scalar1+major[0][1]*scalar2; + major[1][2]-=major[1][0]*scalar1+major[1][1]*scalar2; + major[2][2]-=major[2][0]*scalar1+major[2][1]*scalar2; + + major[0][6]-=major[0][4]*scalar1+major[0][5]*scalar2; + major[1][6]-=major[1][4]*scalar1+major[1][5]*scalar2; + major[2][6]-=major[2][4]*scalar1+major[2][5]*scalar2; + + /* Only major matters now. R(3) and R(7) correspond to the hollowed-out rows. */ + scalar1=major[0][7]; + major[1][7]/=scalar1; + major[2][7]/=scalar1; + + scalar1=major[0][0];major[1][0]-=scalar1*major[1][7];major[2][0]-=scalar1*major[2][7]; + scalar1=major[0][1];major[1][1]-=scalar1*major[1][7];major[2][1]-=scalar1*major[2][7]; + scalar1=major[0][2];major[1][2]-=scalar1*major[1][7];major[2][2]-=scalar1*major[2][7]; + scalar1=major[0][3];major[1][3]-=scalar1*major[1][7];major[2][3]-=scalar1*major[2][7]; + scalar1=major[0][4];major[1][4]-=scalar1*major[1][7];major[2][4]-=scalar1*major[2][7]; + scalar1=major[0][5];major[1][5]-=scalar1*major[1][7];major[2][5]-=scalar1*major[2][7]; + scalar1=major[0][6];major[1][6]-=scalar1*major[1][7];major[2][6]-=scalar1*major[2][7]; + + + /* One column left (Two in fact, but the last one is the homography) */ + scalar1=major[1][3]; + + major[2][3]/=scalar1; + scalar1=major[1][0];major[2][0]-=scalar1*major[2][3]; + scalar1=major[1][1];major[2][1]-=scalar1*major[2][3]; + scalar1=major[1][2];major[2][2]-=scalar1*major[2][3]; + scalar1=major[1][4];major[2][4]-=scalar1*major[2][3]; + scalar1=major[1][5];major[2][5]-=scalar1*major[2][3]; + scalar1=major[1][6];major[2][6]-=scalar1*major[2][3]; + scalar1=major[1][7];major[2][7]-=scalar1*major[2][3]; + + + /* Homography is done. */ + H[0]=major[2][0]; + H[1]=major[2][1]; + H[2]=major[2][2]; + + H[3]=major[2][4]; + H[4]=major[2][5]; + H[5]=major[2][6]; + + H[6]=major[2][7]; + H[7]=major[2][3]; + H[8]=1.0; +} + +/** + * Returns whether refinement is possible. + * + * NB This is separate from whether it is *enabled*. + */ + +static inline int sacCanRefine(RHO_HEST_REFC* p){ + /** + * If we only have 4 matches, GE's result is already optimal and cannot + * be refined any further. + */ + + return p->best.numInl > m; +} + +/** + * Refines the best-so-far homography. + * + * BUG: Totally broken for now. DO NOT ENABLE. + */ + +static inline void sacRefine(RHO_HEST_REFC* p){ + int i, j; + float S; /* Sum of squared errors */ + float L = 1;/* Lambda of LevMarq */ + + for(i=0;ilm.JtJ, p->lm.Jte, &S, p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N); + sacScaleDiag8x8(p->lm.JtJ, L, p->lm.JtJ); + sacChol8x8(p->lm.JtJ, p->lm.JtJ); + sacTRInv8x8(p->lm.JtJ, p->lm.JtJ); + sacTRISolve8x8(p->lm.JtJ, p->lm.Jte, dH); + sacSub8x1(p->best.H, p->best.H, dH); + } +} + +/** + * Compute directly the JtJ, Jte and sum-of-squared-error for a given + * homography and set of inliers. + * + * This is possible because the product of J and its transpose as well as with + * the error and the sum-of-squared-error can all be computed additively + * (match-by-match), as one would intuitively expect; All matches make + * contributions to the error independently of each other. + * + * What this allows is a constant-space implementation of Lev-Marq that can + * nevertheless be vectorized if need be. + * + * @param JtJ + * @param Jte + * @param Sp + * @param H + * @param src + * @param dst + * @param inl + * @param N + */ + +static inline void sacCalcJtMats(float (* restrict JtJ)[8], + float* restrict Jte, + float* restrict Sp, + const float* restrict H, + const float* restrict src, + const float* restrict dst, + const char* restrict inl, + unsigned N){ + unsigned i; + float S; + + /* Zero out JtJ, Jte and S */ + memset(JtJ, 0, 8*8*sizeof(*JtJ)); + memset(Jte, 0, 8*1*sizeof(*Jte)); + S = 0.0f; + + /* Additively compute JtJ and Jte */ + for(i=0;i + * 0 U22 0 U22^-1 + * + * Becomes + * + * L11 0 L11^-1 0 + * -> + * L21 L22 -L22^-1*L21*L11^-1 L22^-1 + * + * Since + * + * ( -L11^T^-1*L21^T*L22^T^-1 )^T = -L22^T^-1^T*L21^T^T*L11^T^-1^T + * = -L22^T^T^-1*L21^T^T*L11^T^T^-1 + * = -L22^-1*L21*L11^-1 + */ + +static inline void sacTRInv8x8(const float (*L)[8], + float (*M)[8]){ + float s[2][2], t[2][2]; + float u[4][4], v[4][4]; + + /* + L00 0 0 0 0 0 0 0 + L10 L11 0 0 0 0 0 0 + L20 L21 L22 0 0 0 0 0 + L30 L31 L32 L33 0 0 0 0 + L40 L41 L42 L43 L44 0 0 0 + L50 L51 L52 L53 L54 L55 0 0 + L60 L61 L62 L63 L64 L65 L66 0 + L70 L71 L72 L73 L74 L75 L76 L77 + */ + + /* Invert 4*2 1x1 matrices; Starts recursion. */ + M[0][0] = 1.0f/L[0][0]; + M[1][1] = 1.0f/L[1][1]; + M[2][2] = 1.0f/L[2][2]; + M[3][3] = 1.0f/L[3][3]; + M[4][4] = 1.0f/L[4][4]; + M[5][5] = 1.0f/L[5][5]; + M[6][6] = 1.0f/L[6][6]; + M[7][7] = 1.0f/L[7][7]; + + /* + M00 0 0 0 0 0 0 0 + L10 M11 0 0 0 0 0 0 + L20 L21 M22 0 0 0 0 0 + L30 L31 L32 M33 0 0 0 0 + L40 L41 L42 L43 M44 0 0 0 + L50 L51 L52 L53 L54 M55 0 0 + L60 L61 L62 L63 L64 L65 M66 0 + L70 L71 L72 L73 L74 L75 L76 M77 + */ + + /* 4*2 Matrix products of 1x1 matrices */ + M[1][0] = -M[1][1]*L[1][0]*M[0][0]; + M[3][2] = -M[3][3]*L[3][2]*M[2][2]; + M[5][4] = -M[5][5]*L[5][4]*M[4][4]; + M[7][6] = -M[7][7]*L[7][6]*M[6][6]; + + /* + M00 0 0 0 0 0 0 0 + M10 M11 0 0 0 0 0 0 + L20 L21 M22 0 0 0 0 0 + L30 L31 M32 M33 0 0 0 0 + L40 L41 L42 L43 M44 0 0 0 + L50 L51 L52 L53 M54 M55 0 0 + L60 L61 L62 L63 L64 L65 M66 0 + L70 L71 L72 L73 L74 L75 M76 M77 + */ + + /* 2*2 Matrix products of 2x2 matrices */ + + /* + (M22 0 ) (L20 L21) (M00 0 ) + - (M32 M33) x (L30 L31) x (M10 M11) + */ + + s[0][0] = M[2][2]*L[2][0]; + s[0][1] = M[2][2]*L[2][1]; + s[1][0] = M[3][2]*L[2][0]+M[3][3]*L[3][0]; + s[1][1] = M[3][2]*L[2][1]+M[3][3]*L[3][1]; + + t[0][0] = s[0][0]*M[0][0]+s[0][1]*M[1][0]; + t[0][1] = s[0][1]*M[1][1]; + t[1][0] = s[1][0]*M[0][0]+s[1][1]*M[1][0]; + t[1][1] = s[1][1]*M[1][1]; + + M[2][0] = -t[0][0]; + M[2][1] = -t[0][1]; + M[3][0] = -t[1][0]; + M[3][1] = -t[1][1]; + + /* + (M66 0 ) (L64 L65) (M44 0 ) + - (L76 M77) x (L74 L75) x (M54 M55) + */ + + s[0][0] = M[6][6]*L[6][4]; + s[0][1] = M[6][6]*L[6][5]; + s[1][0] = M[7][6]*L[6][4]+M[7][7]*L[7][4]; + s[1][1] = M[7][6]*L[6][5]+M[7][7]*L[7][5]; + + t[0][0] = s[0][0]*M[4][4]+s[0][1]*M[5][4]; + t[0][1] = s[0][1]*M[5][5]; + t[1][0] = s[1][0]*M[4][4]+s[1][1]*M[5][4]; + t[1][1] = s[1][1]*M[5][5]; + + M[6][4] = -t[0][0]; + M[6][5] = -t[0][1]; + M[7][4] = -t[1][0]; + M[7][5] = -t[1][1]; + + /* + M00 0 0 0 0 0 0 0 + M10 M11 0 0 0 0 0 0 + M20 M21 M22 0 0 0 0 0 + M30 M31 M32 M33 0 0 0 0 + L40 L41 L42 L43 M44 0 0 0 + L50 L51 L52 L53 M54 M55 0 0 + L60 L61 L62 L63 M64 M65 M66 0 + L70 L71 L72 L73 M74 M75 M76 M77 + */ + + /* 1*2 Matrix products of 4x4 matrices */ + + /* + (M44 0 0 0 ) (L40 L41 L42 L43) (M00 0 0 0 ) + (M54 M55 0 0 ) (L50 L51 L52 L53) (M10 M11 0 0 ) + (M64 M65 M66 0 ) (L60 L61 L62 L63) (M20 M21 M22 0 ) + - (M74 M75 M76 M77) x (L70 L71 L72 L73) x (M30 M31 M32 M33) + */ + + u[0][0] = M[4][4]*L[4][0]; + u[0][1] = M[4][4]*L[4][1]; + u[0][2] = M[4][4]*L[4][2]; + u[0][3] = M[4][4]*L[4][3]; + u[1][0] = M[5][4]*L[4][0]+M[5][5]*L[5][0]; + u[1][1] = M[5][4]*L[4][1]+M[5][5]*L[5][1]; + u[1][2] = M[5][4]*L[4][2]+M[5][5]*L[5][2]; + u[1][3] = M[5][4]*L[4][3]+M[5][5]*L[5][3]; + u[2][0] = M[6][4]*L[4][0]+M[6][5]*L[5][0]+M[6][6]*L[6][0]; + u[2][1] = M[6][4]*L[4][1]+M[6][5]*L[5][1]+M[6][6]*L[6][1]; + u[2][2] = M[6][4]*L[4][2]+M[6][5]*L[5][2]+M[6][6]*L[6][2]; + u[2][3] = M[6][4]*L[4][3]+M[6][5]*L[5][3]+M[6][6]*L[6][3]; + u[3][0] = M[7][4]*L[4][0]+M[7][5]*L[5][0]+M[7][6]*L[6][0]+M[7][7]*L[7][0]; + u[3][1] = M[7][4]*L[4][1]+M[7][5]*L[5][1]+M[7][6]*L[6][1]+M[7][7]*L[7][1]; + u[3][2] = M[7][4]*L[4][2]+M[7][5]*L[5][2]+M[7][6]*L[6][2]+M[7][7]*L[7][2]; + u[3][3] = M[7][4]*L[4][3]+M[7][5]*L[5][3]+M[7][6]*L[6][3]+M[7][7]*L[7][3]; + + v[0][0] = u[0][0]*M[0][0]+u[0][1]*M[1][0]+u[0][2]*M[2][0]+u[0][3]*M[3][0]; + v[0][1] = u[0][1]*M[1][1]+u[0][2]*M[2][1]+u[0][3]*M[3][1]; + v[0][2] = u[0][2]*M[2][2]+u[0][3]*M[3][2]; + v[0][3] = u[0][3]*M[3][3]; + v[1][0] = u[1][0]*M[0][0]+u[1][1]*M[1][0]+u[1][2]*M[2][0]+u[1][3]*M[3][0]; + v[1][1] = u[1][1]*M[1][1]+u[1][2]*M[2][1]+u[1][3]*M[3][1]; + v[1][2] = u[1][2]*M[2][2]+u[1][3]*M[3][2]; + v[1][3] = u[1][3]*M[3][3]; + v[2][0] = u[2][0]*M[0][0]+u[2][1]*M[1][0]+u[2][2]*M[2][0]+u[2][3]*M[3][0]; + v[2][1] = u[2][1]*M[1][1]+u[2][2]*M[2][1]+u[2][3]*M[3][1]; + v[2][2] = u[2][2]*M[2][2]+u[2][3]*M[3][2]; + v[2][3] = u[2][3]*M[3][3]; + v[3][0] = u[3][0]*M[0][0]+u[3][1]*M[1][0]+u[3][2]*M[2][0]+u[3][3]*M[3][0]; + v[3][1] = u[3][1]*M[1][1]+u[3][2]*M[2][1]+u[3][3]*M[3][1]; + v[3][2] = u[3][2]*M[2][2]+u[3][3]*M[3][2]; + v[3][3] = u[3][3]*M[3][3]; + + M[4][0] = -v[0][0]; + M[4][1] = -v[0][1]; + M[4][2] = -v[0][2]; + M[4][3] = -v[0][3]; + M[5][0] = -v[1][0]; + M[5][1] = -v[1][1]; + M[5][2] = -v[1][2]; + M[5][3] = -v[1][3]; + M[6][0] = -v[2][0]; + M[6][1] = -v[2][1]; + M[6][2] = -v[2][2]; + M[6][3] = -v[2][3]; + M[7][0] = -v[3][0]; + M[7][1] = -v[3][1]; + M[7][2] = -v[3][2]; + M[7][3] = -v[3][3]; + + /* + M00 0 0 0 0 0 0 0 + M10 M11 0 0 0 0 0 0 + M20 M21 M22 0 0 0 0 0 + M30 M31 M32 M33 0 0 0 0 + M40 M41 M42 M43 M44 0 0 0 + M50 M51 M52 M53 M54 M55 0 0 + M60 M61 M62 M63 M64 M65 M66 0 + M70 M71 M72 M73 M74 M75 M76 M77 + */ +} + +/** + * Solves dH = inv(JtJ) Jte. The argument lower-triangular matrix is the + * inverse of L as produced by the Cholesky decomposition LL^T of the matrix + * JtJ; Thus the operation performed here is a left-multiplication of a vector + * by two triangular matrices. The math is below: + * + * JtJ = LL^T + * Linv = L^-1 + * (JtJ)^-1 = (LL^T)^-1 + * = (L^T^-1)(Linv) + * = (Linv^T)(Linv) + * dH = ((JtJ)^-1) (Jte) + * = (Linv^T)(Linv) (Jte) + * + * where J is nx8, Jt is 8xn, JtJ is 8x8 PD, e is nx1, Jte is 8x1, L is lower + * triangular 8x8 and dH is 8x1. + */ + +static inline void sacTRISolve8x8(const float (*L)[8], + const float* Jte, + float* dH){ + float t[8]; + + t[0] = L[0][0]*Jte[0]; + t[1] = L[1][0]*Jte[0]+L[1][1]*Jte[1]; + t[2] = L[2][0]*Jte[0]+L[2][1]*Jte[1]+L[2][2]*Jte[2]; + t[3] = L[3][0]*Jte[0]+L[3][1]*Jte[1]+L[3][2]*Jte[2]+L[3][3]*Jte[3]; + t[4] = L[4][0]*Jte[0]+L[4][1]*Jte[1]+L[4][2]*Jte[2]+L[4][3]*Jte[3]+L[4][4]*Jte[4]; + t[5] = L[5][0]*Jte[0]+L[5][1]*Jte[1]+L[5][2]*Jte[2]+L[5][3]*Jte[3]+L[5][4]*Jte[4]+L[5][5]*Jte[5]; + t[6] = L[6][0]*Jte[0]+L[6][1]*Jte[1]+L[6][2]*Jte[2]+L[6][3]*Jte[3]+L[6][4]*Jte[4]+L[6][5]*Jte[5]+L[6][6]*Jte[6]; + t[7] = L[7][0]*Jte[0]+L[7][1]*Jte[1]+L[7][2]*Jte[2]+L[7][3]*Jte[3]+L[7][4]*Jte[4]+L[7][5]*Jte[5]+L[7][6]*Jte[6]+L[7][7]*Jte[7]; + + + dH[0] = L[0][0]*t[0]+L[1][0]*t[1]+L[2][0]*t[2]+L[3][0]*t[3]+L[4][0]*t[4]+L[5][0]*t[5]+L[6][0]*t[6]+L[7][0]*t[7]; + dH[1] = L[1][1]*t[1]+L[2][1]*t[2]+L[3][1]*t[3]+L[4][1]*t[4]+L[5][1]*t[5]+L[6][1]*t[6]+L[7][1]*t[7]; + dH[2] = L[2][2]*t[2]+L[3][2]*t[3]+L[4][2]*t[4]+L[5][2]*t[5]+L[6][2]*t[6]+L[7][2]*t[7]; + dH[3] = L[3][3]*t[3]+L[4][3]*t[4]+L[5][3]*t[5]+L[6][3]*t[6]+L[7][3]*t[7]; + dH[4] = L[4][4]*t[4]+L[5][4]*t[5]+L[6][4]*t[6]+L[7][4]*t[7]; + dH[5] = L[5][5]*t[5]+L[6][5]*t[6]+L[7][5]*t[7]; + dH[6] = L[6][6]*t[6]+L[7][6]*t[7]; + dH[7] = L[7][7]*t[7]; +} + +/** + * Multiply the diagonal elements of the 8x8 matrix A by 1+lambda and store to + * B. + * + * A and B may overlap exactly or not at all; Partial overlap is forbidden. + */ + +static inline void sacScaleDiag8x8(const float (*A)[8], + float lambda, + float (*B)[8]){ + float lambdap1 = lambda + 1.0f; + int i; + + if(A != B){ + memcpy((void*)B, (void*)A, 8*8*sizeof(float)); + } + + for(i=0;i<8;i++){ + B[i][i] *= lambdap1; + } +} + +/** + * Subtract dH from H. + */ + +static inline void sacSub8x1(float* Hout, const float* H, const float* dH){ + Hout[0] = H[0] - dH[0]; + Hout[1] = H[1] - dH[1]; + Hout[2] = H[2] - dH[2]; + Hout[3] = H[3] - dH[3]; + Hout[4] = H[4] - dH[4]; + Hout[5] = H[5] - dH[5]; + Hout[6] = H[6] - dH[6]; + Hout[7] = H[7] - dH[7]; +} + + + +#ifdef __cplusplus +} +#endif diff --git a/modules/calib3d/src/rhorefc.h b/modules/calib3d/src/rhorefc.h new file mode 100644 index 000000000..3c0014188 --- /dev/null +++ b/modules/calib3d/src/rhorefc.h @@ -0,0 +1,368 @@ +/* + IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. + + By downloading, copying, installing or using the software you agree to this license. + If you do not agree to this license, do not download, install, + copy or use the software. + + + BSD 3-Clause License + + Copyright (C) 2014, Olexa Bilaniuk, Hamid Bazargani & Robert Laganiere, all rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistribution's of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + * Redistribution's in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * The name of the copyright holders may not be used to endorse or promote products + derived from this software without specific prior written permission. + + This software is provided by the copyright holders and contributors "as is" and + any express or implied warranties, including, but not limited to, the implied + warranties of merchantability and fitness for a particular purpose are disclaimed. + In no event shall the Intel Corporation or contributors be liable for any direct, + indirect, incidental, special, exemplary, or consequential damages + (including, but not limited to, procurement of substitute goods or services; + loss of use, data, or profits; or business interruption) however caused + and on any theory of liability, whether in contract, strict liability, + or tort (including negligence or otherwise) arising in any way out of + the use of this software, even if advised of the possibility of such damage. +*/ + +/** + * Bilaniuk, Olexa, Hamid Bazargani, and Robert Laganiere. "Fast Target + * Recognition on Mobile Devices: Revisiting Gaussian Elimination for the + * Estimation of Planar Homographies." In Computer Vision and Pattern + * Recognition Workshops (CVPRW), 2014 IEEE Conference on, pp. 119-125. + * IEEE, 2014. + */ + +/* Include Guards */ +#ifndef __RHOREFC_H__ +#define __RHOREFC_H__ + + + +/* Includes */ + + + + + +/* Defines */ +#ifdef __cplusplus + +/* C++ does not have the restrict keyword. */ +#ifdef restrict +#undef restrict +#endif +#define restrict + +#else + +/* C99 and over has the restrict keyword. */ +#if !defined(__STDC_VERSION__) || __STDC_VERSION__ < 199901L +#define restrict +#endif + +#endif + + +/* Flags */ +#ifndef RHO_FLAG_NONE +#define RHO_FLAG_NONE (0U<<0) +#endif +#ifndef RHO_FLAG_ENABLE_NR +#define RHO_FLAG_ENABLE_NR (1U<<0) +#endif +#ifndef RHO_FLAG_ENABLE_REFINEMENT +#define RHO_FLAG_ENABLE_REFINEMENT (1U<<1) +#endif +#ifndef RHO_FLAG_ENABLE_FINAL_REFINEMENT +#define RHO_FLAG_ENABLE_FINAL_REFINEMENT (1U<<2) +#endif + + + +/* Data structures */ + +/** + * Homography Estimation context. + */ + +typedef struct{ + /** + * Virtual Arguments. + * + * Exactly the same as at function call, except: + * - minInl is enforced to be >= 4. + */ + + struct{ + const float* restrict src; + const float* restrict dst; + char* restrict inl; + unsigned N; + float maxD; + unsigned maxI; + unsigned rConvg; + double cfd; + unsigned minInl; + double beta; + unsigned flags; + const float* guessH; + float* finalH; + } arg; + + /* PROSAC Control */ + struct{ + unsigned i; /* Iteration Number */ + unsigned phNum; /* Phase Number */ + unsigned phEndI; /* Phase End Iteration */ + double phEndFpI; /* Phase floating-point End Iteration */ + unsigned phMax; /* Termination phase number */ + unsigned phNumInl; /* Number of inliers for termination phase */ + unsigned numModels; /* Number of models tested */ + unsigned* restrict smpl; /* Sample of match indexes */ + } ctrl; + + /* Current model being tested */ + struct{ + float* restrict pkdPts; /* Packed points */ + float* restrict H; /* Homography */ + char* restrict inl; /* Mask of inliers */ + unsigned numInl; /* Number of inliers */ + } curr; + + /* Best model (so far) */ + struct{ + float* restrict H; /* Homography */ + char* restrict inl; /* Mask of inliers */ + unsigned numInl; /* Number of inliers */ + } best; + + /* Non-randomness criterion */ + struct{ + unsigned* restrict tbl; /* Non-Randomness: Table */ + unsigned size; /* Non-Randomness: Size */ + double beta; /* Non-Randomness: Beta */ + } nr; + + /* SPRT Evaluator */ + struct{ + double t_M; /* t_M */ + double m_S; /* m_S */ + double epsilon; /* Epsilon */ + double delta; /* delta */ + double A; /* SPRT Threshold */ + unsigned Ntested; /* Number of points tested */ + unsigned Ntestedtotal; /* Number of points tested in total */ + int good; /* Good/bad flag */ + double lambdaAccept; /* Accept multiplier */ + double lambdaReject; /* Reject multiplier */ + } eval; + + /* Levenberg-Marquardt Refinement */ + struct{ + float* ws; /* Levenberg-Marqhard Workspace */ + float (* restrict JtJ)[8]; /* JtJ matrix */ + float (* restrict tmp1)[8]; /* Temporary 1 */ + float (* restrict tmp2)[8]; /* Temporary 2 */ + float* restrict Jte; /* Jte vector */ + } lm; +} RHO_HEST_REFC; + + + +/* Extern C */ +#ifdef __cplusplus +namespace cv{ +/* extern "C" { */ +#endif + + + +/* Functions */ + +/** + * Initialize the estimator context, by allocating the aligned buffers + * internally needed. + * + * @param [in/out] p The uninitialized estimator context to initialize. + * @return 0 if successful; non-zero if an error occured. + */ + +int rhoRefCInit(RHO_HEST_REFC* p); + + +/** + * Ensure that the estimator context's internal table for non-randomness + * criterion is at least of the given size, and uses the given beta. The table + * should be larger than the maximum number of matches fed into the estimator. + * + * A value of N of 0 requests deallocation of the table. + * + * @param [in] p The initialized estimator context + * @param [in] N If 0, deallocate internal table. If > 0, ensure that the + * internal table is of at least this size, reallocating if + * necessary. + * @param [in] beta The beta-factor to use within the table. + * @return 0 if successful; non-zero if an error occured. + */ + +int rhoRefCEnsureCapacity(RHO_HEST_REFC* p, unsigned N, double beta); + + + + +/** + * Finalize the estimator context, by freeing the aligned buffers used + * internally. + * + * @param [in] p The initialized estimator context to finalize. + */ + +void rhoRefCFini(RHO_HEST_REFC* p); + + +/** + * Estimates the homography using the given context, matches and parameters to + * PROSAC. + * + * The given context must have been initialized. + * + * The matches are provided as two arrays of N single-precision, floating-point + * (x,y) points. Points with corresponding offsets in the two arrays constitute + * a match. The homography estimation attempts to find the 3x3 matrix H which + * best maps the homogeneous-coordinate points in the source array to their + * corresponding homogeneous-coordinate points in the destination array. + * + * Note: At least 4 matches must be provided (N >= 4). + * Note: A point in either array takes up 2 floats. The first of two stores + * the x-coordinate and the second of the two stores the y-coordinate. + * Thus, the arrays resemble this in memory: + * + * src = [x0, y0, x1, y1, x2, y2, x3, y3, x4, y4, ...] + * Matches: | | | | | + * dst = [x0, y0, x1, y1, x2, y2, x3, y3, x4, y4, ...] + * Note: The matches are expected to be provided sorted by quality, or at + * least not be worse-than-random in ordering. + * + * A pointer to the base of an array of N bytes can be provided. It serves as + * an output mask to indicate whether the corresponding match is an inlier to + * the returned homography, if any. A zero indicates an outlier; A non-zero + * value indicates an inlier. + * + * The PROSAC estimator requires a few parameters of its own. These are: + * + * - The maximum distance that a source point projected onto the destination + * plane can be from its putative match and still be considered an + * inlier. Must be non-negative. + * A sane default is 3.0. + * - The maximum number of PROSAC iterations. This corresponds to the + * largest number of samples that will be drawn and tested. + * A sane default is 2000. + * - The RANSAC convergence parameter. This corresponds to the number of + * iterations after which PROSAC will start sampling like RANSAC. + * A sane default is 2000. + * - The confidence threshold. This corresponds to the probability of + * finding a correct solution. Must be bounded by [0, 1]. + * A sane default is 0.995. + * - The minimum number of inliers acceptable. Only a solution with at + * least this many inliers will be returned. The minimum is 4. + * A sane default is 10% of N. + * - The beta-parameter for the non-randomness termination criterion. + * Ignored if non-randomness criterion disabled, otherwise must be + * bounded by (0, 1). + * A sane default is 0.35. + * - Optional flags to control the estimation. Available flags are: + * HEST_FLAG_NONE: + * No special processing. + * HEST_FLAG_ENABLE_NR: + * Enable non-randomness criterion. If set, the beta parameter + * must also be set. + * HEST_FLAG_ENABLE_REFINEMENT: + * Enable refinement of each new best model, as they are found. + * HEST_FLAG_ENABLE_FINAL_REFINEMENT: + * Enable one final refinement of the best model found before + * returning it. + * + * The PROSAC estimator optionally accepts an extrinsic initial guess of H. + * + * The PROSAC estimator outputs a final estimate of H provided it was able to + * find one with a minimum of supporting inliers. If it was not, it outputs + * the all-zero matrix. + * + * The extrinsic guess at and final estimate of H are both in the same form: + * A 3x3 single-precision floating-point matrix with step 3. Thus, it is a + * 9-element array of floats, with the elements as follows: + * + * [ H00, H01, H02, + * H10, H11, H12, + * H20, H21, 1.0 ] + * + * Notice that the homography is normalized to H22 = 1.0. + * + * The function returns the number of inliers if it was able to find a + * homography with at least the minimum required support, and 0 if it was not. + * + * + * @param [in/out] p The context to use for homography estimation. Must + * be already initialized. Cannot be NULL. + * @param [in] src The pointer to the source points of the matches. + * Must be aligned to 4 bytes. Cannot be NULL. + * @param [in] dst The pointer to the destination points of the matches. + * Must be aligned to 4 bytes. Cannot be NULL. + * @param [out] inl The pointer to the output mask of inlier matches. + * Must be aligned to 4 bytes. May be NULL. + * @param [in] N The number of matches. Minimum 4. + * @param [in] maxD The maximum distance. Minimum 0. + * @param [in] maxI The maximum number of PROSAC iterations. + * @param [in] rConvg The RANSAC convergence parameter. + * @param [in] cfd The required confidence in the solution. + * @param [in] minInl The minimum required number of inliers. Minimum 4. + * @param [in] beta The beta-parameter for the non-randomness criterion. + * @param [in] flags A union of flags to fine-tune the estimation. + * @param [in] guessH An extrinsic guess at the solution H, or NULL if + * none provided. + * @param [out] finalH The final estimation of H, or the zero matrix if + * the minimum number of inliers was not met. + * Cannot be NULL. + * @return The number of inliers if the minimum number of + * inliers for acceptance was reached; 0 otherwise. + */ + +unsigned rhoRefC(RHO_HEST_REFC* restrict p, /* Homography estimation context. */ + const float* restrict src, /* Source points */ + const float* restrict dst, /* Destination points */ + char* restrict inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* 3.0 */ + unsigned maxI, /* 2000 */ + unsigned rConvg, /* 2000 */ + double cfd, /* 0.995 */ + unsigned minInl, /* 4 */ + double beta, /* 0.35 */ + unsigned flags, /* 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH); /* Final result. */ + + + + +/* Extern C */ +#ifdef __cplusplus +/* } *//* End extern "C" */ +} +#endif + + + + +#endif diff --git a/modules/calib3d/src/rhosse2.cpp b/modules/calib3d/src/rhosse2.cpp new file mode 100644 index 000000000..5fc5bc187 --- /dev/null +++ b/modules/calib3d/src/rhosse2.cpp @@ -0,0 +1,1497 @@ +/* + IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. + + By downloading, copying, installing or using the software you agree to this license. + If you do not agree to this license, do not download, install, + copy or use the software. + + + BSD 3-Clause License + + Copyright (C) 2014, Olexa Bilaniuk, Hamid Bazargani & Robert Laganiere, all rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistribution's of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + * Redistribution's in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * The name of the copyright holders may not be used to endorse or promote products + derived from this software without specific prior written permission. + + This software is provided by the copyright holders and contributors "as is" and + any express or implied warranties, including, but not limited to, the implied + warranties of merchantability and fitness for a particular purpose are disclaimed. + In no event shall the Intel Corporation or contributors be liable for any direct, + indirect, incidental, special, exemplary, or consequential damages + (including, but not limited to, procurement of substitute goods or services; + loss of use, data, or profits; or business interruption) however caused + and on any theory of liability, whether in contract, strict liability, + or tort (including negligence or otherwise) arising in any way out of + the use of this software, even if advised of the possibility of such damage. +*/ + +/** + * Bilaniuk, Olexa, Hamid Bazargani, and Robert Laganiere. "Fast Target + * Recognition on Mobile Devices: Revisiting Gaussian Elimination for the + * Estimation of Planar Homographies." In Computer Vision and Pattern + * Recognition Workshops (CVPRW), 2014 IEEE Conference on, pp. 119-125. + * IEEE, 2014. + */ + +/* Includes */ +#include +#include +#include +#include +#include +#include +#include +#include +#include "rhosse2.h" + + + +/* Defines */ +#define MEM_ALIGN 32 +#define HSIZE (3*4*sizeof(float)) +#define MIN_DELTA_CHNG 0.1 +#define REL_CHNG(a, b) (fabs((a) - (b))/(a)) +#define CHNG_SIGNIFICANT(a, b) (REL_CHNG(a, b) > MIN_DELTA_CHNG) +#define CHI_STAT 2.706 +#define CHI_SQ 1.645 + + + +namespace cv{ + +/* Data Structures */ + + + +/* Prototypes */ +static inline void* almalloc(size_t nBytes); +static inline void alfree(void* ptr); + +static inline int sacInitRun(RHO_HEST_SSE2* restrict p, + const float* restrict src, + const float* restrict dst, + char* restrict inl, + unsigned N, + float maxD, + unsigned maxI, + unsigned rConvg, + double cfd, + unsigned minInl, + double beta, + unsigned flags, + const float* guessH, + float* finalH); +static inline void sacFiniRun(RHO_HEST_SSE2* p); +static inline int sacIsNREnabled(RHO_HEST_SSE2* p); +static inline int sacIsRefineEnabled(RHO_HEST_SSE2* p); +static inline int sacIsFinalRefineEnabled(RHO_HEST_SSE2* p); +static inline int sacPhaseEndReached(RHO_HEST_SSE2* p); +static inline void sacGoToNextPhase(RHO_HEST_SSE2* p); +static inline void sacGetPROSACSample(RHO_HEST_SSE2* p); +static inline int sacIsSampleDegenerate(RHO_HEST_SSE2* p); +static inline void sacGenerateModel(RHO_HEST_SSE2* p); +static inline int sacIsModelDegenerate(RHO_HEST_SSE2* p); +static inline void sacEvaluateModelSPRT(RHO_HEST_SSE2* p); +static inline void sacUpdateSPRT(RHO_HEST_SSE2* p); +static inline void sacDesignSPRTTest(RHO_HEST_SSE2* p); +static inline int sacIsBestModel(RHO_HEST_SSE2* p); +static inline int sacIsBestModelGoodEnough(RHO_HEST_SSE2* p); +static inline void sacSaveBestModel(RHO_HEST_SSE2* p); +static inline void sacInitNonRand(double beta, + unsigned start, + unsigned N, + unsigned* nonRandMinInl); +static inline void sacNStarOptimize(RHO_HEST_SSE2* p); +static inline void sacUpdateBounds(RHO_HEST_SSE2* p); +static inline void sacOutputModel(RHO_HEST_SSE2* p); + +static inline double sacInitPEndFpI(const unsigned ransacConvg, + const unsigned n, + const unsigned m); +static inline void sacRndSmpl(unsigned sampleSize, + unsigned* currentSample, + unsigned dataSetSize); +static inline double sacRandom(void); +static inline unsigned sacCalcIterBound(double confidence, + double inlierRate, + unsigned sampleSize, + unsigned maxIterBound); +static inline void hFuncRefC(float* packedPoints, float* H); + + + +/* Functions */ + +/** + * Initialize the estimator context, by allocating the aligned buffers + * internally needed. + * + * @param [in/out] p The uninitialized estimator context to initialize. + * @return 0 if successful; non-zero if an error occured. + */ + +int rhoSSE2Init(RHO_HEST_SSE2* p){ + p->smpl = (unsigned*)almalloc(4*sizeof(*p->smpl)); + p->H = (float*) almalloc(HSIZE); + p->bestH = (float*) almalloc(HSIZE); + p->pkdPts = (float*) almalloc(4*2*2*sizeof(*p->pkdPts)); + p->nrTBL = NULL; + p->nrSize = 0; + p->nrBeta = 0.0; + + int ret = p->smpl && + p->H && + p->bestH && + p->pkdPts; + + if(!ret){ + rhoSSE2Fini(p); + } + + return ret; +} + + +/** + * Ensure that the estimator context's internal table for non-randomness + * criterion is at least of the given size, and uses the given beta. The table + * should be larger than the maximum number of matches fed into the estimator. + * + * A value of N of 0 requests deallocation of the table. + * + * @param [in] p The initialized estimator context + * @param [in] N If 0, deallocate internal table. If > 0, ensure that the + * internal table is of at least this size, reallocating if + * necessary. + * @param [in] beta The beta-factor to use within the table. + * @return 1 if successful; 0 if an error occured. + */ + +int rhoSSE2EnsureCapacity(RHO_HEST_SSE2* p, unsigned N, double beta){ + unsigned* tmp; + + + if(N == 0){ + /* Deallocate table */ + alfree(p->nrTBL); + p->nrTBL = NULL; + p->nrSize = 0; + }else{ + /* Ensure table at least as big as N and made for correct beta. */ + if(p->nrTBL && p->nrBeta == beta && p->nrSize >= N){ + /* Table already correctly set up */ + }else{ + if(p->nrSize < N){ + /* Reallocate table because it is too small. */ + tmp = (unsigned*)almalloc(N*sizeof(unsigned)); + if(!tmp){ + return 0; + } + + /* Must recalculate in whole or part. */ + if(p->nrBeta != beta){ + /* Beta changed; recalculate in whole. */ + sacInitNonRand(beta, 0, N, tmp); + alfree(p->nrTBL); + }else{ + /* Beta did not change; Copy over any work already done. */ + memcpy(tmp, p->nrTBL, p->nrSize*sizeof(unsigned)); + sacInitNonRand(beta, p->nrSize, N, tmp); + alfree(p->nrTBL); + } + + p->nrTBL = tmp; + p->nrSize = N; + p->nrBeta = beta; + }else{ + /* Might recalculate in whole, or not at all. */ + if(p->nrBeta != beta){ + /* Beta changed; recalculate in whole. */ + sacInitNonRand(beta, 0, p->nrSize, p->nrTBL); + p->nrBeta = beta; + }else{ + /* Beta did not change; Table was already big enough. Do nothing. */ + /* Besides, this is unreachable. */ + } + } + } + } + + return 1; +} + + +/** + * Finalize the estimator context, by freeing the aligned buffers used + * internally. + * + * @param [in] p The initialized estimator context to finalize. + */ + +void rhoSSE2Fini(RHO_HEST_SSE2* p){ + alfree(p->smpl); + alfree(p->H); + alfree(p->bestH); + alfree(p->pkdPts); + alfree(p->nrTBL); +} + + +/** + * Estimates the homography using the given context, matches and parameters to + * PROSAC. + * + * @param [in/out] p The context to use for homography estimation. Must + * be already initialized. Cannot be NULL. + * @param [in] src The pointer to the source points of the matches. + * Must be aligned to 16 bytes. Cannot be NULL. + * @param [in] dst The pointer to the destination points of the matches. + * Must be aligned to 16 bytes. Cannot be NULL. + * @param [out] bestInl The pointer to the output mask of inlier matches. + * Must be aligned to 16 bytes. May be NULL. + * @param [in] N The number of matches. + * @param [in] maxD The maximum distance. + * @param [in] maxI The maximum number of PROSAC iterations. + * @param [in] rConvg The RANSAC convergence parameter. + * @param [in] cfd The required confidence in the solution. + * @param [in] minInl The minimum required number of inliers. + * @param [in] beta The beta-parameter for the non-randomness criterion. + * @param [in] flags A union of flags to control the estimation. + * @param [in] guessH An extrinsic guess at the solution H, or NULL if + * none provided. + * @param [out] finalH The final estimation of H, or the zero matrix if + * the minimum number of inliers was not met. + * Cannot be NULL. + * @return The number of inliers if the minimum number of + * inliers for acceptance was reached; 0 otherwise. + */ + +unsigned rhoSSE2(RHO_HEST_SSE2* restrict p, /* Homography estimation context. */ + const float* restrict src, /* Source points */ + const float* restrict dst, /* Destination points */ + char* restrict bestInl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* 3.0 */ + unsigned maxI, /* 2000 */ + unsigned rConvg, /* 2000 */ + double cfd, /* 0.995 */ + unsigned minInl, /* 4 */ + double beta, /* 0.35 */ + unsigned flags, /* 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH){ /* Final result. */ + + /** + * Setup + */ + + if(!sacInitRun(p, src, dst, bestInl, N, maxD, maxI, rConvg, cfd, minInl, beta, flags, guessH, finalH)){ + sacFiniRun(p); + return 0; + } + + + /** + * PROSAC Loop + */ + + for(p->i=0; p->i < p->maxI; p->i++){ + if(sacPhaseEndReached(p)){ + sacGoToNextPhase(p); + } + + sacGetPROSACSample(p); + if(sacIsSampleDegenerate(p)){ + continue; + } + + sacGenerateModel(p); + if(sacIsModelDegenerate(p)){ + continue; + } + + sacEvaluateModelSPRT(p); + sacUpdateSPRT(p); + if(sacIsBestModel(p)){ + if(sacIsRefineEnabled(p)){ + /* sacRefine(p) */ + } + + sacSaveBestModel(p); + sacUpdateBounds(p); + + if(sacIsNREnabled(p)){ + sacNStarOptimize(p); + } + } + } + + + /** + * Teardown + */ + + if(sacIsFinalRefineEnabled(p)){ + /* sacRefineFinal(p) */ + } + + sacOutputModel(p); + sacFiniRun(p); + return sacIsBestModelGoodEnough(p) ? p->bestNumInl : 0; +} + + +/** + * Allocate memory aligned to a boundary of MEMALIGN. + */ + +static inline void* almalloc(size_t nBytes){ + if(nBytes){ + unsigned char* ptr = (unsigned char*)malloc(MEM_ALIGN + nBytes); + if(ptr){ + unsigned char* adj = (unsigned char*)(((intptr_t)(ptr+MEM_ALIGN))&((intptr_t)(-MEM_ALIGN))); + ptrdiff_t diff = adj - ptr; + adj[-1] = diff - 1; + return adj; + } + } + + return NULL; +} + +/** + * Free aligned memory + */ + +static inline void alfree(void* ptr){ + if(ptr){ + unsigned char* cptr = (unsigned char*)ptr; + free(cptr - (ptrdiff_t)cptr[-1] - 1); + } +} + + +/** + * Initialize SAC for a run. + * + * Passed all the arguments of hest. + */ + +static inline int sacInitRun(RHO_HEST_SSE2* restrict p, + const float* restrict src, + const float* restrict dst, + char* restrict bestInl, + unsigned N, + float maxD, + unsigned maxI, + unsigned rConvg, + double cfd, + unsigned minInl, + double beta, + unsigned flags, + const float* guessH, + float* finalH){ + p->src = src; + p->dst = dst; + p->allocBestInl = !bestInl; + p->bestInl = bestInl ? bestInl : (char*)almalloc(N); + p->inl = (char*)almalloc(N); + p->N = N; + p->maxD = maxD; + p->maxI = maxI; + p->rConvg = rConvg; + p->cfd = cfd; + p->minInl = minInl < 4 ? 4 : minInl; + p->beta = beta; + p->flags = flags; + p->guessH = guessH; + p->finalH = finalH; + + if(p->guessH){ + memcpy(p->H, p->guessH, HSIZE); + } + memset(p->bestH, 0, HSIZE); + memset(p->finalH, 0, HSIZE); + + if(!p->inl || !p->bestInl){/* Malloc failure */ + return 0; + } + if(sacIsNREnabled(p) && !rhoSSE2EnsureCapacity(p, N, beta)){ + return 0; + } + + p->phNum = 4; + p->phEndI = 1; + p->phEndFpI = sacInitPEndFpI(p->rConvg, p->N, 4); + p->phMax = p->N; + p->phNumInl = 0; + p->bestNumInl = 0; + p->numInl = 0; + p->numModels = 0; + p->Ntested = 0; + p->Ntestedtotal = 0; + p->good = 1; + p->t_M = 25; + p->m_S = 1; + p->epsilon = 0.1; + p->delta = 0.01; + sacDesignSPRTTest(p); + + return 1; +} + +/** + * Finalize SAC run. + * + * @param p + */ + +static inline void sacFiniRun(RHO_HEST_SSE2* p){ + if(p->allocBestInl){ + alfree(p->bestInl); + } + alfree(p->inl); +} + +/** + * Check whether non-randomness criterion is enabled. + * + * @param p + * @return Zero if disabled; non-zero if not. + */ + +static inline int sacIsNREnabled(RHO_HEST_SSE2* p){ + return p->flags & RHO_FLAG_ENABLE_NR; +} + +/** + * Check whether best-model-so-far refinement is enabled. + * + * @param p + * @return Zero if disabled; non-zero if not. + */ + +static inline int sacIsRefineEnabled(RHO_HEST_SSE2* p){ + return p->flags & RHO_FLAG_ENABLE_REFINEMENT; +} + +/** + * Check whether final-model refinement is enabled. + * + * @param p + * @return Zero if disabled; non-zero if not. + */ + +static inline int sacIsFinalRefineEnabled(RHO_HEST_SSE2* p){ + return p->flags & RHO_FLAG_ENABLE_FINAL_REFINEMENT; +} + +/** + * @brief sacPhaseEndReached + * @param p + * @return + */ + +static inline int sacPhaseEndReached(RHO_HEST_SSE2* p){ + return p->i >= p->phEndI && p->phNum < p->phMax; +} + +/** + * @brief sacGoToNextPhase + * @param p + */ + +static inline void sacGoToNextPhase(RHO_HEST_SSE2* p){ + double next; + unsigned m = 4; + + p->phNum++; + next = (p->phEndFpI * p->phNum)/(p->phNum - m); + p->phEndI += ceil(next - p->phEndFpI); + p->phEndFpI = next; +} + +/** + * @brief sacGetPROSACSample + * @param p + */ + +static inline void sacGetPROSACSample(RHO_HEST_SSE2* p){ + if(p->i > p->phEndI){ + sacRndSmpl(4, p->smpl, p->phNum);/* Used to be phMax */ + }else{ + sacRndSmpl(3, p->smpl, p->phNum-1); + p->smpl[3] = p->phNum-1; + } +} + +/** + * @brief sacIsSampleDegenerate + * @param p + * @return + */ + +static inline int sacIsSampleDegenerate(RHO_HEST_SSE2* p){ + unsigned i0 = p->smpl[0], i1 = p->smpl[1], i2 = p->smpl[2], i3 = p->smpl[3]; + + /** + * Pack the matches selected by the SAC algorithm. + * Must be packed points[0:7] = {srcx0, srcy0, srcx1, srcy1, srcx2, srcy2, srcx3, srcy3} + * points[8:15] = {dstx0, dsty0, dstx1, dsty1, dstx2, dsty2, dstx3, dsty3} + * Gather 4 points into the vector + */ + + __m128 src10 = _mm_castpd_ps(_mm_load_sd((const double*)&p->src[2*i0])); + src10 = _mm_loadh_pi(src10, (__m64*)&p->src[2*i1]); + __m128 src32 = _mm_castpd_ps(_mm_load_sd((const double*)&p->src[2*i2])); + src32 = _mm_loadh_pi(src32, (__m64*)&p->src[2*i3]); + __m128 dst10 = _mm_castpd_ps(_mm_load_sd((const double*)&p->dst[2*i0])); + dst10 = _mm_loadh_pi(dst10, (__m64*)&p->dst[2*i1]); + __m128 dst32 = _mm_castpd_ps(_mm_load_sd((const double*)&p->dst[2*i2])); + dst32 = _mm_loadh_pi(dst32, (__m64*)&p->dst[2*i3]); + + + /** + * If the matches' source points have common x and y coordinates, abort. + */ + + /** + * Check: + * packedPoints[0].x == packedPoints[2].x + * packedPoints[0].y == packedPoints[2].y + * packedPoints[1].x == packedPoints[3].x + * packedPoints[1].y == packedPoints[3].y + */ + + __m128 chkEq0 = _mm_cmpeq_ps(src10, src32); + + /** + * Check: + * packedPoints[1].x == packedPoints[2].x + * packedPoints[1].y == packedPoints[2].y + * packedPoints[0].x == packedPoints[3].x + * packedPoints[0].y == packedPoints[3].y + */ + + __m128 chkEq1 = _mm_cmpeq_ps(_mm_shuffle_ps(src10, src10, _MM_SHUFFLE(1, 0, 3, 2)), src32); + + /** + * Check: + * packedPoints[0].x == packedPoints[1].x + * packedPoints[0].y == packedPoints[1].y + * packedPoints[2].x == packedPoints[3].x + * packedPoints[2].y == packedPoints[3].y + */ + + __m128 chkEq2 = _mm_cmpeq_ps(_mm_shuffle_ps(src10, src32, _MM_SHUFFLE(1, 0, 1, 0)), + _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(3, 2, 3, 2))); + + /* Verify */ + if(_mm_movemask_ps(_mm_or_ps(chkEq0, _mm_or_ps(chkEq1, chkEq2)))){ + return 1; + } + + /* If the matches do not satisfy the strong geometric constraint, abort. */ + + /** + * p6420x = (p6.x, p4.x, p2.x, p0.x) + * p6420y = (p6.y, p4.y, p2.y, p0.y) + * p7531x = (p7.x, p5.x, p3.x, p1.x) + * p7531y = (p7.y, p5.y, p3.y, p1.y) + * crosssd0 = p6420y - p7531y = (cross2d0, cross0d0, cross2s0, cross0s0) + * crosssd1 = p7531x - p6420x = (cross2d1, cross0d1, cross2s1, cross0s1) + * crosssd2 = p6420x * p7531y - p6420y * p7531x = (cross2d2, cross0d2, cross2s2, cross0s2) + * + * shufcrosssd0 = (cross0d0, cross2d0, cross0s0, cross2s0) + * shufcrosssd1 = (cross0d1, cross2d1, cross0s1, cross2s1) + * shufcrosssd2 = (cross0d2, cross2d2, cross0s2, cross2s2) + * + * dotsd0 = shufcrosssd0 * p6420x + + * shufcrosssd1 * p6420y + + * shufcrosssd2 + * = (dotd0, dotd2, dots0, dots2) + * dotsd1 = shufcrosssd0 * p7531x + + * shufcrosssd1 * p7531y + + * shufcrosssd2 + * = (dotd1, dotd3, dots1, dots3) + * + * dots = shufps(dotsd0, dotsd1, _MM_SHUFFLE(1, 0, 1, 0)) + * dotd = shufps(dotsd0, dotsd1, _MM_SHUFFLE(3, 2, 3, 2)) + * movmaskps(dots ^ dotd) + */ + + __m128 p3210x = _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(2, 0, 2, 0)); + __m128 p3210y = _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(3, 1, 3, 1)); + __m128 p7654x = _mm_shuffle_ps(dst10, dst32, _MM_SHUFFLE(2, 0, 2, 0)); + __m128 p7654y = _mm_shuffle_ps(dst10, dst32, _MM_SHUFFLE(3, 1, 3, 1)); + __m128 p6420x = _mm_shuffle_ps(p3210x, p7654x, _MM_SHUFFLE(2, 0, 2, 0)); + __m128 p6420y = _mm_shuffle_ps(p3210y, p7654y, _MM_SHUFFLE(2, 0, 2, 0)); + __m128 p7531x = _mm_shuffle_ps(p3210x, p7654x, _MM_SHUFFLE(3, 1, 3, 1)); + __m128 p7531y = _mm_shuffle_ps(p3210y, p7654y, _MM_SHUFFLE(3, 1, 3, 1)); + + __m128 crosssd0 = _mm_sub_ps(p6420y, p7531y); + __m128 crosssd1 = _mm_sub_ps(p7531x, p6420x); + __m128 crosssd2 = _mm_sub_ps(_mm_mul_ps(p6420x, p7531y), _mm_mul_ps(p6420y, p7531x)); + + __m128 shufcrosssd0 = _mm_shuffle_ps(crosssd0, crosssd0, _MM_SHUFFLE(2, 3, 0, 1)); + __m128 shufcrosssd1 = _mm_shuffle_ps(crosssd1, crosssd1, _MM_SHUFFLE(2, 3, 0, 1)); + __m128 shufcrosssd2 = _mm_shuffle_ps(crosssd2, crosssd2, _MM_SHUFFLE(2, 3, 0, 1)); + + __m128 dotsd0 = _mm_add_ps(_mm_add_ps(_mm_mul_ps(shufcrosssd0, p6420x), + _mm_mul_ps(shufcrosssd1, p6420y)), + shufcrosssd2); + __m128 dotsd1 = _mm_add_ps(_mm_add_ps(_mm_mul_ps(shufcrosssd0, p7531x), + _mm_mul_ps(shufcrosssd1, p7531y)), + shufcrosssd2); + + __m128 dots = _mm_shuffle_ps(dotsd0, dotsd1, _MM_SHUFFLE(0, 1, 0, 1)); + __m128 dotd = _mm_shuffle_ps(dotsd0, dotsd1, _MM_SHUFFLE(2, 3, 2, 3)); + + /* if(_mm_movemask_ps(_mm_cmpge_ps(_mm_setzero_ps(), _mm_mul_ps(dots, dotd)))){ */ + if(_mm_movemask_epi8(_mm_cmplt_epi32(_mm_xor_si128(_mm_cvtps_epi32(dots), _mm_cvtps_epi32(dotd)), _mm_setzero_si128()))){ + return 1; + } + + + /* Otherwise, proceed with evaluation */ + _mm_store_ps(&p->pkdPts[0], src10); + _mm_store_ps(&p->pkdPts[4], src32); + _mm_store_ps(&p->pkdPts[8], dst10); + _mm_store_ps(&p->pkdPts[12], dst32); + + return 0; +} + +/** + * Compute homography of matches in p->pkdPts with hFuncRefC and store in p->H. + * + * @param p + */ + +static inline void sacGenerateModel(RHO_HEST_SSE2* p){ + hFuncRefC(p->pkdPts, p->H); +} + +/** + * @brief sacIsModelDegenerate + * @param p + * @return + */ + +static inline int sacIsModelDegenerate(RHO_HEST_SSE2* p){ + int degenerate; + float* H = p->H; + float f=H[0]+H[1]+H[2]+H[4]+H[5]+H[6]+H[8]+H[9]; + + /* degenerate = isnan(f); */ + degenerate = f!=f;/* Only NaN is not equal to itself. */ + /* degenerate = 0; */ + + if(degenerate){return degenerate;} + +#if 0 + + /** + * Convexity test + * + * x' = Hx for i=1..4 must be convex. + * + * [ x' ] [ H00 H01 H02 ] [ x ] + * [ y' ] = [ H10 H11 H12 ] [ y ], where: + * [ z' ] [ H20 H21 H22 ] [ 1 ] + * + * p0 = (0, 0) + * p1 = (0, 1) + * p2 = (1, 1) + * p3 = (1, 0) + */ + + float pt[4][2]; + float pz[4][1]; + + pt[0][0] = H[2]; + pt[0][1] = H[6]; + pz[0][0] = H[10]; + pt[1][0] = H[1]+H[2]; + pt[1][1] = H[5]+H[6]; + pz[1][0] = H[9]+H[10]; + pt[2][0] = H[0]+H[1]+H[2]; + pt[2][1] = H[4]+H[5]+H[6]; + pz[2][0] = H[8]+H[9]+H[10]; + pt[3][0] = H[0]+H[2]; + pt[3][1] = H[4]+H[6]; + pz[3][0] = H[8]+H[10]; + + pt[0][0] /= pz[0][0]; + pt[0][1] /= pz[0][0]; + pt[1][0] /= pz[1][0]; + pt[1][1] /= pz[1][0]; + pt[2][0] /= pz[2][0]; + pt[2][1] /= pz[2][0]; + pt[3][0] /= pz[3][0]; + pt[3][1] /= pz[3][0]; + + /** + * Crossproduct: + * + * (x, y, z) = (ay bz - az by, + * az bx - ax bz, + * ax by - ay bx) + */ + + __m128 src10 = _mm_load_ps(&pt[0][0]); + __m128 src32 = _mm_load_ps(&pt[2][0]); + + __m128 p3210x = _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(2, 0, 2, 0)); + __m128 p3210y = _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(3, 1, 3, 1)); + __m128 p2103x = _mm_shuffle_ps(p3210x, p3210x, _MM_SHUFFLE(2, 1, 0, 3)); + __m128 p2103y = _mm_shuffle_ps(p3210y, p3210y, _MM_SHUFFLE(2, 1, 0, 3)); + __m128 vax = _mm_sub_ps(p3210x, p2103x); + __m128 vay = _mm_sub_ps(p3210y, p2103y); + __m128 vbx = _mm_shuffle_ps(vax, vax, _MM_SHUFFLE(2, 1, 0, 3)); + __m128 vby = _mm_shuffle_ps(vay, vay, _MM_SHUFFLE(2, 1, 0, 3)); + + __m128 cross = _mm_sub_ps(_mm_mul_ps(vax, vby), _mm_mul_ps(vay, vbx)); + + degenerate = _mm_movemask_ps(cross); + degenerate = degenerate != 0x0; +#endif + return degenerate; +} + +/** + * @brief sacEvaluateModelSPRT + * @param p + */ + +static inline void sacEvaluateModelSPRT(RHO_HEST_SSE2* p){ + unsigned i = 0; + unsigned isInlier; + double lambda = 1.0; + float distSq = p->maxD*p->maxD; + const float* src = p->src; + const float* dst = p->dst; + char* inl = p->inl; + float* H = p->H; + + + p->numModels++; + + p->numInl = 0; + p->Ntested = 0; + p->good = 1; + + + /* VECTOR */ + const __m128 distSqV=_mm_set1_ps(distSq); + + const __m128 H00=_mm_set1_ps(H[0]); + const __m128 H01=_mm_set1_ps(H[1]); + const __m128 H02=_mm_set1_ps(H[2]); + const __m128 H10=_mm_set1_ps(H[4]); + const __m128 H11=_mm_set1_ps(H[5]); + const __m128 H12=_mm_set1_ps(H[6]); + const __m128 H20=_mm_set1_ps(H[8]); + const __m128 H21=_mm_set1_ps(H[9]); + const __m128 H22=_mm_set1_ps(H[10]); + + for(;i<(p->N-3) && p->good;i+=4){ + /* Backproject */ + __m128 x, y, X, Y, inter0, inter1, inter2, inter3; + inter0 = _mm_loadu_ps(src+2*i); + inter1 = _mm_loadu_ps(src+2*i+4); + inter2 = _mm_loadu_ps(dst+2*i); + inter3 = _mm_loadu_ps(dst+2*i+4); + + x = _mm_shuffle_ps(inter0, inter1, _MM_SHUFFLE(2, 0, 2, 0)); + y = _mm_shuffle_ps(inter0, inter1, _MM_SHUFFLE(3, 1, 3, 1)); + X = _mm_shuffle_ps(inter2, inter3, _MM_SHUFFLE(2, 0, 2, 0)); + Y = _mm_shuffle_ps(inter2, inter3, _MM_SHUFFLE(3, 1, 3, 1)); + + __m128 reprojX = _mm_add_ps(_mm_add_ps(_mm_mul_ps(H00, x), _mm_mul_ps(H01, y)), H02); + __m128 reprojY = _mm_add_ps(_mm_add_ps(_mm_mul_ps(H10, x), _mm_mul_ps(H11, y)), H12); + __m128 reprojZ = _mm_add_ps(_mm_add_ps(_mm_mul_ps(H20, x), _mm_mul_ps(H21, y)), H22); + + __m128 recipZ = _mm_rcp_ps(reprojZ); + reprojX = _mm_mul_ps(reprojX, recipZ); + reprojY = _mm_mul_ps(reprojY, recipZ); + /* reprojX = _mm_div_ps(reprojX, reprojZ); */ + /* reprojY = _mm_div_ps(reprojY, reprojZ); */ + + reprojX = _mm_sub_ps(reprojX, X); + reprojY = _mm_sub_ps(reprojY, Y); + + reprojX = _mm_mul_ps(reprojX, reprojX); + reprojY = _mm_mul_ps(reprojY, reprojY); + + __m128 reprojDistV = _mm_add_ps(reprojX, reprojY); + + __m128 cmp = _mm_cmple_ps(reprojDistV, distSqV); + int msk = _mm_movemask_ps(cmp); + + /* ... */ + /* 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15*/ + static const unsigned bitCnt[16] = {0, 1, 1, 2, 1, 2, 2, 3, 1, 2, 2, 3, 2, 3, 3, 4}; + p->numInl += bitCnt[msk]; + + static const char byteMsk[16][4] = {{0,0,0,0},{1,0,0,0},{0,1,0,0},{1,1,0,0}, + {0,0,1,0},{1,0,1,0},{0,1,1,0},{1,1,1,0}, + {0,0,0,1},{1,0,0,1},{0,1,0,1},{1,1,0,1}, + {0,0,1,1},{1,0,1,1},{0,1,1,1},{1,1,1,1}}; + memcpy(inl, byteMsk[msk], 4); + inl+=4; + + + /* SPRT */ + lambda *= p->lambdaTBL[msk]; + p->good = lambda <= p->A; + /* If !p->good, the threshold A was exceeded, so we're rejecting */ + } + + /* SCALAR */ + for(;iN && p->good;i++){ + /* Backproject */ + float x=src[i*2],y=src[i*2+1]; + float X=dst[i*2],Y=dst[i*2+1]; + + float reprojX=H[0]*x+H[1]*y+H[2]; /* ( X_1 ) ( H_11 H_12 H_13 ) (x_1) */ + float reprojY=H[4]*x+H[5]*y+H[6]; /* ( X_2 ) = ( H_21 H_22 H_23 ) (x_2) */ + float reprojZ=H[8]*x+H[9]*y+H[10];/* ( X_3 ) ( H_31 H_32 H_33=1.0 ) (x_3 = 1.0) */ + + /* reproj is in homogeneous coordinates. To bring back to "regular" coordinates, divide by Z. */ + reprojX/=reprojZ; + reprojY/=reprojZ; + + /* Compute distance */ + reprojX-=X; + reprojY-=Y; + reprojX*=reprojX; + reprojY*=reprojY; + float reprojDist = reprojX+reprojY; + + /* ... */ + isInlier = reprojDist <= distSq; + p->numInl += isInlier; + *inl++ = isInlier; + + + /* SPRT */ + lambda *= isInlier ? p->lambdaAccept : p->lambdaReject; + p->good = lambda <= p->A; + /* If !p->good, the threshold A was exceeded, so we're rejecting */ + } + + + p->Ntested = i; + p->Ntestedtotal += i; +} + +/** + * Update either the delta or epsilon SPRT parameters, depending on the events + * that transpired in the previous evaluation. + * + * If a "good" model that is also the best was encountered, update epsilon, + * since + */ + +static inline void sacUpdateSPRT(RHO_HEST_SSE2* p){ + if(p->good){ + if(sacIsBestModel(p)){ + p->epsilon = (double)p->numInl/p->N; + sacDesignSPRTTest(p); + } + }else{ + double newDelta = (double)p->numInl/p->Ntested; + + if(newDelta > 0 && CHNG_SIGNIFICANT(p->delta, newDelta)){ + p->delta = newDelta; + sacDesignSPRTTest(p); + } + } +} + +/** + * Numerically compute threshold A from the estimated delta, epsilon, t_M and + * m_S values. + * + * Epsilon: Denotes the probability that a randomly chosen data point is + * consistent with a good model. + * Delta: Denotes the probability that a randomly chosen data point is + * consistent with a bad model. + * t_M: Time needed to instantiate a model hypotheses given a sample. + * (Computing model parameters from a sample takes the same time + * as verification of t_M data points) + * m_S: The number of models that are verified per sample. + */ + +static inline double designSPRTTest(double delta, double epsilon, double t_M, double m_S){ + double An, C, K, prevAn; + unsigned i; + + /** + * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 + * Eq (2) + */ + + C = (1-delta) * log((1-delta)/(1-epsilon)) + + delta * log( delta / epsilon ); + + /** + * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 + * Eq (6) + * K = K_1/K_2 + 1 = (t_M*C)/m_S + 1 + */ + + K = t_M*C/m_S + 1; + + /** + * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 + * Paragraph below Eq (6) + * + * A* = lim_{n -> infty} A_n, where + * A_0 = K1/K2 + 1 and + * A_{n+1} = K1/K2 + 1 + log(A_n) + * The series converges fast, typically within four iterations. + */ + + An = K; + i = 0; + + do{ + prevAn = An; + An = K + log(An); + }while((An-prevAn > 1.5e-8) && (++i < 10)); + + /** + * Return A = An_stopping, with n_stopping < 10 + */ + + return An; +} + +/** + * Design the SPRT test. Shorthand for + * A = sprt(delta, epsilon, t_M, m_S); + * + * Sets p->A, p->lambdaAccept, p->lambdaReject and p->lambdaLUT + */ + +static inline void sacDesignSPRTTest(RHO_HEST_SSE2* p){ + p->A = designSPRTTest(p->delta, p->epsilon, p->t_M, p->m_S); + p->lambdaReject = ((1.0 - p->delta) / (1.0 - p->epsilon)); + p->lambdaAccept = (( p->delta ) / ( p->epsilon )); + + double a0r4 = p->lambdaReject*p->lambdaReject*p->lambdaReject*p->lambdaReject; + double a1r3 = p->lambdaAccept*p->lambdaReject*p->lambdaReject*p->lambdaReject; + double a2r2 = p->lambdaAccept*p->lambdaAccept*p->lambdaReject*p->lambdaReject; + double a3r1 = p->lambdaAccept*p->lambdaAccept*p->lambdaAccept*p->lambdaReject; + double a4r0 = p->lambdaAccept*p->lambdaAccept*p->lambdaAccept*p->lambdaAccept; + + p->lambdaTBL[ 0] = a0r4; + p->lambdaTBL[ 1] = p->lambdaTBL[ 2] = p->lambdaTBL[ 4] = p->lambdaTBL[ 8] = a1r3; + p->lambdaTBL[ 3] = p->lambdaTBL[ 5] = p->lambdaTBL[ 6] = p->lambdaTBL[ 9] = p->lambdaTBL[10] = p->lambdaTBL[12] = a2r2; + p->lambdaTBL[ 7] = p->lambdaTBL[11] = p->lambdaTBL[13] = p->lambdaTBL[14] = a3r1; + p->lambdaTBL[15] = a4r0; +} + +/** + * Return whether the current model is the best model so far. + */ + +static inline int sacIsBestModel(RHO_HEST_SSE2* p){ + return p->numInl > p->bestNumInl; +} + +/** + * Returns whether the current-best model is good enough to be an + * acceptable best model, by checking whether it meets the minimum + * number of inliers. + */ + +static inline int sacIsBestModelGoodEnough(RHO_HEST_SSE2* p){ + return p->bestNumInl >= p->minInl; +} + +/** + * + */ + +static inline void sacSaveBestModel(RHO_HEST_SSE2* p){ + p->bestNumInl = p->numInl; + memcpy(p->bestH, p->H, HSIZE); + memcpy(p->bestInl, p->inl, p->N); +} + +/** + * + */ + +static inline void sacInitNonRand(double beta, + unsigned start, + unsigned N, + unsigned* nonRandMinInl){ + unsigned m = 4; + unsigned n = m+1 > start ? m+1 : start; + double beta_beta1_sq_chi = sqrt(beta*(1.0-beta)) * CHI_SQ; + + for(; n < N; n++){ + double mu = n * beta; + double sigma = sqrt(n)* beta_beta1_sq_chi; + unsigned i_min = ceil(m + mu + sigma); + + nonRandMinInl[n] = i_min; + } +} + +/** + * + */ + +static inline void sacNStarOptimize(RHO_HEST_SSE2* p){ + unsigned min_sample_length = 10*2; /*(p->N * INLIERS_RATIO) */ + unsigned best_n = p->N; + unsigned test_n = best_n; + unsigned bestNumInl = p->bestNumInl; + unsigned testNumInl = bestNumInl; + + for(;test_n > min_sample_length && testNumInl;test_n--){ + if(testNumInl*best_n > bestNumInl*test_n){ + if(testNumInl < p->nrTBL[test_n]){ + break; + } + best_n = test_n; + bestNumInl = testNumInl; + } + testNumInl -= !!p->bestInl[test_n-1]; + } + + if(bestNumInl*p->phMax > p->phNumInl*best_n){ + p->phMax = best_n; + p->phNumInl = bestNumInl; + p->maxI = sacCalcIterBound(p->cfd, + (double)p->phNumInl/p->phMax, + 4, + p->maxI); + } +} + +/** + * + */ + +static inline void sacUpdateBounds(RHO_HEST_SSE2* p){ + p->maxI = sacCalcIterBound(p->cfd, + (double)p->bestNumInl/p->N, + 4, + p->maxI); +} + +/** + * @brief sacOutputModel + * @param p + */ + +static inline void sacOutputModel(RHO_HEST_SSE2* p){ + if(!sacIsBestModelGoodEnough(p)){ + memset(p->bestH, 0, HSIZE); + } + + if(p->finalH){ + memcpy(p->finalH, p->bestH, HSIZE); + } +} + +/** + * Compute the real-valued number of samples per phase, given the RANSAC convergence speed, + * data set size and sample size. + */ + +static inline double sacInitPEndFpI(const unsigned ransacConvg, + const unsigned n, + const unsigned m){ + double numer=1, denom=1; + + unsigned i; + for(i=0;idataSetSize){ + /** + * Selection Sampling: + * + * Algorithm S (Selection sampling technique). To select n records at random from a set of N, where 0 < n ≤ N. + * S1. [Initialize.] Set t ← 0, m ← 0. (During this algorithm, m represents the number of records selected so far, + * and t is the total number of input records that we have dealt with.) + * S2. [Generate U.] Generate a random number U, uniformly distributed between zero and one. + * S3. [Test.] If (N – t)U ≥ n – m, go to step S5. + * S4. [Select.] Select the next record for the sample, and increase m and t by 1. If m < n, go to step S2; + * otherwise the sample is complete and the algorithm terminates. + * S5. [Skip.] Skip the next record (do not include it in the sample), increase t by 1, and go back to step S2. + */ + + unsigned m=0,t=0; + + for(m=0;m=1.){ + /** + * A certainty of picking at least one outlier means that we will need + * an infinite amount of iterations in order to find a correct solution. + */ + + retVal = maxIterBound; + }else if(atLeastOneOutlierProbability<=0.){ + /** + * The certainty of NOT picking an outlier means that only 1 iteration + * is needed to find a solution. + */ + + retVal = 1; + }else{ + /** + * Since 1-confidence (the probability of the model being based on at + * least one outlier in the data) is equal to + * (1-inlierRate**sampleSize)**numIterations (the probability of picking + * at least one outlier in numIterations samples), we can isolate + * numIterations (the return value) into + */ + + retVal = ceil(log(1.-confidence)/log(atLeastOneOutlierProbability)); + } + + /** + * Clamp to maxIterationBound. + */ + + return retVal <= maxIterBound ? retVal : maxIterBound; +} + + +/* Transposed, C */ +static void hFuncRefC(float* packedPoints,/* Source (four x,y float coordinates) points followed by + destination (four x,y float coordinates) points, aligned by 32 bytes */ + float* H){ /* Homography (three 16-byte aligned rows of 3 floats) */ + float x0=*packedPoints++; + float y0=*packedPoints++; + float x1=*packedPoints++; + float y1=*packedPoints++; + float x2=*packedPoints++; + float y2=*packedPoints++; + float x3=*packedPoints++; + float y3=*packedPoints++; + float X0=*packedPoints++; + float Y0=*packedPoints++; + float X1=*packedPoints++; + float Y1=*packedPoints++; + float X2=*packedPoints++; + float Y2=*packedPoints++; + float X3=*packedPoints++; + float Y3=*packedPoints++; + + float x0X0=x0*X0, x1X1=x1*X1, x2X2=x2*X2, x3X3=x3*X3; + float x0Y0=x0*Y0, x1Y1=x1*Y1, x2Y2=x2*Y2, x3Y3=x3*Y3; + float y0X0=y0*X0, y1X1=y1*X1, y2X2=y2*X2, y3X3=y3*X3; + float y0Y0=y0*Y0, y1Y1=y1*Y1, y2Y2=y2*Y2, y3Y3=y3*Y3; + + + /** + * [0] [1] Hidden Prec + * x0 y0 1 x1 + * x1 y1 1 x1 + * x2 y2 1 x1 + * x3 y3 1 x1 + * + * Eliminate ones in column 2 and 5. + * R(0)-=R(2) + * R(1)-=R(2) + * R(3)-=R(2) + * + * [0] [1] Hidden Prec + * x0-x2 y0-y2 0 x1+1 + * x1-x2 y1-y2 0 x1+1 + * x2 y2 1 x1 + * x3-x2 y3-y2 0 x1+1 + * + * Eliminate column 0 of rows 1 and 3 + * R(1)=(x0-x2)*R(1)-(x1-x2)*R(0), y1'=(y1-y2)(x0-x2)-(x1-x2)(y0-y2) + * R(3)=(x0-x2)*R(3)-(x3-x2)*R(0), y3'=(y3-y2)(x0-x2)-(x3-x2)(y0-y2) + * + * [0] [1] Hidden Prec + * x0-x2 y0-y2 0 x1+1 + * 0 y1' 0 x2+3 + * x2 y2 1 x1 + * 0 y3' 0 x2+3 + * + * Eliminate column 1 of rows 0 and 3 + * R(3)=y1'*R(3)-y3'*R(1) + * R(0)=y1'*R(0)-(y0-y2)*R(1) + * + * [0] [1] Hidden Prec + * x0' 0 0 x3+5 + * 0 y1' 0 x2+3 + * x2 y2 1 x1 + * 0 0 0 x4+7 + * + * Eliminate columns 0 and 1 of row 2 + * R(0)/=x0' + * R(1)/=y1' + * R(2)-= (x2*R(0) + y2*R(1)) + * + * [0] [1] Hidden Prec + * 1 0 0 x6+10 + * 0 1 0 x4+6 + * 0 0 1 x4+7 + * 0 0 0 x4+7 + */ + + /** + * Eliminate ones in column 2 and 5. + * R(0)-=R(2) + * R(1)-=R(2) + * R(3)-=R(2) + */ + + /*float minor[4][2] = {{x0-x2,y0-y2}, + {x1-x2,y1-y2}, + {x2 ,y2 }, + {x3-x2,y3-y2}};*/ + /*float major[8][3] = {{x2X2-x0X0,y2X2-y0X0,(X0-X2)}, + {x2X2-x1X1,y2X2-y1X1,(X1-X2)}, + {-x2X2 ,-y2X2 ,(X2 )}, + {x2X2-x3X3,y2X2-y3X3,(X3-X2)}, + {x2Y2-x0Y0,y2Y2-y0Y0,(Y0-Y2)}, + {x2Y2-x1Y1,y2Y2-y1Y1,(Y1-Y2)}, + {-x2Y2 ,-y2Y2 ,(Y2 )}, + {x2Y2-x3Y3,y2Y2-y3Y3,(Y3-Y2)}};*/ + float minor[2][4] = {{x0-x2,x1-x2,x2 ,x3-x2}, + {y0-y2,y1-y2,y2 ,y3-y2}}; + float major[3][8] = {{x2X2-x0X0,x2X2-x1X1,-x2X2 ,x2X2-x3X3,x2Y2-x0Y0,x2Y2-x1Y1,-x2Y2 ,x2Y2-x3Y3}, + {y2X2-y0X0,y2X2-y1X1,-y2X2 ,y2X2-y3X3,y2Y2-y0Y0,y2Y2-y1Y1,-y2Y2 ,y2Y2-y3Y3}, + { (X0-X2) , (X1-X2) , (X2 ) , (X3-X2) , (Y0-Y2) , (Y1-Y2) , (Y2 ) , (Y3-Y2) }}; + + /** + * int i; + * for(i=0;i<8;i++) major[2][i]=-major[2][i]; + * Eliminate column 0 of rows 1 and 3 + * R(1)=(x0-x2)*R(1)-(x1-x2)*R(0), y1'=(y1-y2)(x0-x2)-(x1-x2)(y0-y2) + * R(3)=(x0-x2)*R(3)-(x3-x2)*R(0), y3'=(y3-y2)(x0-x2)-(x3-x2)(y0-y2) + */ + + float scalar1=minor[0][0], scalar2=minor[0][1]; + minor[1][1]=minor[1][1]*scalar1-minor[1][0]*scalar2; + + major[0][1]=major[0][1]*scalar1-major[0][0]*scalar2; + major[1][1]=major[1][1]*scalar1-major[1][0]*scalar2; + major[2][1]=major[2][1]*scalar1-major[2][0]*scalar2; + + major[0][5]=major[0][5]*scalar1-major[0][4]*scalar2; + major[1][5]=major[1][5]*scalar1-major[1][4]*scalar2; + major[2][5]=major[2][5]*scalar1-major[2][4]*scalar2; + + scalar2=minor[0][3]; + minor[1][3]=minor[1][3]*scalar1-minor[1][0]*scalar2; + + major[0][3]=major[0][3]*scalar1-major[0][0]*scalar2; + major[1][3]=major[1][3]*scalar1-major[1][0]*scalar2; + major[2][3]=major[2][3]*scalar1-major[2][0]*scalar2; + + major[0][7]=major[0][7]*scalar1-major[0][4]*scalar2; + major[1][7]=major[1][7]*scalar1-major[1][4]*scalar2; + major[2][7]=major[2][7]*scalar1-major[2][4]*scalar2; + + /** + * Eliminate column 1 of rows 0 and 3 + * R(3)=y1'*R(3)-y3'*R(1) + * R(0)=y1'*R(0)-(y0-y2)*R(1) + */ + + scalar1=minor[1][1];scalar2=minor[1][3]; + major[0][3]=major[0][3]*scalar1-major[0][1]*scalar2; + major[1][3]=major[1][3]*scalar1-major[1][1]*scalar2; + major[2][3]=major[2][3]*scalar1-major[2][1]*scalar2; + + major[0][7]=major[0][7]*scalar1-major[0][5]*scalar2; + major[1][7]=major[1][7]*scalar1-major[1][5]*scalar2; + major[2][7]=major[2][7]*scalar1-major[2][5]*scalar2; + + scalar2=minor[1][0]; + minor[0][0]=minor[0][0]*scalar1-minor[0][1]*scalar2; + + major[0][0]=major[0][0]*scalar1-major[0][1]*scalar2; + major[1][0]=major[1][0]*scalar1-major[1][1]*scalar2; + major[2][0]=major[2][0]*scalar1-major[2][1]*scalar2; + + major[0][4]=major[0][4]*scalar1-major[0][5]*scalar2; + major[1][4]=major[1][4]*scalar1-major[1][5]*scalar2; + major[2][4]=major[2][4]*scalar1-major[2][5]*scalar2; + + /** + * Eliminate columns 0 and 1 of row 2 + * R(0)/=x0' + * R(1)/=y1' + * R(2)-= (x2*R(0) + y2*R(1)) + */ + + scalar1=minor[0][0]; + major[0][0]/=scalar1; + major[1][0]/=scalar1; + major[2][0]/=scalar1; + major[0][4]/=scalar1; + major[1][4]/=scalar1; + major[2][4]/=scalar1; + + scalar1=minor[1][1]; + major[0][1]/=scalar1; + major[1][1]/=scalar1; + major[2][1]/=scalar1; + major[0][5]/=scalar1; + major[1][5]/=scalar1; + major[2][5]/=scalar1; + + + scalar1=minor[0][2];scalar2=minor[1][2]; + major[0][2]-=major[0][0]*scalar1+major[0][1]*scalar2; + major[1][2]-=major[1][0]*scalar1+major[1][1]*scalar2; + major[2][2]-=major[2][0]*scalar1+major[2][1]*scalar2; + + major[0][6]-=major[0][4]*scalar1+major[0][5]*scalar2; + major[1][6]-=major[1][4]*scalar1+major[1][5]*scalar2; + major[2][6]-=major[2][4]*scalar1+major[2][5]*scalar2; + + /* Only major matters now. R(3) and R(7) correspond to the hollowed-out rows. */ + scalar1=major[0][7]; + major[1][7]/=scalar1; + major[2][7]/=scalar1; + + scalar1=major[0][0];major[1][0]-=scalar1*major[1][7];major[2][0]-=scalar1*major[2][7]; + scalar1=major[0][1];major[1][1]-=scalar1*major[1][7];major[2][1]-=scalar1*major[2][7]; + scalar1=major[0][2];major[1][2]-=scalar1*major[1][7];major[2][2]-=scalar1*major[2][7]; + scalar1=major[0][3];major[1][3]-=scalar1*major[1][7];major[2][3]-=scalar1*major[2][7]; + scalar1=major[0][4];major[1][4]-=scalar1*major[1][7];major[2][4]-=scalar1*major[2][7]; + scalar1=major[0][5];major[1][5]-=scalar1*major[1][7];major[2][5]-=scalar1*major[2][7]; + scalar1=major[0][6];major[1][6]-=scalar1*major[1][7];major[2][6]-=scalar1*major[2][7]; + + + /* One column left (Two in fact, but the last one is the homography) */ + scalar1=major[1][3]; + + major[2][3]/=scalar1; + scalar1=major[1][0];major[2][0]-=scalar1*major[2][3]; + scalar1=major[1][1];major[2][1]-=scalar1*major[2][3]; + scalar1=major[1][2];major[2][2]-=scalar1*major[2][3]; + scalar1=major[1][4];major[2][4]-=scalar1*major[2][3]; + scalar1=major[1][5];major[2][5]-=scalar1*major[2][3]; + scalar1=major[1][6];major[2][6]-=scalar1*major[2][3]; + scalar1=major[1][7];major[2][7]-=scalar1*major[2][3]; + + + /* Homography is done. */ + H[0]=major[2][0]; + H[1]=major[2][1]; + H[2]=major[2][2]; + + H[4]=major[2][4]; + H[5]=major[2][5]; + H[6]=major[2][6]; + + H[8]=major[2][7]; + H[9]=major[2][3]; + H[10]=1.0; +} + + +} /* End namespace cv */ diff --git a/modules/calib3d/src/rhosse2.h b/modules/calib3d/src/rhosse2.h new file mode 100644 index 000000000..ad3d2b18b --- /dev/null +++ b/modules/calib3d/src/rhosse2.h @@ -0,0 +1,331 @@ +/* + IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. + + By downloading, copying, installing or using the software you agree to this license. + If you do not agree to this license, do not download, install, + copy or use the software. + + + BSD 3-Clause License + + Copyright (C) 2014, Olexa Bilaniuk, Hamid Bazargani & Robert Laganiere, all rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistribution's of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + * Redistribution's in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * The name of the copyright holders may not be used to endorse or promote products + derived from this software without specific prior written permission. + + This software is provided by the copyright holders and contributors "as is" and + any express or implied warranties, including, but not limited to, the implied + warranties of merchantability and fitness for a particular purpose are disclaimed. + In no event shall the Intel Corporation or contributors be liable for any direct, + indirect, incidental, special, exemplary, or consequential damages + (including, but not limited to, procurement of substitute goods or services; + loss of use, data, or profits; or business interruption) however caused + and on any theory of liability, whether in contract, strict liability, + or tort (including negligence or otherwise) arising in any way out of + the use of this software, even if advised of the possibility of such damage. +*/ + +/** + * Bilaniuk, Olexa, Hamid Bazargani, and Robert Laganiere. "Fast Target + * Recognition on Mobile Devices: Revisiting Gaussian Elimination for the + * Estimation of Planar Homographies." In Computer Vision and Pattern + * Recognition Workshops (CVPRW), 2014 IEEE Conference on, pp. 119-125. + * IEEE, 2014. + */ + +/* Include Guards */ +#ifndef __RHOSSE2_H__ +#define __RHOSSE2_H__ + + + +/* Includes */ + + + + + +/* Defines */ +#ifdef __cplusplus + +/* C++ does not have the restrict keyword. */ +#ifdef restrict +#undef restrict +#endif +#define restrict + +#else + +/* C99 and over has the restrict keyword. */ +#if !defined(__STDC_VERSION__) || __STDC_VERSION__ < 199901L +#define restrict +#endif + +#endif + + +/* Flags */ +#ifndef RHO_FLAG_NONE +#define RHO_FLAG_NONE (0U<<0) +#endif +#ifndef RHO_FLAG_ENABLE_NR +#define RHO_FLAG_ENABLE_NR (1U<<0) +#endif +#ifndef RHO_FLAG_ENABLE_REFINEMENT +#define RHO_FLAG_ENABLE_REFINEMENT (1U<<1) +#endif +#ifndef RHO_FLAG_ENABLE_FINAL_REFINEMENT +#define RHO_FLAG_ENABLE_FINAL_REFINEMENT (1U<<2) +#endif + + + +/* Data structures */ + +/** + * Homography Estimation context. + */ + +typedef struct{ + /* Virtual Arguments */ + const float* restrict src; + const float* restrict dst; + int allocBestInl; + char* restrict bestInl; + unsigned N; + float maxD; + unsigned maxI; + unsigned rConvg; + double cfd; + unsigned minInl; + double beta; + unsigned flags; + const float* guessH; + float* finalH; + + /* PROSAC */ + unsigned i; /* Iteration Number */ + unsigned phNum; /* Phase Number */ + unsigned phEndI; /* Phase End Iteration */ + double phEndFpI; /* Phase floating-point End Iteration */ + unsigned phMax; /* Termination phase number */ + unsigned phNumInl; /* Number of inliers for termination phase */ + unsigned bestNumInl; /* Best number of inliers */ + unsigned numInl; /* Current number of inliers */ + unsigned numModels; /* Number of models tested */ + unsigned* restrict smpl; /* Sample */ + float* restrict H; /* Current homography */ + float* restrict bestH; /* Best homography */ + float* restrict pkdPts; /* Packed points */ + char* restrict inl; /* Inliers to current model */ + unsigned* restrict nrTBL; /* Non-Randomness: Table */ + unsigned nrSize; /* Non-Randomness: Size */ + double nrBeta; /* Non-Randomness: Beta */ + + /* SPRT */ + double t_M; /* t_M */ + double m_S; /* m_S */ + double epsilon; /* Epsilon */ + double delta; /* delta */ + double A; /* SPRT Threshold */ + unsigned Ntested; /* Number of points tested */ + unsigned Ntestedtotal; /* Number of points tested in total */ + int good; /* Good/bad flag */ + double lambdaAccept; /* Accept multiplier */ + double lambdaReject; /* Reject multiplier */ + double lambdaTBL[16]; /* Multiplier LUT */ +} RHO_HEST_SSE2; + + + +/* Extern C */ +#ifdef __cplusplus +namespace cv{ +//extern "C" { +#endif + + + +/* Functions */ + +/** + * Initialize the estimator context, by allocating the aligned buffers + * internally needed. + * + * @param [in/out] p The uninitialized estimator context to initialize. + * @return 0 if successful; non-zero if an error occured. + */ + +int rhoSSE2Init(RHO_HEST_SSE2* p); + + +/** + * Ensure that the estimator context's internal table for non-randomness + * criterion is at least of the given size, and uses the given beta. The table + * should be larger than the maximum number of matches fed into the estimator. + * + * A value of N of 0 requests deallocation of the table. + * + * @param [in] p The initialized estimator context + * @param [in] N If 0, deallocate internal table. If > 0, ensure that the + * internal table is of at least this size, reallocating if + * necessary. + * @param [in] beta The beta-factor to use within the table. + * @return 0 if successful; non-zero if an error occured. + */ + +int rhoSSE2EnsureCapacity(RHO_HEST_SSE2* p, unsigned N, double beta); + + +/** + * Finalize the estimator context, by freeing the aligned buffers used + * internally. + * + * @param [in] p The initialized estimator context to finalize. + */ + +void rhoSSE2Fini(RHO_HEST_SSE2* p); + + +/** + * Estimates the homography using the given context, matches and parameters to + * PROSAC. + * + * The given context must have been initialized. + * + * The matches are provided as two arrays of N single-precision, floating-point + * (x,y) points. Points with corresponding offsets in the two arrays constitute + * a match. The homography estimation attempts to find the 3x3 matrix H which + * best maps the homogeneous-coordinate points in the source array to their + * corresponding homogeneous-coordinate points in the destination array. + * + * Note: At least 4 matches must be provided (N >= 4). + * Note: A point in either array takes up 2 floats. The first of two stores + * the x-coordinate and the second of the two stores the y-coordinate. + * Thus, the arrays resemble this in memory: + * + * src = [x0, y0, x1, y1, x2, y2, x3, y3, x4, y4, ...] + * Matches: | | | | | + * dst = [x0, y0, x1, y1, x2, y2, x3, y3, x4, y4, ...] + * Note: The matches are expected to be provided sorted by quality, or at + * least not be worse-than-random in ordering. + * + * A pointer to the base of an array of N bytes can be provided. It serves as + * an output mask to indicate whether the corresponding match is an inlier to + * the returned homography, if any. A zero indicates an outlier; A non-zero + * value indicates an inlier. + * + * The PROSAC estimator requires a few parameters of its own. These are: + * + * - The maximum distance that a source point projected onto the destination + * plane can be from its putative match and still be considered an + * inlier. Must be non-negative. + * A sane default is 3.0. + * - The maximum number of PROSAC iterations. This corresponds to the + * largest number of samples that will be drawn and tested. + * A sane default is 2000. + * - The RANSAC convergence parameter. This corresponds to the number of + * iterations after which PROSAC will start sampling like RANSAC. + * A sane default is 2000. + * - The confidence threshold. This corresponds to the probability of + * finding a correct solution. Must be bounded by [0, 1]. + * A sane default is 0.995. + * - The minimum number of inliers acceptable. Only a solution with at + * least this many inliers will be returned. The minimum is 4. + * A sane default is 10% of N. + * - The beta-parameter for the non-randomness termination criterion. + * Ignored if non-randomness criterion disabled, otherwise must be + * bounded by (0, 1). + * A sane default is 0.35. + * - Optional flags to control the estimation. Available flags are: + * HEST_FLAG_NONE: + * No special processing. + * HEST_FLAG_ENABLE_NR: + * Enable non-randomness criterion. If set, the beta parameter + * must also be set. + * HEST_FLAG_ENABLE_REFINEMENT: + * Enable refinement of each new best model, as they are found. + * HEST_FLAG_ENABLE_FINAL_REFINEMENT: + * Enable one final refinement of the best model found before + * returning it. + * + * The PROSAC estimator additionally accepts an extrinsic initial guess of H, + * and outputs a final estimate at H provided it was able to find one with a + * minimum of supporting inliers. If it was not, it outputs the all-zero + * matrix. + * + * The extrinsic guess at and final estimate of H are both in the same form: + * A 3x3 single-precision floating-point matrix with step 4. Thus, it is a + * 12-element array of floats, with the elements as follows: + * + * [ H00, H01, H02, , + * H10, H11, H12, , + * H20, H21, H22, ] + * + * The function returns the number of inliers if it was able to find a + * homography with at least the minimum required support, and 0 if it was not. + * + * + * @param [in/out] p The context to use for homography estimation. Must + * be already initialized. Cannot be NULL. + * @param [in] src The pointer to the source points of the matches. + * Must be aligned to 16 bytes. Cannot be NULL. + * @param [in] dst The pointer to the destination points of the matches. + * Must be aligned to 16 bytes. Cannot be NULL. + * @param [out] inl The pointer to the output mask of inlier matches. + * Must be aligned to 16 bytes. May be NULL. + * @param [in] N The number of matches. + * @param [in] maxD The maximum distance. + * @param [in] maxI The maximum number of PROSAC iterations. + * @param [in] rConvg The RANSAC convergence parameter. + * @param [in] cfd The required confidence in the solution. + * @param [in] minInl The minimum required number of inliers. + * @param [in] beta The beta-parameter for the non-randomness criterion. + * @param [in] flags A union of flags to control the estimation. + * @param [in] guessH An extrinsic guess at the solution H, or NULL if + * none provided. + * @param [out] finalH The final estimation of H, or the zero matrix if + * the minimum number of inliers was not met. + * Cannot be NULL. + * @return The number of inliers if the minimum number of + * inliers for acceptance was reached; 0 otherwise. + */ + +unsigned rhoSSE2(RHO_HEST_SSE2* restrict p, /* Homography estimation context. */ + const float* restrict src, /* Source points */ + const float* restrict dst, /* Destination points */ + char* restrict bestInl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* 3.0 */ + unsigned maxI, /* 2000 */ + unsigned rConvg, /* 2000 */ + double cfd, /* 0.995 */ + unsigned minInl, /* 4 */ + double beta, /* 0.35 */ + unsigned flags, /* 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH); /* Final result. */ + + + + +/* Extern C */ +#ifdef __cplusplus +//} +} +#endif + + + + +#endif diff --git a/modules/calib3d/test/test_homography.cpp b/modules/calib3d/test/test_homography.cpp index 59d92905a..1199cd6cd 100644 --- a/modules/calib3d/test/test_homography.cpp +++ b/modules/calib3d/test/test_homography.cpp @@ -62,10 +62,10 @@ #define MAX_COUNT_OF_POINTS 303 #define COUNT_NORM_TYPES 3 -#define METHODS_COUNT 3 +#define METHODS_COUNT 4 int NORM_TYPE[COUNT_NORM_TYPES] = {cv::NORM_L1, cv::NORM_L2, cv::NORM_INF}; -int METHOD[METHODS_COUNT] = {0, cv::RANSAC, cv::LMEDS}; +int METHOD[METHODS_COUNT] = {0, cv::RANSAC, cv::LMEDS, cv::RHO}; using namespace cv; using namespace std; @@ -144,7 +144,7 @@ void CV_HomographyTest::print_information_1(int j, int N, int _method, const Mat cout << "Type of srcPoints: "; if ((j>-1) && (j<2)) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << " Type of dstPoints: "; if (j % 2 == 0) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << endl; cout << "Count of points: " << N << endl; cout << endl; - cout << "Method: "; if (_method == 0) cout << 0; else if (_method == 8) cout << "RANSAC"; else cout << "LMEDS"; cout << endl; + cout << "Method: "; if (_method == 0) cout << 0; else if (_method == 8) cout << "RANSAC"; else if (_method == cv::RHO) cout << "RHO"; else cout << "LMEDS"; cout << endl; cout << "Homography matrix:" << endl; cout << endl; cout << H << endl; cout << endl; cout << "Number of rows: " << H.rows << " Number of cols: " << H.cols << endl; cout << endl; @@ -156,7 +156,7 @@ void CV_HomographyTest::print_information_2(int j, int N, int _method, const Mat cout << "Type of srcPoints: "; if ((j>-1) && (j<2)) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << " Type of dstPoints: "; if (j % 2 == 0) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << endl; cout << "Count of points: " << N << endl; cout << endl; - cout << "Method: "; if (_method == 0) cout << 0; else if (_method == 8) cout << "RANSAC"; else cout << "LMEDS"; cout << endl; + cout << "Method: "; if (_method == 0) cout << 0; else if (_method == 8) cout << "RANSAC"; else if (_method == cv::RHO) cout << "RHO"; else cout << "LMEDS"; cout << endl; cout << "Original matrix:" << endl; cout << endl; cout << H << endl; cout << endl; cout << "Found matrix:" << endl; cout << endl; @@ -339,14 +339,15 @@ void CV_HomographyTest::run(int) continue; } + case cv::RHO: case RANSAC: { cv::Mat mask [4]; double diff; - Mat H_res_64 [4] = { cv::findHomography(src_mat_2f, dst_mat_2f, RANSAC, reproj_threshold, mask[0]), - cv::findHomography(src_mat_2f, dst_vec, RANSAC, reproj_threshold, mask[1]), - cv::findHomography(src_vec, dst_mat_2f, RANSAC, reproj_threshold, mask[2]), - cv::findHomography(src_vec, dst_vec, RANSAC, reproj_threshold, mask[3]) }; + Mat H_res_64 [4] = { cv::findHomography(src_mat_2f, dst_mat_2f, method, reproj_threshold, mask[0]), + cv::findHomography(src_mat_2f, dst_vec, method, reproj_threshold, mask[1]), + cv::findHomography(src_vec, dst_mat_2f, method, reproj_threshold, mask[2]), + cv::findHomography(src_vec, dst_vec, method, reproj_threshold, mask[3]) }; for (int j = 0; j < 4; ++j) { @@ -466,14 +467,15 @@ void CV_HomographyTest::run(int) continue; } + case cv::RHO: case RANSAC: { cv::Mat mask_res [4]; - Mat H_res_64 [4] = { cv::findHomography(src_mat_2f, dst_mat_2f, RANSAC, reproj_threshold, mask_res[0]), - cv::findHomography(src_mat_2f, dst_vec, RANSAC, reproj_threshold, mask_res[1]), - cv::findHomography(src_vec, dst_mat_2f, RANSAC, reproj_threshold, mask_res[2]), - cv::findHomography(src_vec, dst_vec, RANSAC, reproj_threshold, mask_res[3]) }; + Mat H_res_64 [4] = { cv::findHomography(src_mat_2f, dst_mat_2f, method, reproj_threshold, mask_res[0]), + cv::findHomography(src_mat_2f, dst_vec, method, reproj_threshold, mask_res[1]), + cv::findHomography(src_vec, dst_mat_2f, method, reproj_threshold, mask_res[2]), + cv::findHomography(src_vec, dst_vec, method, reproj_threshold, mask_res[3]) }; for (int j = 0; j < 4; ++j) { From 33a3fba2d1d448166e03a4f83864adc33a657af9 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Mon, 12 Jan 2015 04:58:07 -0500 Subject: [PATCH 02/39] Work on LevMarq code. Refactoring of Cholesky decomposition. Fix for memory corruption bug. LevMarq as a whole still non-functional. --- modules/calib3d/src/rhorefc.cpp | 349 ++++++++++++++++++++------------ modules/calib3d/src/rhorefc.h | 1 - 2 files changed, 218 insertions(+), 132 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index cda70f416..1da916d9b 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -132,24 +132,25 @@ static inline unsigned sacCalcIterBound(double confidence, static inline void hFuncRefC(float* packedPoints, float* H); static inline int sacCanRefine(RHO_HEST_REFC* p); static inline void sacRefine(RHO_HEST_REFC* p); -static inline void sacCalcJtMats(float (* restrict JtJ)[8], - float* restrict Jte, - float* restrict Sp, - const float* restrict H, - const float* restrict src, - const float* restrict dst, - const char* restrict inl, - unsigned N); -static inline void sacChol8x8 (const float (*A)[8], - float (*L)[8]); +static inline void sacCalcJacobianErrors(const float* restrict H, + const float* restrict src, + const float* restrict dst, + const char* restrict inl, + unsigned N, + float (* restrict JtJ)[8], + float* restrict Jte, + float* restrict Sp); +static inline float sacDs(const float (*JtJ)[8], + const float* dH, + const float* Jte); +static inline int sacChol8x8Damped (const float (*A)[8], + float lambda, + float (*L)[8]); static inline void sacTRInv8x8(const float (*L)[8], float (*M)[8]); static inline void sacTRISolve8x8(const float (*L)[8], const float* Jte, float* dH); -static inline void sacScaleDiag8x8(const float (*A)[8], - float lambda, - float (*B)[8]); static inline void sacSub8x1(float* Hout, const float* H, const float* dH); @@ -189,6 +190,11 @@ int rhoRefCInit(RHO_HEST_REFC* p){ p->nr.size = 0; p->nr.beta = 0.0; + p->lm.ws = NULL; + p->lm.JtJ = NULL; + p->lm.tmp1 = NULL; + p->lm.Jte = NULL; + int areAllAllocsSuccessful = p->ctrl.smpl && p->curr.H && @@ -502,10 +508,30 @@ static inline int sacInitRun(RHO_HEST_REFC* p){ return 0; } + /** + * LevMarq workspace alloc. + * + * Runs third, consists only in a few conditional mallocs. If malloc fails + * we wish to quit before doing any serious work. + */ + + if(sacIsRefineEnabled(p) || sacIsFinalRefineEnabled(p)){ + p->lm.ws = (float*)almalloc(2*8*8*sizeof(float) + 1*8*sizeof(float)); + if(!p->lm.ws){ + return 0; + } + + p->lm.JtJ = (float(*)[8])(p->lm.ws + 0*8*8); + p->lm.tmp1 = (float(*)[8])(p->lm.ws + 1*8*8); + p->lm.Jte = (float*) (p->lm.ws + 2*8*8); + }else{ + p->lm.ws = NULL; + } + /** * Reset scalar per-run state. * - * Runs third because there's no point in resetting/calculating a large + * Runs fourth because there's no point in resetting/calculating a large * number of fields if something in the above junk failed. */ @@ -570,6 +596,13 @@ static inline void sacFiniRun(RHO_HEST_REFC* p){ p->best.inl = NULL; p->curr.inl = NULL; + + /** + * ₣ree the Levenberg-Marquardt workspace. + */ + + alfree(p->lm.ws); + p->lm.ws = NULL; } /** @@ -912,6 +945,11 @@ static inline void sacEvaluateModelSPRT(RHO_HEST_REFC* p){ * * If a "good" model that is also the best was encountered, update epsilon, * since + * + * Reads: eval.good, eval.delta, eval.epsilon, eval.t_M, eval.m_S, + * curr.numInl, best.numInl + * Writes: eval.epsilon, eval.delta, eval.A, eval.lambdaAccept, + * eval.lambdaReject */ static inline void sacUpdateSPRT(RHO_HEST_REFC* p){ @@ -1032,9 +1070,11 @@ static inline void sacSaveBestModel(RHO_HEST_REFC* p){ float* H = p->curr.H; char* inl = p->curr.inl; unsigned numInl = p->curr.numInl; + p->curr.H = p->best.H; p->curr.inl = p->best.inl; p->curr.numInl = p->best.numInl; + p->best.H = H; p->best.inl = inl; p->best.numInl = numInl; @@ -1538,18 +1578,47 @@ static inline int sacCanRefine(RHO_HEST_REFC* p){ */ static inline void sacRefine(RHO_HEST_REFC* p){ - int i, j; - float S; /* Sum of squared errors */ - float L = 1;/* Lambda of LevMarq */ + int i = 0; + float S = 0, newS = 0, dS = 0;/* Sum of squared errors */ + float R = 0; /* R - Parameter */ + float L = 1.0f; /* Lambda of LevMarq */ + float dH[8], newH[8]; + /** + * Iteratively refine the homography. + */ + + /* Find initial conditions */ + sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, + p->lm.JtJ, p->lm.Jte, &S); + + /* Levenberg-Marquardt Loop */ for(i=0;ilm.JtJ, p->lm.Jte, &S, p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N); - sacScaleDiag8x8(p->lm.JtJ, L, p->lm.JtJ); - sacChol8x8(p->lm.JtJ, p->lm.JtJ); - sacTRInv8x8(p->lm.JtJ, p->lm.JtJ); - sacTRISolve8x8(p->lm.JtJ, p->lm.Jte, dH); - sacSub8x1(p->best.H, p->best.H, dH); + /* The code below becomes an infinite loop when L reeaches infinity. + while(sacChol8x8Damped(p->lm.JtJ, L, p->lm.tmp1)){ + L *= 2.0f; + }*/ + sacChol8x8Damped(p->lm.JtJ, L, p->lm.tmp1); + sacTRInv8x8 (p->lm.tmp1, p->lm.tmp1); + sacTRISolve8x8(p->lm.tmp1, p->lm.Jte, dH); + sacSub8x1 (newH, p->best.H, dH); + sacCalcJacobianErrors(newH, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, + NULL, NULL, &newS); + dS = sacDs (p->lm.JtJ, dH, p->lm.Jte); + R = (S - newS)/(fabs(dS) > DBL_EPSILON ? dS : 1);/* Don't understand */ + + if(R > 0.75f){ + L *= 0.5f; + }else if(R < 0.25f){ + L *= 2.0f; + } + + if(newS < S){ + S = newS; + memcpy(p->best.H, newH, sizeof(newH)); + sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, + p->lm.JtJ, p->lm.Jte, &S); + } } } @@ -1564,31 +1633,22 @@ static inline void sacRefine(RHO_HEST_REFC* p){ * * What this allows is a constant-space implementation of Lev-Marq that can * nevertheless be vectorized if need be. - * - * @param JtJ - * @param Jte - * @param Sp - * @param H - * @param src - * @param dst - * @param inl - * @param N */ -static inline void sacCalcJtMats(float (* restrict JtJ)[8], - float* restrict Jte, - float* restrict Sp, - const float* restrict H, - const float* restrict src, - const float* restrict dst, - const char* restrict inl, - unsigned N){ +static inline void sacCalcJacobianErrors(const float* restrict H, + const float* restrict src, + const float* restrict dst, + const char* restrict inl, + unsigned N, + float (* restrict JtJ)[8], + float* restrict Jte, + float* restrict Sp){ unsigned i; float S; /* Zero out JtJ, Jte and S */ - memset(JtJ, 0, 8*8*sizeof(*JtJ)); - memset(Jte, 0, 8*1*sizeof(*Jte)); + if(JtJ){memset(JtJ, 0, 8*8*sizeof(float));} + if(Jte){memset(Jte, 0, 8*1*sizeof(float));} S = 0.0f; /* Additively compute JtJ and Jte */ @@ -1633,81 +1693,119 @@ static inline void sacCalcJtMats(float (* restrict JtJ)[8], S += e; /* Compute Jacobian */ - float dxh11 = x * iW; - float dxh12 = y * iW; - float dxh13 = iW; - float dxh21 = 0.0f; - float dxh22 = 0.0f; - float dxh23 = 0.0f; - float dxh31 = -reprojX*x * iW; - float dxh32 = -reprojX*y * iW; + if(JtJ || Jte){ + float dxh11 = x * iW; + float dxh12 = y * iW; + float dxh13 = iW; + float dxh21 = 0.0f; + float dxh22 = 0.0f; + float dxh23 = 0.0f; + float dxh31 = -reprojX*x * iW; + float dxh32 = -reprojX*y * iW; - float dyh11 = 0.0f; - float dyh12 = 0.0f; - float dyh13 = 0.0f; - float dyh21 = x * iW; - float dyh22 = y * iW; - float dyh23 = iW; - float dyh31 = -reprojY*x * iW; - float dyh32 = -reprojY*y * iW; + float dyh11 = 0.0f; + float dyh12 = 0.0f; + float dyh13 = 0.0f; + float dyh21 = x * iW; + float dyh22 = y * iW; + float dyh23 = iW; + float dyh31 = -reprojY*x * iW; + float dyh32 = -reprojY*y * iW; - /* Update Jte: X Y */ - Jte[0] += eX *dxh11 + eY *dyh11; - Jte[1] += eX *dxh12 + eY *dyh12; - Jte[2] += eX *dxh13 + eY *dyh13; - Jte[3] += eX *dxh21 + eY *dyh21; - Jte[4] += eX *dxh22 + eY *dyh22; - Jte[5] += eX *dxh23 + eY *dyh23; - Jte[6] += eX *dxh31 + eY *dyh31; - Jte[7] += eX *dxh32 + eY *dyh32; + /* Update Jte: X Y */ + if(Jte){ + Jte[0] += eX *dxh11 + eY *dyh11; + Jte[1] += eX *dxh12 + eY *dyh12; + Jte[2] += eX *dxh13 + eY *dyh13; + Jte[3] += eX *dxh21 + eY *dyh21; + Jte[4] += eX *dxh22 + eY *dyh22; + Jte[5] += eX *dxh23 + eY *dyh23; + Jte[6] += eX *dxh31 + eY *dyh31; + Jte[7] += eX *dxh32 + eY *dyh32; + } - /* Update JtJ: X Y */ - JtJ[0][0] += dxh11*dxh11 + dyh11*dyh11; + /* Update JtJ: X Y */ + if(JtJ){ + JtJ[0][0] += dxh11*dxh11 + dyh11*dyh11; - JtJ[1][0] += dxh11*dxh12 + dyh11*dyh12; - JtJ[1][1] += dxh12*dxh12 + dyh12*dyh12; + JtJ[1][0] += dxh11*dxh12 + dyh11*dyh12; + JtJ[1][1] += dxh12*dxh12 + dyh12*dyh12; - JtJ[2][0] += dxh11*dxh13 + dyh11*dyh13; - JtJ[2][1] += dxh12*dxh13 + dyh12*dyh13; - JtJ[2][2] += dxh13*dxh13 + dyh13*dyh13; + JtJ[2][0] += dxh11*dxh13 + dyh11*dyh13; + JtJ[2][1] += dxh12*dxh13 + dyh12*dyh13; + JtJ[2][2] += dxh13*dxh13 + dyh13*dyh13; - JtJ[3][0] += dxh11*dxh21 + dyh11*dyh21; - JtJ[3][1] += dxh12*dxh21 + dyh12*dyh21; - JtJ[3][2] += dxh13*dxh21 + dyh13*dyh21; - JtJ[3][3] += dxh21*dxh21 + dyh21*dyh21; + JtJ[3][0] += dxh11*dxh21 + dyh11*dyh21; + JtJ[3][1] += dxh12*dxh21 + dyh12*dyh21; + JtJ[3][2] += dxh13*dxh21 + dyh13*dyh21; + JtJ[3][3] += dxh21*dxh21 + dyh21*dyh21; - JtJ[4][0] += dxh11*dxh22 + dyh11*dyh22; - JtJ[4][1] += dxh12*dxh22 + dyh12*dyh22; - JtJ[4][2] += dxh13*dxh22 + dyh13*dyh22; - JtJ[4][3] += dxh21*dxh22 + dyh21*dyh22; - JtJ[4][4] += dxh22*dxh22 + dyh22*dyh22; + JtJ[4][0] += dxh11*dxh22 + dyh11*dyh22; + JtJ[4][1] += dxh12*dxh22 + dyh12*dyh22; + JtJ[4][2] += dxh13*dxh22 + dyh13*dyh22; + JtJ[4][3] += dxh21*dxh22 + dyh21*dyh22; + JtJ[4][4] += dxh22*dxh22 + dyh22*dyh22; - JtJ[5][0] += dxh11*dxh23 + dyh11*dyh23; - JtJ[5][1] += dxh12*dxh23 + dyh12*dyh23; - JtJ[5][2] += dxh13*dxh23 + dyh13*dyh23; - JtJ[5][3] += dxh21*dxh23 + dyh21*dyh23; - JtJ[5][4] += dxh22*dxh23 + dyh22*dyh23; - JtJ[5][5] += dxh23*dxh23 + dyh23*dyh23; + JtJ[5][0] += dxh11*dxh23 + dyh11*dyh23; + JtJ[5][1] += dxh12*dxh23 + dyh12*dyh23; + JtJ[5][2] += dxh13*dxh23 + dyh13*dyh23; + JtJ[5][3] += dxh21*dxh23 + dyh21*dyh23; + JtJ[5][4] += dxh22*dxh23 + dyh22*dyh23; + JtJ[5][5] += dxh23*dxh23 + dyh23*dyh23; - JtJ[6][0] += dxh11*dxh31 + dyh11*dyh31; - JtJ[6][1] += dxh12*dxh31 + dyh12*dyh31; - JtJ[6][2] += dxh13*dxh31 + dyh13*dyh31; - JtJ[6][3] += dxh21*dxh31 + dyh21*dyh31; - JtJ[6][4] += dxh22*dxh31 + dyh22*dyh31; - JtJ[6][5] += dxh23*dxh31 + dyh23*dyh31; - JtJ[6][6] += dxh31*dxh31 + dyh31*dyh31; + JtJ[6][0] += dxh11*dxh31 + dyh11*dyh31; + JtJ[6][1] += dxh12*dxh31 + dyh12*dyh31; + JtJ[6][2] += dxh13*dxh31 + dyh13*dyh31; + JtJ[6][3] += dxh21*dxh31 + dyh21*dyh31; + JtJ[6][4] += dxh22*dxh31 + dyh22*dyh31; + JtJ[6][5] += dxh23*dxh31 + dyh23*dyh31; + JtJ[6][6] += dxh31*dxh31 + dyh31*dyh31; - JtJ[7][0] += dxh11*dxh32 + dyh11*dyh32; - JtJ[7][1] += dxh12*dxh32 + dyh12*dyh32; - JtJ[7][2] += dxh13*dxh32 + dyh13*dyh32; - JtJ[7][3] += dxh21*dxh32 + dyh21*dyh32; - JtJ[7][4] += dxh22*dxh32 + dyh22*dyh32; - JtJ[7][5] += dxh23*dxh32 + dyh23*dyh32; - JtJ[7][6] += dxh31*dxh32 + dyh31*dyh32; - JtJ[7][7] += dxh32*dxh32 + dyh32*dyh32; + JtJ[7][0] += dxh11*dxh32 + dyh11*dyh32; + JtJ[7][1] += dxh12*dxh32 + dyh12*dyh32; + JtJ[7][2] += dxh13*dxh32 + dyh13*dyh32; + JtJ[7][3] += dxh21*dxh32 + dyh21*dyh32; + JtJ[7][4] += dxh22*dxh32 + dyh22*dyh32; + JtJ[7][5] += dxh23*dxh32 + dyh23*dyh32; + JtJ[7][6] += dxh31*dxh32 + dyh31*dyh32; + JtJ[7][7] += dxh32*dxh32 + dyh32*dyh32; + } + } } - *Sp = S; + if(Sp){*Sp = S;} +} + +/** + * Compute the derivative of the rate of change of the SSE. + * + * Inspired entirely by OpenCV's levmarq.cpp. To be reviewed. + */ + +static inline float sacDs(const float (*JtJ)[8], + const float* dH, + const float* Jte){ + float tdH[8]; + int i, j; + float dS = 0; + + /* Perform tdH = -JtJ*dH + 2*Jte. */ + for(i=0;i<8;i++){ + tdH[i] = 0; + + for(j=0;j<8;j++){ + tdH[i] -= JtJ[i][j] * dH[j]; + } + + tdH[i] += 2*Jte[i]; + } + + /* Perform dS = dH.dot(tdH). */ + for(i=0;i<8;i++){ + dS += dH[i]*tdH[i]; + } + + return dS; } /** @@ -1718,14 +1816,20 @@ static inline void sacCalcJtMats(float (* restrict JtJ)[8], * A and L can overlap fully (in-place) or not at all, but may not partially * overlap. * + * For damping, the diagonal elements are scaled by 1.0 + lambda. + * + * Returns 0 if decomposition successful, and non-zero otherwise. + * * Source: http://en.wikipedia.org/wiki/Cholesky_decomposition# * The_Cholesky.E2.80.93Banachiewicz_and_Cholesky.E2.80.93Crout_algorithms */ -static inline void sacChol8x8(const float (*A)[8], - float (*L)[8]){ +static inline int sacChol8x8Damped(const float (*A)[8], + float lambda, + float (*L)[8]){ const register int N = 8; int i, j, k; + float lambdap1 = lambda + 1.0f; double x; for(i=0;i Date: Mon, 12 Jan 2015 05:37:40 -0500 Subject: [PATCH 03/39] More LevMarq bugfixes. LevMarq now doesn't outright fail, but doesn't seem to improve things much if at all. --- modules/calib3d/src/fundam.cpp | 3 ++- modules/calib3d/src/rhorefc.cpp | 18 +++++++++++++----- 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index 07cf68a0f..79beb3e5c 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -327,7 +327,8 @@ static bool createAndRunRHORegistrator(double confidence, int maxIters, double r confidence, 4, beta, - RHO_FLAG_ENABLE_NR, + /*RHO_FLAG_ENABLE_NR,*/ + RHO_FLAG_ENABLE_NR | RHO_FLAG_ENABLE_FINAL_REFINEMENT, NULL, (float*)tmpH.data); rhoRefCFini(&p); diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 1da916d9b..b4b34eb7c 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -66,7 +66,7 @@ #define CHI_SQ 1.645 #define RLO 0.25 #define RHI 0.75 -#define MAXLEVMARQITERS 10 +#define MAXLEVMARQITERS 50 #define m 4 /* 4 points required per model */ #define SPRT_T_M 25 /* Guessing 25 match evlauations / 1 model generation */ #define SPRT_M_S 1 /* 1 model per sample */ @@ -1592,13 +1592,21 @@ static inline void sacRefine(RHO_HEST_REFC* p){ sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, p->lm.JtJ, p->lm.Jte, &S); + /*{ + for(int j=0;j<8;j++){ + for(int k=0;k<8;k++){ + printf("%12.6g%s", p->lm.JtJ[j][k], k==7 ? "\n" : ", "); + } + } + }*/ + /* Levenberg-Marquardt Loop */ for(i=0;ilm.JtJ, L, p->lm.tmp1)){ L *= 2.0f; - }*/ - sacChol8x8Damped(p->lm.JtJ, L, p->lm.tmp1); + } + //sacChol8x8Damped(p->lm.JtJ, L, p->lm.tmp1); sacTRInv8x8 (p->lm.tmp1, p->lm.tmp1); sacTRISolve8x8(p->lm.tmp1, p->lm.Jte, dH); sacSub8x1 (newH, p->best.H, dH); @@ -1682,7 +1690,7 @@ static inline void sacCalcJacobianErrors(const float* restrict H, float X = dst[2*i+0]; float Y = dst[2*i+1]; float W = (H[6]*x + H[7]*y + 1.0f); - float iW = W FLT_EPSILON ? 1.0f/W : 0; float reprojX = (H[0]*x + H[1]*y + H[2]) * iW; float reprojY = (H[3]*x + H[4]*y + H[5]) * iW; From 4401095b38d02c5d0b99683bfb852d819941578c Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Mon, 12 Jan 2015 11:33:05 -0500 Subject: [PATCH 04/39] Optimizations to Jacobian and error calculations. Deleted multiplications by zero and consequent additions of zero terms. --- modules/calib3d/src/rhorefc.cpp | 88 ++++++++++++++++----------------- 1 file changed, 44 insertions(+), 44 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index b4b34eb7c..5777275ff 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -1722,61 +1722,61 @@ static inline void sacCalcJacobianErrors(const float* restrict H, /* Update Jte: X Y */ if(Jte){ - Jte[0] += eX *dxh11 + eY *dyh11; - Jte[1] += eX *dxh12 + eY *dyh12; - Jte[2] += eX *dxh13 + eY *dyh13; - Jte[3] += eX *dxh21 + eY *dyh21; - Jte[4] += eX *dxh22 + eY *dyh22; - Jte[5] += eX *dxh23 + eY *dyh23; - Jte[6] += eX *dxh31 + eY *dyh31; - Jte[7] += eX *dxh32 + eY *dyh32; + Jte[0] += eX *dxh11 ;/* +0 */ + Jte[1] += eX *dxh12 ;/* +0 */ + Jte[2] += eX *dxh13 ;/* +0 */ + Jte[3] += eY *dyh21;/* 0+ */ + Jte[4] += eY *dyh22;/* 0+ */ + Jte[5] += eY *dyh23;/* 0+ */ + Jte[6] += eX *dxh31 + eY *dyh31;/* + */ + Jte[7] += eX *dxh32 + eY *dyh32;/* + */ } /* Update JtJ: X Y */ if(JtJ){ - JtJ[0][0] += dxh11*dxh11 + dyh11*dyh11; + JtJ[0][0] += dxh11*dxh11 ;/* +0 */ - JtJ[1][0] += dxh11*dxh12 + dyh11*dyh12; - JtJ[1][1] += dxh12*dxh12 + dyh12*dyh12; + JtJ[1][0] += dxh11*dxh12 ;/* +0 */ + JtJ[1][1] += dxh12*dxh12 ;/* +0 */ - JtJ[2][0] += dxh11*dxh13 + dyh11*dyh13; - JtJ[2][1] += dxh12*dxh13 + dyh12*dyh13; - JtJ[2][2] += dxh13*dxh13 + dyh13*dyh13; + JtJ[2][0] += dxh11*dxh13 ;/* +0 */ + JtJ[2][1] += dxh12*dxh13 ;/* +0 */ + JtJ[2][2] += dxh13*dxh13 ;/* +0 */ - JtJ[3][0] += dxh11*dxh21 + dyh11*dyh21; - JtJ[3][1] += dxh12*dxh21 + dyh12*dyh21; - JtJ[3][2] += dxh13*dxh21 + dyh13*dyh21; - JtJ[3][3] += dxh21*dxh21 + dyh21*dyh21; + /*JtJ[3][0] += ;/* 0+0 */ + /*JtJ[3][1] += ;/* 0+0 */ + /*JtJ[3][2] += ;/* 0+0 */ + JtJ[3][3] += dyh21*dyh21;/* 0+ */ - JtJ[4][0] += dxh11*dxh22 + dyh11*dyh22; - JtJ[4][1] += dxh12*dxh22 + dyh12*dyh22; - JtJ[4][2] += dxh13*dxh22 + dyh13*dyh22; - JtJ[4][3] += dxh21*dxh22 + dyh21*dyh22; - JtJ[4][4] += dxh22*dxh22 + dyh22*dyh22; + /*JtJ[4][0] += ;/* 0+0 */ + /*JtJ[4][1] += ;/* 0+0 */ + /*JtJ[4][2] += ;/* 0+0 */ + JtJ[4][3] += dyh21*dyh22;/* 0+ */ + JtJ[4][4] += dyh22*dyh22;/* 0+ */ - JtJ[5][0] += dxh11*dxh23 + dyh11*dyh23; - JtJ[5][1] += dxh12*dxh23 + dyh12*dyh23; - JtJ[5][2] += dxh13*dxh23 + dyh13*dyh23; - JtJ[5][3] += dxh21*dxh23 + dyh21*dyh23; - JtJ[5][4] += dxh22*dxh23 + dyh22*dyh23; - JtJ[5][5] += dxh23*dxh23 + dyh23*dyh23; + /*JtJ[5][0] += ;/* 0+0 */ + /*JtJ[5][1] += ;/* 0+0 */ + /*JtJ[5][2] += ;/* 0+0 */ + JtJ[5][3] += dyh21*dyh23;/* 0+ */ + JtJ[5][4] += dyh22*dyh23;/* 0+ */ + JtJ[5][5] += dyh23*dyh23;/* 0+ */ - JtJ[6][0] += dxh11*dxh31 + dyh11*dyh31; - JtJ[6][1] += dxh12*dxh31 + dyh12*dyh31; - JtJ[6][2] += dxh13*dxh31 + dyh13*dyh31; - JtJ[6][3] += dxh21*dxh31 + dyh21*dyh31; - JtJ[6][4] += dxh22*dxh31 + dyh22*dyh31; - JtJ[6][5] += dxh23*dxh31 + dyh23*dyh31; - JtJ[6][6] += dxh31*dxh31 + dyh31*dyh31; + JtJ[6][0] += dxh11*dxh31 ;/* +0 */ + JtJ[6][1] += dxh12*dxh31 ;/* +0 */ + JtJ[6][2] += dxh13*dxh31 ;/* +0 */ + JtJ[6][3] += dyh21*dyh31;/* 0+ */ + JtJ[6][4] += dyh22*dyh31;/* 0+ */ + JtJ[6][5] += dyh23*dyh31;/* 0+ */ + JtJ[6][6] += dxh31*dxh31 + dyh31*dyh31;/* + */ - JtJ[7][0] += dxh11*dxh32 + dyh11*dyh32; - JtJ[7][1] += dxh12*dxh32 + dyh12*dyh32; - JtJ[7][2] += dxh13*dxh32 + dyh13*dyh32; - JtJ[7][3] += dxh21*dxh32 + dyh21*dyh32; - JtJ[7][4] += dxh22*dxh32 + dyh22*dyh32; - JtJ[7][5] += dxh23*dxh32 + dyh23*dyh32; - JtJ[7][6] += dxh31*dxh32 + dyh31*dyh32; - JtJ[7][7] += dxh32*dxh32 + dyh32*dyh32; + JtJ[7][0] += dxh11*dxh32 ;/* +0 */ + JtJ[7][1] += dxh12*dxh32 ;/* +0 */ + JtJ[7][2] += dxh13*dxh32 ;/* +0 */ + JtJ[7][3] += dyh21*dyh32;/* 0+ */ + JtJ[7][4] += dyh22*dyh32;/* 0+ */ + JtJ[7][5] += dyh23*dyh32;/* 0+ */ + JtJ[7][6] += dxh31*dxh32 + dyh31*dyh32;/* + */ + JtJ[7][7] += dxh32*dxh32 + dyh32*dyh32;/* + */ } } } From ff91af825da1ad4e08de2e224ce5260b1ab8a6e3 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Wed, 14 Jan 2015 04:22:48 -0500 Subject: [PATCH 05/39] LevMarq made semi-functional. Replaced the complex rules OpenCV uses to select lambda with a naive but fast heuristic. It's imperfect but produces good results. It is still subject to the same problem as OpenCV - namely, on occasion LevMarq will make a poor result even worse. --- modules/calib3d/src/rhorefc.cpp | 115 ++++++++++++++++++++------------ 1 file changed, 73 insertions(+), 42 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 5777275ff..4e96eaf67 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -66,7 +66,7 @@ #define CHI_SQ 1.645 #define RLO 0.25 #define RHI 0.75 -#define MAXLEVMARQITERS 50 +#define MAXLEVMARQITERS 100 #define m 4 /* 4 points required per model */ #define SPRT_T_M 25 /* Guessing 25 match evlauations / 1 model generation */ #define SPRT_M_S 1 /* 1 model per sample */ @@ -1571,10 +1571,20 @@ static inline int sacCanRefine(RHO_HEST_REFC* p){ return p->best.numInl > m; } + + +static inline void dumpMat8x8(float (*M)[8]){ + for(int i=0;i<8;i++){ + printf("\t"); + for(int j=0;j<=i;j++){ + printf("%14.6e%s", M[i][j], j==i?"\n":", "); + } + } + printf("\n"); +} + /** - * Refines the best-so-far homography. - * - * BUG: Totally broken for now. DO NOT ENABLE. + * Refines the best-so-far homography (p->best.H). */ static inline void sacRefine(RHO_HEST_REFC* p){ @@ -1591,41 +1601,62 @@ static inline void sacRefine(RHO_HEST_REFC* p){ /* Find initial conditions */ sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, p->lm.JtJ, p->lm.Jte, &S); + /*printf("Initial Error: %12.6f\n", S);*/ - /*{ - for(int j=0;j<8;j++){ - for(int k=0;k<8;k++){ - printf("%12.6g%s", p->lm.JtJ[j][k], k==7 ? "\n" : ", "); - } - } - }*/ - - /* Levenberg-Marquardt Loop */ + /*Levenberg-Marquardt Loop.*/ for(i=0;ilm.JtJ, L, p->lm.tmp1)){ - L *= 2.0f; + /** + * Attempt a step given current state + * - Jacobian-x-Jacobian (JtJ) + * - Jacobian-x-error (Jte) + * - Sum of squared errors (S) + * and current parameter + * - Lambda (L) + * . + * + * This is done by solving the system of equations + * Ax = b + * where A (JtJ) and b (Jte) are sourced from our current state, and + * the solution x becomes a step (dH) that is applied to best.H in + * order to compute a candidate homography (newH). + * + * The system above is solved by Cholesky decomposition of a + * sufficently-damped JtJ into a lower-triangular matrix (and its + * transpose), whose inverse is then computed. This inverse (and its + * transpose) then multiply JtJ in order to find dH. + */ + + /*printf("Lambda: %f\n", L);*/ + while(!sacChol8x8Damped(p->lm.JtJ, L, p->lm.tmp1)){ + L *= 2.0f;/*printf("CholFail! Lambda: %f\n", L);*/ } - //sacChol8x8Damped(p->lm.JtJ, L, p->lm.tmp1); sacTRInv8x8 (p->lm.tmp1, p->lm.tmp1); sacTRISolve8x8(p->lm.tmp1, p->lm.Jte, dH); sacSub8x1 (newH, p->best.H, dH); sacCalcJacobianErrors(newH, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, NULL, NULL, &newS); - dS = sacDs (p->lm.JtJ, dH, p->lm.Jte); - R = (S - newS)/(fabs(dS) > DBL_EPSILON ? dS : 1);/* Don't understand */ - if(R > 0.75f){ - L *= 0.5f; - }else if(R < 0.25f){ - L *= 2.0f; - } + /** + * If the new Sum of Square Errors (newS) corresponding to newH is + * lower than the previous one, save the current state and undamp + * sligthly (decrease L). Else damp more (increase L). + */ if(newS < S){ S = newS; memcpy(p->best.H, newH, sizeof(newH)); sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, p->lm.JtJ, p->lm.Jte, &S); + /*printf("Error: %12.6f\n", S);*/ + L *= 0.5; + if(L1.0f/FLT_EPSILON){ + break; + } } } } @@ -1705,15 +1736,15 @@ static inline void sacCalcJacobianErrors(const float* restrict H, float dxh11 = x * iW; float dxh12 = y * iW; float dxh13 = iW; - float dxh21 = 0.0f; - float dxh22 = 0.0f; - float dxh23 = 0.0f; + /*float dxh21 = 0.0f;*/ + /*float dxh22 = 0.0f;*/ + /*float dxh23 = 0.0f;*/ float dxh31 = -reprojX*x * iW; float dxh32 = -reprojX*y * iW; - float dyh11 = 0.0f; - float dyh12 = 0.0f; - float dyh13 = 0.0f; + /*float dyh11 = 0.0f;*/ + /*float dyh12 = 0.0f;*/ + /*float dyh13 = 0.0f;*/ float dyh21 = x * iW; float dyh22 = y * iW; float dyh23 = iW; @@ -1743,20 +1774,20 @@ static inline void sacCalcJacobianErrors(const float* restrict H, JtJ[2][1] += dxh12*dxh13 ;/* +0 */ JtJ[2][2] += dxh13*dxh13 ;/* +0 */ - /*JtJ[3][0] += ;/* 0+0 */ - /*JtJ[3][1] += ;/* 0+0 */ - /*JtJ[3][2] += ;/* 0+0 */ + /*JtJ[3][0] += ; 0+0 */ + /*JtJ[3][1] += ; 0+0 */ + /*JtJ[3][2] += ; 0+0 */ JtJ[3][3] += dyh21*dyh21;/* 0+ */ - /*JtJ[4][0] += ;/* 0+0 */ - /*JtJ[4][1] += ;/* 0+0 */ - /*JtJ[4][2] += ;/* 0+0 */ + /*JtJ[4][0] += ; 0+0 */ + /*JtJ[4][1] += ; 0+0 */ + /*JtJ[4][2] += ; 0+0 */ JtJ[4][3] += dyh21*dyh22;/* 0+ */ JtJ[4][4] += dyh22*dyh22;/* 0+ */ - /*JtJ[5][0] += ;/* 0+0 */ - /*JtJ[5][1] += ;/* 0+0 */ - /*JtJ[5][2] += ;/* 0+0 */ + /*JtJ[5][0] += ; 0+0 */ + /*JtJ[5][1] += ; 0+0 */ + /*JtJ[5][2] += ; 0+0 */ JtJ[5][3] += dyh21*dyh23;/* 0+ */ JtJ[5][4] += dyh22*dyh23;/* 0+ */ JtJ[5][5] += dyh23*dyh23;/* 0+ */ @@ -1826,7 +1857,7 @@ static inline float sacDs(const float (*JtJ)[8], * * For damping, the diagonal elements are scaled by 1.0 + lambda. * - * Returns 0 if decomposition successful, and non-zero otherwise. + * Returns zero if decomposition unsuccessful, and non-zero otherwise. * * Source: http://en.wikipedia.org/wiki/Cholesky_decomposition# * The_Cholesky.E2.80.93Banachiewicz_and_Cholesky.E2.80.93Crout_algorithms @@ -1857,13 +1888,13 @@ static inline int sacChol8x8Damped(const float (*A)[8], x -= (double)L[j][k] * L[j][k];/* - Sum_{k=0..j-1} Ljk^2 */ } if(x<0){ - return 1; + return 0; } L[j][j] = sqrt(x); /* Ljj = sqrt( ... ) */ } } - return 0; + return 1; } /** From 02124f19e6a445b0712495f69f829afb849214fe Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Thu, 15 Jan 2015 04:21:16 -0500 Subject: [PATCH 06/39] Further LevMarq improvements. Implemented a damping-parameter choice strategy similar to that described in http://www2.imm.dtu.dk/documents/ftp/tr99/tr05_99.pdf. Removed a few debug statements. Chosen a new starting lambda value, 0.01. We now actually output the mask of inliers. --- modules/calib3d/src/fundam.cpp | 5 +- modules/calib3d/src/rhorefc.cpp | 109 ++++++++++++++++---------------- 2 files changed, 57 insertions(+), 57 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index 79beb3e5c..1fafc14ec 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -287,7 +287,9 @@ static bool createAndRunRHORegistrator(double confidence, int maxIters, double r /* Run RHO. Needs cleanup or separate function to invoke. */ Mat tmpH = Mat(3, 3, CV_32FC1); - tempMask = Mat(npoints, 1, CV_8U); + if(!tempMask.data){ + tempMask = Mat(npoints, 1, CV_8U); + } double beta = 0.35;/* 0.35 is a value that often works. */ #if CV_SSE2 && 0 @@ -339,6 +341,7 @@ static bool createAndRunRHORegistrator(double confidence, int maxIters, double r for(int k=0;kbest.numInl > m; } - - -static inline void dumpMat8x8(float (*M)[8]){ - for(int i=0;i<8;i++){ - printf("\t"); - for(int j=0;j<=i;j++){ - printf("%14.6e%s", M[i][j], j==i?"\n":", "); - } - } - printf("\n"); -} - /** * Refines the best-so-far homography (p->best.H). */ static inline void sacRefine(RHO_HEST_REFC* p){ - int i = 0; - float S = 0, newS = 0, dS = 0;/* Sum of squared errors */ - float R = 0; /* R - Parameter */ - float L = 1.0f; /* Lambda of LevMarq */ + int i; + float S, newS; /* Sum of squared errors */ + float gain; /* Gain-parameter. */ + float L = 0.01f;/* Lambda of LevMarq */ float dH[8], newH[8]; /** @@ -1601,7 +1593,6 @@ static inline void sacRefine(RHO_HEST_REFC* p){ /* Find initial conditions */ sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, p->lm.JtJ, p->lm.Jte, &S); - /*printf("Initial Error: %12.6f\n", S);*/ /*Levenberg-Marquardt Loop.*/ for(i=0;ilm.JtJ, L, p->lm.tmp1)){ - L *= 2.0f;/*printf("CholFail! Lambda: %f\n", L);*/ + L *= 2.0f; } sacTRInv8x8 (p->lm.tmp1, p->lm.tmp1); sacTRISolve8x8(p->lm.tmp1, p->lm.Jte, dH); sacSub8x1 (newH, p->best.H, dH); sacCalcJacobianErrors(newH, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, NULL, NULL, &newS); + gain = sacLMGain(dH, p->lm.Jte, S, newS, L); + /*printf("Lambda: %12.6f S: %12.6f newS: %12.6f Gain: %12.6f\n", + L, S, newS, gain);*/ /** - * If the new Sum of Square Errors (newS) corresponding to newH is - * lower than the previous one, save the current state and undamp - * sligthly (decrease L). Else damp more (increase L). + * If the gain is positive (i.e., the new Sum of Square Errors (newS) + * corresponding to newH is lower than the previous one (S) ), save + * the current state and accept the new step dH. + * + * If the gain is below LM_GAIN_LO, damp more (increase L), even if the + * gain was positive. If the gain is above LM_GAIN_HI, damp less + * (decrease L). Otherwise the gain is left unchanged. */ - if(newS < S){ + if(gain < LM_GAIN_LO){ + L *= 8; + if(L>1000.0f/FLT_EPSILON){ + break;/* FIXME: Most naive termination criterion imaginable. */ + } + }else if(gain > LM_GAIN_HI){ + L *= 0.5; + } + + if(gain > 0){ S = newS; memcpy(p->best.H, newH, sizeof(newH)); sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, p->lm.JtJ, p->lm.Jte, &S); - /*printf("Error: %12.6f\n", S);*/ - L *= 0.5; - if(L1.0f/FLT_EPSILON){ - break; - } } } } @@ -1816,35 +1812,36 @@ static inline void sacCalcJacobianErrors(const float* restrict H, } /** - * Compute the derivative of the rate of change of the SSE. + * Compute the Levenberg-Marquardt "gain" obtained by the given step dH. * - * Inspired entirely by OpenCV's levmarq.cpp. To be reviewed. + * Drawn from http://www2.imm.dtu.dk/documents/ftp/tr99/tr05_99.pdf. */ -static inline float sacDs(const float (*JtJ)[8], - const float* dH, - const float* Jte){ - float tdH[8]; - int i, j; - float dS = 0; +static inline float sacLMGain(const float* dH, + const float* Jte, + const float S, + const float newS, + const float lambda){ + float dS = S-newS; + float dL = 0; + int i; - /* Perform tdH = -JtJ*dH + 2*Jte. */ + /* Compute h^t h... */ for(i=0;i<8;i++){ - tdH[i] = 0; - - for(j=0;j<8;j++){ - tdH[i] -= JtJ[i][j] * dH[j]; - } - - tdH[i] += 2*Jte[i]; + dL += dH[i]*dH[i]; } - - /* Perform dS = dH.dot(tdH). */ + /* Compute mu * h^t h... */ + dL *= lambda; + /* Subtract h^t F'... */ for(i=0;i<8;i++){ - dS += dH[i]*tdH[i]; + dL += dH[i]*Jte[i];/* += as opposed to -=, since dH we compute is + opposite sign. */ } + /* Multiply by 1/2... */ + dL *= 0.5; - return dS; + /* Return gain as S-newS / L0 - LH. */ + return fabs(dL) < FLT_EPSILON ? dS : dS / dL; } /** From 69b146412a01d64f68e73686ee7bc21da55485c7 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Feb 2015 22:55:40 -0500 Subject: [PATCH 07/39] Edited Doxygen documentation in the module calib3d. Added a mention within calib3d.hpp that the flag RHO is available as an option on calls to findHomography(). --- modules/calib3d/include/opencv2/calib3d.hpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/modules/calib3d/include/opencv2/calib3d.hpp b/modules/calib3d/include/opencv2/calib3d.hpp index 3b8e3c7c1..bfc5c5f7e 100644 --- a/modules/calib3d/include/opencv2/calib3d.hpp +++ b/modules/calib3d/include/opencv2/calib3d.hpp @@ -266,8 +266,9 @@ a vector\ . - **0** - a regular method using all the points - **RANSAC** - RANSAC-based robust method - **LMEDS** - Least-Median robust method +- **RHO** - PROSAC-based robust method @param ransacReprojThreshold Maximum allowed reprojection error to treat a point pair as an inlier -(used in the RANSAC method only). That is, if +(used in the RANSAC and RHO methods only). That is, if \f[\| \texttt{dstPoints} _i - \texttt{convertPointsHomogeneous} ( \texttt{H} * \texttt{srcPoints} _i) \| > \texttt{ransacReprojThreshold}\f] then the point \f$i\f$ is considered an outlier. If srcPoints and dstPoints are measured in pixels, it usually makes sense to set this parameter somewhere in the range of 1 to 10. @@ -290,7 +291,7 @@ pairs to compute an initial homography estimate with a simple least-squares sche However, if not all of the point pairs ( \f$srcPoints_i\f$, \f$dstPoints_i\f$ ) fit the rigid perspective transformation (that is, there are some outliers), this initial estimate will be poor. In this case, -you can use one of the two robust methods. Both methods, RANSAC and LMeDS , try many different +you can use one of the three robust methods. The methods RANSAC, LMeDS and RHO try many different random subsets of the corresponding point pairs (of four pairs each), estimate the homography matrix using this subset and a simple least-square algorithm, and then compute the quality/goodness of the computed homography (which is the number of inliers for RANSAC or the median re-projection error for @@ -301,7 +302,7 @@ Regardless of the method, robust or not, the computed homography matrix is refin inliers only in case of a robust method) with the Levenberg-Marquardt method to reduce the re-projection error even more. -The method RANSAC can handle practically any ratio of outliers but it needs a threshold to +The methods RANSAC and RHO can handle practically any ratio of outliers but need a threshold to distinguish inliers from outliers. The method LMeDS does not need any threshold but it works correctly only when there are more than 50% of inliers. Finally, if there are no outliers and the noise is rather small, use the default method (method=0). From ce0570b77744676c463ea2c8617d5f6a828950cf Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Feb 2015 23:33:52 -0500 Subject: [PATCH 08/39] Splitting vectorized code into separate branch. Deleted SSE code from master branch. Slight cleanups in fundam.cpp were made as a consequence. --- modules/calib3d/src/fundam.cpp | 123 +-- modules/calib3d/src/rhosse2.cpp | 1497 ------------------------------- modules/calib3d/src/rhosse2.h | 331 ------- 3 files changed, 69 insertions(+), 1882 deletions(-) delete mode 100644 modules/calib3d/src/rhosse2.cpp delete mode 100644 modules/calib3d/src/rhosse2.h diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index 1fafc14ec..16e406057 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -42,9 +42,6 @@ #include "precomp.hpp" #include "rhorefc.h" -#if CV_SSE2 -#include "rhosse2.h" -#endif #include namespace cv @@ -279,65 +276,83 @@ public: namespace cv{ -static bool createAndRunRHORegistrator(double confidence, int maxIters, double ransacReprojThreshold, int npoints, InputArray _src, InputArray _dst, OutputArray _H, OutputArray _tempMask){ - Mat src = _src.getMat(); - Mat dst = _dst.getMat(); - Mat tempMask = _tempMask.getMat(); - bool result; +static bool createAndRunRHORegistrator(double confidence, + int maxIters, + double ransacReprojThreshold, + int npoints, + InputArray _src, + InputArray _dst, + OutputArray _H, + OutputArray _tempMask){ + Mat src = _src.getMat(); + Mat dst = _dst.getMat(); + Mat tempMask = _tempMask.getMat(); + bool result; + double beta = 0.35;/* 0.35 is a value that often works. */ - /* Run RHO. Needs cleanup or separate function to invoke. */ + /* Create temporary output matrix (RHO outputs a single-precision H only). */ Mat tmpH = Mat(3, 3, CV_32FC1); + + /* Create output mask. */ if(!tempMask.data){ tempMask = Mat(npoints, 1, CV_8U); } - double beta = 0.35;/* 0.35 is a value that often works. */ -#if CV_SSE2 && 0 - if(useOptimized()){ - RHO_HEST_SSE2 p; - rhoSSE2Init(&p); - rhoSSE2EnsureCapacity(&p, npoints, beta); - result = !!rhoSSE2(&p, - (const float*)src.data, - (const float*)dst.data, - (char*) tempMask.data, - npoints, - ransacReprojThreshold, - maxIters, - maxIters, - confidence, - 4, - beta, - RHO_FLAG_ENABLE_NR, - NULL, - (float*)tmpH.data); - rhoSSE2Fini(&p); - }else -#endif - { - RHO_HEST_REFC p; - rhoRefCInit(&p); - rhoRefCEnsureCapacity(&p, npoints, beta); - result = !!rhoRefC(&p, - (const float*)src.data, - (const float*)dst.data, - (char*) tempMask.data, - npoints, - ransacReprojThreshold, - maxIters, - maxIters, - confidence, - 4, - beta, - /*RHO_FLAG_ENABLE_NR,*/ - RHO_FLAG_ENABLE_NR | RHO_FLAG_ENABLE_FINAL_REFINEMENT, - NULL, - (float*)tmpH.data); - rhoRefCFini(&p); - } + + /** + * Make use of the RHO estimator API. + * + * This is where the math happens. A homography estimation context is + * initialized, used, then finalized. + */ + + RHO_HEST_REFC p; + rhoRefCInit(&p); + + /** + * Optional. Ideally, the context would survive across calls to + * findHomography(), but no clean way appears to exit to do so. The price + * to pay is marginally more computational work than strictly needed. + */ + + rhoRefCEnsureCapacity(&p, npoints, beta); + + /** + * The critical call. All parameters are heavily documented in rhorefc.h. + * + * Currently, NR (Non-Randomness criterion) and Final Refinement (with + * internal, optimized Levenberg-Marquardt method) are enabled. However, + * while refinement seems to correctly smooth jitter most of the time, when + * refinement fails it tends to make the estimate visually very much worse. + * It may be necessary to remove the refinement flags in a future commit if + * this behaviour is too problematic. + */ + + result = !!rhoRefC(&p, + (const float*)src.data, + (const float*)dst.data, + (char*) tempMask.data, + npoints, + ransacReprojThreshold, + maxIters, + maxIters, + confidence, + 4, + beta, + RHO_FLAG_ENABLE_NR | RHO_FLAG_ENABLE_FINAL_REFINEMENT, + NULL, + (float*)tmpH.data); + + /** + * Cleanup. + */ + + rhoRefCFini(&p); + + /* Convert float homography to double precision. */ tmpH.convertTo(_H, CV_64FC1); - /* Maps non-zero maks elems to 1, for the sake of the testcase. */ + /* Maps non-zero mask elems to 1, for the sake of the testcase. */ for(int k=0;k -#include -#include -#include -#include -#include -#include -#include -#include "rhosse2.h" - - - -/* Defines */ -#define MEM_ALIGN 32 -#define HSIZE (3*4*sizeof(float)) -#define MIN_DELTA_CHNG 0.1 -#define REL_CHNG(a, b) (fabs((a) - (b))/(a)) -#define CHNG_SIGNIFICANT(a, b) (REL_CHNG(a, b) > MIN_DELTA_CHNG) -#define CHI_STAT 2.706 -#define CHI_SQ 1.645 - - - -namespace cv{ - -/* Data Structures */ - - - -/* Prototypes */ -static inline void* almalloc(size_t nBytes); -static inline void alfree(void* ptr); - -static inline int sacInitRun(RHO_HEST_SSE2* restrict p, - const float* restrict src, - const float* restrict dst, - char* restrict inl, - unsigned N, - float maxD, - unsigned maxI, - unsigned rConvg, - double cfd, - unsigned minInl, - double beta, - unsigned flags, - const float* guessH, - float* finalH); -static inline void sacFiniRun(RHO_HEST_SSE2* p); -static inline int sacIsNREnabled(RHO_HEST_SSE2* p); -static inline int sacIsRefineEnabled(RHO_HEST_SSE2* p); -static inline int sacIsFinalRefineEnabled(RHO_HEST_SSE2* p); -static inline int sacPhaseEndReached(RHO_HEST_SSE2* p); -static inline void sacGoToNextPhase(RHO_HEST_SSE2* p); -static inline void sacGetPROSACSample(RHO_HEST_SSE2* p); -static inline int sacIsSampleDegenerate(RHO_HEST_SSE2* p); -static inline void sacGenerateModel(RHO_HEST_SSE2* p); -static inline int sacIsModelDegenerate(RHO_HEST_SSE2* p); -static inline void sacEvaluateModelSPRT(RHO_HEST_SSE2* p); -static inline void sacUpdateSPRT(RHO_HEST_SSE2* p); -static inline void sacDesignSPRTTest(RHO_HEST_SSE2* p); -static inline int sacIsBestModel(RHO_HEST_SSE2* p); -static inline int sacIsBestModelGoodEnough(RHO_HEST_SSE2* p); -static inline void sacSaveBestModel(RHO_HEST_SSE2* p); -static inline void sacInitNonRand(double beta, - unsigned start, - unsigned N, - unsigned* nonRandMinInl); -static inline void sacNStarOptimize(RHO_HEST_SSE2* p); -static inline void sacUpdateBounds(RHO_HEST_SSE2* p); -static inline void sacOutputModel(RHO_HEST_SSE2* p); - -static inline double sacInitPEndFpI(const unsigned ransacConvg, - const unsigned n, - const unsigned m); -static inline void sacRndSmpl(unsigned sampleSize, - unsigned* currentSample, - unsigned dataSetSize); -static inline double sacRandom(void); -static inline unsigned sacCalcIterBound(double confidence, - double inlierRate, - unsigned sampleSize, - unsigned maxIterBound); -static inline void hFuncRefC(float* packedPoints, float* H); - - - -/* Functions */ - -/** - * Initialize the estimator context, by allocating the aligned buffers - * internally needed. - * - * @param [in/out] p The uninitialized estimator context to initialize. - * @return 0 if successful; non-zero if an error occured. - */ - -int rhoSSE2Init(RHO_HEST_SSE2* p){ - p->smpl = (unsigned*)almalloc(4*sizeof(*p->smpl)); - p->H = (float*) almalloc(HSIZE); - p->bestH = (float*) almalloc(HSIZE); - p->pkdPts = (float*) almalloc(4*2*2*sizeof(*p->pkdPts)); - p->nrTBL = NULL; - p->nrSize = 0; - p->nrBeta = 0.0; - - int ret = p->smpl && - p->H && - p->bestH && - p->pkdPts; - - if(!ret){ - rhoSSE2Fini(p); - } - - return ret; -} - - -/** - * Ensure that the estimator context's internal table for non-randomness - * criterion is at least of the given size, and uses the given beta. The table - * should be larger than the maximum number of matches fed into the estimator. - * - * A value of N of 0 requests deallocation of the table. - * - * @param [in] p The initialized estimator context - * @param [in] N If 0, deallocate internal table. If > 0, ensure that the - * internal table is of at least this size, reallocating if - * necessary. - * @param [in] beta The beta-factor to use within the table. - * @return 1 if successful; 0 if an error occured. - */ - -int rhoSSE2EnsureCapacity(RHO_HEST_SSE2* p, unsigned N, double beta){ - unsigned* tmp; - - - if(N == 0){ - /* Deallocate table */ - alfree(p->nrTBL); - p->nrTBL = NULL; - p->nrSize = 0; - }else{ - /* Ensure table at least as big as N and made for correct beta. */ - if(p->nrTBL && p->nrBeta == beta && p->nrSize >= N){ - /* Table already correctly set up */ - }else{ - if(p->nrSize < N){ - /* Reallocate table because it is too small. */ - tmp = (unsigned*)almalloc(N*sizeof(unsigned)); - if(!tmp){ - return 0; - } - - /* Must recalculate in whole or part. */ - if(p->nrBeta != beta){ - /* Beta changed; recalculate in whole. */ - sacInitNonRand(beta, 0, N, tmp); - alfree(p->nrTBL); - }else{ - /* Beta did not change; Copy over any work already done. */ - memcpy(tmp, p->nrTBL, p->nrSize*sizeof(unsigned)); - sacInitNonRand(beta, p->nrSize, N, tmp); - alfree(p->nrTBL); - } - - p->nrTBL = tmp; - p->nrSize = N; - p->nrBeta = beta; - }else{ - /* Might recalculate in whole, or not at all. */ - if(p->nrBeta != beta){ - /* Beta changed; recalculate in whole. */ - sacInitNonRand(beta, 0, p->nrSize, p->nrTBL); - p->nrBeta = beta; - }else{ - /* Beta did not change; Table was already big enough. Do nothing. */ - /* Besides, this is unreachable. */ - } - } - } - } - - return 1; -} - - -/** - * Finalize the estimator context, by freeing the aligned buffers used - * internally. - * - * @param [in] p The initialized estimator context to finalize. - */ - -void rhoSSE2Fini(RHO_HEST_SSE2* p){ - alfree(p->smpl); - alfree(p->H); - alfree(p->bestH); - alfree(p->pkdPts); - alfree(p->nrTBL); -} - - -/** - * Estimates the homography using the given context, matches and parameters to - * PROSAC. - * - * @param [in/out] p The context to use for homography estimation. Must - * be already initialized. Cannot be NULL. - * @param [in] src The pointer to the source points of the matches. - * Must be aligned to 16 bytes. Cannot be NULL. - * @param [in] dst The pointer to the destination points of the matches. - * Must be aligned to 16 bytes. Cannot be NULL. - * @param [out] bestInl The pointer to the output mask of inlier matches. - * Must be aligned to 16 bytes. May be NULL. - * @param [in] N The number of matches. - * @param [in] maxD The maximum distance. - * @param [in] maxI The maximum number of PROSAC iterations. - * @param [in] rConvg The RANSAC convergence parameter. - * @param [in] cfd The required confidence in the solution. - * @param [in] minInl The minimum required number of inliers. - * @param [in] beta The beta-parameter for the non-randomness criterion. - * @param [in] flags A union of flags to control the estimation. - * @param [in] guessH An extrinsic guess at the solution H, or NULL if - * none provided. - * @param [out] finalH The final estimation of H, or the zero matrix if - * the minimum number of inliers was not met. - * Cannot be NULL. - * @return The number of inliers if the minimum number of - * inliers for acceptance was reached; 0 otherwise. - */ - -unsigned rhoSSE2(RHO_HEST_SSE2* restrict p, /* Homography estimation context. */ - const float* restrict src, /* Source points */ - const float* restrict dst, /* Destination points */ - char* restrict bestInl, /* Inlier mask */ - unsigned N, /* = src.length = dst.length = inl.length */ - float maxD, /* 3.0 */ - unsigned maxI, /* 2000 */ - unsigned rConvg, /* 2000 */ - double cfd, /* 0.995 */ - unsigned minInl, /* 4 */ - double beta, /* 0.35 */ - unsigned flags, /* 0 */ - const float* guessH, /* Extrinsic guess, NULL if none provided */ - float* finalH){ /* Final result. */ - - /** - * Setup - */ - - if(!sacInitRun(p, src, dst, bestInl, N, maxD, maxI, rConvg, cfd, minInl, beta, flags, guessH, finalH)){ - sacFiniRun(p); - return 0; - } - - - /** - * PROSAC Loop - */ - - for(p->i=0; p->i < p->maxI; p->i++){ - if(sacPhaseEndReached(p)){ - sacGoToNextPhase(p); - } - - sacGetPROSACSample(p); - if(sacIsSampleDegenerate(p)){ - continue; - } - - sacGenerateModel(p); - if(sacIsModelDegenerate(p)){ - continue; - } - - sacEvaluateModelSPRT(p); - sacUpdateSPRT(p); - if(sacIsBestModel(p)){ - if(sacIsRefineEnabled(p)){ - /* sacRefine(p) */ - } - - sacSaveBestModel(p); - sacUpdateBounds(p); - - if(sacIsNREnabled(p)){ - sacNStarOptimize(p); - } - } - } - - - /** - * Teardown - */ - - if(sacIsFinalRefineEnabled(p)){ - /* sacRefineFinal(p) */ - } - - sacOutputModel(p); - sacFiniRun(p); - return sacIsBestModelGoodEnough(p) ? p->bestNumInl : 0; -} - - -/** - * Allocate memory aligned to a boundary of MEMALIGN. - */ - -static inline void* almalloc(size_t nBytes){ - if(nBytes){ - unsigned char* ptr = (unsigned char*)malloc(MEM_ALIGN + nBytes); - if(ptr){ - unsigned char* adj = (unsigned char*)(((intptr_t)(ptr+MEM_ALIGN))&((intptr_t)(-MEM_ALIGN))); - ptrdiff_t diff = adj - ptr; - adj[-1] = diff - 1; - return adj; - } - } - - return NULL; -} - -/** - * Free aligned memory - */ - -static inline void alfree(void* ptr){ - if(ptr){ - unsigned char* cptr = (unsigned char*)ptr; - free(cptr - (ptrdiff_t)cptr[-1] - 1); - } -} - - -/** - * Initialize SAC for a run. - * - * Passed all the arguments of hest. - */ - -static inline int sacInitRun(RHO_HEST_SSE2* restrict p, - const float* restrict src, - const float* restrict dst, - char* restrict bestInl, - unsigned N, - float maxD, - unsigned maxI, - unsigned rConvg, - double cfd, - unsigned minInl, - double beta, - unsigned flags, - const float* guessH, - float* finalH){ - p->src = src; - p->dst = dst; - p->allocBestInl = !bestInl; - p->bestInl = bestInl ? bestInl : (char*)almalloc(N); - p->inl = (char*)almalloc(N); - p->N = N; - p->maxD = maxD; - p->maxI = maxI; - p->rConvg = rConvg; - p->cfd = cfd; - p->minInl = minInl < 4 ? 4 : minInl; - p->beta = beta; - p->flags = flags; - p->guessH = guessH; - p->finalH = finalH; - - if(p->guessH){ - memcpy(p->H, p->guessH, HSIZE); - } - memset(p->bestH, 0, HSIZE); - memset(p->finalH, 0, HSIZE); - - if(!p->inl || !p->bestInl){/* Malloc failure */ - return 0; - } - if(sacIsNREnabled(p) && !rhoSSE2EnsureCapacity(p, N, beta)){ - return 0; - } - - p->phNum = 4; - p->phEndI = 1; - p->phEndFpI = sacInitPEndFpI(p->rConvg, p->N, 4); - p->phMax = p->N; - p->phNumInl = 0; - p->bestNumInl = 0; - p->numInl = 0; - p->numModels = 0; - p->Ntested = 0; - p->Ntestedtotal = 0; - p->good = 1; - p->t_M = 25; - p->m_S = 1; - p->epsilon = 0.1; - p->delta = 0.01; - sacDesignSPRTTest(p); - - return 1; -} - -/** - * Finalize SAC run. - * - * @param p - */ - -static inline void sacFiniRun(RHO_HEST_SSE2* p){ - if(p->allocBestInl){ - alfree(p->bestInl); - } - alfree(p->inl); -} - -/** - * Check whether non-randomness criterion is enabled. - * - * @param p - * @return Zero if disabled; non-zero if not. - */ - -static inline int sacIsNREnabled(RHO_HEST_SSE2* p){ - return p->flags & RHO_FLAG_ENABLE_NR; -} - -/** - * Check whether best-model-so-far refinement is enabled. - * - * @param p - * @return Zero if disabled; non-zero if not. - */ - -static inline int sacIsRefineEnabled(RHO_HEST_SSE2* p){ - return p->flags & RHO_FLAG_ENABLE_REFINEMENT; -} - -/** - * Check whether final-model refinement is enabled. - * - * @param p - * @return Zero if disabled; non-zero if not. - */ - -static inline int sacIsFinalRefineEnabled(RHO_HEST_SSE2* p){ - return p->flags & RHO_FLAG_ENABLE_FINAL_REFINEMENT; -} - -/** - * @brief sacPhaseEndReached - * @param p - * @return - */ - -static inline int sacPhaseEndReached(RHO_HEST_SSE2* p){ - return p->i >= p->phEndI && p->phNum < p->phMax; -} - -/** - * @brief sacGoToNextPhase - * @param p - */ - -static inline void sacGoToNextPhase(RHO_HEST_SSE2* p){ - double next; - unsigned m = 4; - - p->phNum++; - next = (p->phEndFpI * p->phNum)/(p->phNum - m); - p->phEndI += ceil(next - p->phEndFpI); - p->phEndFpI = next; -} - -/** - * @brief sacGetPROSACSample - * @param p - */ - -static inline void sacGetPROSACSample(RHO_HEST_SSE2* p){ - if(p->i > p->phEndI){ - sacRndSmpl(4, p->smpl, p->phNum);/* Used to be phMax */ - }else{ - sacRndSmpl(3, p->smpl, p->phNum-1); - p->smpl[3] = p->phNum-1; - } -} - -/** - * @brief sacIsSampleDegenerate - * @param p - * @return - */ - -static inline int sacIsSampleDegenerate(RHO_HEST_SSE2* p){ - unsigned i0 = p->smpl[0], i1 = p->smpl[1], i2 = p->smpl[2], i3 = p->smpl[3]; - - /** - * Pack the matches selected by the SAC algorithm. - * Must be packed points[0:7] = {srcx0, srcy0, srcx1, srcy1, srcx2, srcy2, srcx3, srcy3} - * points[8:15] = {dstx0, dsty0, dstx1, dsty1, dstx2, dsty2, dstx3, dsty3} - * Gather 4 points into the vector - */ - - __m128 src10 = _mm_castpd_ps(_mm_load_sd((const double*)&p->src[2*i0])); - src10 = _mm_loadh_pi(src10, (__m64*)&p->src[2*i1]); - __m128 src32 = _mm_castpd_ps(_mm_load_sd((const double*)&p->src[2*i2])); - src32 = _mm_loadh_pi(src32, (__m64*)&p->src[2*i3]); - __m128 dst10 = _mm_castpd_ps(_mm_load_sd((const double*)&p->dst[2*i0])); - dst10 = _mm_loadh_pi(dst10, (__m64*)&p->dst[2*i1]); - __m128 dst32 = _mm_castpd_ps(_mm_load_sd((const double*)&p->dst[2*i2])); - dst32 = _mm_loadh_pi(dst32, (__m64*)&p->dst[2*i3]); - - - /** - * If the matches' source points have common x and y coordinates, abort. - */ - - /** - * Check: - * packedPoints[0].x == packedPoints[2].x - * packedPoints[0].y == packedPoints[2].y - * packedPoints[1].x == packedPoints[3].x - * packedPoints[1].y == packedPoints[3].y - */ - - __m128 chkEq0 = _mm_cmpeq_ps(src10, src32); - - /** - * Check: - * packedPoints[1].x == packedPoints[2].x - * packedPoints[1].y == packedPoints[2].y - * packedPoints[0].x == packedPoints[3].x - * packedPoints[0].y == packedPoints[3].y - */ - - __m128 chkEq1 = _mm_cmpeq_ps(_mm_shuffle_ps(src10, src10, _MM_SHUFFLE(1, 0, 3, 2)), src32); - - /** - * Check: - * packedPoints[0].x == packedPoints[1].x - * packedPoints[0].y == packedPoints[1].y - * packedPoints[2].x == packedPoints[3].x - * packedPoints[2].y == packedPoints[3].y - */ - - __m128 chkEq2 = _mm_cmpeq_ps(_mm_shuffle_ps(src10, src32, _MM_SHUFFLE(1, 0, 1, 0)), - _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(3, 2, 3, 2))); - - /* Verify */ - if(_mm_movemask_ps(_mm_or_ps(chkEq0, _mm_or_ps(chkEq1, chkEq2)))){ - return 1; - } - - /* If the matches do not satisfy the strong geometric constraint, abort. */ - - /** - * p6420x = (p6.x, p4.x, p2.x, p0.x) - * p6420y = (p6.y, p4.y, p2.y, p0.y) - * p7531x = (p7.x, p5.x, p3.x, p1.x) - * p7531y = (p7.y, p5.y, p3.y, p1.y) - * crosssd0 = p6420y - p7531y = (cross2d0, cross0d0, cross2s0, cross0s0) - * crosssd1 = p7531x - p6420x = (cross2d1, cross0d1, cross2s1, cross0s1) - * crosssd2 = p6420x * p7531y - p6420y * p7531x = (cross2d2, cross0d2, cross2s2, cross0s2) - * - * shufcrosssd0 = (cross0d0, cross2d0, cross0s0, cross2s0) - * shufcrosssd1 = (cross0d1, cross2d1, cross0s1, cross2s1) - * shufcrosssd2 = (cross0d2, cross2d2, cross0s2, cross2s2) - * - * dotsd0 = shufcrosssd0 * p6420x + - * shufcrosssd1 * p6420y + - * shufcrosssd2 - * = (dotd0, dotd2, dots0, dots2) - * dotsd1 = shufcrosssd0 * p7531x + - * shufcrosssd1 * p7531y + - * shufcrosssd2 - * = (dotd1, dotd3, dots1, dots3) - * - * dots = shufps(dotsd0, dotsd1, _MM_SHUFFLE(1, 0, 1, 0)) - * dotd = shufps(dotsd0, dotsd1, _MM_SHUFFLE(3, 2, 3, 2)) - * movmaskps(dots ^ dotd) - */ - - __m128 p3210x = _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(2, 0, 2, 0)); - __m128 p3210y = _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(3, 1, 3, 1)); - __m128 p7654x = _mm_shuffle_ps(dst10, dst32, _MM_SHUFFLE(2, 0, 2, 0)); - __m128 p7654y = _mm_shuffle_ps(dst10, dst32, _MM_SHUFFLE(3, 1, 3, 1)); - __m128 p6420x = _mm_shuffle_ps(p3210x, p7654x, _MM_SHUFFLE(2, 0, 2, 0)); - __m128 p6420y = _mm_shuffle_ps(p3210y, p7654y, _MM_SHUFFLE(2, 0, 2, 0)); - __m128 p7531x = _mm_shuffle_ps(p3210x, p7654x, _MM_SHUFFLE(3, 1, 3, 1)); - __m128 p7531y = _mm_shuffle_ps(p3210y, p7654y, _MM_SHUFFLE(3, 1, 3, 1)); - - __m128 crosssd0 = _mm_sub_ps(p6420y, p7531y); - __m128 crosssd1 = _mm_sub_ps(p7531x, p6420x); - __m128 crosssd2 = _mm_sub_ps(_mm_mul_ps(p6420x, p7531y), _mm_mul_ps(p6420y, p7531x)); - - __m128 shufcrosssd0 = _mm_shuffle_ps(crosssd0, crosssd0, _MM_SHUFFLE(2, 3, 0, 1)); - __m128 shufcrosssd1 = _mm_shuffle_ps(crosssd1, crosssd1, _MM_SHUFFLE(2, 3, 0, 1)); - __m128 shufcrosssd2 = _mm_shuffle_ps(crosssd2, crosssd2, _MM_SHUFFLE(2, 3, 0, 1)); - - __m128 dotsd0 = _mm_add_ps(_mm_add_ps(_mm_mul_ps(shufcrosssd0, p6420x), - _mm_mul_ps(shufcrosssd1, p6420y)), - shufcrosssd2); - __m128 dotsd1 = _mm_add_ps(_mm_add_ps(_mm_mul_ps(shufcrosssd0, p7531x), - _mm_mul_ps(shufcrosssd1, p7531y)), - shufcrosssd2); - - __m128 dots = _mm_shuffle_ps(dotsd0, dotsd1, _MM_SHUFFLE(0, 1, 0, 1)); - __m128 dotd = _mm_shuffle_ps(dotsd0, dotsd1, _MM_SHUFFLE(2, 3, 2, 3)); - - /* if(_mm_movemask_ps(_mm_cmpge_ps(_mm_setzero_ps(), _mm_mul_ps(dots, dotd)))){ */ - if(_mm_movemask_epi8(_mm_cmplt_epi32(_mm_xor_si128(_mm_cvtps_epi32(dots), _mm_cvtps_epi32(dotd)), _mm_setzero_si128()))){ - return 1; - } - - - /* Otherwise, proceed with evaluation */ - _mm_store_ps(&p->pkdPts[0], src10); - _mm_store_ps(&p->pkdPts[4], src32); - _mm_store_ps(&p->pkdPts[8], dst10); - _mm_store_ps(&p->pkdPts[12], dst32); - - return 0; -} - -/** - * Compute homography of matches in p->pkdPts with hFuncRefC and store in p->H. - * - * @param p - */ - -static inline void sacGenerateModel(RHO_HEST_SSE2* p){ - hFuncRefC(p->pkdPts, p->H); -} - -/** - * @brief sacIsModelDegenerate - * @param p - * @return - */ - -static inline int sacIsModelDegenerate(RHO_HEST_SSE2* p){ - int degenerate; - float* H = p->H; - float f=H[0]+H[1]+H[2]+H[4]+H[5]+H[6]+H[8]+H[9]; - - /* degenerate = isnan(f); */ - degenerate = f!=f;/* Only NaN is not equal to itself. */ - /* degenerate = 0; */ - - if(degenerate){return degenerate;} - -#if 0 - - /** - * Convexity test - * - * x' = Hx for i=1..4 must be convex. - * - * [ x' ] [ H00 H01 H02 ] [ x ] - * [ y' ] = [ H10 H11 H12 ] [ y ], where: - * [ z' ] [ H20 H21 H22 ] [ 1 ] - * - * p0 = (0, 0) - * p1 = (0, 1) - * p2 = (1, 1) - * p3 = (1, 0) - */ - - float pt[4][2]; - float pz[4][1]; - - pt[0][0] = H[2]; - pt[0][1] = H[6]; - pz[0][0] = H[10]; - pt[1][0] = H[1]+H[2]; - pt[1][1] = H[5]+H[6]; - pz[1][0] = H[9]+H[10]; - pt[2][0] = H[0]+H[1]+H[2]; - pt[2][1] = H[4]+H[5]+H[6]; - pz[2][0] = H[8]+H[9]+H[10]; - pt[3][0] = H[0]+H[2]; - pt[3][1] = H[4]+H[6]; - pz[3][0] = H[8]+H[10]; - - pt[0][0] /= pz[0][0]; - pt[0][1] /= pz[0][0]; - pt[1][0] /= pz[1][0]; - pt[1][1] /= pz[1][0]; - pt[2][0] /= pz[2][0]; - pt[2][1] /= pz[2][0]; - pt[3][0] /= pz[3][0]; - pt[3][1] /= pz[3][0]; - - /** - * Crossproduct: - * - * (x, y, z) = (ay bz - az by, - * az bx - ax bz, - * ax by - ay bx) - */ - - __m128 src10 = _mm_load_ps(&pt[0][0]); - __m128 src32 = _mm_load_ps(&pt[2][0]); - - __m128 p3210x = _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(2, 0, 2, 0)); - __m128 p3210y = _mm_shuffle_ps(src10, src32, _MM_SHUFFLE(3, 1, 3, 1)); - __m128 p2103x = _mm_shuffle_ps(p3210x, p3210x, _MM_SHUFFLE(2, 1, 0, 3)); - __m128 p2103y = _mm_shuffle_ps(p3210y, p3210y, _MM_SHUFFLE(2, 1, 0, 3)); - __m128 vax = _mm_sub_ps(p3210x, p2103x); - __m128 vay = _mm_sub_ps(p3210y, p2103y); - __m128 vbx = _mm_shuffle_ps(vax, vax, _MM_SHUFFLE(2, 1, 0, 3)); - __m128 vby = _mm_shuffle_ps(vay, vay, _MM_SHUFFLE(2, 1, 0, 3)); - - __m128 cross = _mm_sub_ps(_mm_mul_ps(vax, vby), _mm_mul_ps(vay, vbx)); - - degenerate = _mm_movemask_ps(cross); - degenerate = degenerate != 0x0; -#endif - return degenerate; -} - -/** - * @brief sacEvaluateModelSPRT - * @param p - */ - -static inline void sacEvaluateModelSPRT(RHO_HEST_SSE2* p){ - unsigned i = 0; - unsigned isInlier; - double lambda = 1.0; - float distSq = p->maxD*p->maxD; - const float* src = p->src; - const float* dst = p->dst; - char* inl = p->inl; - float* H = p->H; - - - p->numModels++; - - p->numInl = 0; - p->Ntested = 0; - p->good = 1; - - - /* VECTOR */ - const __m128 distSqV=_mm_set1_ps(distSq); - - const __m128 H00=_mm_set1_ps(H[0]); - const __m128 H01=_mm_set1_ps(H[1]); - const __m128 H02=_mm_set1_ps(H[2]); - const __m128 H10=_mm_set1_ps(H[4]); - const __m128 H11=_mm_set1_ps(H[5]); - const __m128 H12=_mm_set1_ps(H[6]); - const __m128 H20=_mm_set1_ps(H[8]); - const __m128 H21=_mm_set1_ps(H[9]); - const __m128 H22=_mm_set1_ps(H[10]); - - for(;i<(p->N-3) && p->good;i+=4){ - /* Backproject */ - __m128 x, y, X, Y, inter0, inter1, inter2, inter3; - inter0 = _mm_loadu_ps(src+2*i); - inter1 = _mm_loadu_ps(src+2*i+4); - inter2 = _mm_loadu_ps(dst+2*i); - inter3 = _mm_loadu_ps(dst+2*i+4); - - x = _mm_shuffle_ps(inter0, inter1, _MM_SHUFFLE(2, 0, 2, 0)); - y = _mm_shuffle_ps(inter0, inter1, _MM_SHUFFLE(3, 1, 3, 1)); - X = _mm_shuffle_ps(inter2, inter3, _MM_SHUFFLE(2, 0, 2, 0)); - Y = _mm_shuffle_ps(inter2, inter3, _MM_SHUFFLE(3, 1, 3, 1)); - - __m128 reprojX = _mm_add_ps(_mm_add_ps(_mm_mul_ps(H00, x), _mm_mul_ps(H01, y)), H02); - __m128 reprojY = _mm_add_ps(_mm_add_ps(_mm_mul_ps(H10, x), _mm_mul_ps(H11, y)), H12); - __m128 reprojZ = _mm_add_ps(_mm_add_ps(_mm_mul_ps(H20, x), _mm_mul_ps(H21, y)), H22); - - __m128 recipZ = _mm_rcp_ps(reprojZ); - reprojX = _mm_mul_ps(reprojX, recipZ); - reprojY = _mm_mul_ps(reprojY, recipZ); - /* reprojX = _mm_div_ps(reprojX, reprojZ); */ - /* reprojY = _mm_div_ps(reprojY, reprojZ); */ - - reprojX = _mm_sub_ps(reprojX, X); - reprojY = _mm_sub_ps(reprojY, Y); - - reprojX = _mm_mul_ps(reprojX, reprojX); - reprojY = _mm_mul_ps(reprojY, reprojY); - - __m128 reprojDistV = _mm_add_ps(reprojX, reprojY); - - __m128 cmp = _mm_cmple_ps(reprojDistV, distSqV); - int msk = _mm_movemask_ps(cmp); - - /* ... */ - /* 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15*/ - static const unsigned bitCnt[16] = {0, 1, 1, 2, 1, 2, 2, 3, 1, 2, 2, 3, 2, 3, 3, 4}; - p->numInl += bitCnt[msk]; - - static const char byteMsk[16][4] = {{0,0,0,0},{1,0,0,0},{0,1,0,0},{1,1,0,0}, - {0,0,1,0},{1,0,1,0},{0,1,1,0},{1,1,1,0}, - {0,0,0,1},{1,0,0,1},{0,1,0,1},{1,1,0,1}, - {0,0,1,1},{1,0,1,1},{0,1,1,1},{1,1,1,1}}; - memcpy(inl, byteMsk[msk], 4); - inl+=4; - - - /* SPRT */ - lambda *= p->lambdaTBL[msk]; - p->good = lambda <= p->A; - /* If !p->good, the threshold A was exceeded, so we're rejecting */ - } - - /* SCALAR */ - for(;iN && p->good;i++){ - /* Backproject */ - float x=src[i*2],y=src[i*2+1]; - float X=dst[i*2],Y=dst[i*2+1]; - - float reprojX=H[0]*x+H[1]*y+H[2]; /* ( X_1 ) ( H_11 H_12 H_13 ) (x_1) */ - float reprojY=H[4]*x+H[5]*y+H[6]; /* ( X_2 ) = ( H_21 H_22 H_23 ) (x_2) */ - float reprojZ=H[8]*x+H[9]*y+H[10];/* ( X_3 ) ( H_31 H_32 H_33=1.0 ) (x_3 = 1.0) */ - - /* reproj is in homogeneous coordinates. To bring back to "regular" coordinates, divide by Z. */ - reprojX/=reprojZ; - reprojY/=reprojZ; - - /* Compute distance */ - reprojX-=X; - reprojY-=Y; - reprojX*=reprojX; - reprojY*=reprojY; - float reprojDist = reprojX+reprojY; - - /* ... */ - isInlier = reprojDist <= distSq; - p->numInl += isInlier; - *inl++ = isInlier; - - - /* SPRT */ - lambda *= isInlier ? p->lambdaAccept : p->lambdaReject; - p->good = lambda <= p->A; - /* If !p->good, the threshold A was exceeded, so we're rejecting */ - } - - - p->Ntested = i; - p->Ntestedtotal += i; -} - -/** - * Update either the delta or epsilon SPRT parameters, depending on the events - * that transpired in the previous evaluation. - * - * If a "good" model that is also the best was encountered, update epsilon, - * since - */ - -static inline void sacUpdateSPRT(RHO_HEST_SSE2* p){ - if(p->good){ - if(sacIsBestModel(p)){ - p->epsilon = (double)p->numInl/p->N; - sacDesignSPRTTest(p); - } - }else{ - double newDelta = (double)p->numInl/p->Ntested; - - if(newDelta > 0 && CHNG_SIGNIFICANT(p->delta, newDelta)){ - p->delta = newDelta; - sacDesignSPRTTest(p); - } - } -} - -/** - * Numerically compute threshold A from the estimated delta, epsilon, t_M and - * m_S values. - * - * Epsilon: Denotes the probability that a randomly chosen data point is - * consistent with a good model. - * Delta: Denotes the probability that a randomly chosen data point is - * consistent with a bad model. - * t_M: Time needed to instantiate a model hypotheses given a sample. - * (Computing model parameters from a sample takes the same time - * as verification of t_M data points) - * m_S: The number of models that are verified per sample. - */ - -static inline double designSPRTTest(double delta, double epsilon, double t_M, double m_S){ - double An, C, K, prevAn; - unsigned i; - - /** - * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 - * Eq (2) - */ - - C = (1-delta) * log((1-delta)/(1-epsilon)) + - delta * log( delta / epsilon ); - - /** - * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 - * Eq (6) - * K = K_1/K_2 + 1 = (t_M*C)/m_S + 1 - */ - - K = t_M*C/m_S + 1; - - /** - * Randomized RANSAC with Sequential Probability Ratio Test, ICCV 2005 - * Paragraph below Eq (6) - * - * A* = lim_{n -> infty} A_n, where - * A_0 = K1/K2 + 1 and - * A_{n+1} = K1/K2 + 1 + log(A_n) - * The series converges fast, typically within four iterations. - */ - - An = K; - i = 0; - - do{ - prevAn = An; - An = K + log(An); - }while((An-prevAn > 1.5e-8) && (++i < 10)); - - /** - * Return A = An_stopping, with n_stopping < 10 - */ - - return An; -} - -/** - * Design the SPRT test. Shorthand for - * A = sprt(delta, epsilon, t_M, m_S); - * - * Sets p->A, p->lambdaAccept, p->lambdaReject and p->lambdaLUT - */ - -static inline void sacDesignSPRTTest(RHO_HEST_SSE2* p){ - p->A = designSPRTTest(p->delta, p->epsilon, p->t_M, p->m_S); - p->lambdaReject = ((1.0 - p->delta) / (1.0 - p->epsilon)); - p->lambdaAccept = (( p->delta ) / ( p->epsilon )); - - double a0r4 = p->lambdaReject*p->lambdaReject*p->lambdaReject*p->lambdaReject; - double a1r3 = p->lambdaAccept*p->lambdaReject*p->lambdaReject*p->lambdaReject; - double a2r2 = p->lambdaAccept*p->lambdaAccept*p->lambdaReject*p->lambdaReject; - double a3r1 = p->lambdaAccept*p->lambdaAccept*p->lambdaAccept*p->lambdaReject; - double a4r0 = p->lambdaAccept*p->lambdaAccept*p->lambdaAccept*p->lambdaAccept; - - p->lambdaTBL[ 0] = a0r4; - p->lambdaTBL[ 1] = p->lambdaTBL[ 2] = p->lambdaTBL[ 4] = p->lambdaTBL[ 8] = a1r3; - p->lambdaTBL[ 3] = p->lambdaTBL[ 5] = p->lambdaTBL[ 6] = p->lambdaTBL[ 9] = p->lambdaTBL[10] = p->lambdaTBL[12] = a2r2; - p->lambdaTBL[ 7] = p->lambdaTBL[11] = p->lambdaTBL[13] = p->lambdaTBL[14] = a3r1; - p->lambdaTBL[15] = a4r0; -} - -/** - * Return whether the current model is the best model so far. - */ - -static inline int sacIsBestModel(RHO_HEST_SSE2* p){ - return p->numInl > p->bestNumInl; -} - -/** - * Returns whether the current-best model is good enough to be an - * acceptable best model, by checking whether it meets the minimum - * number of inliers. - */ - -static inline int sacIsBestModelGoodEnough(RHO_HEST_SSE2* p){ - return p->bestNumInl >= p->minInl; -} - -/** - * - */ - -static inline void sacSaveBestModel(RHO_HEST_SSE2* p){ - p->bestNumInl = p->numInl; - memcpy(p->bestH, p->H, HSIZE); - memcpy(p->bestInl, p->inl, p->N); -} - -/** - * - */ - -static inline void sacInitNonRand(double beta, - unsigned start, - unsigned N, - unsigned* nonRandMinInl){ - unsigned m = 4; - unsigned n = m+1 > start ? m+1 : start; - double beta_beta1_sq_chi = sqrt(beta*(1.0-beta)) * CHI_SQ; - - for(; n < N; n++){ - double mu = n * beta; - double sigma = sqrt(n)* beta_beta1_sq_chi; - unsigned i_min = ceil(m + mu + sigma); - - nonRandMinInl[n] = i_min; - } -} - -/** - * - */ - -static inline void sacNStarOptimize(RHO_HEST_SSE2* p){ - unsigned min_sample_length = 10*2; /*(p->N * INLIERS_RATIO) */ - unsigned best_n = p->N; - unsigned test_n = best_n; - unsigned bestNumInl = p->bestNumInl; - unsigned testNumInl = bestNumInl; - - for(;test_n > min_sample_length && testNumInl;test_n--){ - if(testNumInl*best_n > bestNumInl*test_n){ - if(testNumInl < p->nrTBL[test_n]){ - break; - } - best_n = test_n; - bestNumInl = testNumInl; - } - testNumInl -= !!p->bestInl[test_n-1]; - } - - if(bestNumInl*p->phMax > p->phNumInl*best_n){ - p->phMax = best_n; - p->phNumInl = bestNumInl; - p->maxI = sacCalcIterBound(p->cfd, - (double)p->phNumInl/p->phMax, - 4, - p->maxI); - } -} - -/** - * - */ - -static inline void sacUpdateBounds(RHO_HEST_SSE2* p){ - p->maxI = sacCalcIterBound(p->cfd, - (double)p->bestNumInl/p->N, - 4, - p->maxI); -} - -/** - * @brief sacOutputModel - * @param p - */ - -static inline void sacOutputModel(RHO_HEST_SSE2* p){ - if(!sacIsBestModelGoodEnough(p)){ - memset(p->bestH, 0, HSIZE); - } - - if(p->finalH){ - memcpy(p->finalH, p->bestH, HSIZE); - } -} - -/** - * Compute the real-valued number of samples per phase, given the RANSAC convergence speed, - * data set size and sample size. - */ - -static inline double sacInitPEndFpI(const unsigned ransacConvg, - const unsigned n, - const unsigned m){ - double numer=1, denom=1; - - unsigned i; - for(i=0;idataSetSize){ - /** - * Selection Sampling: - * - * Algorithm S (Selection sampling technique). To select n records at random from a set of N, where 0 < n ≤ N. - * S1. [Initialize.] Set t ← 0, m ← 0. (During this algorithm, m represents the number of records selected so far, - * and t is the total number of input records that we have dealt with.) - * S2. [Generate U.] Generate a random number U, uniformly distributed between zero and one. - * S3. [Test.] If (N – t)U ≥ n – m, go to step S5. - * S4. [Select.] Select the next record for the sample, and increase m and t by 1. If m < n, go to step S2; - * otherwise the sample is complete and the algorithm terminates. - * S5. [Skip.] Skip the next record (do not include it in the sample), increase t by 1, and go back to step S2. - */ - - unsigned m=0,t=0; - - for(m=0;m=1.){ - /** - * A certainty of picking at least one outlier means that we will need - * an infinite amount of iterations in order to find a correct solution. - */ - - retVal = maxIterBound; - }else if(atLeastOneOutlierProbability<=0.){ - /** - * The certainty of NOT picking an outlier means that only 1 iteration - * is needed to find a solution. - */ - - retVal = 1; - }else{ - /** - * Since 1-confidence (the probability of the model being based on at - * least one outlier in the data) is equal to - * (1-inlierRate**sampleSize)**numIterations (the probability of picking - * at least one outlier in numIterations samples), we can isolate - * numIterations (the return value) into - */ - - retVal = ceil(log(1.-confidence)/log(atLeastOneOutlierProbability)); - } - - /** - * Clamp to maxIterationBound. - */ - - return retVal <= maxIterBound ? retVal : maxIterBound; -} - - -/* Transposed, C */ -static void hFuncRefC(float* packedPoints,/* Source (four x,y float coordinates) points followed by - destination (four x,y float coordinates) points, aligned by 32 bytes */ - float* H){ /* Homography (three 16-byte aligned rows of 3 floats) */ - float x0=*packedPoints++; - float y0=*packedPoints++; - float x1=*packedPoints++; - float y1=*packedPoints++; - float x2=*packedPoints++; - float y2=*packedPoints++; - float x3=*packedPoints++; - float y3=*packedPoints++; - float X0=*packedPoints++; - float Y0=*packedPoints++; - float X1=*packedPoints++; - float Y1=*packedPoints++; - float X2=*packedPoints++; - float Y2=*packedPoints++; - float X3=*packedPoints++; - float Y3=*packedPoints++; - - float x0X0=x0*X0, x1X1=x1*X1, x2X2=x2*X2, x3X3=x3*X3; - float x0Y0=x0*Y0, x1Y1=x1*Y1, x2Y2=x2*Y2, x3Y3=x3*Y3; - float y0X0=y0*X0, y1X1=y1*X1, y2X2=y2*X2, y3X3=y3*X3; - float y0Y0=y0*Y0, y1Y1=y1*Y1, y2Y2=y2*Y2, y3Y3=y3*Y3; - - - /** - * [0] [1] Hidden Prec - * x0 y0 1 x1 - * x1 y1 1 x1 - * x2 y2 1 x1 - * x3 y3 1 x1 - * - * Eliminate ones in column 2 and 5. - * R(0)-=R(2) - * R(1)-=R(2) - * R(3)-=R(2) - * - * [0] [1] Hidden Prec - * x0-x2 y0-y2 0 x1+1 - * x1-x2 y1-y2 0 x1+1 - * x2 y2 1 x1 - * x3-x2 y3-y2 0 x1+1 - * - * Eliminate column 0 of rows 1 and 3 - * R(1)=(x0-x2)*R(1)-(x1-x2)*R(0), y1'=(y1-y2)(x0-x2)-(x1-x2)(y0-y2) - * R(3)=(x0-x2)*R(3)-(x3-x2)*R(0), y3'=(y3-y2)(x0-x2)-(x3-x2)(y0-y2) - * - * [0] [1] Hidden Prec - * x0-x2 y0-y2 0 x1+1 - * 0 y1' 0 x2+3 - * x2 y2 1 x1 - * 0 y3' 0 x2+3 - * - * Eliminate column 1 of rows 0 and 3 - * R(3)=y1'*R(3)-y3'*R(1) - * R(0)=y1'*R(0)-(y0-y2)*R(1) - * - * [0] [1] Hidden Prec - * x0' 0 0 x3+5 - * 0 y1' 0 x2+3 - * x2 y2 1 x1 - * 0 0 0 x4+7 - * - * Eliminate columns 0 and 1 of row 2 - * R(0)/=x0' - * R(1)/=y1' - * R(2)-= (x2*R(0) + y2*R(1)) - * - * [0] [1] Hidden Prec - * 1 0 0 x6+10 - * 0 1 0 x4+6 - * 0 0 1 x4+7 - * 0 0 0 x4+7 - */ - - /** - * Eliminate ones in column 2 and 5. - * R(0)-=R(2) - * R(1)-=R(2) - * R(3)-=R(2) - */ - - /*float minor[4][2] = {{x0-x2,y0-y2}, - {x1-x2,y1-y2}, - {x2 ,y2 }, - {x3-x2,y3-y2}};*/ - /*float major[8][3] = {{x2X2-x0X0,y2X2-y0X0,(X0-X2)}, - {x2X2-x1X1,y2X2-y1X1,(X1-X2)}, - {-x2X2 ,-y2X2 ,(X2 )}, - {x2X2-x3X3,y2X2-y3X3,(X3-X2)}, - {x2Y2-x0Y0,y2Y2-y0Y0,(Y0-Y2)}, - {x2Y2-x1Y1,y2Y2-y1Y1,(Y1-Y2)}, - {-x2Y2 ,-y2Y2 ,(Y2 )}, - {x2Y2-x3Y3,y2Y2-y3Y3,(Y3-Y2)}};*/ - float minor[2][4] = {{x0-x2,x1-x2,x2 ,x3-x2}, - {y0-y2,y1-y2,y2 ,y3-y2}}; - float major[3][8] = {{x2X2-x0X0,x2X2-x1X1,-x2X2 ,x2X2-x3X3,x2Y2-x0Y0,x2Y2-x1Y1,-x2Y2 ,x2Y2-x3Y3}, - {y2X2-y0X0,y2X2-y1X1,-y2X2 ,y2X2-y3X3,y2Y2-y0Y0,y2Y2-y1Y1,-y2Y2 ,y2Y2-y3Y3}, - { (X0-X2) , (X1-X2) , (X2 ) , (X3-X2) , (Y0-Y2) , (Y1-Y2) , (Y2 ) , (Y3-Y2) }}; - - /** - * int i; - * for(i=0;i<8;i++) major[2][i]=-major[2][i]; - * Eliminate column 0 of rows 1 and 3 - * R(1)=(x0-x2)*R(1)-(x1-x2)*R(0), y1'=(y1-y2)(x0-x2)-(x1-x2)(y0-y2) - * R(3)=(x0-x2)*R(3)-(x3-x2)*R(0), y3'=(y3-y2)(x0-x2)-(x3-x2)(y0-y2) - */ - - float scalar1=minor[0][0], scalar2=minor[0][1]; - minor[1][1]=minor[1][1]*scalar1-minor[1][0]*scalar2; - - major[0][1]=major[0][1]*scalar1-major[0][0]*scalar2; - major[1][1]=major[1][1]*scalar1-major[1][0]*scalar2; - major[2][1]=major[2][1]*scalar1-major[2][0]*scalar2; - - major[0][5]=major[0][5]*scalar1-major[0][4]*scalar2; - major[1][5]=major[1][5]*scalar1-major[1][4]*scalar2; - major[2][5]=major[2][5]*scalar1-major[2][4]*scalar2; - - scalar2=minor[0][3]; - minor[1][3]=minor[1][3]*scalar1-minor[1][0]*scalar2; - - major[0][3]=major[0][3]*scalar1-major[0][0]*scalar2; - major[1][3]=major[1][3]*scalar1-major[1][0]*scalar2; - major[2][3]=major[2][3]*scalar1-major[2][0]*scalar2; - - major[0][7]=major[0][7]*scalar1-major[0][4]*scalar2; - major[1][7]=major[1][7]*scalar1-major[1][4]*scalar2; - major[2][7]=major[2][7]*scalar1-major[2][4]*scalar2; - - /** - * Eliminate column 1 of rows 0 and 3 - * R(3)=y1'*R(3)-y3'*R(1) - * R(0)=y1'*R(0)-(y0-y2)*R(1) - */ - - scalar1=minor[1][1];scalar2=minor[1][3]; - major[0][3]=major[0][3]*scalar1-major[0][1]*scalar2; - major[1][3]=major[1][3]*scalar1-major[1][1]*scalar2; - major[2][3]=major[2][3]*scalar1-major[2][1]*scalar2; - - major[0][7]=major[0][7]*scalar1-major[0][5]*scalar2; - major[1][7]=major[1][7]*scalar1-major[1][5]*scalar2; - major[2][7]=major[2][7]*scalar1-major[2][5]*scalar2; - - scalar2=minor[1][0]; - minor[0][0]=minor[0][0]*scalar1-minor[0][1]*scalar2; - - major[0][0]=major[0][0]*scalar1-major[0][1]*scalar2; - major[1][0]=major[1][0]*scalar1-major[1][1]*scalar2; - major[2][0]=major[2][0]*scalar1-major[2][1]*scalar2; - - major[0][4]=major[0][4]*scalar1-major[0][5]*scalar2; - major[1][4]=major[1][4]*scalar1-major[1][5]*scalar2; - major[2][4]=major[2][4]*scalar1-major[2][5]*scalar2; - - /** - * Eliminate columns 0 and 1 of row 2 - * R(0)/=x0' - * R(1)/=y1' - * R(2)-= (x2*R(0) + y2*R(1)) - */ - - scalar1=minor[0][0]; - major[0][0]/=scalar1; - major[1][0]/=scalar1; - major[2][0]/=scalar1; - major[0][4]/=scalar1; - major[1][4]/=scalar1; - major[2][4]/=scalar1; - - scalar1=minor[1][1]; - major[0][1]/=scalar1; - major[1][1]/=scalar1; - major[2][1]/=scalar1; - major[0][5]/=scalar1; - major[1][5]/=scalar1; - major[2][5]/=scalar1; - - - scalar1=minor[0][2];scalar2=minor[1][2]; - major[0][2]-=major[0][0]*scalar1+major[0][1]*scalar2; - major[1][2]-=major[1][0]*scalar1+major[1][1]*scalar2; - major[2][2]-=major[2][0]*scalar1+major[2][1]*scalar2; - - major[0][6]-=major[0][4]*scalar1+major[0][5]*scalar2; - major[1][6]-=major[1][4]*scalar1+major[1][5]*scalar2; - major[2][6]-=major[2][4]*scalar1+major[2][5]*scalar2; - - /* Only major matters now. R(3) and R(7) correspond to the hollowed-out rows. */ - scalar1=major[0][7]; - major[1][7]/=scalar1; - major[2][7]/=scalar1; - - scalar1=major[0][0];major[1][0]-=scalar1*major[1][7];major[2][0]-=scalar1*major[2][7]; - scalar1=major[0][1];major[1][1]-=scalar1*major[1][7];major[2][1]-=scalar1*major[2][7]; - scalar1=major[0][2];major[1][2]-=scalar1*major[1][7];major[2][2]-=scalar1*major[2][7]; - scalar1=major[0][3];major[1][3]-=scalar1*major[1][7];major[2][3]-=scalar1*major[2][7]; - scalar1=major[0][4];major[1][4]-=scalar1*major[1][7];major[2][4]-=scalar1*major[2][7]; - scalar1=major[0][5];major[1][5]-=scalar1*major[1][7];major[2][5]-=scalar1*major[2][7]; - scalar1=major[0][6];major[1][6]-=scalar1*major[1][7];major[2][6]-=scalar1*major[2][7]; - - - /* One column left (Two in fact, but the last one is the homography) */ - scalar1=major[1][3]; - - major[2][3]/=scalar1; - scalar1=major[1][0];major[2][0]-=scalar1*major[2][3]; - scalar1=major[1][1];major[2][1]-=scalar1*major[2][3]; - scalar1=major[1][2];major[2][2]-=scalar1*major[2][3]; - scalar1=major[1][4];major[2][4]-=scalar1*major[2][3]; - scalar1=major[1][5];major[2][5]-=scalar1*major[2][3]; - scalar1=major[1][6];major[2][6]-=scalar1*major[2][3]; - scalar1=major[1][7];major[2][7]-=scalar1*major[2][3]; - - - /* Homography is done. */ - H[0]=major[2][0]; - H[1]=major[2][1]; - H[2]=major[2][2]; - - H[4]=major[2][4]; - H[5]=major[2][5]; - H[6]=major[2][6]; - - H[8]=major[2][7]; - H[9]=major[2][3]; - H[10]=1.0; -} - - -} /* End namespace cv */ diff --git a/modules/calib3d/src/rhosse2.h b/modules/calib3d/src/rhosse2.h deleted file mode 100644 index ad3d2b18b..000000000 --- a/modules/calib3d/src/rhosse2.h +++ /dev/null @@ -1,331 +0,0 @@ -/* - IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. - - By downloading, copying, installing or using the software you agree to this license. - If you do not agree to this license, do not download, install, - copy or use the software. - - - BSD 3-Clause License - - Copyright (C) 2014, Olexa Bilaniuk, Hamid Bazargani & Robert Laganiere, all rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistribution's of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - - * Redistribution's in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - * The name of the copyright holders may not be used to endorse or promote products - derived from this software without specific prior written permission. - - This software is provided by the copyright holders and contributors "as is" and - any express or implied warranties, including, but not limited to, the implied - warranties of merchantability and fitness for a particular purpose are disclaimed. - In no event shall the Intel Corporation or contributors be liable for any direct, - indirect, incidental, special, exemplary, or consequential damages - (including, but not limited to, procurement of substitute goods or services; - loss of use, data, or profits; or business interruption) however caused - and on any theory of liability, whether in contract, strict liability, - or tort (including negligence or otherwise) arising in any way out of - the use of this software, even if advised of the possibility of such damage. -*/ - -/** - * Bilaniuk, Olexa, Hamid Bazargani, and Robert Laganiere. "Fast Target - * Recognition on Mobile Devices: Revisiting Gaussian Elimination for the - * Estimation of Planar Homographies." In Computer Vision and Pattern - * Recognition Workshops (CVPRW), 2014 IEEE Conference on, pp. 119-125. - * IEEE, 2014. - */ - -/* Include Guards */ -#ifndef __RHOSSE2_H__ -#define __RHOSSE2_H__ - - - -/* Includes */ - - - - - -/* Defines */ -#ifdef __cplusplus - -/* C++ does not have the restrict keyword. */ -#ifdef restrict -#undef restrict -#endif -#define restrict - -#else - -/* C99 and over has the restrict keyword. */ -#if !defined(__STDC_VERSION__) || __STDC_VERSION__ < 199901L -#define restrict -#endif - -#endif - - -/* Flags */ -#ifndef RHO_FLAG_NONE -#define RHO_FLAG_NONE (0U<<0) -#endif -#ifndef RHO_FLAG_ENABLE_NR -#define RHO_FLAG_ENABLE_NR (1U<<0) -#endif -#ifndef RHO_FLAG_ENABLE_REFINEMENT -#define RHO_FLAG_ENABLE_REFINEMENT (1U<<1) -#endif -#ifndef RHO_FLAG_ENABLE_FINAL_REFINEMENT -#define RHO_FLAG_ENABLE_FINAL_REFINEMENT (1U<<2) -#endif - - - -/* Data structures */ - -/** - * Homography Estimation context. - */ - -typedef struct{ - /* Virtual Arguments */ - const float* restrict src; - const float* restrict dst; - int allocBestInl; - char* restrict bestInl; - unsigned N; - float maxD; - unsigned maxI; - unsigned rConvg; - double cfd; - unsigned minInl; - double beta; - unsigned flags; - const float* guessH; - float* finalH; - - /* PROSAC */ - unsigned i; /* Iteration Number */ - unsigned phNum; /* Phase Number */ - unsigned phEndI; /* Phase End Iteration */ - double phEndFpI; /* Phase floating-point End Iteration */ - unsigned phMax; /* Termination phase number */ - unsigned phNumInl; /* Number of inliers for termination phase */ - unsigned bestNumInl; /* Best number of inliers */ - unsigned numInl; /* Current number of inliers */ - unsigned numModels; /* Number of models tested */ - unsigned* restrict smpl; /* Sample */ - float* restrict H; /* Current homography */ - float* restrict bestH; /* Best homography */ - float* restrict pkdPts; /* Packed points */ - char* restrict inl; /* Inliers to current model */ - unsigned* restrict nrTBL; /* Non-Randomness: Table */ - unsigned nrSize; /* Non-Randomness: Size */ - double nrBeta; /* Non-Randomness: Beta */ - - /* SPRT */ - double t_M; /* t_M */ - double m_S; /* m_S */ - double epsilon; /* Epsilon */ - double delta; /* delta */ - double A; /* SPRT Threshold */ - unsigned Ntested; /* Number of points tested */ - unsigned Ntestedtotal; /* Number of points tested in total */ - int good; /* Good/bad flag */ - double lambdaAccept; /* Accept multiplier */ - double lambdaReject; /* Reject multiplier */ - double lambdaTBL[16]; /* Multiplier LUT */ -} RHO_HEST_SSE2; - - - -/* Extern C */ -#ifdef __cplusplus -namespace cv{ -//extern "C" { -#endif - - - -/* Functions */ - -/** - * Initialize the estimator context, by allocating the aligned buffers - * internally needed. - * - * @param [in/out] p The uninitialized estimator context to initialize. - * @return 0 if successful; non-zero if an error occured. - */ - -int rhoSSE2Init(RHO_HEST_SSE2* p); - - -/** - * Ensure that the estimator context's internal table for non-randomness - * criterion is at least of the given size, and uses the given beta. The table - * should be larger than the maximum number of matches fed into the estimator. - * - * A value of N of 0 requests deallocation of the table. - * - * @param [in] p The initialized estimator context - * @param [in] N If 0, deallocate internal table. If > 0, ensure that the - * internal table is of at least this size, reallocating if - * necessary. - * @param [in] beta The beta-factor to use within the table. - * @return 0 if successful; non-zero if an error occured. - */ - -int rhoSSE2EnsureCapacity(RHO_HEST_SSE2* p, unsigned N, double beta); - - -/** - * Finalize the estimator context, by freeing the aligned buffers used - * internally. - * - * @param [in] p The initialized estimator context to finalize. - */ - -void rhoSSE2Fini(RHO_HEST_SSE2* p); - - -/** - * Estimates the homography using the given context, matches and parameters to - * PROSAC. - * - * The given context must have been initialized. - * - * The matches are provided as two arrays of N single-precision, floating-point - * (x,y) points. Points with corresponding offsets in the two arrays constitute - * a match. The homography estimation attempts to find the 3x3 matrix H which - * best maps the homogeneous-coordinate points in the source array to their - * corresponding homogeneous-coordinate points in the destination array. - * - * Note: At least 4 matches must be provided (N >= 4). - * Note: A point in either array takes up 2 floats. The first of two stores - * the x-coordinate and the second of the two stores the y-coordinate. - * Thus, the arrays resemble this in memory: - * - * src = [x0, y0, x1, y1, x2, y2, x3, y3, x4, y4, ...] - * Matches: | | | | | - * dst = [x0, y0, x1, y1, x2, y2, x3, y3, x4, y4, ...] - * Note: The matches are expected to be provided sorted by quality, or at - * least not be worse-than-random in ordering. - * - * A pointer to the base of an array of N bytes can be provided. It serves as - * an output mask to indicate whether the corresponding match is an inlier to - * the returned homography, if any. A zero indicates an outlier; A non-zero - * value indicates an inlier. - * - * The PROSAC estimator requires a few parameters of its own. These are: - * - * - The maximum distance that a source point projected onto the destination - * plane can be from its putative match and still be considered an - * inlier. Must be non-negative. - * A sane default is 3.0. - * - The maximum number of PROSAC iterations. This corresponds to the - * largest number of samples that will be drawn and tested. - * A sane default is 2000. - * - The RANSAC convergence parameter. This corresponds to the number of - * iterations after which PROSAC will start sampling like RANSAC. - * A sane default is 2000. - * - The confidence threshold. This corresponds to the probability of - * finding a correct solution. Must be bounded by [0, 1]. - * A sane default is 0.995. - * - The minimum number of inliers acceptable. Only a solution with at - * least this many inliers will be returned. The minimum is 4. - * A sane default is 10% of N. - * - The beta-parameter for the non-randomness termination criterion. - * Ignored if non-randomness criterion disabled, otherwise must be - * bounded by (0, 1). - * A sane default is 0.35. - * - Optional flags to control the estimation. Available flags are: - * HEST_FLAG_NONE: - * No special processing. - * HEST_FLAG_ENABLE_NR: - * Enable non-randomness criterion. If set, the beta parameter - * must also be set. - * HEST_FLAG_ENABLE_REFINEMENT: - * Enable refinement of each new best model, as they are found. - * HEST_FLAG_ENABLE_FINAL_REFINEMENT: - * Enable one final refinement of the best model found before - * returning it. - * - * The PROSAC estimator additionally accepts an extrinsic initial guess of H, - * and outputs a final estimate at H provided it was able to find one with a - * minimum of supporting inliers. If it was not, it outputs the all-zero - * matrix. - * - * The extrinsic guess at and final estimate of H are both in the same form: - * A 3x3 single-precision floating-point matrix with step 4. Thus, it is a - * 12-element array of floats, with the elements as follows: - * - * [ H00, H01, H02, , - * H10, H11, H12, , - * H20, H21, H22, ] - * - * The function returns the number of inliers if it was able to find a - * homography with at least the minimum required support, and 0 if it was not. - * - * - * @param [in/out] p The context to use for homography estimation. Must - * be already initialized. Cannot be NULL. - * @param [in] src The pointer to the source points of the matches. - * Must be aligned to 16 bytes. Cannot be NULL. - * @param [in] dst The pointer to the destination points of the matches. - * Must be aligned to 16 bytes. Cannot be NULL. - * @param [out] inl The pointer to the output mask of inlier matches. - * Must be aligned to 16 bytes. May be NULL. - * @param [in] N The number of matches. - * @param [in] maxD The maximum distance. - * @param [in] maxI The maximum number of PROSAC iterations. - * @param [in] rConvg The RANSAC convergence parameter. - * @param [in] cfd The required confidence in the solution. - * @param [in] minInl The minimum required number of inliers. - * @param [in] beta The beta-parameter for the non-randomness criterion. - * @param [in] flags A union of flags to control the estimation. - * @param [in] guessH An extrinsic guess at the solution H, or NULL if - * none provided. - * @param [out] finalH The final estimation of H, or the zero matrix if - * the minimum number of inliers was not met. - * Cannot be NULL. - * @return The number of inliers if the minimum number of - * inliers for acceptance was reached; 0 otherwise. - */ - -unsigned rhoSSE2(RHO_HEST_SSE2* restrict p, /* Homography estimation context. */ - const float* restrict src, /* Source points */ - const float* restrict dst, /* Destination points */ - char* restrict bestInl, /* Inlier mask */ - unsigned N, /* = src.length = dst.length = inl.length */ - float maxD, /* 3.0 */ - unsigned maxI, /* 2000 */ - unsigned rConvg, /* 2000 */ - double cfd, /* 0.995 */ - unsigned minInl, /* 4 */ - double beta, /* 0.35 */ - unsigned flags, /* 0 */ - const float* guessH, /* Extrinsic guess, NULL if none provided */ - float* finalH); /* Final result. */ - - - - -/* Extern C */ -#ifdef __cplusplus -//} -} -#endif - - - - -#endif From 2609e77af791949db374dbeb3f337be62345aa0a Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Wed, 4 Feb 2015 02:26:01 -0500 Subject: [PATCH 09/39] Silence spurious loss-of-data warnings from Windows. Added explicit casts to silence warnings in fundam.cpp and rhorefc.cpp. --- modules/calib3d/src/fundam.cpp | 10 +++++----- modules/calib3d/src/rhorefc.cpp | 18 +++++++++--------- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index 16e406057..327670249 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -332,12 +332,12 @@ static bool createAndRunRHORegistrator(double confidence, (const float*)src.data, (const float*)dst.data, (char*) tempMask.data, - npoints, - ransacReprojThreshold, - maxIters, - maxIters, + (unsigned) npoints, + (float) ransacReprojThreshold, + (unsigned) maxIters, + (unsigned) maxIters, confidence, - 4, + 4U, beta, RHO_FLAG_ENABLE_NR | RHO_FLAG_ENABLE_FINAL_REFINEMENT, NULL, diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 40d125a53..6fc410d98 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -412,7 +412,7 @@ static inline void* almalloc(size_t nBytes){ if(ptr){ unsigned char* adj = (unsigned char*)(((intptr_t)(ptr+MEM_ALIGN))&((intptr_t)(-MEM_ALIGN))); ptrdiff_t diff = adj - ptr; - adj[-1] = diff - 1; + adj[-1] = (unsigned char)(diff - 1); return adj; } } @@ -735,7 +735,7 @@ static inline void sacPROSACGoToNextPhase(RHO_HEST_REFC* p){ p->ctrl.phNum++; next = (p->ctrl.phEndFpI * p->ctrl.phNum)/(p->ctrl.phNum - m); - p->ctrl.phEndI += ceil(next - p->ctrl.phEndFpI); + p->ctrl.phEndI += (unsigned)ceil(next - p->ctrl.phEndFpI); p->ctrl.phEndFpI = next; } @@ -913,7 +913,7 @@ static inline void sacEvaluateModelSPRT(RHO_HEST_REFC* p){ float reprojX=H[0]*x+H[1]*y+H[2]; /* ( X_1 ) ( H_11 H_12 H_13 ) (x_1) */ float reprojY=H[3]*x+H[4]*y+H[5]; /* ( X_2 ) = ( H_21 H_22 H_23 ) (x_2) */ - float reprojZ=H[6]*x+H[7]*y+1.0; /* ( X_3 ) ( H_31 H_32 H_33=1.0 ) (x_3 = 1.0) */ + float reprojZ=H[6]*x+H[7]*y+1.0f; /* ( X_3 ) ( H_31 H_32 H_33=1.0 ) (x_3 = 1.0) */ /* reproj is in homogeneous coordinates. To bring back to "regular" coordinates, divide by Z. */ reprojX/=reprojZ; @@ -929,7 +929,7 @@ static inline void sacEvaluateModelSPRT(RHO_HEST_REFC* p){ /* ... */ isInlier = reprojDist <= distSq; p->curr.numInl += isInlier; - *inl++ = isInlier; + *inl++ = (char)isInlier; /* SPRT */ @@ -1098,7 +1098,7 @@ static inline void sacInitNonRand(double beta, for(; n < N; n++){ double mu = n * beta; double sigma = sqrt(n)* beta_beta1_sq_chi; - unsigned i_min = ceil(m + mu + sigma); + unsigned i_min = (unsigned)ceil(m + mu + sigma); nonRandMinInl[n] = i_min; } @@ -1234,7 +1234,7 @@ static inline void sacRndSmpl(unsigned sampleSize, int inList; do{ - currentSample[i]=dataSetSize*sacRandom(); + currentSample[i] = (unsigned)(dataSetSize*sacRandom()); inList=0; for(j=0;j Date: Wed, 4 Feb 2015 12:12:14 -0500 Subject: [PATCH 10/39] Corrected typo in comment. The inverted JtJ does not multiply itself, but rather Jte. Correct this in the comment. --- modules/calib3d/src/rhorefc.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 6fc410d98..6d8924480 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -1583,7 +1583,7 @@ static inline void sacRefine(RHO_HEST_REFC* p){ int i; float S, newS; /* Sum of squared errors */ float gain; /* Gain-parameter. */ - float L = 0.01f;/* Lambda of LevMarq */ + float L = 100.0f;/* Lambda of LevMarq */ float dH[8], newH[8]; /** @@ -1614,7 +1614,7 @@ static inline void sacRefine(RHO_HEST_REFC* p){ * The system above is solved by Cholesky decomposition of a * sufficently-damped JtJ into a lower-triangular matrix (and its * transpose), whose inverse is then computed. This inverse (and its - * transpose) then multiply JtJ in order to find dH. + * transpose) then multiply Jte in order to find dH. */ while(!sacChol8x8Damped(p->lm.JtJ, L, p->lm.tmp1)){ From 87c2b8197ac4b4af3d049577d5c0e3443fc33c28 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Thu, 5 Feb 2015 02:18:41 -0500 Subject: [PATCH 11/39] Bug fixes in mask output. Previously, the output mask of inliers could remain completely uninitialized. This fix is the first part of a solution. --- modules/calib3d/src/fundam.cpp | 7 ++----- modules/calib3d/src/rhorefc.cpp | 6 ++++++ 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index 327670249..1366e9baa 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -286,7 +286,7 @@ static bool createAndRunRHORegistrator(double confidence, OutputArray _tempMask){ Mat src = _src.getMat(); Mat dst = _dst.getMat(); - Mat tempMask = _tempMask.getMat(); + Mat tempMask; bool result; double beta = 0.35;/* 0.35 is a value that often works. */ @@ -294,10 +294,7 @@ static bool createAndRunRHORegistrator(double confidence, Mat tmpH = Mat(3, 3, CV_32FC1); /* Create output mask. */ - if(!tempMask.data){ - tempMask = Mat(npoints, 1, CV_8U); - } - + tempMask = Mat(npoints, 1, CV_8U); /** * Make use of the RHO estimator API. diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 6d8924480..3cc9a8a1c 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -512,6 +512,9 @@ static inline int sacInitRun(RHO_HEST_REFC* p){ return 0; } + memset(p->best.inl, 0, p->arg.N); + memset(p->curr.inl, 0, p->arg.N); + /** * LevMarq workspace alloc. * @@ -1155,6 +1158,9 @@ static inline void sacUpdateBounds(RHO_HEST_REFC* p){ static inline void sacOutputModel(RHO_HEST_REFC* p){ if(sacIsBestModelGoodEnough(p)){ memcpy(p->arg.finalH, p->best.H, HSIZE); + if(p->arg.inl != p->best.inl){ + memcpy(p->arg.inl, p->best.inl, p->arg.N); + } }else{ sacOutputZeroH(p); } From adac8c04bb8dcd07f01fe865b75156dea79419e9 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Sat, 7 Feb 2015 00:56:58 -0500 Subject: [PATCH 12/39] Converted to C++ style, + bugfixes. The code has been refactored in response to feedback on Pull Request Also, outputZeroH() now also zeroes the inlier set, much like outputModel(). --- modules/calib3d/src/fundam.cpp | 9 +- modules/calib3d/src/rhorefc.cpp | 1098 ++++++++++++++++++------------- modules/calib3d/src/rhorefc.h | 114 +--- 3 files changed, 662 insertions(+), 559 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index 1366e9baa..554827583 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -303,8 +303,7 @@ static bool createAndRunRHORegistrator(double confidence, * initialized, used, then finalized. */ - RHO_HEST_REFC p; - rhoRefCInit(&p); + RHO_HEST_REFC* p = rhoRefCInit(); /** * Optional. Ideally, the context would survive across calls to @@ -312,7 +311,7 @@ static bool createAndRunRHORegistrator(double confidence, * to pay is marginally more computational work than strictly needed. */ - rhoRefCEnsureCapacity(&p, npoints, beta); + rhoRefCEnsureCapacity(p, npoints, beta); /** * The critical call. All parameters are heavily documented in rhorefc.h. @@ -325,7 +324,7 @@ static bool createAndRunRHORegistrator(double confidence, * this behaviour is too problematic. */ - result = !!rhoRefC(&p, + result = !!rhoRefC(p, (const float*)src.data, (const float*)dst.data, (char*) tempMask.data, @@ -344,7 +343,7 @@ static bool createAndRunRHORegistrator(double confidence, * Cleanup. */ - rhoRefCFini(&p); + rhoRefCFini(p); /* Convert float homography to double precision. */ tmpH.convertTo(_H, CV_64FC1); diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 3cc9a8a1c..167accd97 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -44,6 +44,7 @@ */ /* Includes */ +#include #include #include #include @@ -52,88 +53,203 @@ #include #include #include +#include #include "rhorefc.h" /* Defines */ -#define MEM_ALIGN 32 -#define HSIZE (3*3*sizeof(float)) -#define MIN_DELTA_CHNG 0.1 -#define REL_CHNG(a, b) (fabs((a) - (b))/(a)) -#define CHNG_SIGNIFICANT(a, b) (REL_CHNG(a, b) > MIN_DELTA_CHNG) -#define CHI_STAT 2.706 -#define CHI_SQ 1.645 -#define RLO 0.25 -#define RHI 0.75 -#define MAXLEVMARQITERS 100 -#define m 4 /* 4 points required per model */ -#define SPRT_T_M 25 /* Guessing 25 match evlauations / 1 model generation */ -#define SPRT_M_S 1 /* 1 model per sample */ -#define SPRT_EPSILON 0.1 /* No explanation */ -#define SPRT_DELTA 0.01 /* No explanation */ -#define LM_GAIN_LO 0.25 /* See sacLMGain(). */ -#define LM_GAIN_HI 0.75 /* See sacLMGain(). */ +const int MEM_ALIGN = 32; +const size_t HSIZE = (3*3*sizeof(float)); +const double MIN_DELTA_CHNG = 0.1; +const double CHI_STAT = 2.706; +const double CHI_SQ = 1.645; +const double RLO = 0.25; +const double RHI = 0.75; +const int MAXLEVMARQITERS = 100; +const int SMPL_SIZE = 4; /* 4 points required per model */ +const int SPRT_T_M = 25; /* Guessing 25 match evlauations / 1 model generation */ +const int SPRT_M_S = 1; /* 1 model per sample */ +const double SPRT_EPSILON = 0.1; /* No explanation */ +const double SPRT_DELTA = 0.01; /* No explanation */ +const double LM_GAIN_LO = 0.25; /* See sacLMGain(). */ +const double LM_GAIN_HI = 0.75; /* See sacLMGain(). */ + + /* For the sake of cv:: namespace ONLY: */ -#ifdef __cplusplus namespace cv{/* For C support, replace with extern "C" { */ -#endif - /* Data Structures */ +struct RHO_HEST_REFC{ + /** + * Virtual Arguments. + * + * Exactly the same as at function call, except: + * - minInl is enforced to be >= 4. + */ + + struct{ + const float* src; + const float* dst; + char* inl; + unsigned N; + float maxD; + unsigned maxI; + unsigned rConvg; + double cfd; + unsigned minInl; + double beta; + unsigned flags; + const float* guessH; + float* finalH; + } arg; + + /* PROSAC Control */ + struct{ + unsigned i; /* Iteration Number */ + unsigned phNum; /* Phase Number */ + unsigned phEndI; /* Phase End Iteration */ + double phEndFpI; /* Phase floating-point End Iteration */ + unsigned phMax; /* Termination phase number */ + unsigned phNumInl; /* Number of inliers for termination phase */ + unsigned numModels; /* Number of models tested */ + unsigned* smpl; /* Sample of match indexes */ + } ctrl; + + /* Current model being tested */ + struct{ + float* pkdPts; /* Packed points */ + float* H; /* Homography */ + char* inl; /* Mask of inliers */ + unsigned numInl; /* Number of inliers */ + } curr; + + /* Best model (so far) */ + struct{ + float* H; /* Homography */ + char* inl; /* Mask of inliers */ + unsigned numInl; /* Number of inliers */ + } best; + + /* Non-randomness criterion */ + struct{ + std::vector tbl; /* Non-Randomness: Table */ + unsigned size; /* Non-Randomness: Size */ + double beta; /* Non-Randomness: Beta */ + } nr; + + /* SPRT Evaluator */ + struct{ + double t_M; /* t_M */ + double m_S; /* m_S */ + double epsilon; /* Epsilon */ + double delta; /* delta */ + double A; /* SPRT Threshold */ + unsigned Ntested; /* Number of points tested */ + unsigned Ntestedtotal; /* Number of points tested in total */ + int good; /* Good/bad flag */ + double lambdaAccept; /* Accept multiplier */ + double lambdaReject; /* Reject multiplier */ + } eval; + + /* Levenberg-Marquardt Refinement */ + struct{ + float* ws; /* Levenberg-Marqhard Workspace */ + float (* JtJ)[8]; /* JtJ matrix */ + float (* tmp1)[8]; /* Temporary 1 */ + float* Jte; /* Jte vector */ + } lm; + + /* Initialized? */ + int init; + + + /* Empty constructors and destructors */ + public: + RHO_HEST_REFC(); + private: /* Forbid copying. */ + RHO_HEST_REFC(const RHO_HEST_REFC&); + public: + ~RHO_HEST_REFC(); + + /* Methods to implement external interface */ + inline int initialize(void); + inline int sacEnsureCapacity(unsigned N, double beta); + inline void finalize(void); + unsigned rhoRefC(const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* Works: 3.0 */ + unsigned maxI, /* Works: 2000 */ + unsigned rConvg, /* Works: 2000 */ + double cfd, /* Works: 0.995 */ + unsigned minInl, /* Minimum: 4 */ + double beta, /* Works: 0.35 */ + unsigned flags, /* Works: 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH); /* Final result. */ -/* Prototypes */ + /* Methods to implement internals */ + inline int initRun(void); + inline void finiRun(void); + inline int haveExtrinsicGuess(void); + inline int hypothesize(void); + inline int verify(void); + inline int isNREnabled(void); + inline int isRefineEnabled(void); + inline int isFinalRefineEnabled(void); + inline int PROSACPhaseEndReached(void); + inline void PROSACGoToNextPhase(void); + inline void getPROSACSample(void); + inline int isSampleDegenerate(void); + inline void generateModel(void); + inline int isModelDegenerate(void); + inline void evaluateModelSPRT(void); + inline void updateSPRT(void); + inline void designSPRTTest(void); + inline int isBestModel(void); + inline int isBestModelGoodEnough(void); + inline void saveBestModel(void); + inline void nStarOptimize(void); + inline void updateBounds(void); + inline void outputModel(void); + inline void outputZeroH(void); + inline int canRefine(void); + inline void refine(void); +}; + + + + +/** + * Prototypes for purely-computational code. + */ + static inline void* almalloc(size_t nBytes); -static inline void alfree(void* ptr); +static inline void alfree (void* ptr); -static inline int sacInitRun(RHO_HEST_REFC* p); -static inline void sacFiniRun(RHO_HEST_REFC* p); -static inline int sacHaveExtrinsicGuess(RHO_HEST_REFC* p); -static inline int sacHypothesize(RHO_HEST_REFC* p); -static inline int sacVerify(RHO_HEST_REFC* p); -static inline int sacIsNREnabled(RHO_HEST_REFC* p); -static inline int sacIsRefineEnabled(RHO_HEST_REFC* p); -static inline int sacIsFinalRefineEnabled(RHO_HEST_REFC* p); -static inline int sacPROSACPhaseEndReached(RHO_HEST_REFC* p); -static inline void sacPROSACGoToNextPhase(RHO_HEST_REFC* p); -static inline void sacGetPROSACSample(RHO_HEST_REFC* p); -static inline int sacIsSampleDegenerate(RHO_HEST_REFC* p); -static inline void sacGenerateModel(RHO_HEST_REFC* p); -static inline int sacIsModelDegenerate(RHO_HEST_REFC* p); -static inline void sacEvaluateModelSPRT(RHO_HEST_REFC* p); -static inline void sacUpdateSPRT(RHO_HEST_REFC* p); -static inline void sacDesignSPRTTest(RHO_HEST_REFC* p); -static inline int sacIsBestModel(RHO_HEST_REFC* p); -static inline int sacIsBestModelGoodEnough(RHO_HEST_REFC* p); -static inline void sacSaveBestModel(RHO_HEST_REFC* p); -static inline void sacInitNonRand(double beta, - unsigned start, - unsigned N, - unsigned* nonRandMinInl); -static inline void sacNStarOptimize(RHO_HEST_REFC* p); -static inline void sacUpdateBounds(RHO_HEST_REFC* p); -static inline void sacOutputModel(RHO_HEST_REFC* p); -static inline void sacOutputZeroH(RHO_HEST_REFC* p); - -static inline double sacInitPEndFpI(const unsigned ransacConvg, - const unsigned n, - const unsigned s); -static inline void sacRndSmpl(unsigned sampleSize, - unsigned* currentSample, - unsigned dataSetSize); -static inline double sacRandom(void); -static inline unsigned sacCalcIterBound(double confidence, - double inlierRate, - unsigned sampleSize, - unsigned maxIterBound); -static inline void hFuncRefC(float* packedPoints, float* H); -static inline int sacCanRefine(RHO_HEST_REFC* p); -static inline void sacRefine(RHO_HEST_REFC* p); +static inline void sacInitNonRand (double beta, + unsigned start, + unsigned N, + unsigned* nonRandMinInl); +static inline double sacInitPEndFpI (const unsigned ransacConvg, + const unsigned n, + const unsigned s); +static inline void sacRndSmpl (unsigned sampleSize, + unsigned* currentSample, + unsigned dataSetSize); +static inline double sacRandom (void); +static inline unsigned sacCalcIterBound (double confidence, + double inlierRate, + unsigned sampleSize, + unsigned maxIterBound); +static inline void hFuncRefC (float* packedPoints, float* H); static inline void sacCalcJacobianErrors(const float* restrict H, const float* restrict src, const float* restrict dst, @@ -142,164 +258,62 @@ static inline void sacCalcJacobianErrors(const float* restrict H, float (* restrict JtJ)[8], float* restrict Jte, float* restrict Sp); -static inline float sacLMGain(const float* dH, - const float* Jte, - const float S, - const float newS, - const float lambda); -static inline int sacChol8x8Damped (const float (*A)[8], - float lambda, - float (*L)[8]); -static inline void sacTRInv8x8(const float (*L)[8], - float (*M)[8]); -static inline void sacTRISolve8x8(const float (*L)[8], - const float* Jte, - float* dH); -static inline void sacSub8x1(float* Hout, const float* H, const float* dH); +static inline float sacLMGain (const float* dH, + const float* Jte, + const float S, + const float newS, + const float lambda); +static inline int sacChol8x8Damped (const float (*A)[8], + float lambda, + float (*L)[8]); +static inline void sacTRInv8x8 (const float (*L)[8], + float (*M)[8]); +static inline void sacTRISolve8x8 (const float (*L)[8], + const float* Jte, + float* dH); +static inline void sacSub8x1 (float* Hout, + const float* H, + const float* dH); /* Functions */ /** - * Initialize the estimator context, by allocating the aligned buffers - * internally needed. + * External access to context constructor. * - * Currently there are 5 per-estimator buffers: - * - The buffer of m indexes representing a sample - * - The buffer of 16 floats representing m matches (x,y) -> (X,Y). - * - The buffer for the current homography - * - The buffer for the best-so-far homography - * - Optionally, the non-randomness criterion table - * - * @param [in/out] p The uninitialized estimator context to initialize. - * @return 0 if successful; non-zero if an error occured. + * @return A pointer to the context if successful; NULL if an error occured. */ -int rhoRefCInit(RHO_HEST_REFC* p){ - memset(p, 0, sizeof(*p)); +RHO_HEST_REFC* rhoRefCInit(void){ + RHO_HEST_REFC* p = new RHO_HEST_REFC; - p->ctrl.smpl = (unsigned*)almalloc(m*sizeof(*p->ctrl.smpl)); - - p->curr.pkdPts = (float*) almalloc(m*2*2*sizeof(*p->curr.pkdPts)); - p->curr.H = (float*) almalloc(HSIZE); - p->curr.inl = NULL; - p->curr.numInl = 0; - - p->best.H = (float*) almalloc(HSIZE); - p->best.inl = NULL; - p->best.numInl = 0; - - p->nr.tbl = NULL;/* By default this table is not computed. */ - p->nr.size = 0; - p->nr.beta = 0.0; - - p->lm.ws = NULL; - p->lm.JtJ = NULL; - p->lm.tmp1 = NULL; - p->lm.Jte = NULL; - - - int areAllAllocsSuccessful = p->ctrl.smpl && - p->curr.H && - p->best.H && - p->curr.pkdPts; - - if(!areAllAllocsSuccessful){ - rhoRefCFini(p); + if(!p->initialize()){ + delete p; + p = NULL; } - return areAllAllocsSuccessful; + return p; } /** - * Ensure that the estimator context's internal table for non-randomness - * criterion is at least of the given size, and uses the given beta. The table - * should be larger than the maximum number of matches fed into the estimator. - * - * A value of N of 0 requests deallocation of the table. - * - * @param [in] p The initialized estimator context - * @param [in] N If 0, deallocate internal table. If > 0, ensure that the - * internal table is of at least this size, reallocating if - * necessary. - * @param [in] beta The beta-factor to use within the table. - * @return 1 if successful; 0 if an error occured. - * - * Reads: nr.* - * Writes: nr.* + * External access to non-randomness table resize. */ int rhoRefCEnsureCapacity(RHO_HEST_REFC* p, unsigned N, double beta){ - unsigned* tmp; - - - if(N == 0){ - /* Deallocate table */ - alfree(p->nr.tbl); - p->nr.tbl = NULL; - p->nr.size = 0; - }else{ - /* Ensure table at least as big as N and made for correct beta. */ - if(p->nr.tbl && p->nr.beta == beta && p->nr.size >= N){ - /* Table already correctly set up */ - }else{ - if(p->nr.size < N){ - /* Reallocate table because it is too small. */ - tmp = (unsigned*)almalloc(N*sizeof(unsigned)); - if(!tmp){ - return 0; - } - - /* Must recalculate in whole or part. */ - if(p->nr.beta != beta){ - /* Beta changed; recalculate in whole. */ - sacInitNonRand(beta, 0, N, tmp); - alfree(p->nr.tbl); - }else{ - /* Beta did not change; Copy over any work already done. */ - memcpy(tmp, p->nr.tbl, p->nr.size*sizeof(unsigned)); - sacInitNonRand(beta, p->nr.size, N, tmp); - alfree(p->nr.tbl); - } - - p->nr.tbl = tmp; - p->nr.size = N; - p->nr.beta = beta; - }else{ - /* Might recalculate in whole, or not at all. */ - if(p->nr.beta != beta){ - /* Beta changed; recalculate in whole. */ - sacInitNonRand(beta, 0, p->nr.size, p->nr.tbl); - p->nr.beta = beta; - }else{ - /* Beta did not change; Table was already big enough. Do nothing. */ - /* Besides, this is unreachable. */ - } - } - } - } - - return 1; + return p->sacEnsureCapacity(N, beta); } /** - * Finalize the estimator context, by freeing the aligned buffers used - * internally. + * External access to context destructor. * * @param [in] p The initialized estimator context to finalize. */ void rhoRefCFini(RHO_HEST_REFC* p){ - alfree(p->ctrl.smpl); - alfree(p->curr.H); - alfree(p->best.H); - alfree(p->curr.pkdPts); - alfree(p->nr.tbl); - - memset(p, 0, sizeof(*p)); + delete p; } @@ -332,76 +346,26 @@ void rhoRefCFini(RHO_HEST_REFC* p){ * inliers for acceptance was reached; 0 otherwise. */ -unsigned rhoRefC(RHO_HEST_REFC* restrict p, /* Homography estimation context. */ - const float* restrict src, /* Source points */ - const float* restrict dst, /* Destination points */ - char* restrict inl, /* Inlier mask */ - unsigned N, /* = src.length = dst.length = inl.length */ - float maxD, /* Works: 3.0 */ - unsigned maxI, /* Works: 2000 */ - unsigned rConvg, /* Works: 2000 */ - double cfd, /* Works: 0.995 */ - unsigned minInl, /* Minimum: 4 */ - double beta, /* Works: 0.35 */ - unsigned flags, /* Works: 0 */ - const float* guessH, /* Extrinsic guess, NULL if none provided */ - float* finalH){ /* Final result. */ - - /** - * Setup - */ - - p->arg.src = src; - p->arg.dst = dst; - p->arg.inl = inl; - p->arg.N = N; - p->arg.maxD = maxD; - p->arg.maxI = maxI; - p->arg.rConvg = rConvg; - p->arg.cfd = cfd; - p->arg.minInl = minInl; - p->arg.beta = beta; - p->arg.flags = flags; - p->arg.guessH = guessH; - p->arg.finalH = finalH; - if(!sacInitRun(p)){ - sacOutputZeroH(p); - sacFiniRun(p); - return 0; - } - - /** - * Extrinsic Guess - */ - - if(sacHaveExtrinsicGuess(p)){ - sacVerify(p); - } - - - /** - * PROSAC Loop - */ - - for(p->ctrl.i=0; p->ctrl.i < p->arg.maxI; p->ctrl.i++){ - sacHypothesize(p) && sacVerify(p); - } - - - /** - * Teardown - */ - - if(sacIsFinalRefineEnabled(p) && sacCanRefine(p)){ - sacRefine(p); - } - - sacOutputModel(p); - sacFiniRun(p); - return sacIsBestModelGoodEnough(p) ? p->best.numInl : 0; +unsigned rhoRefC(RHO_HEST_REFC* p, /* Homography estimation context. */ + const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* Works: 3.0 */ + unsigned maxI, /* Works: 2000 */ + unsigned rConvg, /* Works: 2000 */ + double cfd, /* Works: 0.995 */ + unsigned minInl, /* Minimum: 4 */ + double beta, /* Works: 0.35 */ + unsigned flags, /* Works: 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH){ /* Final result. */ + return p->rhoRefC(src, dst, inl, N, maxD, maxI, rConvg, cfd, minInl, beta, + flags, guessH, finalH); } + /** * Allocate memory aligned to a boundary of MEMALIGN. */ @@ -433,6 +397,241 @@ static inline void alfree(void* ptr){ } } +/** + * Constructor for RHO_HEST_REFC. + * + * Does nothing. True initialization is done by initialize(). + */ + +RHO_HEST_REFC::RHO_HEST_REFC() : init(0){ + +} + +/** + * Private copy constructor for RHO_HEST_REFC. Disabled. + */ + +RHO_HEST_REFC::RHO_HEST_REFC(const RHO_HEST_REFC&) : init(0){ + +} + +/** + * Destructor for RHO_HEST_REFC. + */ + +RHO_HEST_REFC::~RHO_HEST_REFC(){ + if(init){ + finalize(); + } +} + + + +/** + * Initialize the estimator context, by allocating the aligned buffers + * internally needed. + * + * Currently there are 5 per-estimator buffers: + * - The buffer of m indexes representing a sample + * - The buffer of 16 floats representing m matches (x,y) -> (X,Y). + * - The buffer for the current homography + * - The buffer for the best-so-far homography + * - Optionally, the non-randomness criterion table + * + * Returns 0 if unsuccessful and non-0 otherwise. + */ + +inline int RHO_HEST_REFC::initialize(void){ + ctrl.smpl = (unsigned*)almalloc(SMPL_SIZE*sizeof(*ctrl.smpl)); + + curr.pkdPts = (float*) almalloc(SMPL_SIZE*2*2*sizeof(*curr.pkdPts)); + curr.H = (float*) almalloc(HSIZE); + curr.inl = NULL; + curr.numInl = 0; + + best.H = (float*) almalloc(HSIZE); + best.inl = NULL; + best.numInl = 0; + + nr.size = 0; + nr.beta = 0.0; + + lm.ws = NULL; + lm.JtJ = NULL; + lm.tmp1 = NULL; + lm.Jte = NULL; + + + int areAllAllocsSuccessful = ctrl.smpl && + curr.H && + best.H && + curr.pkdPts; + + if(!areAllAllocsSuccessful){ + finalize(); + }else{ + init = 1; + } + + return areAllAllocsSuccessful; +} + +/** + * Finalize. + * + * Finalize the estimator context, by freeing the aligned buffers used + * internally. + */ + +inline void RHO_HEST_REFC::finalize(void){ + if(init){ + alfree(ctrl.smpl); + alfree(curr.H); + alfree(best.H); + alfree(curr.pkdPts); + + memset(this, 0, sizeof(*this)); + + init = 0; + } +} + +/** + * Ensure that the estimator context's internal table for non-randomness + * criterion is at least of the given size, and uses the given beta. The table + * should be larger than the maximum number of matches fed into the estimator. + * + * A value of N of 0 requests deallocation of the table. + * + * @param [in] N If 0, deallocate internal table. If > 0, ensure that the + * internal table is of at least this size, reallocating if + * necessary. + * @param [in] beta The beta-factor to use within the table. + * @return 1 if successful; 0 if an error occured. + * + * Reads: nr.* + * Writes: nr.* + */ + +inline int RHO_HEST_REFC::sacEnsureCapacity(unsigned N, double beta){ + if(N == 0){ + /* Clear. */ + nr.tbl.clear(); + nr.size = 0; + }else if(nr.beta != beta){ + /* Beta changed. Redo all the work. */ + nr.tbl.resize(N); + nr.beta = beta; + sacInitNonRand(nr.beta, 0, N, &nr.tbl[0]); + nr.size = N; + }else if(N > nr.size){ + /* Work is partially done. Do rest of it. */ + nr.tbl.resize(N); + sacInitNonRand(nr.beta, nr.size, N, &nr.tbl[nr.size]); + nr.size = N; + }else{ + /* Work is already done. Do nothing. */ + } + + return 1; +} + + +/** + * Estimates the homography using the given context, matches and parameters to + * PROSAC. + * + * @param [in] src The pointer to the source points of the matches. + * Must be aligned to 4 bytes. Cannot be NULL. + * @param [in] dst The pointer to the destination points of the matches. + * Must be aligned to 16 bytes. Cannot be NULL. + * @param [out] inl The pointer to the output mask of inlier matches. + * Must be aligned to 16 bytes. May be NULL. + * @param [in] N The number of matches. + * @param [in] maxD The maximum distance. + * @param [in] maxI The maximum number of PROSAC iterations. + * @param [in] rConvg The RANSAC convergence parameter. + * @param [in] cfd The required confidence in the solution. + * @param [in] minInl The minimum required number of inliers. + * @param [in] beta The beta-parameter for the non-randomness criterion. + * @param [in] flags A union of flags to control the estimation. + * @param [in] guessH An extrinsic guess at the solution H, or NULL if + * none provided. + * @param [out] finalH The final estimation of H, or the zero matrix if + * the minimum number of inliers was not met. + * Cannot be NULL. + * @return The number of inliers if the minimum number of + * inliers for acceptance was reached; 0 otherwise. + */ + +unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* Works: 3.0 */ + unsigned maxI, /* Works: 2000 */ + unsigned rConvg, /* Works: 2000 */ + double cfd, /* Works: 0.995 */ + unsigned minInl, /* Minimum: 4 */ + double beta, /* Works: 0.35 */ + unsigned flags, /* Works: 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH){ /* Final result. */ + + /** + * Setup + */ + + arg.src = src; + arg.dst = dst; + arg.inl = inl; + arg.N = N; + arg.maxD = maxD; + arg.maxI = maxI; + arg.rConvg = rConvg; + arg.cfd = cfd; + arg.minInl = minInl; + arg.beta = beta; + arg.flags = flags; + arg.guessH = guessH; + arg.finalH = finalH; + if(!initRun()){ + outputZeroH(); + finiRun(); + return 0; + } + + /** + * Extrinsic Guess + */ + + if(haveExtrinsicGuess()){ + verify(); + } + + + /** + * PROSAC Loop + */ + + for(ctrl.i=0; ctrl.i < arg.maxI; ctrl.i++){ + hypothesize() && verify(); + } + + + /** + * Teardown + */ + + if(isFinalRefineEnabled() && canRefine()){ + refine(); + } + + outputModel(); + finiRun(); + return isBestModelGoodEnough() ? best.numInl : 0; +} + /** * Initialize SAC for a run given its arguments. @@ -446,7 +645,7 @@ static inline void alfree(void* ptr){ * Writes: curr.*, best.*, ctrl.*, eval.* */ -static inline int sacInitRun(RHO_HEST_REFC* p){ +inline int RHO_HEST_REFC::initRun(void){ /** * Sanitize arguments. * @@ -454,29 +653,29 @@ static inline int sacInitRun(RHO_HEST_REFC* p){ * mean something or other. */ - if(!p->arg.src || !p->arg.dst){ + if(!arg.src || !arg.dst){ /* Arguments src or dst are insane, must be != NULL */ return 0; } - if(p->arg.N < m){ + if(arg.N < SMPL_SIZE){ /* Argument N is insane, must be >= 4. */ return 0; } - if(p->arg.maxD < 0){ + if(arg.maxD < 0){ /* Argument maxD is insane, must be >= 0. */ return 0; } - if(p->arg.cfd < 0 || p->arg.cfd > 1){ + if(arg.cfd < 0 || arg.cfd > 1){ /* Argument cfd is insane, must be in [0, 1]. */ return 0; } /* Clamp minInl to 4 or higher. */ - p->arg.minInl = p->arg.minInl < m ? m : p->arg.minInl; - if(sacIsNREnabled(p) && (p->arg.beta <= 0 || p->arg.beta >= 1)){ + arg.minInl = arg.minInl < SMPL_SIZE ? SMPL_SIZE : arg.minInl; + if(isNREnabled() && (arg.beta <= 0 || arg.beta >= 1)){ /* Argument beta is insane, must be in (0, 1). */ return 0; } - if(!p->arg.finalH){ + if(!arg.finalH){ /* Argument finalH is insane, must be != NULL */ return 0; } @@ -491,7 +690,7 @@ static inline int sacInitRun(RHO_HEST_REFC* p){ * substruct and the sanity-checked N and beta arguments from above. */ - if(sacIsNREnabled(p) && !rhoRefCEnsureCapacity(p, p->arg.N, p->arg.beta)){ + if(isNREnabled() && !sacEnsureCapacity(arg.N, arg.beta)){ return 0; } @@ -505,15 +704,15 @@ static inline int sacInitRun(RHO_HEST_REFC* p){ * not, allocate one anyways internally. */ - p->best.inl = p->arg.inl ? p->arg.inl : (char*)almalloc(p->arg.N); - p->curr.inl = (char*)almalloc(p->arg.N); + best.inl = arg.inl ? arg.inl : (char*)almalloc(arg.N); + curr.inl = (char*)almalloc(arg.N); - if(!p->curr.inl || !p->best.inl){ + if(!curr.inl || !best.inl){ return 0; } - memset(p->best.inl, 0, p->arg.N); - memset(p->curr.inl, 0, p->arg.N); + memset(best.inl, 0, arg.N); + memset(curr.inl, 0, arg.N); /** * LevMarq workspace alloc. @@ -522,17 +721,17 @@ static inline int sacInitRun(RHO_HEST_REFC* p){ * we wish to quit before doing any serious work. */ - if(sacIsRefineEnabled(p) || sacIsFinalRefineEnabled(p)){ - p->lm.ws = (float*)almalloc(2*8*8*sizeof(float) + 1*8*sizeof(float)); - if(!p->lm.ws){ + if(isRefineEnabled() || isFinalRefineEnabled()){ + lm.ws = (float*)almalloc(2*8*8*sizeof(float) + 1*8*sizeof(float)); + if(!lm.ws){ return 0; } - p->lm.JtJ = (float(*)[8])(p->lm.ws + 0*8*8); - p->lm.tmp1 = (float(*)[8])(p->lm.ws + 1*8*8); - p->lm.Jte = (float*) (p->lm.ws + 2*8*8); + lm.JtJ = (float(*)[8])(lm.ws + 0*8*8); + lm.tmp1 = (float(*)[8])(lm.ws + 1*8*8); + lm.Jte = (float*) (lm.ws + 2*8*8); }else{ - p->lm.ws = NULL; + lm.ws = NULL; } /** @@ -542,32 +741,32 @@ static inline int sacInitRun(RHO_HEST_REFC* p){ * number of fields if something in the above junk failed. */ - p->ctrl.i = 0; - p->ctrl.phNum = m; - p->ctrl.phEndI = 1; - p->ctrl.phEndFpI = sacInitPEndFpI(p->arg.rConvg, p->arg.N, m); - p->ctrl.phMax = p->arg.N; - p->ctrl.phNumInl = 0; - p->ctrl.numModels = 0; + ctrl.i = 0; + ctrl.phNum = SMPL_SIZE; + ctrl.phEndI = 1; + ctrl.phEndFpI = sacInitPEndFpI(arg.rConvg, arg.N, SMPL_SIZE); + ctrl.phMax = arg.N; + ctrl.phNumInl = 0; + ctrl.numModels = 0; - if(sacHaveExtrinsicGuess(p)){ - memcpy(p->curr.H, p->arg.guessH, HSIZE); + if(haveExtrinsicGuess()){ + memcpy(curr.H, arg.guessH, HSIZE); }else{ - memset(p->curr.H, 0, HSIZE); + memset(curr.H, 0, HSIZE); } - p->curr.numInl = 0; + curr.numInl = 0; - memset(p->best.H, 0, HSIZE); - p->best.numInl = 0; + memset(best.H, 0, HSIZE); + best.numInl = 0; - p->eval.Ntested = 0; - p->eval.Ntestedtotal = 0; - p->eval.good = 1; - p->eval.t_M = SPRT_T_M; - p->eval.m_S = SPRT_M_S; - p->eval.epsilon = SPRT_EPSILON; - p->eval.delta = SPRT_DELTA; - sacDesignSPRTTest(p); + eval.Ntested = 0; + eval.Ntestedtotal = 0; + eval.good = 1; + eval.t_M = SPRT_T_M; + eval.m_S = SPRT_M_S; + eval.epsilon = SPRT_EPSILON; + eval.delta = SPRT_DELTA; + designSPRTTest(); return 1; } @@ -583,33 +782,33 @@ static inline int sacInitRun(RHO_HEST_REFC* p){ * Writes: curr.inl, best.inl */ -static inline void sacFiniRun(RHO_HEST_REFC* p){ +inline void RHO_HEST_REFC::finiRun(void){ /** * If no output inlier mask was required, free both (internal) masks. * Else if an (external) mask was provided as argument, find the other * (the internal one) and free it. */ - if(p->arg.inl){ - if(p->arg.inl == p->best.inl){ - alfree(p->curr.inl); + if(arg.inl){ + if(arg.inl == best.inl){ + alfree(curr.inl); }else{ - alfree(p->best.inl); + alfree(best.inl); } }else{ - alfree(p->best.inl); - alfree(p->curr.inl); + alfree(best.inl); + alfree(curr.inl); } - p->best.inl = NULL; - p->curr.inl = NULL; + best.inl = NULL; + curr.inl = NULL; /** * ₣ree the Levenberg-Marquardt workspace. */ - alfree(p->lm.ws); - p->lm.ws = NULL; + alfree(lm.ws); + lm.ws = NULL; } /** @@ -622,18 +821,18 @@ static inline void sacFiniRun(RHO_HEST_REFC* p){ * non-zero otherwise. */ -static inline int sacHypothesize(RHO_HEST_REFC* p){ - if(sacPROSACPhaseEndReached(p)){ - sacPROSACGoToNextPhase(p); +inline int RHO_HEST_REFC::hypothesize(void){ + if(PROSACPhaseEndReached()){ + PROSACGoToNextPhase(); } - sacGetPROSACSample(p); - if(sacIsSampleDegenerate(p)){ + getPROSACSample(); + if(isSampleDegenerate()){ return 0; } - sacGenerateModel(p); - if(sacIsModelDegenerate(p)){ + generateModel(); + if(isModelDegenerate()){ return 0; } @@ -649,21 +848,21 @@ static inline int sacHypothesize(RHO_HEST_REFC* p){ * Returns 1. */ -static inline int sacVerify(RHO_HEST_REFC* p){ - sacEvaluateModelSPRT(p); - sacUpdateSPRT(p); +inline int RHO_HEST_REFC::verify(void){ + evaluateModelSPRT(); + updateSPRT(); - if(sacIsBestModel(p)){ - sacSaveBestModel(p); + if(isBestModel()){ + saveBestModel(); - if(sacIsRefineEnabled(p) && sacCanRefine(p)){ - sacRefine(p); + if(isRefineEnabled() && canRefine()){ + refine(); } - sacUpdateBounds(p); + updateBounds(); - if(sacIsNREnabled(p)){ - sacNStarOptimize(p); + if(isNREnabled()){ + nStarOptimize(); } } @@ -676,8 +875,8 @@ static inline int sacVerify(RHO_HEST_REFC* p){ * @return Zero if no extrinsic guess was provided; non-zero otherwiseEE. */ -static inline int sacHaveExtrinsicGuess(RHO_HEST_REFC* p){ - return !!p->arg.guessH; +inline int RHO_HEST_REFC::haveExtrinsicGuess(void){ + return !!arg.guessH; } /** @@ -686,8 +885,8 @@ static inline int sacHaveExtrinsicGuess(RHO_HEST_REFC* p){ * @return Zero if non-randomness criterion disabled; non-zero if not. */ -static inline int sacIsNREnabled(RHO_HEST_REFC* p){ - return p->arg.flags & RHO_FLAG_ENABLE_NR; +inline int RHO_HEST_REFC::isNREnabled(void){ + return arg.flags & RHO_FLAG_ENABLE_NR; } /** @@ -696,8 +895,8 @@ static inline int sacIsNREnabled(RHO_HEST_REFC* p){ * @return Zero if best-model-so-far refinement disabled; non-zero if not. */ -static inline int sacIsRefineEnabled(RHO_HEST_REFC* p){ - return p->arg.flags & RHO_FLAG_ENABLE_REFINEMENT; +inline int RHO_HEST_REFC::isRefineEnabled(void){ + return arg.flags & RHO_FLAG_ENABLE_REFINEMENT; } /** @@ -706,8 +905,8 @@ static inline int sacIsRefineEnabled(RHO_HEST_REFC* p){ * @return Zero if final-model refinement disabled; non-zero if not. */ -static inline int sacIsFinalRefineEnabled(RHO_HEST_REFC* p){ - return p->arg.flags & RHO_FLAG_ENABLE_FINAL_REFINEMENT; +inline int RHO_HEST_REFC::isFinalRefineEnabled(void){ + return arg.flags & RHO_FLAG_ENABLE_FINAL_REFINEMENT; } /** @@ -718,8 +917,8 @@ static inline int sacIsFinalRefineEnabled(RHO_HEST_REFC* p){ * Read: i, phEndI, phNum, phMax. */ -static inline int sacPROSACPhaseEndReached(RHO_HEST_REFC* p){ - return p->ctrl.i >= p->ctrl.phEndI && p->ctrl.phNum < p->ctrl.phMax; +inline int RHO_HEST_REFC::PROSACPhaseEndReached(void){ + return ctrl.i >= ctrl.phEndI && ctrl.phNum < ctrl.phMax; } /** @@ -733,13 +932,13 @@ static inline int sacPROSACPhaseEndReached(RHO_HEST_REFC* p){ * Write: phNum, phEndFpI, phEndI */ -static inline void sacPROSACGoToNextPhase(RHO_HEST_REFC* p){ +inline void RHO_HEST_REFC::PROSACGoToNextPhase(void){ double next; - p->ctrl.phNum++; - next = (p->ctrl.phEndFpI * p->ctrl.phNum)/(p->ctrl.phNum - m); - p->ctrl.phEndI += (unsigned)ceil(next - p->ctrl.phEndFpI); - p->ctrl.phEndFpI = next; + ctrl.phNum++; + next = (ctrl.phEndFpI * ctrl.phNum)/(ctrl.phNum - SMPL_SIZE); + ctrl.phEndI += (unsigned)ceil(next - ctrl.phEndFpI); + ctrl.phEndFpI = next; } /** @@ -750,12 +949,13 @@ static inline void sacPROSACGoToNextPhase(RHO_HEST_REFC* p){ * the first phNum-1 matches. */ -static inline void sacGetPROSACSample(RHO_HEST_REFC* p){ - if(p->ctrl.i > p->ctrl.phEndI){ - sacRndSmpl(4, p->ctrl.smpl, p->ctrl.phNum);/* Used to be phMax */ +inline void RHO_HEST_REFC::getPROSACSample(void){ + if(ctrl.i > ctrl.phEndI){ + /* FIXME: Dubious. Review. */ + sacRndSmpl(4, ctrl.smpl, ctrl.phNum);/* Used to be phMax */ }else{ - sacRndSmpl(3, p->ctrl.smpl, p->ctrl.phNum-1); - p->ctrl.smpl[3] = p->ctrl.phNum-1; + sacRndSmpl(3, ctrl.smpl, ctrl.phNum-1); + ctrl.smpl[3] = ctrl.phNum-1; } } @@ -767,10 +967,10 @@ static inline void sacGetPROSACSample(RHO_HEST_REFC* p){ * bad samples. */ -static inline int sacIsSampleDegenerate(RHO_HEST_REFC* p){ - unsigned i0 = p->ctrl.smpl[0], i1 = p->ctrl.smpl[1], i2 = p->ctrl.smpl[2], i3 = p->ctrl.smpl[3]; +inline int RHO_HEST_REFC::isSampleDegenerate(void){ + unsigned i0 = ctrl.smpl[0], i1 = ctrl.smpl[1], i2 = ctrl.smpl[2], i3 = ctrl.smpl[3]; typedef struct{float x,y;} MyPt2f; - MyPt2f* pkdPts = (MyPt2f*)p->curr.pkdPts, *src = (MyPt2f*)p->arg.src, *dst = (MyPt2f*)p->arg.dst; + MyPt2f* pkdPts = (MyPt2f*)curr.pkdPts, *src = (MyPt2f*)arg.src, *dst = (MyPt2f*)arg.dst; /** * Pack the matches selected by the SAC algorithm. @@ -860,8 +1060,8 @@ static inline int sacIsSampleDegenerate(RHO_HEST_REFC* p){ * current homography. */ -static inline void sacGenerateModel(RHO_HEST_REFC* p){ - hFuncRefC(p->curr.pkdPts, p->curr.H); +inline void RHO_HEST_REFC::generateModel(void){ + hFuncRefC(curr.pkdPts, curr.H); } /** @@ -870,9 +1070,9 @@ static inline void sacGenerateModel(RHO_HEST_REFC* p){ * NaN the homography is rejected. */ -static inline int sacIsModelDegenerate(RHO_HEST_REFC* p){ +inline int RHO_HEST_REFC::isModelDegenerate(void){ int degenerate; - float* H = p->curr.H; + float* H = curr.H; float f=H[0]+H[1]+H[2]+H[3]+H[4]+H[5]+H[6]+H[7]; /* degenerate = isnan(f); */ @@ -890,26 +1090,26 @@ static inline int sacIsModelDegenerate(RHO_HEST_REFC* p){ * Writes: eval.*, curr.inl, curr.numInl */ -static inline void sacEvaluateModelSPRT(RHO_HEST_REFC* p){ +inline void RHO_HEST_REFC::evaluateModelSPRT(void){ unsigned i; unsigned isInlier; double lambda = 1.0; - float distSq = p->arg.maxD*p->arg.maxD; - const float* src = p->arg.src; - const float* dst = p->arg.dst; - char* inl = p->curr.inl; - const float* H = p->curr.H; + float distSq = arg.maxD*arg.maxD; + const float* src = arg.src; + const float* dst = arg.dst; + char* inl = curr.inl; + const float* H = curr.H; - p->ctrl.numModels++; + ctrl.numModels++; - p->curr.numInl = 0; - p->eval.Ntested = 0; - p->eval.good = 1; + curr.numInl = 0; + eval.Ntested = 0; + eval.good = 1; /* SCALAR */ - for(i=0;iarg.N && p->eval.good;i++){ + for(i=0;icurr.numInl += isInlier; + curr.numInl += isInlier; *inl++ = (char)isInlier; /* SPRT */ - lambda *= isInlier ? p->eval.lambdaAccept : p->eval.lambdaReject; - p->eval.good = lambda <= p->eval.A; - /* If !p->good, the threshold A was exceeded, so we're rejecting */ + lambda *= isInlier ? eval.lambdaAccept : eval.lambdaReject; + eval.good = lambda <= eval.A; + /* If !good, the threshold A was exceeded, so we're rejecting */ } - p->eval.Ntested = i; - p->eval.Ntestedtotal += i; + eval.Ntested = i; + eval.Ntestedtotal += i; } /** @@ -959,18 +1159,21 @@ static inline void sacEvaluateModelSPRT(RHO_HEST_REFC* p){ * eval.lambdaReject */ -static inline void sacUpdateSPRT(RHO_HEST_REFC* p){ - if(p->eval.good){ - if(sacIsBestModel(p)){ - p->eval.epsilon = (double)p->curr.numInl/p->arg.N; - sacDesignSPRTTest(p); +inline void RHO_HEST_REFC::updateSPRT(void){ + if(eval.good){ + if(isBestModel()){ + eval.epsilon = (double)curr.numInl/arg.N; + designSPRTTest(); } }else{ - double newDelta = (double)p->curr.numInl/p->eval.Ntested; + double newDelta = (double)curr.numInl/eval.Ntested; - if(newDelta > 0 && CHNG_SIGNIFICANT(p->eval.delta, newDelta)){ - p->eval.delta = newDelta; - sacDesignSPRTTest(p); + if(newDelta > 0){ + double relChange = fabs(eval.delta - newDelta)/ eval.delta; + if(relChange > MIN_DELTA_CHNG){ + eval.delta = newDelta; + designSPRTTest(); + } } } } @@ -1044,18 +1247,18 @@ static inline double designSPRTTest(double delta, double epsilon, double t_M, do * Writes: eval.A, eval.lambdaAccept, eval.lambdaReject */ -static inline void sacDesignSPRTTest(RHO_HEST_REFC* p){ - p->eval.A = designSPRTTest(p->eval.delta, p->eval.epsilon, p->eval.t_M, p->eval.m_S); - p->eval.lambdaReject = ((1.0 - p->eval.delta) / (1.0 - p->eval.epsilon)); - p->eval.lambdaAccept = (( p->eval.delta ) / ( p->eval.epsilon )); +inline void RHO_HEST_REFC::designSPRTTest(void){ + eval.A = designSPRTTest(eval.delta, eval.epsilon, eval.t_M, eval.m_S); + eval.lambdaReject = ((1.0 - eval.delta) / (1.0 - eval.epsilon)); + eval.lambdaAccept = (( eval.delta ) / ( eval.epsilon )); } /** * Return whether the current model is the best model so far. */ -static inline int sacIsBestModel(RHO_HEST_REFC* p){ - return p->curr.numInl > p->best.numInl; +inline int RHO_HEST_REFC::isBestModel(void){ + return curr.numInl > best.numInl; } /** @@ -1064,8 +1267,8 @@ static inline int sacIsBestModel(RHO_HEST_REFC* p){ * number of inliers. */ -static inline int sacIsBestModelGoodEnough(RHO_HEST_REFC* p){ - return p->best.numInl >= p->arg.minInl; +inline int RHO_HEST_REFC::isBestModelGoodEnough(void){ + return best.numInl >= arg.minInl; } /** @@ -1073,18 +1276,18 @@ static inline int sacIsBestModelGoodEnough(RHO_HEST_REFC* p){ * and count of inliers between the current and best models. */ -static inline void sacSaveBestModel(RHO_HEST_REFC* p){ - float* H = p->curr.H; - char* inl = p->curr.inl; - unsigned numInl = p->curr.numInl; +inline void RHO_HEST_REFC::saveBestModel(void){ + float* H = curr.H; + char* inl = curr.inl; + unsigned numInl = curr.numInl; - p->curr.H = p->best.H; - p->curr.inl = p->best.inl; - p->curr.numInl = p->best.numInl; + curr.H = best.H; + curr.inl = best.inl; + curr.numInl = best.numInl; - p->best.H = H; - p->best.inl = inl; - p->best.numInl = numInl; + best.H = H; + best.inl = inl; + best.numInl = numInl; } /** @@ -1095,13 +1298,13 @@ static inline void sacInitNonRand(double beta, unsigned start, unsigned N, unsigned* nonRandMinInl){ - unsigned n = m+1 > start ? m+1 : start; + unsigned n = SMPL_SIZE+1 > start ? SMPL_SIZE+1 : start; double beta_beta1_sq_chi = sqrt(beta*(1.0-beta)) * CHI_SQ; for(; n < N; n++){ double mu = n * beta; double sigma = sqrt(n)* beta_beta1_sq_chi; - unsigned i_min = (unsigned)ceil(m + mu + sigma); + unsigned i_min = (unsigned)ceil(SMPL_SIZE + mu + sigma); nonRandMinInl[n] = i_min; } @@ -1112,31 +1315,31 @@ static inline void sacInitNonRand(double beta, * of PROSAC. */ -static inline void sacNStarOptimize(RHO_HEST_REFC* p){ - unsigned min_sample_length = 10*2; /*(p->N * INLIERS_RATIO) */ - unsigned best_n = p->arg.N; +inline void RHO_HEST_REFC::nStarOptimize(void){ + unsigned min_sample_length = 10*2; /*(N * INLIERS_RATIO) */ + unsigned best_n = arg.N; unsigned test_n = best_n; - unsigned bestNumInl = p->best.numInl; + unsigned bestNumInl = best.numInl; unsigned testNumInl = bestNumInl; for(;test_n > min_sample_length && testNumInl;test_n--){ if(testNumInl*best_n > bestNumInl*test_n){ - if(testNumInl < p->nr.tbl[test_n]){ + if(testNumInl < nr.tbl[test_n]){ break; } best_n = test_n; bestNumInl = testNumInl; } - testNumInl -= !!p->arg.inl[test_n-1]; + testNumInl -= !!arg.inl[test_n-1]; } - if(bestNumInl*p->ctrl.phMax > p->ctrl.phNumInl*best_n){ - p->ctrl.phMax = best_n; - p->ctrl.phNumInl = bestNumInl; - p->arg.maxI = sacCalcIterBound(p->arg.cfd, - (double)p->ctrl.phNumInl/p->ctrl.phMax, - m, - p->arg.maxI); + if(bestNumInl*ctrl.phMax > ctrl.phNumInl*best_n){ + ctrl.phMax = best_n; + ctrl.phNumInl = bestNumInl; + arg.maxI = sacCalcIterBound(arg.cfd, + (double)ctrl.phNumInl/ctrl.phMax, + SMPL_SIZE, + arg.maxI); } } @@ -1144,25 +1347,25 @@ static inline void sacNStarOptimize(RHO_HEST_REFC* p){ * Classic RANSAC iteration bound based on largest # of inliers. */ -static inline void sacUpdateBounds(RHO_HEST_REFC* p){ - p->arg.maxI = sacCalcIterBound(p->arg.cfd, - (double)p->best.numInl/p->arg.N, - m, - p->arg.maxI); +inline void RHO_HEST_REFC::updateBounds(void){ + arg.maxI = sacCalcIterBound(arg.cfd, + (double)best.numInl/arg.N, + SMPL_SIZE, + arg.maxI); } /** * Ouput the best model so far to the output argument. */ -static inline void sacOutputModel(RHO_HEST_REFC* p){ - if(sacIsBestModelGoodEnough(p)){ - memcpy(p->arg.finalH, p->best.H, HSIZE); - if(p->arg.inl != p->best.inl){ - memcpy(p->arg.inl, p->best.inl, p->arg.N); +inline void RHO_HEST_REFC::outputModel(void){ + if(isBestModelGoodEnough()){ + memcpy(arg.finalH, best.H, HSIZE); + if(arg.inl != best.inl){ + memcpy(arg.inl, best.inl, arg.N); } }else{ - sacOutputZeroH(p); + outputZeroH(); } } @@ -1170,8 +1373,9 @@ static inline void sacOutputModel(RHO_HEST_REFC* p){ * Ouput a zeroed H to the output argument. */ -static inline void sacOutputZeroH(RHO_HEST_REFC* p){ - memset(p->arg.finalH, 0, HSIZE); +inline void RHO_HEST_REFC::outputZeroH(void){ + memset(arg.finalH, 0, HSIZE); + memset(arg.inl, 0, arg.N); } /** @@ -1572,20 +1776,20 @@ static void hFuncRefC(float* packedPoints,/* Source (four x,y float coordinates) * NB This is separate from whether it is *enabled*. */ -static inline int sacCanRefine(RHO_HEST_REFC* p){ +inline int RHO_HEST_REFC::canRefine(void){ /** * If we only have 4 matches, GE's result is already optimal and cannot * be refined any further. */ - return p->best.numInl > m; + return best.numInl > SMPL_SIZE; } /** * Refines the best-so-far homography (p->best.H). */ -static inline void sacRefine(RHO_HEST_REFC* p){ +inline void RHO_HEST_REFC::refine(void){ int i; float S, newS; /* Sum of squared errors */ float gain; /* Gain-parameter. */ @@ -1597,8 +1801,8 @@ static inline void sacRefine(RHO_HEST_REFC* p){ */ /* Find initial conditions */ - sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, - p->lm.JtJ, p->lm.Jte, &S); + sacCalcJacobianErrors(best.H, arg.src, arg.dst, arg.inl, arg.N, + lm.JtJ, lm.Jte, &S); /*Levenberg-Marquardt Loop.*/ for(i=0;ilm.JtJ, L, p->lm.tmp1)){ + while(!sacChol8x8Damped(lm.JtJ, L, lm.tmp1)){ L *= 2.0f; } - sacTRInv8x8 (p->lm.tmp1, p->lm.tmp1); - sacTRISolve8x8(p->lm.tmp1, p->lm.Jte, dH); - sacSub8x1 (newH, p->best.H, dH); - sacCalcJacobianErrors(newH, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, + sacTRInv8x8 (lm.tmp1, lm.tmp1); + sacTRISolve8x8(lm.tmp1, lm.Jte, dH); + sacSub8x1 (newH, best.H, dH); + sacCalcJacobianErrors(newH, arg.src, arg.dst, arg.inl, arg.N, NULL, NULL, &newS); - gain = sacLMGain(dH, p->lm.Jte, S, newS, L); + gain = sacLMGain(dH, lm.Jte, S, newS, L); /*printf("Lambda: %12.6f S: %12.6f newS: %12.6f Gain: %12.6f\n", L, S, newS, gain);*/ @@ -1656,9 +1860,9 @@ static inline void sacRefine(RHO_HEST_REFC* p){ if(gain > 0){ S = newS; - memcpy(p->best.H, newH, sizeof(newH)); - sacCalcJacobianErrors(p->best.H, p->arg.src, p->arg.dst, p->arg.inl, p->arg.N, - p->lm.JtJ, p->lm.Jte, &S); + memcpy(best.H, newH, sizeof(newH)); + sacCalcJacobianErrors(best.H, arg.src, arg.dst, arg.inl, arg.N, + lm.JtJ, lm.Jte, &S); } } } @@ -2165,7 +2369,5 @@ static inline void sacSub8x1(float* Hout, const float* H, const float* dH){ } - -#ifdef __cplusplus +/* End namespace cv */ } -#endif diff --git a/modules/calib3d/src/rhorefc.h b/modules/calib3d/src/rhorefc.h index be7012f00..49bc58a86 100644 --- a/modules/calib3d/src/rhorefc.h +++ b/modules/calib3d/src/rhorefc.h @@ -56,7 +56,6 @@ /* Defines */ -#ifdef __cplusplus /* C++ does not have the restrict keyword. */ #ifdef restrict @@ -64,15 +63,6 @@ #endif #define restrict -#else - -/* C99 and over has the restrict keyword. */ -#if !defined(__STDC_VERSION__) || __STDC_VERSION__ < 199901L -#define restrict -#endif - -#endif - /* Flags */ #ifndef RHO_FLAG_NONE @@ -90,101 +80,17 @@ +/* Namespace cv */ +namespace cv{ + /* Data structures */ /** * Homography Estimation context. */ -typedef struct{ - /** - * Virtual Arguments. - * - * Exactly the same as at function call, except: - * - minInl is enforced to be >= 4. - */ - - struct{ - const float* restrict src; - const float* restrict dst; - char* restrict inl; - unsigned N; - float maxD; - unsigned maxI; - unsigned rConvg; - double cfd; - unsigned minInl; - double beta; - unsigned flags; - const float* guessH; - float* finalH; - } arg; - - /* PROSAC Control */ - struct{ - unsigned i; /* Iteration Number */ - unsigned phNum; /* Phase Number */ - unsigned phEndI; /* Phase End Iteration */ - double phEndFpI; /* Phase floating-point End Iteration */ - unsigned phMax; /* Termination phase number */ - unsigned phNumInl; /* Number of inliers for termination phase */ - unsigned numModels; /* Number of models tested */ - unsigned* restrict smpl; /* Sample of match indexes */ - } ctrl; - - /* Current model being tested */ - struct{ - float* restrict pkdPts; /* Packed points */ - float* restrict H; /* Homography */ - char* restrict inl; /* Mask of inliers */ - unsigned numInl; /* Number of inliers */ - } curr; - - /* Best model (so far) */ - struct{ - float* restrict H; /* Homography */ - char* restrict inl; /* Mask of inliers */ - unsigned numInl; /* Number of inliers */ - } best; - - /* Non-randomness criterion */ - struct{ - unsigned* restrict tbl; /* Non-Randomness: Table */ - unsigned size; /* Non-Randomness: Size */ - double beta; /* Non-Randomness: Beta */ - } nr; - - /* SPRT Evaluator */ - struct{ - double t_M; /* t_M */ - double m_S; /* m_S */ - double epsilon; /* Epsilon */ - double delta; /* delta */ - double A; /* SPRT Threshold */ - unsigned Ntested; /* Number of points tested */ - unsigned Ntestedtotal; /* Number of points tested in total */ - int good; /* Good/bad flag */ - double lambdaAccept; /* Accept multiplier */ - double lambdaReject; /* Reject multiplier */ - } eval; - - /* Levenberg-Marquardt Refinement */ - struct{ - float* ws; /* Levenberg-Marqhard Workspace */ - float (* restrict JtJ)[8]; /* JtJ matrix */ - float (* restrict tmp1)[8]; /* Temporary 1 */ - float* restrict Jte; /* Jte vector */ - } lm; -} RHO_HEST_REFC; - - - -/* Extern C */ -#ifdef __cplusplus -namespace cv{ -/* extern "C" { */ -#endif - +struct RHO_HEST_REFC; +typedef struct RHO_HEST_REFC RHO_HEST_REFC; /* Functions */ @@ -193,11 +99,10 @@ namespace cv{ * Initialize the estimator context, by allocating the aligned buffers * internally needed. * - * @param [in/out] p The uninitialized estimator context to initialize. - * @return 0 if successful; non-zero if an error occured. + * @return A pointer to the context if successful; NULL if an error occured. */ -int rhoRefCInit(RHO_HEST_REFC* p); +RHO_HEST_REFC* rhoRefCInit(void); /** @@ -355,11 +260,8 @@ unsigned rhoRefC(RHO_HEST_REFC* restrict p, /* Homography estimation conte -/* Extern C */ -#ifdef __cplusplus -/* } *//* End extern "C" */ +/* End Namespace cv */ } -#endif From ccd33a721e6b45ab2c392293200d02edf7923a7b Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Sat, 7 Feb 2015 01:19:40 -0500 Subject: [PATCH 13/39] Fixed build failures related to designSPRTTest(). --- modules/calib3d/src/rhorefc.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 167accd97..03ec79ebe 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -1192,7 +1192,7 @@ inline void RHO_HEST_REFC::updateSPRT(void){ * m_S: The number of models that are verified per sample. */ -static inline double designSPRTTest(double delta, double epsilon, double t_M, double m_S){ +static inline double sacDesignSPRTTest(double delta, double epsilon, double t_M, double m_S){ double An, C, K, prevAn; unsigned i; @@ -1248,7 +1248,7 @@ static inline double designSPRTTest(double delta, double epsilon, double t_M, do */ inline void RHO_HEST_REFC::designSPRTTest(void){ - eval.A = designSPRTTest(eval.delta, eval.epsilon, eval.t_M, eval.m_S); + eval.A = sacDesignSPRTTest(eval.delta, eval.epsilon, eval.t_M, eval.m_S); eval.lambdaReject = ((1.0 - eval.delta) / (1.0 - eval.epsilon)); eval.lambdaAccept = (( eval.delta ) / ( eval.epsilon )); } From ff2509af56bb694c07edd80eb102e5e1edff41c3 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Thu, 12 Feb 2015 14:42:37 -0500 Subject: [PATCH 14/39] Fixed printouts in testcase to blame the correct method for a failure. Previously, certain test failures by the method RHO would result in an error blaming RANSAC instead. The fix involves a parameter change to several functions in test_homography.cpp. --- modules/calib3d/test/test_homography.cpp | 34 ++++++++++++------------ 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/modules/calib3d/test/test_homography.cpp b/modules/calib3d/test/test_homography.cpp index 1199cd6cd..a31b75d2b 100644 --- a/modules/calib3d/test/test_homography.cpp +++ b/modules/calib3d/test/test_homography.cpp @@ -94,12 +94,12 @@ private: void print_information_1(int j, int N, int method, const Mat& H); void print_information_2(int j, int N, int method, const Mat& H, const Mat& H_res, int k, double diff); - void print_information_3(int j, int N, const Mat& mask); + void print_information_3(int method, int j, int N, const Mat& mask); void print_information_4(int method, int j, int N, int k, int l, double diff); void print_information_5(int method, int j, int N, int l, double diff); - void print_information_6(int j, int N, int k, double diff, bool value); - void print_information_7(int j, int N, int k, double diff, bool original_value, bool found_value); - void print_information_8(int j, int N, int k, int l, double diff); + void print_information_6(int method, int j, int N, int k, double diff, bool value); + void print_information_7(int method, int j, int N, int k, double diff, bool original_value, bool found_value); + void print_information_8(int method, int j, int N, int k, int l, double diff); }; CV_HomographyTest::CV_HomographyTest() : max_diff(1e-2f), max_2diff(2e-2f) @@ -166,13 +166,13 @@ void CV_HomographyTest::print_information_2(int j, int N, int _method, const Mat cout << "Maximum allowed difference: " << max_diff << endl; cout << endl; } -void CV_HomographyTest::print_information_3(int j, int N, const Mat& mask) +void CV_HomographyTest::print_information_3(int _method, int j, int N, const Mat& mask) { cout << endl; cout << "Checking for inliers/outliers mask..." << endl; cout << endl; cout << "Type of srcPoints: "; if ((j>-1) && (j<2)) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << " Type of dstPoints: "; if (j % 2 == 0) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << endl; cout << "Count of points: " << N << endl; cout << endl; - cout << "Method: RANSAC" << endl; + cout << "Method: "; if (_method == RANSAC) cout << "RANSAC" << endl; else if (_method == cv::RHO) cout << "RHO" << endl; else cout << _method << endl; cout << "Found mask:" << endl; cout << endl; cout << mask << endl; cout << endl; cout << "Number of rows: " << mask.rows << " Number of cols: " << mask.cols << endl; cout << endl; @@ -205,10 +205,10 @@ void CV_HomographyTest::print_information_5(int _method, int j, int N, int l, do cout << "Maxumum allowed difference: " << max_diff << endl; cout << endl; } -void CV_HomographyTest::print_information_6(int j, int N, int k, double diff, bool value) +void CV_HomographyTest::print_information_6(int _method, int j, int N, int k, double diff, bool value) { cout << endl; cout << "Checking for inliers/outliers mask..." << endl; cout << endl; - cout << "Method: RANSAC" << endl; + cout << "Method: "; if (_method == RANSAC) cout << "RANSAC" << endl; else if (_method == cv::RHO) cout << "RHO" << endl; else cout << _method << endl; cout << "Type of srcPoints: "; if ((j>-1) && (j<2)) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << " Type of dstPoints: "; if (j % 2 == 0) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << endl; cout << "Count of points: " << N << " " << endl; @@ -218,10 +218,10 @@ void CV_HomographyTest::print_information_6(int j, int N, int k, double diff, bo cout << "Value of found mask: "<< value << endl; cout << endl; } -void CV_HomographyTest::print_information_7(int j, int N, int k, double diff, bool original_value, bool found_value) +void CV_HomographyTest::print_information_7(int _method, int j, int N, int k, double diff, bool original_value, bool found_value) { cout << endl; cout << "Checking for inliers/outliers mask..." << endl; cout << endl; - cout << "Method: RANSAC" << endl; + cout << "Method: "; if (_method == RANSAC) cout << "RANSAC" << endl; else if (_method == cv::RHO) cout << "RHO" << endl; else cout << _method << endl; cout << "Type of srcPoints: "; if ((j>-1) && (j<2)) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << " Type of dstPoints: "; if (j % 2 == 0) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << endl; cout << "Count of points: " << N << " " << endl; @@ -231,10 +231,10 @@ void CV_HomographyTest::print_information_7(int j, int N, int k, double diff, bo cout << "Value of original mask: "<< original_value << " Value of found mask: " << found_value << endl; cout << endl; } -void CV_HomographyTest::print_information_8(int j, int N, int k, int l, double diff) +void CV_HomographyTest::print_information_8(int _method, int j, int N, int k, int l, double diff) { cout << endl; cout << "Checking for reprojection error of inlier..." << endl; cout << endl; - cout << "Method: RANSAC" << endl; + cout << "Method: "; if (_method == RANSAC) cout << "RANSAC" << endl; else if (_method == cv::RHO) cout << "RHO" << endl; else cout << _method << endl; cout << "Sigma of normal noise: " << sigma << endl; cout << "Type of srcPoints: "; if ((j>-1) && (j<2)) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << " Type of dstPoints: "; if (j % 2 == 0) cout << "Mat of CV_32FC2"; else cout << "vector "; cout << endl; @@ -371,7 +371,7 @@ void CV_HomographyTest::run(int) if (code) { - print_information_3(j, N, mask[j]); + print_information_3(method, j, N, mask[j]); switch (code) { @@ -490,7 +490,7 @@ void CV_HomographyTest::run(int) if (code) { - print_information_3(j, N, mask_res[j]); + print_information_3(method, j, N, mask_res[j]); switch (code) { @@ -522,14 +522,14 @@ void CV_HomographyTest::run(int) if (mask_res[j].at(k, 0) != (diff <= reproj_threshold)) { - print_information_6(j, N, k, diff, mask_res[j].at(k, 0)); + print_information_6(method, j, N, k, diff, mask_res[j].at(k, 0)); CV_Error(CALIB3D_HOMOGRAPHY_ERROR_RANSAC_MASK, MESSAGE_RANSAC_MASK_4); return; } if (mask.at(k, 0) && !mask_res[j].at(k, 0)) { - print_information_7(j, N, k, diff, mask.at(k, 0), mask_res[j].at(k, 0)); + print_information_7(method, j, N, k, diff, mask.at(k, 0), mask_res[j].at(k, 0)); CV_Error(CALIB3D_HOMOGRAPHY_ERROR_RANSAC_MASK, MESSAGE_RANSAC_MASK_5); return; } @@ -549,7 +549,7 @@ void CV_HomographyTest::run(int) if (diff - cv::norm(noise_2d, NORM_TYPE[l]) > max_2diff) { - print_information_8(j, N, k, l, diff - cv::norm(noise_2d, NORM_TYPE[l])); + print_information_8(method, j, N, k, l, diff - cv::norm(noise_2d, NORM_TYPE[l])); CV_Error(CALIB3D_HOMOGRAPHY_ERROR_RANSAC_DIFF, MESSAGE_RANSAC_DIFF); return; } From 6dbf13d7b5e017a8b16cf5f12a38000896e64583 Mon Sep 17 00:00:00 2001 From: ASUS Date: Thu, 12 Feb 2015 21:22:52 -0500 Subject: [PATCH 15/39] saveBestModel() is modified. accuracy test is passed. --- modules/calib3d/src/fundam.cpp | 13 +++++---- modules/calib3d/src/rhorefc.cpp | 47 +++++++++++++++++++++++++-------- 2 files changed, 44 insertions(+), 16 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index 1366e9baa..2f6058c74 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -399,16 +399,18 @@ cv::Mat cv::findHomography( InputArray _points1, InputArray _points2, { tempMask = Mat::ones(npoints, 1, CV_8U); result = cb->runKernel(src, dst, H) > 0; - } - else if( method == RANSAC ) + } + + else if( method == RANSAC) result = createRANSACPointSetRegistrator(cb, 4, ransacReprojThreshold, confidence, maxIters)->run(src, dst, H, tempMask); else if( method == LMEDS ) result = createLMeDSPointSetRegistrator(cb, 4, confidence, maxIters)->run(src, dst, H, tempMask); - else if( method == RHO ){ + else if( method == RHO ) result = createAndRunRHORegistrator(confidence, maxIters, ransacReprojThreshold, npoints, src, dst, H, tempMask); - }else + else CV_Error(Error::StsBadArg, "Unknown estimation method"); + if( result && npoints > 4 && method != RHO) { compressPoints( src.ptr(), tempMask.ptr(), 1, npoints ); @@ -419,8 +421,9 @@ cv::Mat cv::findHomography( InputArray _points1, InputArray _points2, Mat dst1 = dst.rowRange(0, npoints); src = src1; dst = dst1; - if( method == RANSAC || method == LMEDS ) + if( method == RANSAC || method == LMEDS) cb->runKernel( src, dst, H ); + Mat H8(8, 1, CV_64F, H.ptr()); createLMSolver(makePtr(src, dst), 10)->run(H8); } diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 3cc9a8a1c..976f8d341 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -55,7 +55,6 @@ #include "rhorefc.h" - /* Defines */ #define MEM_ALIGN 32 #define HSIZE (3*3*sizeof(float)) @@ -383,7 +382,7 @@ unsigned rhoRefC(RHO_HEST_REFC* restrict p, /* Homography estimation conte * PROSAC Loop */ - for(p->ctrl.i=0; p->ctrl.i < p->arg.maxI; p->ctrl.i++){ + for(p->ctrl.i=0; p->ctrl.i < p->arg.maxI || p->ctrl.i<100; p->ctrl.i++){ sacHypothesize(p) && sacVerify(p); } @@ -861,7 +860,28 @@ static inline int sacIsSampleDegenerate(RHO_HEST_REFC* p){ */ static inline void sacGenerateModel(RHO_HEST_REFC* p){ +#if 1 hFuncRefC(p->curr.pkdPts, p->curr.H); +#else + int mm = 4; + cv::Mat _H(3,3,CV_32FC1); + std::vector _srcPoints(mm,cv::Point2f()); + std::vector _dstPoints(mm,cv::Point2f()); + for (int i=0 ; i< mm ; i++){ + cv::Point2f tempPoint2f(p->curr.pkdPts[2*i], p->curr.pkdPts[2*i+1]); + _srcPoints[i] = tempPoint2f; + tempPoint2f=cv::Point2f((float)p->curr.pkdPts[2*i+8],(float) p->curr.pkdPts[2*i+9]); + _dstPoints[i] = tempPoint2f; + } + + _H = cv::findHomography(_srcPoints, _dstPoints,0,3); + double* data = (double*) _H.data; + + p->curr.H[0]=data[0]; p->curr.H[1]=data[1]; p->curr.H[2]=data[2]; + p->curr.H[3]=data[3]; p->curr.H[4]=data[4]; p->curr.H[5]=data[5]; + p->curr.H[6]=data[6]; p->curr.H[7]=data[7]; p->curr.H[8]=1.0; + +#endif } /** @@ -1074,17 +1094,22 @@ static inline int sacIsBestModelGoodEnough(RHO_HEST_REFC* p){ */ static inline void sacSaveBestModel(RHO_HEST_REFC* p){ - float* H = p->curr.H; - char* inl = p->curr.inl; - unsigned numInl = p->curr.numInl; - p->curr.H = p->best.H; - p->curr.inl = p->best.inl; - p->curr.numInl = p->best.numInl; + memcpy(p->best.H, p->curr.H, HSIZE); + memcpy(p->best.inl, p->curr.inl, p->arg.N); + p->best.numInl = p->curr.numInl; - p->best.H = H; - p->best.inl = inl; - p->best.numInl = numInl; +// float* H = p->curr.H; +// char* inl = p->curr.inl; +// unsigned numInl = p->curr.numInl; + +// p->curr.H = p->best.H; +// p->curr.inl = p->best.inl; +// p->curr.numInl = p->best.numInl; + +// p->best.H = H; +// p->best.inl = inl; +// p->best.numInl = numInl; } /** From 9a555063e86747323cd10fd64e39102991ab0cd8 Mon Sep 17 00:00:00 2001 From: ASUS Date: Thu, 12 Feb 2015 23:34:48 -0500 Subject: [PATCH 16/39] Fix sacCalcJacobianErrors arguments. (curr.inl replaced with best.inl) Fix the issue given NULL inlMask --- modules/calib3d/src/rhorefc.cpp | 78 ++++++--------------------------- 1 file changed, 14 insertions(+), 64 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 00802e602..272995cee 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -56,7 +56,6 @@ #include #include "rhorefc.h" - /* Defines */ const int MEM_ALIGN = 32; const size_t HSIZE = (3*3*sizeof(float)); @@ -613,15 +612,10 @@ unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ * PROSAC Loop */ -<<<<<<< HEAD - for(p->ctrl.i=0; p->ctrl.i < p->arg.maxI || p->ctrl.i<100; p->ctrl.i++){ - sacHypothesize(p) && sacVerify(p); -======= - for(ctrl.i=0; ctrl.i < arg.maxI; ctrl.i++){ + for(ctrl.i=0; ctrl.i < arg.maxI || ctrl.i < 100; ctrl.i++){ hypothesize() && verify(); ->>>>>>> ff2509af56bb694c07edd80eb102e5e1edff41c3 - } + } /** * Teardown @@ -631,9 +625,10 @@ unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ refine(); } - outputModel(); - finiRun(); + outputModel(); + finiRun(); return isBestModelGoodEnough() ? best.numInl : 0; + } @@ -661,7 +656,7 @@ inline int RHO_HEST_REFC::initRun(void){ /* Arguments src or dst are insane, must be != NULL */ return 0; } - if(arg.N < SMPL_SIZE){ + if(arg.N < (unsigned)SMPL_SIZE){ /* Argument N is insane, must be >= 4. */ return 0; } @@ -674,7 +669,7 @@ inline int RHO_HEST_REFC::initRun(void){ return 0; } /* Clamp minInl to 4 or higher. */ - arg.minInl = arg.minInl < SMPL_SIZE ? SMPL_SIZE : arg.minInl; + arg.minInl = arg.minInl < (unsigned)SMPL_SIZE ? SMPL_SIZE : arg.minInl; if(isNREnabled() && (arg.beta <= 0 || arg.beta >= 1)){ /* Argument beta is insane, must be in (0, 1). */ return 0; @@ -868,6 +863,7 @@ inline int RHO_HEST_REFC::verify(void){ if(isNREnabled()){ nStarOptimize(); } + } return 1; @@ -1064,34 +1060,8 @@ inline int RHO_HEST_REFC::isSampleDegenerate(void){ * current homography. */ -<<<<<<< HEAD -static inline void sacGenerateModel(RHO_HEST_REFC* p){ -#if 1 - hFuncRefC(p->curr.pkdPts, p->curr.H); -#else - int mm = 4; - cv::Mat _H(3,3,CV_32FC1); - std::vector _srcPoints(mm,cv::Point2f()); - std::vector _dstPoints(mm,cv::Point2f()); - for (int i=0 ; i< mm ; i++){ - cv::Point2f tempPoint2f(p->curr.pkdPts[2*i], p->curr.pkdPts[2*i+1]); - _srcPoints[i] = tempPoint2f; - tempPoint2f=cv::Point2f((float)p->curr.pkdPts[2*i+8],(float) p->curr.pkdPts[2*i+9]); - _dstPoints[i] = tempPoint2f; - } - - _H = cv::findHomography(_srcPoints, _dstPoints,0,3); - double* data = (double*) _H.data; - - p->curr.H[0]=data[0]; p->curr.H[1]=data[1]; p->curr.H[2]=data[2]; - p->curr.H[3]=data[3]; p->curr.H[4]=data[4]; p->curr.H[5]=data[5]; - p->curr.H[6]=data[6]; p->curr.H[7]=data[7]; p->curr.H[8]=1.0; - -#endif -======= inline void RHO_HEST_REFC::generateModel(void){ hFuncRefC(curr.pkdPts, curr.H); ->>>>>>> ff2509af56bb694c07edd80eb102e5e1edff41c3 } /** @@ -1306,25 +1276,6 @@ inline int RHO_HEST_REFC::isBestModelGoodEnough(void){ * and count of inliers between the current and best models. */ -<<<<<<< HEAD -static inline void sacSaveBestModel(RHO_HEST_REFC* p){ - - memcpy(p->best.H, p->curr.H, HSIZE); - memcpy(p->best.inl, p->curr.inl, p->arg.N); - p->best.numInl = p->curr.numInl; - -// float* H = p->curr.H; -// char* inl = p->curr.inl; -// unsigned numInl = p->curr.numInl; - -// p->curr.H = p->best.H; -// p->curr.inl = p->best.inl; -// p->curr.numInl = p->best.numInl; - -// p->best.H = H; -// p->best.inl = inl; -// p->best.numInl = numInl; -======= inline void RHO_HEST_REFC::saveBestModel(void){ float* H = curr.H; char* inl = curr.inl; @@ -1337,7 +1288,6 @@ inline void RHO_HEST_REFC::saveBestModel(void){ best.H = H; best.inl = inl; best.numInl = numInl; ->>>>>>> ff2509af56bb694c07edd80eb102e5e1edff41c3 } /** @@ -1398,7 +1348,7 @@ inline void RHO_HEST_REFC::nStarOptimize(void){ */ inline void RHO_HEST_REFC::updateBounds(void){ - arg.maxI = sacCalcIterBound(arg.cfd, + arg.maxI = sacCalcIterBound(arg.cfd, (double)best.numInl/arg.N, SMPL_SIZE, arg.maxI); @@ -1411,7 +1361,7 @@ inline void RHO_HEST_REFC::updateBounds(void){ inline void RHO_HEST_REFC::outputModel(void){ if(isBestModelGoodEnough()){ memcpy(arg.finalH, best.H, HSIZE); - if(arg.inl != best.inl){ + if(arg.inl && arg.inl != best.inl){ memcpy(arg.inl, best.inl, arg.N); } }else{ @@ -1832,7 +1782,7 @@ inline int RHO_HEST_REFC::canRefine(void){ * be refined any further. */ - return best.numInl > SMPL_SIZE; + return best.numInl > (unsigned)SMPL_SIZE; } /** @@ -1851,7 +1801,7 @@ inline void RHO_HEST_REFC::refine(void){ */ /* Find initial conditions */ - sacCalcJacobianErrors(best.H, arg.src, arg.dst, arg.inl, arg.N, + sacCalcJacobianErrors(best.H, arg.src, arg.dst, best.inl, arg.N, lm.JtJ, lm.Jte, &S); /*Levenberg-Marquardt Loop.*/ @@ -1883,7 +1833,7 @@ inline void RHO_HEST_REFC::refine(void){ sacTRInv8x8 (lm.tmp1, lm.tmp1); sacTRISolve8x8(lm.tmp1, lm.Jte, dH); sacSub8x1 (newH, best.H, dH); - sacCalcJacobianErrors(newH, arg.src, arg.dst, arg.inl, arg.N, + sacCalcJacobianErrors(newH, arg.src, arg.dst, best.inl, arg.N, NULL, NULL, &newS); gain = sacLMGain(dH, lm.Jte, S, newS, L); /*printf("Lambda: %12.6f S: %12.6f newS: %12.6f Gain: %12.6f\n", @@ -1911,7 +1861,7 @@ inline void RHO_HEST_REFC::refine(void){ if(gain > 0){ S = newS; memcpy(best.H, newH, sizeof(newH)); - sacCalcJacobianErrors(best.H, arg.src, arg.dst, arg.inl, arg.N, + sacCalcJacobianErrors(best.H, arg.src, arg.dst, best.inl, arg.N, lm.JtJ, lm.Jte, &S); } } From 42176f8eb1145abd4b046769e9ad1b7abda9d22c Mon Sep 17 00:00:00 2001 From: Hamid Bazargani Date: Fri, 13 Feb 2015 00:09:37 -0500 Subject: [PATCH 17/39] Fix sacCalcJacobianErrors arguments. (curr.inl replaced with best.inl) Fix the issue given NULL inlMask --- modules/calib3d/src/rhorefc.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 272995cee..bc36e0bd8 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -1799,7 +1799,6 @@ inline void RHO_HEST_REFC::refine(void){ /** * Iteratively refine the homography. */ - /* Find initial conditions */ sacCalcJacobianErrors(best.H, arg.src, arg.dst, best.inl, arg.N, lm.JtJ, lm.Jte, &S); From e22678018b084e8c0e17ece43114894aaea8fae8 Mon Sep 17 00:00:00 2001 From: Hamid Bazargani Date: Fri, 13 Feb 2015 00:30:18 -0500 Subject: [PATCH 18/39] Fix sacCalcJacobianErrors arguments. (curr.inl replaced with best.inl) Fix the issue given NULL inlMask --- modules/calib3d/src/fundam.cpp | 1 - modules/calib3d/src/rhorefc.cpp | 2 -- 2 files changed, 3 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index beba572c9..af7c4dfb0 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -399,7 +399,6 @@ cv::Mat cv::findHomography( InputArray _points1, InputArray _points2, tempMask = Mat::ones(npoints, 1, CV_8U); result = cb->runKernel(src, dst, H) > 0; } - else if( method == RANSAC) result = createRANSACPointSetRegistrator(cb, 4, ransacReprojThreshold, confidence, maxIters)->run(src, dst, H, tempMask); else if( method == LMEDS ) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index bc36e0bd8..2fffadac8 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -624,11 +624,9 @@ unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ if(isFinalRefineEnabled() && canRefine()){ refine(); } - outputModel(); finiRun(); return isBestModelGoodEnough() ? best.numInl : 0; - } From 44f906eb356f1de71517a82904d897186dbf6e96 Mon Sep 17 00:00:00 2001 From: Hamid Bazargani Date: Fri, 13 Feb 2015 00:38:19 -0500 Subject: [PATCH 19/39] Fix sacCalcJacobianErrors arguments. (curr.inl replaced with best.inl) Fix the issue given NULL inlMask --- modules/calib3d/src/fundam.cpp | 2 +- modules/calib3d/src/rhorefc.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index af7c4dfb0..584ba5af1 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -398,7 +398,7 @@ cv::Mat cv::findHomography( InputArray _points1, InputArray _points2, { tempMask = Mat::ones(npoints, 1, CV_8U); result = cb->runKernel(src, dst, H) > 0; - } + } else if( method == RANSAC) result = createRANSACPointSetRegistrator(cb, 4, ransacReprojThreshold, confidence, maxIters)->run(src, dst, H, tempMask); else if( method == LMEDS ) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 2fffadac8..8a7b57fea 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -624,8 +624,8 @@ unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ if(isFinalRefineEnabled() && canRefine()){ refine(); } - outputModel(); - finiRun(); + outputModel(); + finiRun(); return isBestModelGoodEnough() ? best.numInl : 0; } @@ -1346,7 +1346,7 @@ inline void RHO_HEST_REFC::nStarOptimize(void){ */ inline void RHO_HEST_REFC::updateBounds(void){ - arg.maxI = sacCalcIterBound(arg.cfd, + arg.maxI = sacCalcIterBound(arg.cfd, (double)best.numInl/arg.N, SMPL_SIZE, arg.maxI); From 5070f2a33418e22e9b63f7254b458b07c3305d04 Mon Sep 17 00:00:00 2001 From: Hamid Bazargani Date: Fri, 13 Feb 2015 00:44:19 -0500 Subject: [PATCH 20/39] Fix sacCalcJacobianErrors arguments. (curr.inl replaced with best.inl) Fix the issue given NULL inlMask --- modules/calib3d/src/rhorefc.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 8a7b57fea..6214813ca 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -1346,7 +1346,7 @@ inline void RHO_HEST_REFC::nStarOptimize(void){ */ inline void RHO_HEST_REFC::updateBounds(void){ - arg.maxI = sacCalcIterBound(arg.cfd, + arg.maxI = sacCalcIterBound(arg.cfd, (double)best.numInl/arg.N, SMPL_SIZE, arg.maxI); From e5696bc5e6042752f8bce7207ad39e516a923d02 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Fri, 13 Feb 2015 08:01:57 -0500 Subject: [PATCH 21/39] Whitespace change reverts to minimize delta w.r.t master. --- modules/calib3d/src/fundam.cpp | 8 +++----- modules/calib3d/src/rhorefc.cpp | 10 +++++----- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index af7c4dfb0..5ec12161d 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -398,8 +398,8 @@ cv::Mat cv::findHomography( InputArray _points1, InputArray _points2, { tempMask = Mat::ones(npoints, 1, CV_8U); result = cb->runKernel(src, dst, H) > 0; - } - else if( method == RANSAC) + } + else if( method == RANSAC ) result = createRANSACPointSetRegistrator(cb, 4, ransacReprojThreshold, confidence, maxIters)->run(src, dst, H, tempMask); else if( method == LMEDS ) result = createLMeDSPointSetRegistrator(cb, 4, confidence, maxIters)->run(src, dst, H, tempMask); @@ -408,7 +408,6 @@ cv::Mat cv::findHomography( InputArray _points1, InputArray _points2, else CV_Error(Error::StsBadArg, "Unknown estimation method"); - if( result && npoints > 4 && method != RHO) { compressPoints( src.ptr(), tempMask.ptr(), 1, npoints ); @@ -419,9 +418,8 @@ cv::Mat cv::findHomography( InputArray _points1, InputArray _points2, Mat dst1 = dst.rowRange(0, npoints); src = src1; dst = dst1; - if( method == RANSAC || method == LMEDS) + if( method == RANSAC || method == LMEDS ) cb->runKernel( src, dst, H ); - Mat H8(8, 1, CV_64F, H.ptr()); createLMSolver(makePtr(src, dst), 10)->run(H8); } diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 2fffadac8..f60f68a04 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -614,9 +614,9 @@ unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ for(ctrl.i=0; ctrl.i < arg.maxI || ctrl.i < 100; ctrl.i++){ hypothesize() && verify(); - } + /** * Teardown */ @@ -624,8 +624,9 @@ unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ if(isFinalRefineEnabled() && canRefine()){ refine(); } - outputModel(); - finiRun(); + + outputModel(); + finiRun(); return isBestModelGoodEnough() ? best.numInl : 0; } @@ -861,7 +862,6 @@ inline int RHO_HEST_REFC::verify(void){ if(isNREnabled()){ nStarOptimize(); } - } return 1; @@ -1346,7 +1346,7 @@ inline void RHO_HEST_REFC::nStarOptimize(void){ */ inline void RHO_HEST_REFC::updateBounds(void){ - arg.maxI = sacCalcIterBound(arg.cfd, + arg.maxI = sacCalcIterBound(arg.cfd, (double)best.numInl/arg.N, SMPL_SIZE, arg.maxI); From f454929d9c2f96f74cee0c8006458fd40e20da46 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Sat, 21 Feb 2015 12:31:55 -0500 Subject: [PATCH 22/39] PRNG changes: xorshift128+ algorithm, and seeding API. - Switched to the extremely fast, while simple and high-quality, xorshift128+ PRNG algorithm by Sebastiano Vigna in "Further scramblings of Marsaglia's xorshift generators. CoRR, abs/1402.6246, 2014" (2^128-1 period, passes BigCrush tests). Performance improved by 10% over random(). - Added an API to allow seeding with a specified seed, rather than using rand() or random(). This allows deterministic, reproducible results in tests using our algorithm (although findHomography() does not yet support passing an entropy source on its own end). --- modules/calib3d/src/rhorefc.cpp | 214 ++++++++++++++++++++------------ modules/calib3d/src/rhorefc.h | 14 +++ 2 files changed, 149 insertions(+), 79 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index f60f68a04..86d2f0977 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -161,6 +161,11 @@ struct RHO_HEST_REFC{ float* Jte; /* Jte vector */ } lm; + /* PRNG XORshift128+ */ + struct{ + uint64_t s[2]; /* PRNG state */ + } prng; + /* Initialized? */ int init; @@ -205,6 +210,11 @@ struct RHO_HEST_REFC{ inline int PROSACPhaseEndReached(void); inline void PROSACGoToNextPhase(void); inline void getPROSACSample(void); + inline void rndSmpl(unsigned sampleSize, + unsigned* currentSample, + unsigned dataSetSize); + inline double fastRandom(void); + inline void fastSeed(uint64_t seed); inline int isSampleDegenerate(void); inline void generateModel(void); inline int isModelDegenerate(void); @@ -239,10 +249,6 @@ static inline void sacInitNonRand (double beta, static inline double sacInitPEndFpI (const unsigned ransacConvg, const unsigned n, const unsigned s); -static inline void sacRndSmpl (unsigned sampleSize, - unsigned* currentSample, - unsigned dataSetSize); -static inline double sacRandom (void); static inline unsigned sacCalcIterBound (double confidence, double inlierRate, unsigned sampleSize, @@ -304,6 +310,15 @@ int rhoRefCEnsureCapacity(RHO_HEST_REFC* p, unsigned N, double beta){ } +/** + * Seeds the internal PRNG with the given seed. + */ + +void rhoRefCSeed(RHO_HEST_REFC* p, unsigned long long seed){ + p->fastSeed((uint64_t)seed); +} + + /** * External access to context destructor. * @@ -459,6 +474,12 @@ inline int RHO_HEST_REFC::initialize(void){ lm.tmp1 = NULL; lm.Jte = NULL; +#ifdef _WIN32 + fastSeed(rand()); +#else + fastSeed(random()); +#endif + int areAllAllocsSuccessful = ctrl.smpl && curr.H && @@ -950,13 +971,121 @@ inline void RHO_HEST_REFC::PROSACGoToNextPhase(void){ inline void RHO_HEST_REFC::getPROSACSample(void){ if(ctrl.i > ctrl.phEndI){ /* FIXME: Dubious. Review. */ - sacRndSmpl(4, ctrl.smpl, ctrl.phNum);/* Used to be phMax */ + rndSmpl(4, ctrl.smpl, ctrl.phNum);/* Used to be phMax */ }else{ - sacRndSmpl(3, ctrl.smpl, ctrl.phNum-1); + rndSmpl(3, ctrl.smpl, ctrl.phNum-1); ctrl.smpl[3] = ctrl.phNum-1; } } +/** + * Choose, without repetition, sampleSize integers in the range [0, numDataPoints). + */ + +inline void RHO_HEST_REFC::rndSmpl(unsigned sampleSize, + unsigned* currentSample, + unsigned dataSetSize){ + /** + * If sampleSize is very close to dataSetSize, we use selection sampling. + * Otherwise we use the naive sampling technique wherein we select random + * indexes until sampleSize of them are distinct. + */ + + if(sampleSize*2>dataSetSize){ + /** + * Selection Sampling: + * + * Algorithm S (Selection sampling technique). To select n records at random from a set of N, where 0 < n ≤ N. + * S1. [Initialize.] Set t ← 0, m ← 0. (During this algorithm, m represents the number of records selected so far, + * and t is the total number of input records that we have dealt with.) + * S2. [Generate U.] Generate a random number U, uniformly distributed between zero and one. + * S3. [Test.] If (N – t)U ≥ n – m, go to step S5. + * S4. [Select.] Select the next record for the sample, and increase m and t by 1. If m < n, go to step S2; + * otherwise the sample is complete and the algorithm terminates. + * S5. [Skip.] Skip the next record (do not include it in the sample), increase t by 1, and go back to step S2. + * + * Replaced m with i and t with j in the below code. + */ + + unsigned i=0,j=0; + + for(i=0;i> 17; // b + x ^= y ^ (y >> 26); // c + prng.s[0] = y; + prng.s[1] = x; + uint64_t s = x + y; + + return s * 5.421010862427522e-20;/* 2^-64 */ +} + +/** + * Seeds the PRNG. + * + * The seed should not be zero, since the state must be initialized to non-zero. + */ + +inline void RHO_HEST_REFC::fastSeed(uint64_t seed){ + int i; + + prng.s[0] = seed; + prng.s[1] = ~seed;/* Guarantees one of the elements will be non-zero. */ + + /** + * Escape from zero-land (see xorshift128+ paper). Approximately 20 + * iterations required according to the graph. + */ + + for(i=0;i<20;i++){ + fastRandom(); + } +} + /** * Checks whether the *sample* is degenerate prior to model generation. * - First, the extremely cheap numerical degeneracy test is run, which weeds @@ -1395,79 +1524,6 @@ static inline double sacInitPEndFpI(const unsigned ransacConvg, return ransacConvg*numer/denom; } -/** - * Choose, without repetition, sampleSize integers in the range [0, numDataPoints). - */ - -static inline void sacRndSmpl(unsigned sampleSize, - unsigned* currentSample, - unsigned dataSetSize){ - /** - * If sampleSize is very close to dataSetSize, we use selection sampling. - * Otherwise we use the naive sampling technique wherein we select random - * indexes until sampleSize of them are distinct. - */ - - if(sampleSize*2>dataSetSize){ - /** - * Selection Sampling: - * - * Algorithm S (Selection sampling technique). To select n records at random from a set of N, where 0 < n ≤ N. - * S1. [Initialize.] Set t ← 0, m ← 0. (During this algorithm, m represents the number of records selected so far, - * and t is the total number of input records that we have dealt with.) - * S2. [Generate U.] Generate a random number U, uniformly distributed between zero and one. - * S3. [Test.] If (N – t)U ≥ n – m, go to step S5. - * S4. [Select.] Select the next record for the sample, and increase m and t by 1. If m < n, go to step S2; - * otherwise the sample is complete and the algorithm terminates. - * S5. [Skip.] Skip the next record (do not include it in the sample), increase t by 1, and go back to step S2. - * - * Replaced m with i and t with j in the below code. - */ - - unsigned i=0,j=0; - - for(i=0;i Date: Thu, 26 Feb 2015 21:47:29 -0500 Subject: [PATCH 23/39] Removed unnecessary precision in damped Cholesky decomposition. Cholesky decomposition is stable; It is not necessary to carry it out internally at double precision if the result will be truncated to single precision when stored. --- modules/calib3d/src/rhorefc.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 86d2f0977..8372d251a 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -2129,28 +2129,28 @@ static inline int sacChol8x8Damped(const float (*A)[8], const register int N = 8; int i, j, k; float lambdap1 = lambda + 1.0f; - double x; + float x; for(i=0;i Date: Tue, 3 Mar 2015 08:05:52 -0500 Subject: [PATCH 24/39] Moved constants to cv:: namespace. --- modules/calib3d/src/rhorefc.cpp | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 8372d251a..c829bb15a 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -56,7 +56,15 @@ #include #include "rhorefc.h" -/* Defines */ + + + + +/* For the sake of cv:: namespace ONLY: */ +namespace cv{/* For C support, replace with extern "C" { */ + + +/* Constants */ const int MEM_ALIGN = 32; const size_t HSIZE = (3*3*sizeof(float)); const double MIN_DELTA_CHNG = 0.1; @@ -74,12 +82,6 @@ const double LM_GAIN_LO = 0.25; /* See sacLMGain(). */ const double LM_GAIN_HI = 0.75; /* See sacLMGain(). */ - - - -/* For the sake of cv:: namespace ONLY: */ -namespace cv{/* For C support, replace with extern "C" { */ - /* Data Structures */ struct RHO_HEST_REFC{ /** From a2affe70d923818fb1556366e70c263c1885cfac Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Mar 2015 11:40:44 -0500 Subject: [PATCH 25/39] Deleted last remnants of restrict keyword. --- modules/calib3d/src/rhorefc.cpp | 32 +++++++++++++++---------------- modules/calib3d/src/rhorefc.h | 34 ++++++++++++++------------------- 2 files changed, 30 insertions(+), 36 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index c829bb15a..4abbd4ec3 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -256,14 +256,14 @@ static inline unsigned sacCalcIterBound (double confidence, unsigned sampleSize, unsigned maxIterBound); static inline void hFuncRefC (float* packedPoints, float* H); -static inline void sacCalcJacobianErrors(const float* restrict H, - const float* restrict src, - const float* restrict dst, - const char* restrict inl, - unsigned N, - float (* restrict JtJ)[8], - float* restrict Jte, - float* restrict Sp); +static inline void sacCalcJacobianErrors(const float* H, + const float* src, + const float* dst, + const char* inl, + unsigned N, + float (* JtJ)[8], + float* Jte, + float* Sp); static inline float sacLMGain (const float* dH, const float* Jte, const float S, @@ -1935,14 +1935,14 @@ inline void RHO_HEST_REFC::refine(void){ * nevertheless be vectorized if need be. */ -static inline void sacCalcJacobianErrors(const float* restrict H, - const float* restrict src, - const float* restrict dst, - const char* restrict inl, - unsigned N, - float (* restrict JtJ)[8], - float* restrict Jte, - float* restrict Sp){ +static inline void sacCalcJacobianErrors(const float* H, + const float* src, + const float* dst, + const char* inl, + unsigned N, + float (* JtJ)[8], + float* Jte, + float* Sp){ unsigned i; float S; diff --git a/modules/calib3d/src/rhorefc.h b/modules/calib3d/src/rhorefc.h index e6c324dcc..9fcb3677b 100644 --- a/modules/calib3d/src/rhorefc.h +++ b/modules/calib3d/src/rhorefc.h @@ -57,12 +57,6 @@ /* Defines */ -/* C++ does not have the restrict keyword. */ -#ifdef restrict -#undef restrict -#endif -#define restrict - /* Flags */ #ifndef RHO_FLAG_NONE @@ -256,20 +250,20 @@ void rhoRefCFini(RHO_HEST_REFC* p); * inliers for acceptance was reached; 0 otherwise. */ -unsigned rhoRefC(RHO_HEST_REFC* restrict p, /* Homography estimation context. */ - const float* restrict src, /* Source points */ - const float* restrict dst, /* Destination points */ - char* restrict inl, /* Inlier mask */ - unsigned N, /* = src.length = dst.length = inl.length */ - float maxD, /* 3.0 */ - unsigned maxI, /* 2000 */ - unsigned rConvg, /* 2000 */ - double cfd, /* 0.995 */ - unsigned minInl, /* 4 */ - double beta, /* 0.35 */ - unsigned flags, /* 0 */ - const float* guessH, /* Extrinsic guess, NULL if none provided */ - float* finalH); /* Final result. */ +unsigned rhoRefC(RHO_HEST_REFC* p, /* Homography estimation context. */ + const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* 3.0 */ + unsigned maxI, /* 2000 */ + unsigned rConvg, /* 2000 */ + double cfd, /* 0.995 */ + unsigned minInl, /* 4 */ + double beta, /* 0.35 */ + unsigned flags, /* 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH); /* Final result. */ From 0f6ea38eac79d0931eb1cd03b8c11b17a899aae4 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Mar 2015 11:42:04 -0500 Subject: [PATCH 26/39] Added OPENCV_ prefix to #include guard. --- modules/calib3d/src/rhorefc.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/calib3d/src/rhorefc.h b/modules/calib3d/src/rhorefc.h index 9fcb3677b..8ebc277ad 100644 --- a/modules/calib3d/src/rhorefc.h +++ b/modules/calib3d/src/rhorefc.h @@ -44,8 +44,8 @@ */ /* Include Guards */ -#ifndef __RHOREFC_H__ -#define __RHOREFC_H__ +#ifndef __OPENCV_RHOREFC_H__ +#define __OPENCV_RHOREFC_H__ From e1abc416cfc25ddeaf11d919fc10afdadbfa0670 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Mar 2015 11:48:41 -0500 Subject: [PATCH 27/39] Changed seeding in initialization. The call to rand()/random() is now a call to (unsigned)cv::theRNG(). --- modules/calib3d/src/rhorefc.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 4abbd4ec3..7b3082506 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -45,6 +45,7 @@ /* Includes */ #include +#include #include #include #include @@ -476,11 +477,7 @@ inline int RHO_HEST_REFC::initialize(void){ lm.tmp1 = NULL; lm.Jte = NULL; -#ifdef _WIN32 - fastSeed(rand()); -#else - fastSeed(random()); -#endif + fastSeed((unsigned)cv::theRNG()); int areAllAllocsSuccessful = ctrl.smpl && From 16f36a5fda13ffc313619e9b2b08c4224ad25995 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Mar 2015 11:55:36 -0500 Subject: [PATCH 28/39] Replaced division by reciprocal + multiply in a few places. --- modules/calib3d/src/rhorefc.cpp | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 7b3082506..2b5b79d98 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -1756,21 +1756,21 @@ static void hFuncRefC(float* packedPoints,/* Source (four x,y float coordinates) * R(2)-= (x2*R(0) + y2*R(1)) */ - scalar1=minor[0][0]; - major[0][0]/=scalar1; - major[1][0]/=scalar1; - major[2][0]/=scalar1; - major[0][4]/=scalar1; - major[1][4]/=scalar1; - major[2][4]/=scalar1; + scalar1=1.0f/minor[0][0]; + major[0][0]*=scalar1; + major[1][0]*=scalar1; + major[2][0]*=scalar1; + major[0][4]*=scalar1; + major[1][4]*=scalar1; + major[2][4]*=scalar1; - scalar1=minor[1][1]; - major[0][1]/=scalar1; - major[1][1]/=scalar1; - major[2][1]/=scalar1; - major[0][5]/=scalar1; - major[1][5]/=scalar1; - major[2][5]/=scalar1; + scalar1=1.0f/minor[1][1]; + major[0][1]*=scalar1; + major[1][1]*=scalar1; + major[2][1]*=scalar1; + major[0][5]*=scalar1; + major[1][5]*=scalar1; + major[2][5]*=scalar1; scalar1=minor[0][2];scalar2=minor[1][2]; From bb01231990bf7b500c6564dacc46e44f761c00ff Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Mar 2015 13:06:36 -0500 Subject: [PATCH 29/39] Substituted the NaN check with OpenCV's implementation. --- modules/calib3d/src/rhorefc.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 2b5b79d98..a4a63dc6e 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -1202,7 +1202,8 @@ inline int RHO_HEST_REFC::isModelDegenerate(void){ float f=H[0]+H[1]+H[2]+H[3]+H[4]+H[5]+H[6]+H[7]; /* degenerate = isnan(f); */ - degenerate = f!=f;/* Only NaN is not equal to itself. */ + /* degenerate = f!=f;// Only NaN is not equal to itself. */ + degenerate = cvIsNaN(f); /* degenerate = 0; */ From f592321771296acf662dbdcf0032f2401887d764 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Mar 2015 22:57:40 -0500 Subject: [PATCH 30/39] Internal buffers converted to use OpenCV dynamic memory allocation. --- modules/calib3d/src/rhorefc.cpp | 281 ++++++++++++++++++-------------- 1 file changed, 159 insertions(+), 122 deletions(-) diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index a4a63dc6e..0aab9a8b7 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -158,7 +158,6 @@ struct RHO_HEST_REFC{ /* Levenberg-Marquardt Refinement */ struct{ - float* ws; /* Levenberg-Marqhard Workspace */ float (* JtJ)[8]; /* JtJ matrix */ float (* tmp1)[8]; /* Temporary 1 */ float* Jte; /* Jte vector */ @@ -169,8 +168,14 @@ struct RHO_HEST_REFC{ uint64_t s[2]; /* PRNG state */ } prng; + /* Memory Management */ + struct{ + cv::Mat perObj; + cv::Mat perRun; + } mem; + /* Initialized? */ - int init; + int initialized; /* Empty constructors and destructors */ @@ -202,6 +207,10 @@ struct RHO_HEST_REFC{ /* Methods to implement internals */ + inline void allocatePerObj(void); + inline void allocatePerRun(void); + inline void deallocatePerRun(void); + inline void deallocatePerObj(void); inline int initRun(void); inline void finiRun(void); inline int haveExtrinsicGuess(void); @@ -242,9 +251,6 @@ struct RHO_HEST_REFC{ * Prototypes for purely-computational code. */ -static inline void* almalloc(size_t nBytes); -static inline void alfree (void* ptr); - static inline void sacInitNonRand (double beta, unsigned start, unsigned N, @@ -382,36 +388,6 @@ unsigned rhoRefC(RHO_HEST_REFC* p, /* Homography estimation context. */ -/** - * Allocate memory aligned to a boundary of MEMALIGN. - */ - -static inline void* almalloc(size_t nBytes){ - if(nBytes){ - unsigned char* ptr = (unsigned char*)malloc(MEM_ALIGN + nBytes); - if(ptr){ - unsigned char* adj = (unsigned char*)(((intptr_t)(ptr+MEM_ALIGN))&((intptr_t)(-MEM_ALIGN))); - ptrdiff_t diff = adj - ptr; - adj[-1] = (unsigned char)(diff - 1); - return adj; - } - } - - return NULL; -} - -/** - * Free aligned memory. - * - * If argument is NULL, do nothing in accordance with free() semantics. - */ - -static inline void alfree(void* ptr){ - if(ptr){ - unsigned char* cptr = (unsigned char*)ptr; - free(cptr - (ptrdiff_t)cptr[-1] - 1); - } -} /** * Constructor for RHO_HEST_REFC. @@ -419,7 +395,7 @@ static inline void alfree(void* ptr){ * Does nothing. True initialization is done by initialize(). */ -RHO_HEST_REFC::RHO_HEST_REFC() : init(0){ +RHO_HEST_REFC::RHO_HEST_REFC() : initialized(0){ } @@ -427,7 +403,7 @@ RHO_HEST_REFC::RHO_HEST_REFC() : init(0){ * Private copy constructor for RHO_HEST_REFC. Disabled. */ -RHO_HEST_REFC::RHO_HEST_REFC(const RHO_HEST_REFC&) : init(0){ +RHO_HEST_REFC::RHO_HEST_REFC(const RHO_HEST_REFC&) : initialized(0){ } @@ -436,7 +412,7 @@ RHO_HEST_REFC::RHO_HEST_REFC(const RHO_HEST_REFC&) : init(0){ */ RHO_HEST_REFC::~RHO_HEST_REFC(){ - if(init){ + if(initialized){ finalize(); } } @@ -458,37 +434,30 @@ RHO_HEST_REFC::~RHO_HEST_REFC(){ */ inline int RHO_HEST_REFC::initialize(void){ - ctrl.smpl = (unsigned*)almalloc(SMPL_SIZE*sizeof(*ctrl.smpl)); + initialized = 0; + + + allocatePerObj(); - curr.pkdPts = (float*) almalloc(SMPL_SIZE*2*2*sizeof(*curr.pkdPts)); - curr.H = (float*) almalloc(HSIZE); curr.inl = NULL; curr.numInl = 0; - best.H = (float*) almalloc(HSIZE); best.inl = NULL; best.numInl = 0; nr.size = 0; nr.beta = 0.0; - lm.ws = NULL; - lm.JtJ = NULL; - lm.tmp1 = NULL; - lm.Jte = NULL; fastSeed((unsigned)cv::theRNG()); - int areAllAllocsSuccessful = ctrl.smpl && - curr.H && - best.H && - curr.pkdPts; + int areAllAllocsSuccessful = !mem.perObj.empty(); if(!areAllAllocsSuccessful){ finalize(); }else{ - init = 1; + initialized = 1; } return areAllAllocsSuccessful; @@ -502,15 +471,10 @@ inline int RHO_HEST_REFC::initialize(void){ */ inline void RHO_HEST_REFC::finalize(void){ - if(init){ - alfree(ctrl.smpl); - alfree(curr.H); - alfree(best.H); - alfree(curr.pkdPts); + if(initialized){ + deallocatePerObj(); - memset(this, 0, sizeof(*this)); - - init = 0; + initialized = 0; } } @@ -651,6 +615,128 @@ unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ } +/** + * Allocate per-object dynamic storage. + * + * This includes aligned, fixed-size internal buffers, but excludes any buffers + * whose size cannot be determined ahead-of-time (before the number of matches + * is known). + * + * All buffer memory is allocated in one single shot, and all pointers are + * initialized. + */ + +inline void RHO_HEST_REFC::allocatePerObj(void){ + /* We have known sizes */ + size_t ctrl_smpl_sz = SMPL_SIZE*sizeof(*ctrl.smpl); + size_t curr_pkdPts_sz = SMPL_SIZE*2*2*sizeof(*curr.pkdPts); + size_t curr_H_sz = HSIZE; + size_t best_H_sz = HSIZE; + size_t lm_JtJ_sz = 8*8*sizeof(float); + size_t lm_tmp1_sz = 8*8*sizeof(float); + size_t lm_Jte_sz = 1*8*sizeof(float); + + /* We compute offsets */ + size_t total = 0; +#define MK_OFFSET(v) \ + size_t v ## _of = total; \ + total = alignSize(v ## _of + v ## _sz, MEM_ALIGN) + + MK_OFFSET(ctrl_smpl); + MK_OFFSET(curr_pkdPts); + MK_OFFSET(curr_H); + MK_OFFSET(best_H); + MK_OFFSET(lm_JtJ); + MK_OFFSET(lm_tmp1); + MK_OFFSET(lm_Jte); + +#undef MK_OFFSET + + /* Allocate dynamic memory managed by cv::Mat */ + mem.perObj.create(1, total + MEM_ALIGN, CV_8UC1); + + /* Extract aligned pointer */ + unsigned char* ptr = alignPtr(mem.perObj.data, MEM_ALIGN); + + /* Assign pointers */ + ctrl.smpl = (unsigned*) (ptr + ctrl_smpl_of); + curr.pkdPts = (float*) (ptr + curr_pkdPts_of); + curr.H = (float*) (ptr + curr_H_of); + best.H = (float*) (ptr + best_H_of); + lm.JtJ = (float(*)[8])(ptr + lm_JtJ_of); + lm.tmp1 = (float(*)[8])(ptr + lm_tmp1_of); + lm.Jte = (float*) (ptr + lm_Jte_of); +} + + +/** + * Allocate per-run dynamic storage. + * + * This includes storage that is proportional to the number of points, such as + * the inlier mask. + */ + +inline void RHO_HEST_REFC::allocatePerRun(void){ + /* We have known sizes */ + size_t best_inl_sz = arg.N; + size_t curr_inl_sz = arg.N; + + /* We compute offsets */ + size_t total = 0; +#define MK_OFFSET(v) \ + size_t v ## _of = total; \ + total = alignSize(v ## _of + v ## _sz, MEM_ALIGN) + + MK_OFFSET(best_inl); + MK_OFFSET(curr_inl); + +#undef MK_OFFSET + + /* Allocate dynamic memory managed by cv::Mat */ + mem.perRun.create(1, total + MEM_ALIGN, CV_8UC1); + + /* Extract aligned pointer */ + unsigned char* ptr = alignPtr(mem.perRun.data, MEM_ALIGN); + + /* Assign pointers */ + best.inl = (char*)(ptr + best_inl_of); + curr.inl = (char*)(ptr + curr_inl_of); +} + + +/** + * Deallocate per-run dynamic storage. + * + * Undoes the work by allocatePerRun(). + */ + +inline void RHO_HEST_REFC::deallocatePerRun(void){ + best.inl = NULL; + curr.inl = NULL; + + mem.perRun.release(); +} + + +/** + * Deallocate per-object dynamic storage. + * + * Undoes the work by allocatePerObj(). + */ + +inline void RHO_HEST_REFC::deallocatePerObj(void){ + ctrl.smpl = NULL; + curr.pkdPts = NULL; + curr.H = NULL; + best.H = NULL; + lm.JtJ = NULL; + lm.tmp1 = NULL; + lm.Jte = NULL; + + mem.perObj.release(); +} + + /** * Initialize SAC for a run given its arguments. * @@ -716,46 +802,18 @@ inline int RHO_HEST_REFC::initRun(void){ * Inlier mask alloc. * * Runs second because we want to quit as fast as possible if we can't even - * allocate the up tp two masks. - * - * If the calling software wants an output mask, use buffer provided. If - * not, allocate one anyways internally. + * allocate the two masks. */ - best.inl = arg.inl ? arg.inl : (char*)almalloc(arg.N); - curr.inl = (char*)almalloc(arg.N); - - if(!curr.inl || !best.inl){ - return 0; - } + allocatePerRun(); memset(best.inl, 0, arg.N); memset(curr.inl, 0, arg.N); - /** - * LevMarq workspace alloc. - * - * Runs third, consists only in a few conditional mallocs. If malloc fails - * we wish to quit before doing any serious work. - */ - - if(isRefineEnabled() || isFinalRefineEnabled()){ - lm.ws = (float*)almalloc(2*8*8*sizeof(float) + 1*8*sizeof(float)); - if(!lm.ws){ - return 0; - } - - lm.JtJ = (float(*)[8])(lm.ws + 0*8*8); - lm.tmp1 = (float(*)[8])(lm.ws + 1*8*8); - lm.Jte = (float*) (lm.ws + 2*8*8); - }else{ - lm.ws = NULL; - } - /** * Reset scalar per-run state. * - * Runs fourth because there's no point in resetting/calculating a large + * Runs third because there's no point in resetting/calculating a large * number of fields if something in the above junk failed. */ @@ -801,32 +859,7 @@ inline int RHO_HEST_REFC::initRun(void){ */ inline void RHO_HEST_REFC::finiRun(void){ - /** - * If no output inlier mask was required, free both (internal) masks. - * Else if an (external) mask was provided as argument, find the other - * (the internal one) and free it. - */ - - if(arg.inl){ - if(arg.inl == best.inl){ - alfree(curr.inl); - }else{ - alfree(best.inl); - } - }else{ - alfree(best.inl); - alfree(curr.inl); - } - - best.inl = NULL; - curr.inl = NULL; - - /** - * ₣ree the Levenberg-Marquardt workspace. - */ - - alfree(lm.ws); - lm.ws = NULL; + deallocatePerRun(); } /** @@ -1464,9 +1497,9 @@ inline void RHO_HEST_REFC::nStarOptimize(void){ ctrl.phMax = best_n; ctrl.phNumInl = bestNumInl; arg.maxI = sacCalcIterBound(arg.cfd, - (double)ctrl.phNumInl/ctrl.phMax, - SMPL_SIZE, - arg.maxI); + (double)ctrl.phNumInl/ctrl.phMax, + SMPL_SIZE, + arg.maxI); } } @@ -1488,7 +1521,7 @@ inline void RHO_HEST_REFC::updateBounds(void){ inline void RHO_HEST_REFC::outputModel(void){ if(isBestModelGoodEnough()){ memcpy(arg.finalH, best.H, HSIZE); - if(arg.inl && arg.inl != best.inl){ + if(arg.inl){ memcpy(arg.inl, best.inl, arg.N); } }else{ @@ -1501,8 +1534,12 @@ inline void RHO_HEST_REFC::outputModel(void){ */ inline void RHO_HEST_REFC::outputZeroH(void){ - memset(arg.finalH, 0, HSIZE); - memset(arg.inl, 0, arg.N); + if(arg.finalH){ + memset(arg.finalH, 0, HSIZE); + } + if(arg.inl){ + memset(arg.inl, 0, arg.N); + } } /** From 408f93340a837764768d208bdd1de2c9f1574b77 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Tue, 3 Mar 2015 23:12:33 -0500 Subject: [PATCH 31/39] External interface converted to use OpenCV Ptr<> smart pointer. --- modules/calib3d/src/fundam.cpp | 8 +---- modules/calib3d/src/rhorefc.cpp | 54 ++++++++++++++------------------- modules/calib3d/src/rhorefc.h | 46 +++++++++++----------------- 3 files changed, 41 insertions(+), 67 deletions(-) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index 5ec12161d..f5e88d7e9 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -303,7 +303,7 @@ static bool createAndRunRHORegistrator(double confidence, * initialized, used, then finalized. */ - RHO_HEST_REFC* p = rhoRefCInit(); + Ptr p = rhoRefCInit(); /** * Optional. Ideally, the context would survive across calls to @@ -339,12 +339,6 @@ static bool createAndRunRHORegistrator(double confidence, NULL, (float*)tmpH.data); - /** - * Cleanup. - */ - - rhoRefCFini(p); - /* Convert float homography to double precision. */ tmpH.convertTo(_H, CV_64FC1); diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rhorefc.cpp index 0aab9a8b7..90aa16ee9 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rhorefc.cpp @@ -298,12 +298,13 @@ static inline void sacSub8x1 (float* Hout, * @return A pointer to the context if successful; NULL if an error occured. */ -RHO_HEST_REFC* rhoRefCInit(void){ - RHO_HEST_REFC* p = new RHO_HEST_REFC; +Ptr rhoRefCInit(void){ + Ptr p = Ptr(new RHO_HEST_REFC); - if(!p->initialize()){ - delete p; - p = NULL; + if(p){ + if(!p->initialize()){ + p = Ptr((RHO_HEST_REFC*)NULL); + } } return p; @@ -314,7 +315,7 @@ RHO_HEST_REFC* rhoRefCInit(void){ * External access to non-randomness table resize. */ -int rhoRefCEnsureCapacity(RHO_HEST_REFC* p, unsigned N, double beta){ +int rhoRefCEnsureCapacity(Ptr p, unsigned N, double beta){ return p->sacEnsureCapacity(N, beta); } @@ -323,22 +324,11 @@ int rhoRefCEnsureCapacity(RHO_HEST_REFC* p, unsigned N, double beta){ * Seeds the internal PRNG with the given seed. */ -void rhoRefCSeed(RHO_HEST_REFC* p, unsigned long long seed){ +void rhoRefCSeed(Ptr p, unsigned long long seed){ p->fastSeed((uint64_t)seed); } -/** - * External access to context destructor. - * - * @param [in] p The initialized estimator context to finalize. - */ - -void rhoRefCFini(RHO_HEST_REFC* p){ - delete p; -} - - /** * Estimates the homography using the given context, matches and parameters to * PROSAC. @@ -368,20 +358,20 @@ void rhoRefCFini(RHO_HEST_REFC* p){ * inliers for acceptance was reached; 0 otherwise. */ -unsigned rhoRefC(RHO_HEST_REFC* p, /* Homography estimation context. */ - const float* src, /* Source points */ - const float* dst, /* Destination points */ - char* inl, /* Inlier mask */ - unsigned N, /* = src.length = dst.length = inl.length */ - float maxD, /* Works: 3.0 */ - unsigned maxI, /* Works: 2000 */ - unsigned rConvg, /* Works: 2000 */ - double cfd, /* Works: 0.995 */ - unsigned minInl, /* Minimum: 4 */ - double beta, /* Works: 0.35 */ - unsigned flags, /* Works: 0 */ - const float* guessH, /* Extrinsic guess, NULL if none provided */ - float* finalH){ /* Final result. */ +unsigned rhoRefC(Ptr p, /* Homography estimation context. */ + const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* Works: 3.0 */ + unsigned maxI, /* Works: 2000 */ + unsigned rConvg, /* Works: 2000 */ + double cfd, /* Works: 0.995 */ + unsigned minInl, /* Minimum: 4 */ + double beta, /* Works: 0.35 */ + unsigned flags, /* Works: 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH){ /* Final result. */ return p->rhoRefC(src, dst, inl, N, maxD, maxI, rConvg, cfd, minInl, beta, flags, guessH, finalH); } diff --git a/modules/calib3d/src/rhorefc.h b/modules/calib3d/src/rhorefc.h index 8ebc277ad..bcd9fba1e 100644 --- a/modules/calib3d/src/rhorefc.h +++ b/modules/calib3d/src/rhorefc.h @@ -50,6 +50,7 @@ /* Includes */ +#include @@ -96,7 +97,7 @@ typedef struct RHO_HEST_REFC RHO_HEST_REFC; * @return A pointer to the context if successful; NULL if an error occured. */ -RHO_HEST_REFC* rhoRefCInit(void); +Ptr rhoRefCInit(void); /** @@ -114,7 +115,7 @@ RHO_HEST_REFC* rhoRefCInit(void); * @return 0 if successful; non-zero if an error occured. */ -int rhoRefCEnsureCapacity(RHO_HEST_REFC* p, unsigned N, double beta); +int rhoRefCEnsureCapacity(Ptr p, unsigned N, double beta); @@ -129,18 +130,7 @@ int rhoRefCEnsureCapacity(RHO_HEST_REFC* p, unsigned N, double beta); * @param [in] seed The 64-bit integer seed. */ -void rhoRefCSeed(RHO_HEST_REFC* p, unsigned long long seed); - - - -/** - * Finalize the estimator context, by freeing the aligned buffers used - * internally. - * - * @param [in] p The initialized estimator context to finalize. - */ - -void rhoRefCFini(RHO_HEST_REFC* p); +void rhoRefCSeed(Ptr p, unsigned long long seed); /** @@ -250,20 +240,20 @@ void rhoRefCFini(RHO_HEST_REFC* p); * inliers for acceptance was reached; 0 otherwise. */ -unsigned rhoRefC(RHO_HEST_REFC* p, /* Homography estimation context. */ - const float* src, /* Source points */ - const float* dst, /* Destination points */ - char* inl, /* Inlier mask */ - unsigned N, /* = src.length = dst.length = inl.length */ - float maxD, /* 3.0 */ - unsigned maxI, /* 2000 */ - unsigned rConvg, /* 2000 */ - double cfd, /* 0.995 */ - unsigned minInl, /* 4 */ - double beta, /* 0.35 */ - unsigned flags, /* 0 */ - const float* guessH, /* Extrinsic guess, NULL if none provided */ - float* finalH); /* Final result. */ +unsigned rhoRefC(Ptr p, /* Homography estimation context. */ + const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* 3.0 */ + unsigned maxI, /* 2000 */ + unsigned rConvg, /* 2000 */ + double cfd, /* 0.995 */ + unsigned minInl, /* 4 */ + double beta, /* 0.35 */ + unsigned flags, /* 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH); /* Final result. */ From 736b42b3722a064ffdf48d2b6a954e5b4a40e94a Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Wed, 4 Mar 2015 01:43:13 -0500 Subject: [PATCH 32/39] Refactorings and renamings. - Deleted "RefC" from names of external-interface functions. - Renamed rhorefc.[cpp|hpp] to rho.[cpp|hpp] - Introduced RHO_HEST base class, from which RHO_HEST_REFC inherits. - rhoInit() currently only returns a Ptr, but in the future it will be allowed to return pointers to other derived classes, depending on the values returned by cv::checkHardwareSupport(). --- modules/calib3d/src/fundam.cpp | 8 +- modules/calib3d/src/{rhorefc.cpp => rho.cpp} | 295 +++++++++++++------ modules/calib3d/src/{rhorefc.h => rho.h} | 45 +-- 3 files changed, 236 insertions(+), 112 deletions(-) rename modules/calib3d/src/{rhorefc.cpp => rho.cpp} (90%) rename modules/calib3d/src/{rhorefc.h => rho.h} (88%) diff --git a/modules/calib3d/src/fundam.cpp b/modules/calib3d/src/fundam.cpp index f5e88d7e9..153f2a1e9 100644 --- a/modules/calib3d/src/fundam.cpp +++ b/modules/calib3d/src/fundam.cpp @@ -41,7 +41,7 @@ //M*/ #include "precomp.hpp" -#include "rhorefc.h" +#include "rho.h" #include namespace cv @@ -303,7 +303,7 @@ static bool createAndRunRHORegistrator(double confidence, * initialized, used, then finalized. */ - Ptr p = rhoRefCInit(); + Ptr p = rhoInit(); /** * Optional. Ideally, the context would survive across calls to @@ -311,7 +311,7 @@ static bool createAndRunRHORegistrator(double confidence, * to pay is marginally more computational work than strictly needed. */ - rhoRefCEnsureCapacity(p, npoints, beta); + rhoEnsureCapacity(p, npoints, beta); /** * The critical call. All parameters are heavily documented in rhorefc.h. @@ -324,7 +324,7 @@ static bool createAndRunRHORegistrator(double confidence, * this behaviour is too problematic. */ - result = !!rhoRefC(p, + result = !!rhoHest(p, (const float*)src.data, (const float*)dst.data, (char*) tempMask.data, diff --git a/modules/calib3d/src/rhorefc.cpp b/modules/calib3d/src/rho.cpp similarity index 90% rename from modules/calib3d/src/rhorefc.cpp rename to modules/calib3d/src/rho.cpp index 90aa16ee9..2289366bc 100644 --- a/modules/calib3d/src/rhorefc.cpp +++ b/modules/calib3d/src/rho.cpp @@ -55,7 +55,7 @@ #include #include #include -#include "rhorefc.h" +#include "rho.h" @@ -84,7 +84,162 @@ const double LM_GAIN_HI = 0.75; /* See sacLMGain(). */ /* Data Structures */ -struct RHO_HEST_REFC{ + +/** + * Base Struct for RHO algorithm. + * + * A RHO estimator has initialization, finalization, capacity, seeding and + * homography-estimation APIs that must be implemented. + */ + +struct RHO_HEST{ + /* This is a virtual base class; It should have a virtual destructor. */ + virtual ~RHO_HEST(){} + + /* External Interface Methods */ + + /** + * Initialization work. + * + * @return 0 if initialization is unsuccessful; non-zero otherwise. + */ + + virtual inline int initialize(void){return 1;} + + + /** + * Finalization work. + */ + + virtual inline void finalize(void){} + + /** + * Ensure that the estimator context's internal table for the non-randomness + * criterion is at least of the given size, and uses the given beta. The table + * should be larger than the maximum number of matches fed into the estimator. + * + * A value of N of 0 requests deallocation of the table. + * + * @param [in] N If 0, deallocate internal table. If > 0, ensure that the + * internal table is of at least this size, reallocating if + * necessary. + * @param [in] beta The beta-factor to use within the table. + * @return 0 if unsuccessful; non-zero otherwise. + */ + + virtual inline int ensureCapacity(unsigned N, double beta){ + (void)N; + (void)beta; + + return 1; + } + + + /** + * Generates a random double uniformly distributed in the range [0, 1). + * + * The default implementation uses the xorshift128+ algorithm from + * Sebastiano Vigna. Further scramblings of Marsaglia's xorshift generators. + * CoRR, abs/1402.6246, 2014. + * http://vigna.di.unimi.it/ftp/papers/xorshiftplus.pdf + * + * Source roughly as given in + * http://en.wikipedia.org/wiki/Xorshift#Xorshift.2B + */ + + virtual inline double fastRandom(void){ + uint64_t x = prng.s[0]; + uint64_t y = prng.s[1]; + x ^= x << 23; // a + x ^= x >> 17; // b + x ^= y ^ (y >> 26); // c + prng.s[0] = y; + prng.s[1] = x; + uint64_t s = x + y; + + return s * 5.421010862427522e-20;/* 2^-64 */ + } + + + /** + * Seeds the context's PRNG. + * + * @param [in] seed A 64-bit unsigned integer seed. + */ + + virtual inline void fastSeed(uint64_t seed){ + int i; + + prng.s[0] = seed; + prng.s[1] = ~seed;/* Guarantees one of the elements will be non-zero. */ + + /** + * Escape from zero-land (see xorshift128+ paper). Approximately 20 + * iterations required according to the graph. + */ + + for(i=0;i<20;i++){ + fastRandom(); + } + } + + + /** + * Estimates the homography using the given context, matches and parameters to + * PROSAC. + * + * @param [in] src The pointer to the source points of the matches. + * Cannot be NULL. + * @param [in] dst The pointer to the destination points of the matches. + * Cannot be NULL. + * @param [out] inl The pointer to the output mask of inlier matches. + * May be NULL. + * @param [in] N The number of matches. + * @param [in] maxD The maximum distance. + * @param [in] maxI The maximum number of PROSAC iterations. + * @param [in] rConvg The RANSAC convergence parameter. + * @param [in] cfd The required confidence in the solution. + * @param [in] minInl The minimum required number of inliers. + * @param [in] beta The beta-parameter for the non-randomness criterion. + * @param [in] flags A union of flags to control the estimation. + * @param [in] guessH An extrinsic guess at the solution H, or NULL if + * none provided. + * @param [out] finalH The final estimation of H, or the zero matrix if + * the minimum number of inliers was not met. + * Cannot be NULL. + * @return The number of inliers if the minimum number of + * inliers for acceptance was reached; 0 otherwise. + */ + + virtual unsigned rhoHest(const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* Works: 3.0 */ + unsigned maxI, /* Works: 2000 */ + unsigned rConvg, /* Works: 2000 */ + double cfd, /* Works: 0.995 */ + unsigned minInl, /* Minimum: 4 */ + double beta, /* Works: 0.35 */ + unsigned flags, /* Works: 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH) = 0; /* Final result. */ + + + + /* PRNG XORshift128+ */ + struct{ + uint64_t s[2]; /* PRNG state */ + } prng; +}; + + + +/** + * Generic C implementation of RHO algorithm. + */ + +struct RHO_HEST_REFC : RHO_HEST{ /** * Virtual Arguments. * @@ -163,11 +318,6 @@ struct RHO_HEST_REFC{ float* Jte; /* Jte vector */ } lm; - /* PRNG XORshift128+ */ - struct{ - uint64_t s[2]; /* PRNG state */ - } prng; - /* Memory Management */ struct{ cv::Mat perObj; @@ -188,9 +338,9 @@ struct RHO_HEST_REFC{ /* Methods to implement external interface */ inline int initialize(void); - inline int sacEnsureCapacity(unsigned N, double beta); inline void finalize(void); - unsigned rhoRefC(const float* src, /* Source points */ + inline int ensureCapacity(unsigned N, double beta); + unsigned rhoHest(const float* src, /* Source points */ const float* dst, /* Destination points */ char* inl, /* Inlier mask */ unsigned N, /* = src.length = dst.length = inl.length */ @@ -225,8 +375,6 @@ struct RHO_HEST_REFC{ inline void rndSmpl(unsigned sampleSize, unsigned* currentSample, unsigned dataSetSize); - inline double fastRandom(void); - inline void fastSeed(uint64_t seed); inline int isSampleDegenerate(void); inline void generateModel(void); inline int isModelDegenerate(void); @@ -298,15 +446,27 @@ static inline void sacSub8x1 (float* Hout, * @return A pointer to the context if successful; NULL if an error occured. */ -Ptr rhoRefCInit(void){ - Ptr p = Ptr(new RHO_HEST_REFC); +Ptr rhoInit(void){ + /* Select an optimized implementation of RHO here. */ +#if 1 + /** + * For now, only the generic C implementation is available. In the future, + * SSE2/AVX/AVX2/FMA/NEON versions may be added, and they will be selected + * depending on cv::checkHardwareSupport()'s return values. + */ + + Ptr p = Ptr(new RHO_HEST_REFC); +#endif + + /* Initialize it. */ if(p){ if(!p->initialize()){ - p = Ptr((RHO_HEST_REFC*)NULL); + p = Ptr((RHO_HEST*)NULL); } } + /* Return it. */ return p; } @@ -315,8 +475,8 @@ Ptr rhoRefCInit(void){ * External access to non-randomness table resize. */ -int rhoRefCEnsureCapacity(Ptr p, unsigned N, double beta){ - return p->sacEnsureCapacity(N, beta); +int rhoEnsureCapacity(Ptr p, unsigned N, double beta){ + return p->ensureCapacity(N, beta); } @@ -324,8 +484,8 @@ int rhoRefCEnsureCapacity(Ptr p, unsigned N, double beta){ * Seeds the internal PRNG with the given seed. */ -void rhoRefCSeed(Ptr p, unsigned long long seed){ - p->fastSeed((uint64_t)seed); +void rhoSeed(Ptr p, uint64_t seed){ + p->fastSeed(seed); } @@ -358,27 +518,37 @@ void rhoRefCSeed(Ptr p, unsigned long long seed){ * inliers for acceptance was reached; 0 otherwise. */ -unsigned rhoRefC(Ptr p, /* Homography estimation context. */ - const float* src, /* Source points */ - const float* dst, /* Destination points */ - char* inl, /* Inlier mask */ - unsigned N, /* = src.length = dst.length = inl.length */ - float maxD, /* Works: 3.0 */ - unsigned maxI, /* Works: 2000 */ - unsigned rConvg, /* Works: 2000 */ - double cfd, /* Works: 0.995 */ - unsigned minInl, /* Minimum: 4 */ - double beta, /* Works: 0.35 */ - unsigned flags, /* Works: 0 */ - const float* guessH, /* Extrinsic guess, NULL if none provided */ - float* finalH){ /* Final result. */ - return p->rhoRefC(src, dst, inl, N, maxD, maxI, rConvg, cfd, minInl, beta, +unsigned rhoHest(Ptr p, /* Homography estimation context. */ + const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* Works: 3.0 */ + unsigned maxI, /* Works: 2000 */ + unsigned rConvg, /* Works: 2000 */ + double cfd, /* Works: 0.995 */ + unsigned minInl, /* Minimum: 4 */ + double beta, /* Works: 0.35 */ + unsigned flags, /* Works: 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH){ /* Final result. */ + return p->rhoHest(src, dst, inl, N, maxD, maxI, rConvg, cfd, minInl, beta, flags, guessH, finalH); } + + + + + + + + +/*********************** RHO_HEST_REFC implementation **********************/ + /** * Constructor for RHO_HEST_REFC. * @@ -479,13 +649,13 @@ inline void RHO_HEST_REFC::finalize(void){ * internal table is of at least this size, reallocating if * necessary. * @param [in] beta The beta-factor to use within the table. - * @return 1 if successful; 0 if an error occured. + * @return 0 if unsuccessful; non-zero otherwise. * * Reads: nr.* * Writes: nr.* */ -inline int RHO_HEST_REFC::sacEnsureCapacity(unsigned N, double beta){ +inline int RHO_HEST_REFC::ensureCapacity(unsigned N, double beta){ if(N == 0){ /* Clear. */ nr.tbl.clear(); @@ -516,9 +686,9 @@ inline int RHO_HEST_REFC::sacEnsureCapacity(unsigned N, double beta){ * @param [in] src The pointer to the source points of the matches. * Must be aligned to 4 bytes. Cannot be NULL. * @param [in] dst The pointer to the destination points of the matches. - * Must be aligned to 16 bytes. Cannot be NULL. + * Must be aligned to 4 bytes. Cannot be NULL. * @param [out] inl The pointer to the output mask of inlier matches. - * Must be aligned to 16 bytes. May be NULL. + * Must be aligned to 4 bytes. May be NULL. * @param [in] N The number of matches. * @param [in] maxD The maximum distance. * @param [in] maxI The maximum number of PROSAC iterations. @@ -536,7 +706,7 @@ inline int RHO_HEST_REFC::sacEnsureCapacity(unsigned N, double beta){ * inliers for acceptance was reached; 0 otherwise. */ -unsigned RHO_HEST_REFC::rhoRefC(const float* src, /* Source points */ +unsigned RHO_HEST_REFC::rhoHest(const float* src, /* Source points */ const float* dst, /* Destination points */ char* inl, /* Inlier mask */ unsigned N, /* = src.length = dst.length = inl.length */ @@ -784,7 +954,7 @@ inline int RHO_HEST_REFC::initRun(void){ * substruct and the sanity-checked N and beta arguments from above. */ - if(isNREnabled() && !sacEnsureCapacity(arg.N, arg.beta)){ + if(isNREnabled() && !ensureCapacity(arg.N, arg.beta)){ return 0; } @@ -1061,53 +1231,6 @@ inline void RHO_HEST_REFC::rndSmpl(unsigned sampleSize, } } -/** - * Generates a random double uniformly distributed in the range [0, 1). - * - * Uses xorshift128+ algorithm from - * Sebastiano Vigna. Further scramblings of Marsaglia's xorshift generators. - * CoRR, abs/1402.6246, 2014. - * http://vigna.di.unimi.it/ftp/papers/xorshiftplus.pdf - * - * Source roughly as given in - * http://en.wikipedia.org/wiki/Xorshift#Xorshift.2B - */ - -inline double RHO_HEST_REFC::fastRandom(void){ - uint64_t x = prng.s[0]; - uint64_t y = prng.s[1]; - x ^= x << 23; // a - x ^= x >> 17; // b - x ^= y ^ (y >> 26); // c - prng.s[0] = y; - prng.s[1] = x; - uint64_t s = x + y; - - return s * 5.421010862427522e-20;/* 2^-64 */ -} - -/** - * Seeds the PRNG. - * - * The seed should not be zero, since the state must be initialized to non-zero. - */ - -inline void RHO_HEST_REFC::fastSeed(uint64_t seed){ - int i; - - prng.s[0] = seed; - prng.s[1] = ~seed;/* Guarantees one of the elements will be non-zero. */ - - /** - * Escape from zero-land (see xorshift128+ paper). Approximately 20 - * iterations required according to the graph. - */ - - for(i=0;i<20;i++){ - fastRandom(); - } -} - /** * Checks whether the *sample* is degenerate prior to model generation. * - First, the extremely cheap numerical degeneracy test is run, which weeds diff --git a/modules/calib3d/src/rhorefc.h b/modules/calib3d/src/rho.h similarity index 88% rename from modules/calib3d/src/rhorefc.h rename to modules/calib3d/src/rho.h index bcd9fba1e..082a41603 100644 --- a/modules/calib3d/src/rhorefc.h +++ b/modules/calib3d/src/rho.h @@ -44,13 +44,14 @@ */ /* Include Guards */ -#ifndef __OPENCV_RHOREFC_H__ -#define __OPENCV_RHOREFC_H__ +#ifndef __OPENCV_RHO_H__ +#define __OPENCV_RHO_H__ /* Includes */ #include +#include @@ -84,8 +85,8 @@ namespace cv{ * Homography Estimation context. */ -struct RHO_HEST_REFC; -typedef struct RHO_HEST_REFC RHO_HEST_REFC; +struct RHO_HEST; +typedef struct RHO_HEST RHO_HEST; /* Functions */ @@ -97,7 +98,7 @@ typedef struct RHO_HEST_REFC RHO_HEST_REFC; * @return A pointer to the context if successful; NULL if an error occured. */ -Ptr rhoRefCInit(void); +Ptr rhoInit(void); /** @@ -112,10 +113,10 @@ Ptr rhoRefCInit(void); * internal table is of at least this size, reallocating if * necessary. * @param [in] beta The beta-factor to use within the table. - * @return 0 if successful; non-zero if an error occured. + * @return 0 if unsuccessful; non-zero otherwise. */ -int rhoRefCEnsureCapacity(Ptr p, unsigned N, double beta); +int rhoEnsureCapacity(Ptr p, unsigned N, double beta); @@ -130,7 +131,7 @@ int rhoRefCEnsureCapacity(Ptr p, unsigned N, double beta); * @param [in] seed The 64-bit integer seed. */ -void rhoRefCSeed(Ptr p, unsigned long long seed); +void rhoSeed(Ptr p, uint64_t seed); /** @@ -240,20 +241,20 @@ void rhoRefCSeed(Ptr p, unsigned long long seed); * inliers for acceptance was reached; 0 otherwise. */ -unsigned rhoRefC(Ptr p, /* Homography estimation context. */ - const float* src, /* Source points */ - const float* dst, /* Destination points */ - char* inl, /* Inlier mask */ - unsigned N, /* = src.length = dst.length = inl.length */ - float maxD, /* 3.0 */ - unsigned maxI, /* 2000 */ - unsigned rConvg, /* 2000 */ - double cfd, /* 0.995 */ - unsigned minInl, /* 4 */ - double beta, /* 0.35 */ - unsigned flags, /* 0 */ - const float* guessH, /* Extrinsic guess, NULL if none provided */ - float* finalH); /* Final result. */ +unsigned rhoHest(Ptr p, /* Homography estimation context. */ + const float* src, /* Source points */ + const float* dst, /* Destination points */ + char* inl, /* Inlier mask */ + unsigned N, /* = src.length = dst.length = inl.length */ + float maxD, /* 3.0 */ + unsigned maxI, /* 2000 */ + unsigned rConvg, /* 2000 */ + double cfd, /* 0.995 */ + unsigned minInl, /* 4 */ + double beta, /* 0.35 */ + unsigned flags, /* 0 */ + const float* guessH, /* Extrinsic guess, NULL if none provided */ + float* finalH); /* Final result. */ From 27fd810b6fdf7b86d2445acf72fac182944ba9cf Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Wed, 4 Mar 2015 02:09:59 -0500 Subject: [PATCH 33/39] Silenced build warnings on Windows. --- modules/calib3d/src/rho.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/calib3d/src/rho.cpp b/modules/calib3d/src/rho.cpp index 2289366bc..fdd81c37b 100644 --- a/modules/calib3d/src/rho.cpp +++ b/modules/calib3d/src/rho.cpp @@ -813,7 +813,7 @@ inline void RHO_HEST_REFC::allocatePerObj(void){ #undef MK_OFFSET /* Allocate dynamic memory managed by cv::Mat */ - mem.perObj.create(1, total + MEM_ALIGN, CV_8UC1); + mem.perObj.create(1, (int)(total + MEM_ALIGN), CV_8UC1); /* Extract aligned pointer */ unsigned char* ptr = alignPtr(mem.perObj.data, MEM_ALIGN); @@ -853,7 +853,7 @@ inline void RHO_HEST_REFC::allocatePerRun(void){ #undef MK_OFFSET /* Allocate dynamic memory managed by cv::Mat */ - mem.perRun.create(1, total + MEM_ALIGN, CV_8UC1); + mem.perRun.create(1, (int)(total + MEM_ALIGN), CV_8UC1); /* Extract aligned pointer */ unsigned char* ptr = alignPtr(mem.perRun.data, MEM_ALIGN); From 52e67c1a292832d919be1adbb37e3497b5b65f1d Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Wed, 4 Mar 2015 05:04:52 -0500 Subject: [PATCH 34/39] Whitespace & Doc fixes on lower half of rho.cpp. Spaced methods & functions more consistently, and started documenting which members does each method access directly or through its callers within RHO_HEST_REFC. --- modules/calib3d/src/rho.cpp | 75 +++++++++++++++++++++++++++++++++++-- 1 file changed, 71 insertions(+), 4 deletions(-) diff --git a/modules/calib3d/src/rho.cpp b/modules/calib3d/src/rho.cpp index fdd81c37b..b690f541c 100644 --- a/modules/calib3d/src/rho.cpp +++ b/modules/calib3d/src/rho.cpp @@ -1514,10 +1514,12 @@ static inline double sacDesignSPRTTest(double delta, double epsilon, double t_M, * Design the SPRT test. Shorthand for * A = sprt(delta, epsilon, t_M, m_S); * - * Idempotent, reentrant, thread-safe. + * Idempotent. * - * Reads: eval.delta, eval.epsilon, eval.t_M, eval.m_S - * Writes: eval.A, eval.lambdaAccept, eval.lambdaReject + * Reads (direct): eval.delta, eval.epsilon, eval.t_M, eval.m_S + * Reads (callees): None. + * Writes (direct): eval.A, eval.lambdaReject, eval.lambdaAccept. + * Writes (callees): None. */ inline void RHO_HEST_REFC::designSPRTTest(void){ @@ -1528,6 +1530,14 @@ inline void RHO_HEST_REFC::designSPRTTest(void){ /** * Return whether the current model is the best model so far. + * + * @return Non-zero if this is the model with the most inliers seen so far; + * 0 otherwise. + * + * Reads (direct): curr.numInl, best.numInl + * Reads (callees): None. + * Writes (direct): None. + * Writes (callees): None. */ inline int RHO_HEST_REFC::isBestModel(void){ @@ -1538,6 +1548,14 @@ inline int RHO_HEST_REFC::isBestModel(void){ * Returns whether the current-best model is good enough to be an * acceptable best model, by checking whether it meets the minimum * number of inliers. + * + * @return Non-zero if the current model is "good enough" to save; + * 0 otherwise. + * + * Reads (direct): best.numInl, arg.minInl + * Reads (callees): None. + * Writes (direct): None. + * Writes (callees): None. */ inline int RHO_HEST_REFC::isBestModelGoodEnough(void){ @@ -1547,6 +1565,13 @@ inline int RHO_HEST_REFC::isBestModelGoodEnough(void){ /** * Make current model new best model by swapping the homography, inlier mask * and count of inliers between the current and best models. + * + * Reads (direct): curr.H, curr.inl, curr.numInl, + * best.H, best.inl, best.numInl + * Reads (callees): None. + * Writes (direct): curr.H, curr.inl, curr.numInl, + * best.H, best.inl, best.numInl + * Writes (callees): None. */ inline void RHO_HEST_REFC::saveBestModel(void){ @@ -1586,6 +1611,12 @@ static inline void sacInitNonRand(double beta, /** * Optimize the stopping criterion to account for the non-randomness criterion * of PROSAC. + * + * Reads (direct): arg.N, best.numInl, nr.tbl, arg.inl, ctrl.phMax, + * ctrl.phNumInl, arg.cfd, arg.maxI + * Reads (callees): None. + * Writes (direct): arg.maxI, ctrl.phMax, ctrl.phNumInl + * Writes (callees): None. */ inline void RHO_HEST_REFC::nStarOptimize(void){ @@ -1603,7 +1634,7 @@ inline void RHO_HEST_REFC::nStarOptimize(void){ best_n = test_n; bestNumInl = testNumInl; } - testNumInl -= !!arg.inl[test_n-1]; + testNumInl -= !!arg.inl[test_n-1];/* FIXME: Probable bug! */ } if(bestNumInl*ctrl.phMax > ctrl.phNumInl*best_n){ @@ -1618,6 +1649,11 @@ inline void RHO_HEST_REFC::nStarOptimize(void){ /** * Classic RANSAC iteration bound based on largest # of inliers. + * + * Reads (direct): arg.maxI, arg.cfd, best.numInl, arg.N + * Reads (callees): None. + * Writes (direct): arg.maxI + * Writes (callees): None. */ inline void RHO_HEST_REFC::updateBounds(void){ @@ -1629,6 +1665,11 @@ inline void RHO_HEST_REFC::updateBounds(void){ /** * Ouput the best model so far to the output argument. + * + * Reads (direct): arg.finalH, best.H, arg.inl, best.inl, arg.N + * Reads (callees): arg.finalH, arg.inl, arg.N + * Writes (direct): arg.finalH, arg.inl + * Writes (callees): arg.finalH, arg.inl */ inline void RHO_HEST_REFC::outputModel(void){ @@ -1644,6 +1685,11 @@ inline void RHO_HEST_REFC::outputModel(void){ /** * Ouput a zeroed H to the output argument. + * + * Reads (direct): arg.finalH, arg.inl, arg.N + * Reads (callees): None. + * Writes (direct): arg.finalH, arg.inl + * Writes (callees): None. */ inline void RHO_HEST_REFC::outputZeroH(void){ @@ -1974,10 +2020,18 @@ static void hFuncRefC(float* packedPoints,/* Source (four x,y float coordinates) H[8]=1.0; } + /** * Returns whether refinement is possible. * * NB This is separate from whether it is *enabled*. + * + * @return 0 if refinement isn't possible, non-zero otherwise. + * + * Reads (direct): best.numInl + * Reads (callees): None. + * Writes (direct): None. + * Writes (callees): None. */ inline int RHO_HEST_REFC::canRefine(void){ @@ -1989,8 +2043,15 @@ inline int RHO_HEST_REFC::canRefine(void){ return best.numInl > (unsigned)SMPL_SIZE; } + /** * Refines the best-so-far homography (p->best.H). + * + * Reads (direct): best.H, arg.src, arg.dst, best.inl, arg.N, lm.JtJ, + * lm.Jte, lm.tmp1 + * Reads (callees): None. + * Writes (direct): best.H, lm.JtJ, lm.Jte, lm.tmp1 + * Writes (callees): None. */ inline void RHO_HEST_REFC::refine(void){ @@ -2070,6 +2131,7 @@ inline void RHO_HEST_REFC::refine(void){ } } + /** * Compute directly the JtJ, Jte and sum-of-squared-error for a given * homography and set of inliers. @@ -2224,6 +2286,7 @@ static inline void sacCalcJacobianErrors(const float* H, if(Sp){*Sp = S;} } + /** * Compute the Levenberg-Marquardt "gain" obtained by the given step dH. * @@ -2257,6 +2320,7 @@ static inline float sacLMGain(const float* dH, return fabs(dL) < FLT_EPSILON ? dS : dS / dL; } + /** * Cholesky decomposition on 8x8 real positive-definite matrix defined by its * lower-triangular half. Outputs L, the lower triangular part of the @@ -2307,6 +2371,7 @@ static inline int sacChol8x8Damped(const float (*A)[8], return 1; } + /** * Invert lower-triangular 8x8 matrix L into lower-triangular matrix M. * @@ -2513,6 +2578,7 @@ static inline void sacTRInv8x8(const float (*L)[8], */ } + /** * Solves dH = inv(JtJ) Jte. The argument lower-triangular matrix is the * inverse of L as produced by the Cholesky decomposition LL^T of the matrix @@ -2556,6 +2622,7 @@ static inline void sacTRISolve8x8(const float (*L)[8], dH[7] = L[7][7]*t[7]; } + /** * Subtract dH from H. */ From fcdbacdbb0625380ab58873eb4dc085bde9a1489 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Fri, 6 Mar 2015 09:15:00 -0500 Subject: [PATCH 35/39] Corrected initialization of smart pointer. --- modules/calib3d/src/rho.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/calib3d/src/rho.cpp b/modules/calib3d/src/rho.cpp index b690f541c..832b921c0 100644 --- a/modules/calib3d/src/rho.cpp +++ b/modules/calib3d/src/rho.cpp @@ -462,7 +462,7 @@ Ptr rhoInit(void){ /* Initialize it. */ if(p){ if(!p->initialize()){ - p = Ptr((RHO_HEST*)NULL); + p.release(); } } From 2113636d29ab0b87676832ed634370d0b558ffd5 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Fri, 6 Mar 2015 09:24:45 -0500 Subject: [PATCH 36/39] Made seed a constant. --- modules/calib3d/src/rho.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/calib3d/src/rho.cpp b/modules/calib3d/src/rho.cpp index 832b921c0..bb41e0630 100644 --- a/modules/calib3d/src/rho.cpp +++ b/modules/calib3d/src/rho.cpp @@ -609,7 +609,7 @@ inline int RHO_HEST_REFC::initialize(void){ nr.beta = 0.0; - fastSeed((unsigned)cv::theRNG()); + fastSeed(~0); int areAllAllocsSuccessful = !mem.perObj.empty(); From 9c432f4f75eefe7c5fd39dc0689a2398ce43e9b5 Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Fri, 6 Mar 2015 12:16:38 -0500 Subject: [PATCH 37/39] Silence Windows warnings. --- modules/calib3d/src/rho.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/calib3d/src/rho.cpp b/modules/calib3d/src/rho.cpp index bb41e0630..1de801720 100644 --- a/modules/calib3d/src/rho.cpp +++ b/modules/calib3d/src/rho.cpp @@ -609,7 +609,7 @@ inline int RHO_HEST_REFC::initialize(void){ nr.beta = 0.0; - fastSeed(~0); + fastSeed((uint64_t)~0); int areAllAllocsSuccessful = !mem.perObj.empty(); From 7e3cc4473884984131d7b8a37e96c6496bba9b7a Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Sat, 14 Mar 2015 12:41:25 -0400 Subject: [PATCH 38/39] More docs on variable accesses. Listed accesses for more functions. --- modules/calib3d/src/rho.cpp | 58 ++++++++++++++++++++++++++++--------- 1 file changed, 44 insertions(+), 14 deletions(-) diff --git a/modules/calib3d/src/rho.cpp b/modules/calib3d/src/rho.cpp index 1de801720..8ac22df33 100644 --- a/modules/calib3d/src/rho.cpp +++ b/modules/calib3d/src/rho.cpp @@ -1124,8 +1124,10 @@ inline int RHO_HEST_REFC::isFinalRefineEnabled(void){ * Computes whether the end of the current PROSAC phase has been reached. At * PROSAC phase phNum, only matches [0, phNum) are sampled from. * - * Accesses: - * Read: i, phEndI, phNum, phMax. + * Reads (direct): ctrl.i, ctrl.phEndI, ctrl.phNum, ctrl.phMax + * Reads (callees): None. + * Writes (direct): None. + * Writes (callees): None. */ inline int RHO_HEST_REFC::PROSACPhaseEndReached(void){ @@ -1138,9 +1140,10 @@ inline int RHO_HEST_REFC::PROSACPhaseEndReached(void){ * * Not idempotent. * - * Accesses: - * Read: phNum, phEndFpI, phEndI - * Write: phNum, phEndFpI, phEndI + * Reads (direct): ctrl.phNum, ctrl.phEndFpI, ctrl.phEndI + * Reads (callees): None. + * Writes (direct): ctrl.phNum, ctrl.phEndFpI, ctrl.phEndI + * Writes (callees): None. */ inline void RHO_HEST_REFC::PROSACGoToNextPhase(void){ @@ -1158,6 +1161,11 @@ inline void RHO_HEST_REFC::PROSACGoToNextPhase(void){ * phNum matches. * - Otherwise, select match phNum-1 and select randomly the 3 others out of * the first phNum-1 matches. + * + * Reads (direct): ctrl.i, ctrl.phEndI, ctrl.phNum + * Reads (callees): prng.s + * Writes (direct): ctrl.smpl + * Writes (callees): prng.s */ inline void RHO_HEST_REFC::getPROSACSample(void){ @@ -1172,6 +1180,11 @@ inline void RHO_HEST_REFC::getPROSACSample(void){ /** * Choose, without repetition, sampleSize integers in the range [0, numDataPoints). + * + * Reads (direct): None. + * Reads (callees): prng.s + * Writes (direct): None. + * Writes (callees): prng.s */ inline void RHO_HEST_REFC::rndSmpl(unsigned sampleSize, @@ -1237,6 +1250,11 @@ inline void RHO_HEST_REFC::rndSmpl(unsigned sampleSize, * out bad samples to the optimized GE implementation. * - Second, the geometrical degeneracy test is run, which weeds out most other * bad samples. + * + * Reads (direct): ctrl.smpl, arg.src, arg.dst + * Reads (callees): None. + * Writes (direct): curr.pkdPts + * Writes (callees): None. */ inline int RHO_HEST_REFC::isSampleDegenerate(void){ @@ -1330,6 +1348,11 @@ inline int RHO_HEST_REFC::isSampleDegenerate(void){ /** * Compute homography of matches in gathered, packed sample and output the * current homography. + * + * Reads (direct): None. + * Reads (callees): curr.pkdPts + * Writes (direct): None. + * Writes (callees): curr.H */ inline void RHO_HEST_REFC::generateModel(void){ @@ -1340,6 +1363,11 @@ inline void RHO_HEST_REFC::generateModel(void){ * Checks whether the model is itself degenerate. * - One test: All elements of the homography are added, and if the result is * NaN the homography is rejected. + * + * Reads (direct): curr.H + * Reads (callees): None. + * Writes (direct): None. + * Writes (callees): None. */ inline int RHO_HEST_REFC::isModelDegenerate(void){ @@ -1359,8 +1387,13 @@ inline int RHO_HEST_REFC::isModelDegenerate(void){ /** * Evaluates the current model using SPRT for early exiting. * - * Reads: arg.maxD, arg.src, arg.dst, curr.H, eval.* - * Writes: eval.*, curr.inl, curr.numInl + * Reads (direct): arg.maxD, arg.src, arg.dst, arg.N, curr.inl, curr.H, + * ctrl.numModels, eval.Ntestedtotal, eval.lambdaAccept, + * eval.lambdaReject, eval.A + * Reads (callees): None. + * Writes (direct): ctrl.numModels, curr.numInl, eval.Ntested, eval.good, + * eval.Ntestedtotal + * Writes (callees): None. */ inline void RHO_HEST_REFC::evaluateModelSPRT(void){ @@ -1423,13 +1456,10 @@ inline void RHO_HEST_REFC::evaluateModelSPRT(void){ * Update either the delta or epsilon SPRT parameters, depending on the events * that transpired in the previous evaluation. * - * If a "good" model that is also the best was encountered, update epsilon, - * since - * - * Reads: eval.good, eval.delta, eval.epsilon, eval.t_M, eval.m_S, - * curr.numInl, best.numInl - * Writes: eval.epsilon, eval.delta, eval.A, eval.lambdaAccept, - * eval.lambdaReject + * Reads (direct): eval.good, curr.numInl, arg.N, eval.Ntested, eval.delta + * Reads (callees): eval.delta, eval.epsilon, eval.t_M, eval.m_S + * Writes (direct): eval.epsilon, eval.delta + * Writes (callees): eval.A, eval.lambdaReject, eval.lambdaAccept */ inline void RHO_HEST_REFC::updateSPRT(void){ From 6d27d488bf98bbf9698787f5aea33e9f9747026e Mon Sep 17 00:00:00 2001 From: Olexa Bilaniuk Date: Wed, 18 Mar 2015 02:21:16 -0400 Subject: [PATCH 39/39] Bugfix in n* optimization. Similar to the problem in LevMarq, arg.inl was being used instead of best.inl. This opened us up to a potential segfault. --- modules/calib3d/src/rho.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/calib3d/src/rho.cpp b/modules/calib3d/src/rho.cpp index 8ac22df33..81d641c3f 100644 --- a/modules/calib3d/src/rho.cpp +++ b/modules/calib3d/src/rho.cpp @@ -1664,7 +1664,7 @@ inline void RHO_HEST_REFC::nStarOptimize(void){ best_n = test_n; bestNumInl = testNumInl; } - testNumInl -= !!arg.inl[test_n-1];/* FIXME: Probable bug! */ + testNumInl -= !!best.inl[test_n-1]; } if(bestNumInl*ctrl.phMax > ctrl.phNumInl*best_n){