///////////////////////////////////////////////////////////////////////////////// //// //// Expert drivers for sparse bundle adjustment based on the //// Levenberg - Marquardt minimization algorithm //// Copyright (C) 2004 Manolis Lourakis (lourakis@ics.forth.gr) //// Institute of Computer Science, Foundation for Research & Technology - Hellas //// Heraklion, Crete, Greece. //// //// This program is free software; you can redistribute it and/or modify //// it under the terms of the GNU General Public License as published by //// the Free Software Foundation; either version 2 of the License, or //// (at your option) any later version. //// //// This program is distributed in the hope that it will be useful, //// but WITHOUT ANY WARRANTY; without even the implied warranty of //// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the //// GNU General Public License for more details. //// /////////////////////////////////////////////////////////////////////////////////// #include #include #include #include #include #include "sba.h" #include "sba_chkjac.h" #define SBA_EPSILON 1E-12 #define SBA_EPSILON_SQ ( (SBA_EPSILON)*(SBA_EPSILON) ) #define SBA_ONE_THIRD 0.3333333334 /* 1.0/3.0 */ #define emalloc(sz) emalloc_(__FILE__, __LINE__, sz) #define FABS(x) (((x)>=0)? (x) : -(x)) #define ROW_MAJOR 0 #define COLUMN_MAJOR 1 #define MAT_STORAGE COLUMN_MAJOR /* inline */ #ifdef _MSC_VER #define inline __inline //MSVC #elif !defined(__GNUC__) #define inline //other than MSVC, GCC: define empty #endif /* contains information necessary for computing a finite difference approximation to a jacobian, * e.g. function to differentiate, problem dimensions and pointers to working memory buffers */ struct fdj_data_x_ { void (*func)(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *hx, void *adata); /* function to differentiate */ int cnp, pnp, mnp; /* parameter numbers */ int *func_rcidxs, *func_rcsubs; /* working memory for func invocations. * Notice that this has to be different * than the working memory used for * evaluating the jacobian! */ double *hx, *hxx; /* memory to save results in */ void *adata; }; /* auxiliary memory allocation routine with error checking */ inline static void *emalloc_(char *file, int line, size_t sz) { void *ptr; ptr=(void *)malloc(sz); if(ptr==NULL){ fprintf(stderr, "memory allocation request for %u bytes failed in file %s, line %d, exiting", sz, file, line); exit(1); } return ptr; } /* auxiliary routine for clearing an array of doubles */ inline static void _dblzero(register double *arr, register int count) { while(--count>=0) *arr++=0.0; } /* auxiliary routine for computing the mean reprojection error; used for debugging */ static double sba_mean_repr_error(int n, int mnp, double *x, double *hx, struct sba_crsm *idxij, int *rcidxs, int *rcsubs) { register int i, j; int nnz, nprojs; double *ptr1, *ptr2; double err; for(i=nprojs=0, err=0.0; ival[rcidxs[j]]*mnp; ptr2=hx + idxij->val[rcidxs[j]]*mnp; err+=sqrt((ptr1[0]-ptr2[0])*(ptr1[0]-ptr2[0]) + (ptr1[1]-ptr2[1])*(ptr1[1]-ptr2[1])); } } return err/((double)(nprojs)); } /* print the solution in p using sba's text format. If cnp/pnp==0 only points/cameras are printed */ static void sba_print_sol(int n, int m, double *p, int cnp, int pnp, double *x, int mnp, struct sba_crsm *idxij, int *rcidxs, int *rcsubs) { register int i, j, ii; int nnz; double *ptr; if(cnp){ /* print camera parameters */ for(j=0; jval[rcidxs[j]]*mnp; printf("%d ", rcsubs[j]); for(ii=0; iifunc; cnp=fdjd->cnp; pnp=fdjd->pnp; mnp=fdjd->mnp; hx=fdjd->hx; hxx=fdjd->hxx; adata=fdjd->adata; n=idxij->nr; m=idxij->nc; pa=p; pb=p+m*cnp; Asz=mnp*cnp; Bsz=mnp*pnp; jaca=jac; jacb=jac+idxij->nnz*Asz; nm=(n>=m)? n : m; // max(n, m); tmpd=(double *)emalloc(nm*sizeof(double)); (*func)(p, idxij, fdjd->func_rcidxs, fdjd->func_rcsubs, hx, adata); // evaluate supplied function on current solution if(cnp){ // is motion varying? /* compute A_ij */ for(jj=0; jjfunc_rcidxs, fdjd->func_rcsubs, hxx, adata); for(j=0; jval[rcidxs[i]]; phx=hx + idx*mnp; // set phx to point to hx_ij phxx=hxx + idx*mnp; // set phxx to point to hxx_ij pAB=jaca + idx*Asz; // set pAB to point to A_ij for(ii=0; iifunc_rcidxs, fdjd->func_rcsubs, hxx, adata); for(i=0; ival[rcidxs[j]]; phx=hx + idx*mnp; // set phx to point to hx_ij phxx=hxx + idx*mnp; // set phxx to point to hxx_ij pAB=jacb + idx*Bsz; // set pAB to point to B_ij for(ii=0; ii=m)? n:m, /* max. of (n, m) */ *rcidxs, /* work array for the indexes corresponding to the nonzero elements of a single row or column in a sparse matrix, size max(n, m) */ *rcsubs; /* work array for the subscripts of nonzero elements in a single row or column of a sparse matrix, size max(n, m) */ /* The following variables are needed by the LM algorithm */ register int itno; /* iteration counter */ int issolved; /* temporary work arrays that are dynamically allocated */ double *hx, /* \hat{x}_i, max. size m*n*mnp */ *diagUV, /* diagonals of U_j, V_i, size m*cnp + n*pnp */ *pdp; /* p + dp, size m*cnp + n*pnp */ double *diagU, *diagV; /* pointers into diagUV */ register double mu, /* damping constant */ tmp; /* mainly used in matrix & vector multiplications */ double p_eL2, eab_inf, pdp_eL2; /* ||e(p)||_2, ||J^T e||_inf, ||e(p+dp)||_2 */ double p_L2, dp_L2=DBL_MAX, dF, dL; double tau=FABS(opts[0]), eps1=FABS(opts[1]), eps2=FABS(opts[2]), eps2_sq=opts[2]*opts[2], eps3_sq=opts[3]*opts[3]; double init_p_eL2; int nu=2, nu2, stop, nfev, njev=0, nlss=0; int nobs, nvars; const int mmcon=m-mcon; struct fdj_data_x_ fdj_data; void *jac_adata; /* Initialization */ /* block sizes */ Asz=mnp * cnp; Bsz=mnp * pnp; Usz=cnp * cnp; Vsz=pnp * pnp; Wsz=cnp * pnp; Ysz=cnp * pnp; esz=mnp; easz=cnp; ebsz=pnp; YWtsz=cnp * cnp; Wtdasz=pnp; Sblsz=cnp * cnp; Sdim=mmcon * cnp; /* count total number of visible image points */ for(i=nvis=0, jj=n*m; itmp) tmp=diagUV[i]; /* find max diagonal element */ mu=tau*tmp; } /* determine increment using adaptive damping */ while(1){ /* augment U, V */ for(j=mcon; j=mcon /* compute \sum_i Y_ij W_ik^T in YWt */ /* Recall that Y_ij is cnp x pnp and W_ik is cnp x pnp */ _dblzero(YWt, YWtsz); /* clear YWt */ for(i=0; ijj) continue; /* W_ik == 0 */ /* set ptr2 to point to W_ik */ l=sba_crsm_elmidx(&idxij, rcsubs[i], k); if(l==-1) continue; /* W_ik == 0 */ ptr2=W + idxij.val[l]*Wsz; /* set ptr1 to point to Y_ij, actual row number in rcsubs[i] */ ptr1=Y + idxij.val[rcidxs[i]]*Ysz; for(ii=0; ii1){ /* count the nonzeros in S */ for(i=ii=0; i=(p_L2+eps2)/SBA_EPSILON_SQ){ /* almost singular */ //if(dp_L2>=(p_L2+eps2)/SBA_EPSILON){ /* almost singular */ stop=4; break; } (*func)(pdp, &idxij, rcidxs, rcsubs, hx, adata); ++nfev; /* evaluate function at p + dp */ if(verbose>1) printf("mean reprojection error %g\n", sba_mean_repr_error(n, mnp, x, hx, &idxij, rcidxs, rcsubs)); for(i=0, pdp_eL2=0.0; i1) printf("\ndamping term %8g, gain ratio %8g, errors %8g / %8g = %g\n", mu, dL!=0.0? dF/dL : dF/DBL_EPSILON, p_eL2/nvis, pdp_eL2/nvis, p_eL2/pdp_eL2); if(dL>0.0 && dF>0.0){ /* reduction in error, increment is accepted */ tmp=(2.0*dF/dL-1.0); tmp=1.0-tmp*tmp*tmp; mu=mu*( (tmp>=SBA_ONE_THIRD)? tmp : SBA_ONE_THIRD ); nu=2; for(i=0; i=itmax) stop=3; /* restore U, V diagonal entries */ for(j=mcon; j=m)? n:m, /* max. of (n, m) */ *rcidxs, /* work array for the indexes corresponding to the nonzero elements of a single row or column in a sparse matrix, size max(n, m) */ *rcsubs; /* work array for the subscripts of nonzero elements in a single row or column of a sparse matrix, size max(n, m) */ /* The following variables are needed by the LM algorithm */ register int itno; /* iteration counter */ int nsolved; /* temporary work arrays that are dynamically allocated */ double *hx, /* \hat{x}_i, max. size m*n*mnp */ *diagU, /* diagonals of U_j, size m*cnp */ *pdp; /* p + dp, size m*cnp */ register double mu, /* damping constant */ tmp; /* mainly used in matrix & vector multiplications */ double p_eL2, ea_inf, pdp_eL2; /* ||e(p)||_2, ||J^T e||_inf, ||e(p+dp)||_2 */ double p_L2, dp_L2=DBL_MAX, dF, dL; double tau=FABS(opts[0]), eps1=FABS(opts[1]), eps2=FABS(opts[2]), eps2_sq=opts[2]*opts[2], eps3_sq=opts[3]*opts[3]; double init_p_eL2; int nu=2, nu2, stop, nfev, njev=0, nlss=0; int nobs, nvars; struct fdj_data_x_ fdj_data; void *jac_adata; /* Initialization */ /* block sizes */ Asz=mnp * cnp; Usz=cnp * cnp; esz=mnp; easz=cnp; /* count total number of visible image points */ for(i=nvis=0, jj=n*m; itmp) tmp=diagU[i]; /* find max diagonal element */ mu=tau*tmp; } /* determine increment using adaptive damping */ while(1){ /* augment U */ for(j=mcon; j 0); ++nlss; } if(nsolved==m){ /* parameter vector updates are now in dp */ /* compute p's new estimate and ||dp||^2 */ for(i=0, dp_L2=0.0; i=(p_L2+eps2)/SBA_EPSILON_SQ){ /* almost singular */ //if(dp_L2>=(p_L2+eps2)/SBA_EPSILON){ /* almost singular */ stop=4; break; } (*func)(pdp, &idxij, rcidxs, rcsubs, hx, adata); ++nfev; /* evaluate function at p + dp */ if(verbose>1) printf("mean reprojection error %g\n", sba_mean_repr_error(n, mnp, x, hx, &idxij, rcidxs, rcsubs)); for(i=0, pdp_eL2=0.0; i1) printf("\ndamping term %8g, gain ratio %8g, errors %8g / %8g = %g\n", mu, dL!=0.0? dF/dL : dF/DBL_EPSILON, p_eL2/nvis, pdp_eL2/nvis, p_eL2/pdp_eL2); if(dL>0.0 && dF>0.0){ /* reduction in error, increment is accepted */ tmp=(2.0*dF/dL-1.0); tmp=1.0-tmp*tmp*tmp; mu=mu*( (tmp>=SBA_ONE_THIRD)? tmp : SBA_ONE_THIRD ); nu=2; for(i=0; i=itmax) stop=3; /* restore U diagonal entries */ for(j=mcon; j=m)? n:m, /* max. of (n, m) */ *rcidxs, /* work array for the indexes corresponding to the nonzero elements of a single row or column in a sparse matrix, size max(n, m) */ *rcsubs; /* work array for the subscripts of nonzero elements in a single row or column of a sparse matrix, size max(n, m) */ /* The following variables are needed by the LM algorithm */ register int itno; /* iteration counter */ int nsolved; /* temporary work arrays that are dynamically allocated */ double *hx, /* \hat{x}_i, max. size m*n*mnp */ *diagV, /* diagonals of V_i, size n*pnp */ *pdp; /* p + dp, size n*pnp */ register double mu, /* damping constant */ tmp; /* mainly used in matrix & vector multiplications */ double p_eL2, eb_inf, pdp_eL2; /* ||e(p)||_2, ||J^T e||_inf, ||e(p+dp)||_2 */ double p_L2, dp_L2=DBL_MAX, dF, dL; double tau=FABS(opts[0]), eps1=FABS(opts[1]), eps2=FABS(opts[2]), eps2_sq=opts[2]*opts[2], eps3_sq=opts[3]*opts[3]; double init_p_eL2; int nu=2, nu2, stop, nfev, njev=0, nlss=0; int nobs, nvars; struct fdj_data_x_ fdj_data; void *jac_adata; /* Initialization */ /* block sizes */ Bsz=mnp * pnp; Vsz=pnp * pnp; esz=mnp; ebsz=pnp; /* count total number of visible image points */ for(i=nvis=0, jj=n*m; itmp) tmp=diagV[i]; /* find max diagonal element */ mu=tau*tmp; } /* determine increment using adaptive damping */ while(1){ /* augment V */ for(i=0; i 0); ++nlss; } if(nsolved==n){ /* parameter vector updates are now in dp */ /* compute p's new estimate and ||dp||^2 */ for(i=0, dp_L2=0.0; i=(p_L2+eps2)/SBA_EPSILON_SQ){ /* almost singular */ //if(dp_L2>=(p_L2+eps2)/SBA_EPSILON){ /* almost singular */ stop=4; break; } (*func)(pdp, &idxij, rcidxs, rcsubs, hx, adata); ++nfev; /* evaluate function at p + dp */ if(verbose>1) printf("mean reprojection error %g\n", sba_mean_repr_error(n, mnp, x, hx, &idxij, rcidxs, rcsubs)); for(i=0, pdp_eL2=0.0; i1) printf("\ndamping term %8g, gain ratio %8g, errors %8g / %8g = %g\n", mu, dL!=0.0? dF/dL : dF/DBL_EPSILON, p_eL2/nvis, pdp_eL2/nvis, p_eL2/pdp_eL2); if(dL>0.0 && dF>0.0){ /* reduction in error, increment is accepted */ tmp=(2.0*dF/dL-1.0); tmp=1.0-tmp*tmp*tmp; mu=mu*( (tmp>=SBA_ONE_THIRD)? tmp : SBA_ONE_THIRD ); nu=2; for(i=0; i=itmax) stop=3; /* restore V diagonal entries */ for(i=0; i