diff --git a/gtsam/slam/tests/testEssentialMatrixFactor.cpp b/gtsam/slam/tests/testEssentialMatrixFactor.cpp index 54b12a2928..19234bec29 100644 --- a/gtsam/slam/tests/testEssentialMatrixFactor.cpp +++ b/gtsam/slam/tests/testEssentialMatrixFactor.cpp @@ -547,7 +547,7 @@ TEST(EssentialMatrixFactor4, minimizationWithStrongCal3BundlerPrior) { // add prior factor for calibration Vector3 priorNoiseModelSigma; - priorNoiseModelSigma << 1, 1, 1; + priorNoiseModelSigma << 0.1, 0.1, 0.1; graph.emplace_shared>(2, trueK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma)); LevenbergMarquardtOptimizer optimizer(graph, initial);