modified test
parent
3d8641c0c3
commit
eb1a2b8fb3
|
@ -459,11 +459,12 @@ TEST(NonlinearOptimizer, RobustMeanCalculation) {
|
|||
init.insert(0, 100.0);
|
||||
expected.insert(0, 3.33333333);
|
||||
|
||||
LevenbergMarquardtParams params;
|
||||
DoglegParams params_dl;
|
||||
params_dl.setRelativeErrorTol(1e-10);
|
||||
|
||||
auto gn_result = GaussNewtonOptimizer(fg, init).optimize();
|
||||
auto lm_result = LevenbergMarquardtOptimizer(fg, init, params).optimize();
|
||||
auto dl_result = DoglegOptimizer(fg, init).optimize();
|
||||
auto lm_result = LevenbergMarquardtOptimizer(fg, init).optimize();
|
||||
auto dl_result = DoglegOptimizer(fg, init, params_dl).optimize();
|
||||
|
||||
EXPECT(assert_equal(expected, gn_result, tol));
|
||||
EXPECT(assert_equal(expected, lm_result, tol));
|
||||
|
|
Loading…
Reference in New Issue