@@ -147,51 +147,149 @@ class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA> >
147147 * G = F' * F - F' * E * P * E' * F
148148 * g = F' * (b - E * P * E' * b)
149149 * Fixed size version
150- */
151- template <int N, int ND> // N = 2 or 3, ND is the camera dimension
152- static SymmetricBlockMatrix SchurComplement (
153- const std::vector< Eigen::Matrix<double , ZDim, ND>, Eigen::aligned_allocator< Eigen::Matrix<double , ZDim, ND> > >& Fs,
154- const Matrix& E, const Eigen::Matrix<double , N, N>& P, const Vector& b) {
155-
156- // a single point is observed in m cameras
157- size_t m = Fs.size ();
158-
159- // Create a SymmetricBlockMatrix (augmented hessian, with extra row/column with info vector)
160- size_t M1 = ND * m + 1 ;
161- std::vector<DenseIndex> dims (m + 1 ); // this also includes the b term
162- std::fill (dims.begin (), dims.end () - 1 , ND);
163- dims.back () = 1 ;
164- SymmetricBlockMatrix augmentedHessian (dims, Matrix::Zero (M1, M1));
165-
166- // Blockwise Schur complement
167- for (size_t i = 0 ; i < m; i++) { // for each camera
168-
169- const Eigen::Matrix<double , ZDim, ND>& Fi = Fs[i];
170- const auto FiT = Fi.transpose ();
171- const Eigen::Matrix<double , ZDim, N> Ei_P = //
172- E.block (ZDim * i, 0 , ZDim, N) * P;
173-
174- // D = (Dx2) * ZDim
175- augmentedHessian.setOffDiagonalBlock (i, m, FiT * b.segment <ZDim>(ZDim * i) // F' * b
176- - FiT * (Ei_P * (E.transpose () * b))); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1)
150+ */
151+ template <int N,
152+ int ND> // N = 2 or 3 (point dimension), ND is the camera dimension
153+ static SymmetricBlockMatrix SchurComplement (
154+ const std::vector<
155+ Eigen::Matrix<double , ZDim, ND>,
156+ Eigen::aligned_allocator<Eigen::Matrix<double , ZDim, ND>>>& Fs,
157+ const Matrix& E, const Eigen::Matrix<double , N, N>& P, const Vector& b) {
158+ // a single point is observed in m cameras
159+ size_t m = Fs.size ();
160+
161+ // Create a SymmetricBlockMatrix (augmented hessian, with extra row/column with info vector)
162+ size_t M1 = ND * m + 1 ;
163+ std::vector<DenseIndex> dims (m + 1 ); // this also includes the b term
164+ std::fill (dims.begin (), dims.end () - 1 , ND);
165+ dims.back () = 1 ;
166+ SymmetricBlockMatrix augmentedHessian (dims, Matrix::Zero (M1, M1));
167+
168+ // Blockwise Schur complement
169+ for (size_t i = 0 ; i < m; i++) { // for each camera
170+
171+ const Eigen::Matrix<double , ZDim, ND>& Fi = Fs[i];
172+ const auto FiT = Fi.transpose ();
173+ const Eigen::Matrix<double , ZDim, N> Ei_P = //
174+ E.block (ZDim * i, 0 , ZDim, N) * P;
175+
176+ // D = (Dx2) * ZDim
177+ augmentedHessian.setOffDiagonalBlock (i, m, FiT * b.segment <ZDim>(ZDim * i) // F' * b
178+ - FiT * (Ei_P * (E.transpose () * b))); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1)
179+
180+ // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) )
181+ augmentedHessian.setDiagonalBlock (i, FiT
182+ * (Fi - Ei_P * E.block (ZDim * i, 0 , ZDim, N).transpose () * Fi));
183+
184+ // upper triangular part of the hessian
185+ for (size_t j = i + 1 ; j < m; j++) { // for each camera
186+ const Eigen::Matrix<double , ZDim, ND>& Fj = Fs[j];
187+
188+ // (DxD) = (Dx2) * ( (2x2) * (2xD) )
189+ augmentedHessian.setOffDiagonalBlock (i, j, -FiT
190+ * (Ei_P * E.block (ZDim * j, 0 , ZDim, N).transpose () * Fj));
191+ }
192+ } // end of for over cameras
177193
178- // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) )
179- augmentedHessian. setDiagonalBlock (i, FiT
180- * (Fi - Ei_P * E. block (ZDim * i, 0 , ZDim, N). transpose () * Fi));
194+ augmentedHessian. diagonalBlock (m)( 0 , 0 ) += b. squaredNorm ();
195+ return augmentedHessian;
196+ }
181197
182- // upper triangular part of the hessian
183- for (size_t j = i + 1 ; j < m; j++) { // for each camera
184- const Eigen::Matrix<double , ZDim, ND>& Fj = Fs[j];
198+ /* *
199+ * Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix
200+ * G = F' * F - F' * E * P * E' * F
201+ * g = F' * (b - E * P * E' * b)
202+ * In this version, we allow for the case where the keys in the Jacobian are
203+ * organized differently from the keys in the output SymmetricBlockMatrix In
204+ * particular: each diagonal block of the Jacobian F captures 2 poses (useful
205+ * for rolling shutter and extrinsic calibration) such that F keeps the block
206+ * structure that makes the Schur complement trick fast.
207+ *
208+ * N = 2 or 3 (point dimension), ND is the Jacobian block dimension, NDD is
209+ * the Hessian block dimension
210+ */
211+ template <int N, int ND, int NDD>
212+ static SymmetricBlockMatrix SchurComplementAndRearrangeBlocks (
213+ const std::vector<
214+ Eigen::Matrix<double , ZDim, ND>,
215+ Eigen::aligned_allocator<Eigen::Matrix<double , ZDim, ND>>>& Fs,
216+ const Matrix& E, const Eigen::Matrix<double , N, N>& P, const Vector& b,
217+ const KeyVector& jacobianKeys, const KeyVector& hessianKeys) {
218+ size_t nrNonuniqueKeys = jacobianKeys.size ();
219+ size_t nrUniqueKeys = hessianKeys.size ();
220+
221+ // Marginalize point: note - we reuse the standard SchurComplement function.
222+ SymmetricBlockMatrix augmentedHessian = SchurComplement<N, ND>(Fs, E, P, b);
223+
224+ // Pack into an Hessian factor, allow space for b term.
225+ std::vector<DenseIndex> dims (nrUniqueKeys + 1 );
226+ std::fill (dims.begin (), dims.end () - 1 , NDD);
227+ dims.back () = 1 ;
228+ SymmetricBlockMatrix augmentedHessianUniqueKeys;
229+
230+ // Deal with the fact that some blocks may share the same keys.
231+ if (nrUniqueKeys == nrNonuniqueKeys) {
232+ // Case when there is 1 calibration key per camera:
233+ augmentedHessianUniqueKeys = SymmetricBlockMatrix (
234+ dims, Matrix (augmentedHessian.selfadjointView ()));
235+ } else {
236+ // When multiple cameras share a calibration we have to rearrange
237+ // the results of the Schur complement matrix.
238+ std::vector<DenseIndex> nonuniqueDims (nrNonuniqueKeys + 1 ); // includes b
239+ std::fill (nonuniqueDims.begin (), nonuniqueDims.end () - 1 , NDD);
240+ nonuniqueDims.back () = 1 ;
241+ augmentedHessian = SymmetricBlockMatrix (
242+ nonuniqueDims, Matrix (augmentedHessian.selfadjointView ()));
243+
244+ // Get map from key to location in the new augmented Hessian matrix (the
245+ // one including only unique keys).
246+ std::map<Key, size_t > keyToSlotMap;
247+ for (size_t k = 0 ; k < nrUniqueKeys; k++) {
248+ keyToSlotMap[hessianKeys[k]] = k;
249+ }
185250
186- // (DxD) = (Dx2) * ( (2x2) * (2xD) )
187- augmentedHessian.setOffDiagonalBlock (i, j, -FiT
188- * (Ei_P * E.block (ZDim * j, 0 , ZDim, N).transpose () * Fj));
251+ // Initialize matrix to zero.
252+ augmentedHessianUniqueKeys = SymmetricBlockMatrix (
253+ dims, Matrix::Zero (NDD * nrUniqueKeys + 1 , NDD * nrUniqueKeys + 1 ));
254+
255+ // Add contributions for each key: note this loops over the hessian with
256+ // nonUnique keys (augmentedHessian) and populates an Hessian that only
257+ // includes the unique keys (that is what we want to return).
258+ for (size_t i = 0 ; i < nrNonuniqueKeys; i++) { // rows
259+ Key key_i = jacobianKeys.at (i);
260+
261+ // Update information vector.
262+ augmentedHessianUniqueKeys.updateOffDiagonalBlock (
263+ keyToSlotMap[key_i], nrUniqueKeys,
264+ augmentedHessian.aboveDiagonalBlock (i, nrNonuniqueKeys));
265+
266+ // Update blocks.
267+ for (size_t j = i; j < nrNonuniqueKeys; j++) { // cols
268+ Key key_j = jacobianKeys.at (j);
269+ if (i == j) {
270+ augmentedHessianUniqueKeys.updateDiagonalBlock (
271+ keyToSlotMap[key_i], augmentedHessian.diagonalBlock (i));
272+ } else { // (i < j)
273+ if (keyToSlotMap[key_i] != keyToSlotMap[key_j]) {
274+ augmentedHessianUniqueKeys.updateOffDiagonalBlock (
275+ keyToSlotMap[key_i], keyToSlotMap[key_j],
276+ augmentedHessian.aboveDiagonalBlock (i, j));
277+ } else {
278+ augmentedHessianUniqueKeys.updateDiagonalBlock (
279+ keyToSlotMap[key_i],
280+ augmentedHessian.aboveDiagonalBlock (i, j) +
281+ augmentedHessian.aboveDiagonalBlock (i, j).transpose ());
282+ }
283+ }
189284 }
190- } // end of for over cameras
285+ }
191286
192- augmentedHessian.diagonalBlock (m)(0 , 0 ) += b.squaredNorm ();
193- return augmentedHessian;
287+ // Update bottom right element of the matrix.
288+ augmentedHessianUniqueKeys.updateDiagonalBlock (
289+ nrUniqueKeys, augmentedHessian.diagonalBlock (nrNonuniqueKeys));
194290 }
291+ return augmentedHessianUniqueKeys;
292+ }
195293
196294 /* *
197295 * Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix
@@ -206,7 +304,7 @@ class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA> >
206304 }
207305
208306 // / Computes Point Covariance P, with lambda parameter
209- template <int N> // N = 2 or 3
307+ template <int N> // N = 2 or 3 (point dimension)
210308 static void ComputePointCovariance (Eigen::Matrix<double , N, N>& P,
211309 const Matrix& E, double lambda, bool diagonalDamping = false ) {
212310
@@ -258,7 +356,7 @@ class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA> >
258356 * Applies Schur complement (exploiting block structure) to get a smart factor on cameras,
259357 * and adds the contribution of the smart factor to a pre-allocated augmented Hessian.
260358 */
261- template <int N> // N = 2 or 3
359+ template <int N> // N = 2 or 3 (point dimension)
262360 static void UpdateSchurComplement (const FBlocks& Fs, const Matrix& E,
263361 const Eigen::Matrix<double , N, N>& P, const Vector& b,
264362 const KeyVector& allKeys, const KeyVector& keys,
0 commit comments