fixing docstring

release/4.3a0
Ayush Baid 2021-04-26 20:55:25 -04:00
parent b0fb6a3908
commit bd0838c0c9
1 changed files with 4 additions and 8 deletions

View File

@ -341,15 +341,14 @@ class EssentialMatrixFactor4
<< std::endl; << std::endl;
} }
/// vector of errors returns 1D vector
/** /**
* @brief Calculate the algebraic epipolar error p' (K^-1)' E K p. * @brief Calculate the algebraic epipolar error p' (K^-1)' E K p.
* *
* @param E essential matrix for key keyE * @param E essential matrix for key keyE
* @param K calibration (common for both images) for key keyK * @param K calibration (common for both images) for key keyK
* @param H1 optional jacobian in E * @param H1 optional jacobian of error w.r.t E
* @param H2 optional jacobian in K * @param H2 optional jacobian of error w.r.t K
* @return * Vector * @return * Vector 1D vector of algebraic error
*/ */
Vector evaluateError( Vector evaluateError(
const EssentialMatrix& E, const CALIBRATION& K, const EssentialMatrix& E, const CALIBRATION& K,
@ -370,12 +369,9 @@ class EssentialMatrixFactor4
if (H2) { if (H2) {
// compute the jacobian of error w.r.t K // compute the jacobian of error w.r.t K
// using dvA/dK = dvA/dcA * dcA/dK and dVB/dK = dvB/dcB * dcB/dK
// Matrix vA_H_K = vA_H_cA * cA_H_K;
// Matrix vB_H_K = vB_H_cB * cB_H_K;
// error function f = vA.T * E * vB // error function f = vA.T * E * vB
// H2 = df/dK = vB.T * E.T * dvA/dK + vA.T * E * dvB/dK // H2 = df/dK = vB.T * E.T * dvA/dK + vA.T * E * dvB/dK
// where dvA/dK = dvA/dcA * dcA/dK, dVB/dK = dvB/dcB * dcB/dK
*H2 = vB.transpose() * E.matrix().transpose() * vA_H_cA * cA_H_K + *H2 = vB.transpose() * E.matrix().transpose() * vA_H_cA * cA_H_K +
vA.transpose() * E.matrix() * vB_H_cB * cB_H_K; vA.transpose() * E.matrix() * vB_H_cB * cB_H_K;
} }