From 2f84788c2aaf58e4541d760a0a5df0abb42e7ae8 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Fri, 9 Aug 2013 19:03:38 +0000 Subject: [PATCH] Adjusted sigma --- matlab/gtsam_examples/IMUKittiExampleSimple.m | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matlab/gtsam_examples/IMUKittiExampleSimple.m b/matlab/gtsam_examples/IMUKittiExampleSimple.m index 127c59d98..f3940a4b4 100644 --- a/matlab/gtsam_examples/IMUKittiExampleSimple.m +++ b/matlab/gtsam_examples/IMUKittiExampleSimple.m @@ -51,7 +51,7 @@ newValues.insert(symbol('b',1), currentBias); sigma_init_x = noiseModel.Diagonal.Precisions([0;0;0; 1;1;1]); sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0); -sigma_init_b = noiseModel.Isotropic.Sigma(6, 100000.0); +sigma_init_b = noiseModel.Isotropic.Sigma(6, 0.01); newFactors.add(PriorFactorPose3(symbol('x',firstGPSPose), currentPoseGlobal, sigma_init_x)); newFactors.add(PriorFactorLieVector(symbol('v',firstGPSPose), currentVelocityGlobal, sigma_init_v));