Fix for unit test based on previous LM change

release/4.3a0
Zsolt Kira 2014-04-24 12:05:37 -04:00
parent a95126599f
commit 4769e3c3fa
1 changed files with 2 additions and 2 deletions

View File

@ -295,7 +295,7 @@ TEST_UNSAFE(NonlinearOptimizer, MoreOptimization) {
// test the diagonal
GaussianFactorGraph::shared_ptr linear = optimizer.linearize();
GaussianFactorGraph damped = optimizer.buildDampedSystem(*linear);
GaussianFactorGraph damped = *optimizer.buildDampedSystem(*linear);
VectorValues d = linear->hessianDiagonal(), //
expectedDiagonal = d + params.lambdaInitial * d;
EXPECT(assert_equal(expectedDiagonal, damped.hessianDiagonal()));
@ -309,7 +309,7 @@ TEST_UNSAFE(NonlinearOptimizer, MoreOptimization) {
EXPECT(assert_equal(expectedGradient,linear->gradientAtZero()));
// Check that the gradient is zero for damped system (it is not!)
damped = optimizer.buildDampedSystem(*linear);
damped = *optimizer.buildDampedSystem(*linear);
VectorValues actualGradient = damped.gradientAtZero();
EXPECT(assert_equal(expectedGradient,actualGradient));