Only call iSAM2 marginalize function if there are actually keys to marginalizae out
parent
9e1a07fcec
commit
396732ff6a
|
|
@ -102,16 +102,15 @@ bool checkMarginalizeLeaves(ISAM2& isam, const FastList<Key>& leafKeys) {
|
||||||
|
|
||||||
isam.getLinearizationPoint(), isam.getOrdering())->augmentedHessian();
|
isam.getLinearizationPoint(), isam.getOrdering())->augmentedHessian();
|
||||||
|
|
||||||
assert(
|
assert(actualAugmentedHessian.unaryExpr(std::ptr_fun(&std::isfinite<double>)).all());
|
||||||
actualAugmentedHessian.unaryExpr(std::ptr_fun(&std::isfinite<double>)).all());
|
|
||||||
|
|
||||||
// Check full marginalization
|
// Check full marginalization
|
||||||
|
std::cout << "Checking treeEqual..." << std::endl;
|
||||||
bool treeEqual = assert_equal(expectedAugmentedHessian,
|
bool treeEqual = assert_equal(expectedAugmentedHessian,
|
||||||
actualAugmentedHessian, 1e-6);
|
actualAugmentedHessian, 1e-6);
|
||||||
|
|
||||||
//bool linEqual = assert_equal(expected2AugmentedHessian, actualAugmentedHessian, 1e-6);
|
//bool linEqual = assert_equal(expected2AugmentedHessian, actualAugmentedHessian, 1e-6);
|
||||||
|
std::cout << "Checking nonlinEqual..." << std::endl;
|
||||||
bool nonlinEqual = assert_equal(expected3AugmentedHessian,
|
bool nonlinEqual = assert_equal(expected3AugmentedHessian,
|
||||||
actualAugmentedHessian, 1e-6);
|
actualAugmentedHessian, 1e-6);
|
||||||
|
|
||||||
|
|
@ -121,6 +120,8 @@ bool checkMarginalizeLeaves(ISAM2& isam, const FastList<Key>& leafKeys) {
|
||||||
|
|
||||||
actual3AugmentedHessian.bottomRightCorner(1, 1) =
|
actual3AugmentedHessian.bottomRightCorner(1, 1) =
|
||||||
expected3AugmentedHessian.bottomRightCorner(1, 1);
|
expected3AugmentedHessian.bottomRightCorner(1, 1);
|
||||||
|
|
||||||
|
std::cout << "Checking afterNonlinCorrect..." << std::endl;
|
||||||
bool afterNonlinCorrect = assert_equal(expected3AugmentedHessian,
|
bool afterNonlinCorrect = assert_equal(expected3AugmentedHessian,
|
||||||
actual3AugmentedHessian, 1e-6);
|
actual3AugmentedHessian, 1e-6);
|
||||||
|
|
||||||
|
|
@ -185,9 +186,11 @@ FixedLagSmoother::Result IncrementalFixedLagSmoother::update(const NonlinearFact
|
||||||
}
|
}
|
||||||
|
|
||||||
// Marginalize out any needed variables
|
// Marginalize out any needed variables
|
||||||
FastList<Key> leafKeys(marginalizableKeys.begin(), marginalizableKeys.end());
|
if(marginalizableKeys.size() > 0) {
|
||||||
// isam_.experimentalMarginalizeLeaves(leafKeys);
|
FastList<Key> leafKeys(marginalizableKeys.begin(), marginalizableKeys.end());
|
||||||
checkMarginalizeLeaves(isam_, leafKeys);
|
// isam_.experimentalMarginalizeLeaves(leafKeys);
|
||||||
|
checkMarginalizeLeaves(isam_, leafKeys);
|
||||||
|
}
|
||||||
|
|
||||||
// Remove marginalized keys from the KeyTimestampMap
|
// Remove marginalized keys from the KeyTimestampMap
|
||||||
eraseKeyTimestampMap(marginalizableKeys);
|
eraseKeyTimestampMap(marginalizableKeys);
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue