From 319342ab89c510d46e899b5d6caef10c7af7a184 Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Wed, 11 Jan 2023 11:21:05 -0800 Subject: [PATCH] use auto instead --- gtsam/navigation/tests/testAttitudeFactor.cpp | 4 ++-- gtsam/slam/tests/testOrientedPlane3Factor.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/tests/testAttitudeFactor.cpp b/gtsam/navigation/tests/testAttitudeFactor.cpp index 3bd07a323..f599e3957 100644 --- a/gtsam/navigation/tests/testAttitudeFactor.cpp +++ b/gtsam/navigation/tests/testAttitudeFactor.cpp @@ -49,8 +49,8 @@ TEST( Rot3AttitudeFactor, Constructor ) { Rot3 nRb; EXPECT(assert_equal((Vector) Z_2x1,factor.evaluateError(nRb),1e-5)); - std::function err_fn = [&factor](const Rot3& r){ - return factor.evaluateError(r, OptionalNone); + auto err_fn = [&factor](const Rot3& r){ + return factor.evaluateError(r, OptionalNone); }; // Calculate numerical derivatives Matrix expectedH = numericalDerivative11(err_fn, nRb); diff --git a/gtsam/slam/tests/testOrientedPlane3Factor.cpp b/gtsam/slam/tests/testOrientedPlane3Factor.cpp index e393ee16b..6e0753c53 100644 --- a/gtsam/slam/tests/testOrientedPlane3Factor.cpp +++ b/gtsam/slam/tests/testOrientedPlane3Factor.cpp @@ -140,7 +140,7 @@ TEST( OrientedPlane3Factor, Derivatives ) { OrientedPlane3Factor factor(p.planeCoefficients(), noise, poseKey, planeKey); // Calculate numerical derivatives - std::function f = [&factor](const Pose3& p, const OrientedPlane3& o) { + auto f = [&factor](const Pose3& p, const OrientedPlane3& o) { return factor.evaluateError(p, o); }; Matrix numericalH1 = numericalDerivative21(f, poseLin, pLin);