diff --git a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp index 0261ef833f..be720dbca4 100644 --- a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp +++ b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp @@ -54,7 +54,7 @@ void dot(const T&f, const string& filename) { } /** I can't get this to work ! - class Mul: boost::function { + class Mul: std::function { inline double operator()(const double& a, const double& b) { return a * b; } diff --git a/gtsam/discrete/tests/testDecisionTree.cpp b/gtsam/discrete/tests/testDecisionTree.cpp index 71cb4abe39..96f503abc9 100644 --- a/gtsam/discrete/tests/testDecisionTree.cpp +++ b/gtsam/discrete/tests/testDecisionTree.cpp @@ -196,7 +196,7 @@ TEST(DT, conversion) map ordering; ordering[A] = X; ordering[B] = Y; - boost::function op = convert; + std::function op = convert; BDT f2(f1, ordering, op); // f1.print("f1"); // f2.print("f2"); diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index 1db1926bcd..0fb0754feb 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -20,12 +20,11 @@ #include #include -#include #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -54,8 +53,8 @@ TEST(CalibratedCamera, Create) { EXPECT(assert_equal(camera, CalibratedCamera::Create(kDefaultPose, actualH))); // Check derivative - boost::function f = // - boost::bind(CalibratedCamera::Create, _1, boost::none); + std::function f = // + std::bind(CalibratedCamera::Create, std::placeholders::_1, boost::none); Matrix numericalH = numericalDerivative11(f, kDefaultPose); EXPECT(assert_equal(numericalH, actualH, 1e-9)); } diff --git a/gtsam/geometry/tests/testEssentialMatrix.cpp b/gtsam/geometry/tests/testEssentialMatrix.cpp index 7362cf7bf8..ff8c61f355 100644 --- a/gtsam/geometry/tests/testEssentialMatrix.cpp +++ b/gtsam/geometry/tests/testEssentialMatrix.cpp @@ -5,16 +5,15 @@ * @date December 17, 2013 */ -#include -#include -#include +#include #include +#include +#include +#include -#include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -42,15 +41,15 @@ TEST(EssentialMatrix, FromRotationAndDirection) { 1e-8)); Matrix expectedH1 = numericalDerivative11( - boost::bind(EssentialMatrix::FromRotationAndDirection, _1, trueDirection, boost::none, - boost::none), + std::bind(EssentialMatrix::FromRotationAndDirection, + std::placeholders::_1, trueDirection, boost::none, boost::none), trueRotation); EXPECT(assert_equal(expectedH1, actualH1, 1e-7)); Matrix expectedH2 = numericalDerivative11( - boost::bind(EssentialMatrix::FromRotationAndDirection, trueRotation, _1, boost::none, - boost::none), - trueDirection); + std::bind(EssentialMatrix::FromRotationAndDirection, trueRotation, + std::placeholders::_1, boost::none, boost::none), + trueDirection); EXPECT(assert_equal(expectedH2, actualH2, 1e-7)); } @@ -176,7 +175,7 @@ TEST (EssentialMatrix, FromPose3_a) { Pose3 pose(trueRotation, trueTranslation); // Pose between two cameras EXPECT(assert_equal(trueE, EssentialMatrix::FromPose3(pose, actualH), 1e-8)); Matrix expectedH = numericalDerivative11( - boost::bind(EssentialMatrix::FromPose3, _1, boost::none), pose); + std::bind(EssentialMatrix::FromPose3, std::placeholders::_1, boost::none), pose); EXPECT(assert_equal(expectedH, actualH, 1e-7)); } @@ -189,7 +188,7 @@ TEST (EssentialMatrix, FromPose3_b) { Pose3 pose(c1Rc2, c1Tc2); // Pose between two cameras EXPECT(assert_equal(E, EssentialMatrix::FromPose3(pose, actualH), 1e-8)); Matrix expectedH = numericalDerivative11( - boost::bind(EssentialMatrix::FromPose3, _1, boost::none), pose); + std::bind(EssentialMatrix::FromPose3, std::placeholders::_1, boost::none), pose); EXPECT(assert_equal(expectedH, actualH, 1e-5)); } diff --git a/gtsam/geometry/tests/testOrientedPlane3.cpp b/gtsam/geometry/tests/testOrientedPlane3.cpp index 5c7c6142e1..533041a2cf 100644 --- a/gtsam/geometry/tests/testOrientedPlane3.cpp +++ b/gtsam/geometry/tests/testOrientedPlane3.cpp @@ -21,10 +21,9 @@ #include #include #include -#include using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace std; using boost::none; @@ -138,8 +137,9 @@ TEST(OrientedPlane3, errorVector) { Vector2(actual[0], actual[1]))); EXPECT(assert_equal(plane1.distance() - plane2.distance(), actual[2])); - boost::function f = - boost::bind(&OrientedPlane3::errorVector, _1, _2, boost::none, boost::none); + std::function f = + std::bind(&OrientedPlane3::errorVector, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none); expectedH1 = numericalDerivative21(f, plane1, plane2); expectedH2 = numericalDerivative22(f, plane1, plane2); EXPECT(assert_equal(expectedH1, actualH1, 1e-5)); @@ -150,8 +150,8 @@ TEST(OrientedPlane3, errorVector) { TEST(OrientedPlane3, jacobian_retract) { OrientedPlane3 plane(-1, 0.1, 0.2, 5); Matrix33 H_actual; - boost::function f = - boost::bind(&OrientedPlane3::retract, plane, _1, boost::none); + std::function f = std::bind( + &OrientedPlane3::retract, plane, std::placeholders::_1, boost::none); { Vector3 v(-0.1, 0.2, 0.3); plane.retract(v, H_actual); diff --git a/gtsam/geometry/tests/testPinholeCamera.cpp b/gtsam/geometry/tests/testPinholeCamera.cpp index 92deda6a53..0679a46097 100644 --- a/gtsam/geometry/tests/testPinholeCamera.cpp +++ b/gtsam/geometry/tests/testPinholeCamera.cpp @@ -22,13 +22,12 @@ #include #include -#include #include #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -66,8 +65,9 @@ TEST(PinholeCamera, Create) { EXPECT(assert_equal(camera, Camera::Create(pose,K, actualH1, actualH2))); // Check derivative - boost::function f = // - boost::bind(Camera::Create,_1,_2,boost::none,boost::none); + std::function f = // + std::bind(Camera::Create, std::placeholders::_1, std::placeholders::_2, + boost::none, boost::none); Matrix numericalH1 = numericalDerivative21(f,pose,K); EXPECT(assert_equal(numericalH1, actualH1, 1e-9)); Matrix numericalH2 = numericalDerivative22(f,pose,K); @@ -81,8 +81,8 @@ TEST(PinholeCamera, Pose) { EXPECT(assert_equal(pose, camera.getPose(actualH))); // Check derivative - boost::function f = // - boost::bind(&Camera::getPose,_1,boost::none); + std::function f = // + std::bind(&Camera::getPose, std::placeholders::_1, boost::none); Matrix numericalH = numericalDerivative11(f,camera); EXPECT(assert_equal(numericalH, actualH, 1e-9)); } diff --git a/gtsam/geometry/tests/testPinholePose.cpp b/gtsam/geometry/tests/testPinholePose.cpp index 1cf2f4a3fd..acfcd9f396 100644 --- a/gtsam/geometry/tests/testPinholePose.cpp +++ b/gtsam/geometry/tests/testPinholePose.cpp @@ -65,8 +65,8 @@ TEST(PinholeCamera, Pose) { EXPECT(assert_equal(pose, camera.getPose(actualH))); // Check derivative - boost::function f = // - boost::bind(&Camera::getPose,_1,boost::none); + std::function f = // + std::bind(&Camera::getPose,_1,boost::none); Matrix numericalH = numericalDerivative11(f,camera); EXPECT(assert_equal(numericalH, actualH, 1e-9)); } diff --git a/gtsam/geometry/tests/testPoint3.cpp b/gtsam/geometry/tests/testPoint3.cpp index 79e44c0b35..315391ac89 100644 --- a/gtsam/geometry/tests/testPoint3.cpp +++ b/gtsam/geometry/tests/testPoint3.cpp @@ -14,14 +14,14 @@ * @brief Unit tests for Point3 class */ -#include +#include #include #include +#include -#include -#include +#include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Point3) @@ -101,7 +101,7 @@ TEST( Point3, dot) { // Use numerical derivatives to calculate the expected Jacobians Matrix H1, H2; - boost::function f = + std::function f = [](const Point3& p, const Point3& q) { return gtsam::dot(p, q); }; { gtsam::dot(p, q, H1, H2); @@ -123,8 +123,9 @@ TEST( Point3, dot) { /* ************************************************************************* */ TEST(Point3, cross) { Matrix aH1, aH2; - boost::function f = - boost::bind(>sam::cross, _1, _2, boost::none, boost::none); + std::function f = + std::bind(>sam::cross, std::placeholders::_1, std::placeholders::_2, + boost::none, boost::none); const Point3 omega(0, 1, 0), theta(4, 6, 8); cross(omega, theta, aH1, aH2); EXPECT(assert_equal(numericalDerivative21(f, omega, theta), aH1)); @@ -142,8 +143,9 @@ TEST( Point3, cross2) { // Use numerical derivatives to calculate the expected Jacobians Matrix H1, H2; - boost::function f = boost::bind(>sam::cross, _1, _2, // - boost::none, boost::none); + std::function f = + std::bind(>sam::cross, std::placeholders::_1, std::placeholders::_2, // + boost::none, boost::none); { gtsam::cross(p, q, H1, H2); EXPECT(assert_equal(numericalDerivative21(f, p, q), H1, 1e-9)); @@ -163,7 +165,7 @@ TEST (Point3, normalize) { Point3 expected(point / sqrt(14.0)); EXPECT(assert_equal(expected, normalize(point, actualH), 1e-8)); Matrix expectedH = numericalDerivative11( - boost::bind(gtsam::normalize, _1, boost::none), point); + std::bind(gtsam::normalize, std::placeholders::_1, boost::none), point); EXPECT(assert_equal(expectedH, actualH, 1e-8)); } diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index 9ed76d4a67..11b8791d46 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -22,8 +22,7 @@ #include // for operator += using namespace boost::assign; -#include -using namespace boost::placeholders; +using namespace std::placeholders; #include #include @@ -215,7 +214,7 @@ TEST(Pose3, translation) { EXPECT(assert_equal(Point3(3.5, -8.2, 4.2), T.translation(actualH), 1e-8)); Matrix numericalH = numericalDerivative11( - boost::bind(&Pose3::translation, _1, boost::none), T); + std::bind(&Pose3::translation, std::placeholders::_1, boost::none), T); EXPECT(assert_equal(numericalH, actualH, 1e-6)); } @@ -226,7 +225,7 @@ TEST(Pose3, rotation) { EXPECT(assert_equal(R, T.rotation(actualH), 1e-8)); Matrix numericalH = numericalDerivative11( - boost::bind(&Pose3::rotation, _1, boost::none), T); + std::bind(&Pose3::rotation, std::placeholders::_1, boost::none), T); EXPECT(assert_equal(numericalH, actualH, 1e-6)); } @@ -1052,7 +1051,9 @@ TEST(Pose3, Create) { Matrix63 actualH1, actualH2; Pose3 actual = Pose3::Create(R, P2, actualH1, actualH2); EXPECT(assert_equal(T, actual)); - boost::function create = boost::bind(Pose3::Create,_1,_2,boost::none,boost::none); + std::function create = + std::bind(Pose3::Create, std::placeholders::_1, std::placeholders::_2, + boost::none, boost::none); EXPECT(assert_equal(numericalDerivative21(create, R, P2), actualH1, 1e-9)); EXPECT(assert_equal(numericalDerivative22(create, R, P2), actualH2, 1e-9)); } diff --git a/gtsam/geometry/tests/testSO3.cpp b/gtsam/geometry/tests/testSO3.cpp index 58ad967d21..910d482b06 100644 --- a/gtsam/geometry/tests/testSO3.cpp +++ b/gtsam/geometry/tests/testSO3.cpp @@ -15,15 +15,12 @@ * @author Frank Dellaert **/ -#include - +#include #include #include +#include -#include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -211,7 +208,7 @@ TEST(SO3, ExpmapDerivative) { TEST(SO3, ExpmapDerivative2) { const Vector3 theta(0.1, 0, 0.1); const Matrix Jexpected = numericalDerivative11( - boost::bind(&SO3::Expmap, _1, boost::none), theta); + std::bind(&SO3::Expmap, std::placeholders::_1, boost::none), theta); CHECK(assert_equal(Jexpected, SO3::ExpmapDerivative(theta))); CHECK(assert_equal(Matrix3(Jexpected.transpose()), @@ -222,7 +219,7 @@ TEST(SO3, ExpmapDerivative2) { TEST(SO3, ExpmapDerivative3) { const Vector3 theta(10, 20, 30); const Matrix Jexpected = numericalDerivative11( - boost::bind(&SO3::Expmap, _1, boost::none), theta); + std::bind(&SO3::Expmap, std::placeholders::_1, boost::none), theta); CHECK(assert_equal(Jexpected, SO3::ExpmapDerivative(theta))); CHECK(assert_equal(Matrix3(Jexpected.transpose()), @@ -277,7 +274,7 @@ TEST(SO3, ExpmapDerivative5) { TEST(SO3, ExpmapDerivative6) { const Vector3 thetahat(0.1, 0, 0.1); const Matrix Jexpected = numericalDerivative11( - boost::bind(&SO3::Expmap, _1, boost::none), thetahat); + std::bind(&SO3::Expmap, std::placeholders::_1, boost::none), thetahat); Matrix3 Jactual; SO3::Expmap(thetahat, Jactual); EXPECT(assert_equal(Jexpected, Jactual)); @@ -288,7 +285,7 @@ TEST(SO3, LogmapDerivative) { const Vector3 thetahat(0.1, 0, 0.1); const SO3 R = SO3::Expmap(thetahat); // some rotation const Matrix Jexpected = numericalDerivative11( - boost::bind(&SO3::Logmap, _1, boost::none), R); + std::bind(&SO3::Logmap, std::placeholders::_1, boost::none), R); const Matrix3 Jactual = SO3::LogmapDerivative(thetahat); EXPECT(assert_equal(Jexpected, Jactual)); } @@ -298,7 +295,7 @@ TEST(SO3, JacobianLogmap) { const Vector3 thetahat(0.1, 0, 0.1); const SO3 R = SO3::Expmap(thetahat); // some rotation const Matrix Jexpected = numericalDerivative11( - boost::bind(&SO3::Logmap, _1, boost::none), R); + std::bind(&SO3::Logmap, std::placeholders::_1, boost::none), R); Matrix3 Jactual; SO3::Logmap(R, Jactual); EXPECT(assert_equal(Jexpected, Jactual)); @@ -308,7 +305,7 @@ TEST(SO3, JacobianLogmap) { TEST(SO3, ApplyDexp) { Matrix aH1, aH2; for (bool nearZeroApprox : {true, false}) { - boost::function f = + std::function f = [=](const Vector3& omega, const Vector3& v) { return so3::DexpFunctor(omega, nearZeroApprox).applyDexp(v); }; @@ -331,7 +328,7 @@ TEST(SO3, ApplyDexp) { TEST(SO3, ApplyInvDexp) { Matrix aH1, aH2; for (bool nearZeroApprox : {true, false}) { - boost::function f = + std::function f = [=](const Vector3& omega, const Vector3& v) { return so3::DexpFunctor(omega, nearZeroApprox).applyInvDexp(v); }; @@ -357,7 +354,7 @@ TEST(SO3, vec) { Matrix actualH; const Vector9 actual = R2.vec(actualH); CHECK(assert_equal(expected, actual)); - boost::function f = [](const SO3& Q) { return Q.vec(); }; + std::function f = [](const SO3& Q) { return Q.vec(); }; const Matrix numericalH = numericalDerivative11(f, R2, 1e-5); CHECK(assert_equal(numericalH, actualH)); } @@ -371,7 +368,7 @@ TEST(Matrix, compose) { Matrix actualH; const Matrix3 actual = so3::compose(M, R, actualH); CHECK(assert_equal(expected, actual)); - boost::function f = [R](const Matrix3& M) { + std::function f = [R](const Matrix3& M) { return so3::compose(M, R); }; Matrix numericalH = numericalDerivative11(f, M, 1e-2); diff --git a/gtsam/geometry/tests/testSO4.cpp b/gtsam/geometry/tests/testSO4.cpp index f771eea5f3..5486755f77 100644 --- a/gtsam/geometry/tests/testSO4.cpp +++ b/gtsam/geometry/tests/testSO4.cpp @@ -166,7 +166,7 @@ TEST(SO4, vec) { Matrix actualH; const Vector16 actual = Q2.vec(actualH); EXPECT(assert_equal(expected, actual)); - boost::function f = [](const SO4& Q) { + std::function f = [](const SO4& Q) { return Q.vec(); }; const Matrix numericalH = numericalDerivative11(f, Q2, 1e-5); @@ -179,7 +179,7 @@ TEST(SO4, topLeft) { Matrix actualH; const Matrix3 actual = topLeft(Q3, actualH); EXPECT(assert_equal(expected, actual)); - boost::function f = [](const SO4& Q3) { + std::function f = [](const SO4& Q3) { return topLeft(Q3); }; const Matrix numericalH = numericalDerivative11(f, Q3, 1e-5); @@ -192,7 +192,7 @@ TEST(SO4, stiefel) { Matrix actualH; const Matrix43 actual = stiefel(Q3, actualH); EXPECT(assert_equal(expected, actual)); - boost::function f = [](const SO4& Q3) { + std::function f = [](const SO4& Q3) { return stiefel(Q3); }; const Matrix numericalH = numericalDerivative11(f, Q3, 1e-5); diff --git a/gtsam/geometry/tests/testSOn.cpp b/gtsam/geometry/tests/testSOn.cpp index 4d0ed98b36..d9d4da34c1 100644 --- a/gtsam/geometry/tests/testSOn.cpp +++ b/gtsam/geometry/tests/testSOn.cpp @@ -189,7 +189,7 @@ Matrix RetractJacobian(size_t n) { return SOn::VectorizedGenerators(n); } /// Test Jacobian of Retract at origin TEST(SOn, RetractJacobian) { Matrix actualH = RetractJacobian(3); - boost::function h = [](const Vector &v) { + std::function h = [](const Vector &v) { return SOn::ChartAtOrigin::Retract(v).matrix(); }; Vector3 v; @@ -205,7 +205,7 @@ TEST(SOn, vec) { SOn Q = SOn::ChartAtOrigin::Retract(v); Matrix actualH; const Vector actual = Q.vec(actualH); - boost::function h = [](const SOn &Q) { return Q.vec(); }; + std::function h = [](const SOn &Q) { return Q.vec(); }; const Matrix H = numericalDerivative11(h, Q, 1e-5); CHECK(assert_equal(H, actualH)); } diff --git a/gtsam/geometry/tests/testSimilarity3.cpp b/gtsam/geometry/tests/testSimilarity3.cpp index 10a9b2ac49..428422072f 100644 --- a/gtsam/geometry/tests/testSimilarity3.cpp +++ b/gtsam/geometry/tests/testSimilarity3.cpp @@ -16,24 +16,22 @@ * @author Zhaoyang Lv */ +#include +#include +#include +#include +#include #include -#include -#include +#include #include -#include #include -#include -#include -#include -#include -#include - -#include +#include +#include +#include -#include -#include +#include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace std; using symbol_shorthand::X; @@ -243,8 +241,9 @@ TEST(Similarity3, GroupAction) { EXPECT(assert_equal(Point3(2, 6, 6), Td.transformFrom(pa))); // Test derivative - boost::function f = boost::bind( - &Similarity3::transformFrom, _1, _2, boost::none, boost::none); + // Use lambda to resolve overloaded method + std::function + f = [](const Similarity3& S, const Point3& p){ return S.transformFrom(p); }; Point3 q(1, 2, 3); for (const auto& T : { T1, T2, T3, T4, T5, T6 }) { diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index 4d609380c8..b548b93153 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -32,13 +32,12 @@ #include #include -#include #include #include using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace std; using gtsam::symbol_shorthand::U; @@ -127,8 +126,9 @@ TEST(Unit3, dot) { // Use numerical derivatives to calculate the expected Jacobians Matrix H1, H2; - boost::function f = boost::bind(&Unit3::dot, _1, _2, // - boost::none, boost::none); + std::function f = + std::bind(&Unit3::dot, std::placeholders::_1, std::placeholders::_2, // + boost::none, boost::none); { p.dot(q, H1, H2); EXPECT(assert_equal(numericalDerivative21(f, p, q), H1, 1e-5)); @@ -158,13 +158,13 @@ TEST(Unit3, error) { // Use numerical derivatives to calculate the expected Jacobian { expected = numericalDerivative11( - boost::bind(&Unit3::error, &p, _1, boost::none), q); + std::bind(&Unit3::error, &p, std::placeholders::_1, boost::none), q); p.error(q, actual); EXPECT(assert_equal(expected.transpose(), actual, 1e-5)); } { expected = numericalDerivative11( - boost::bind(&Unit3::error, &p, _1, boost::none), r); + std::bind(&Unit3::error, &p, std::placeholders::_1, boost::none), r); p.error(r, actual); EXPECT(assert_equal(expected.transpose(), actual, 1e-5)); } @@ -185,25 +185,33 @@ TEST(Unit3, error2) { // Use numerical derivatives to calculate the expected Jacobian { expected = numericalDerivative21( - boost::bind(&Unit3::errorVector, _1, _2, boost::none, boost::none), p, q); + std::bind(&Unit3::errorVector, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none), + p, q); p.errorVector(q, actual, boost::none); EXPECT(assert_equal(expected, actual, 1e-5)); } { expected = numericalDerivative21( - boost::bind(&Unit3::errorVector, _1, _2, boost::none, boost::none), p, r); + std::bind(&Unit3::errorVector, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none), + p, r); p.errorVector(r, actual, boost::none); EXPECT(assert_equal(expected, actual, 1e-5)); } { expected = numericalDerivative22( - boost::bind(&Unit3::errorVector, _1, _2, boost::none, boost::none), p, q); + std::bind(&Unit3::errorVector, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none), + p, q); p.errorVector(q, boost::none, actual); EXPECT(assert_equal(expected, actual, 1e-5)); } { expected = numericalDerivative22( - boost::bind(&Unit3::errorVector, _1, _2, boost::none, boost::none), p, r); + std::bind(&Unit3::errorVector, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none), + p, r); p.errorVector(r, boost::none, actual); EXPECT(assert_equal(expected, actual, 1e-5)); } @@ -221,13 +229,13 @@ TEST(Unit3, distance) { // Use numerical derivatives to calculate the expected Jacobian { expected = numericalGradient( - boost::bind(&Unit3::distance, &p, _1, boost::none), q); + std::bind(&Unit3::distance, &p, std::placeholders::_1, boost::none), q); p.distance(q, actual); EXPECT(assert_equal(expected.transpose(), actual, 1e-5)); } { expected = numericalGradient( - boost::bind(&Unit3::distance, &p, _1, boost::none), r); + std::bind(&Unit3::distance, &p, std::placeholders::_1, boost::none), r); p.distance(r, actual); EXPECT(assert_equal(expected.transpose(), actual, 1e-5)); } @@ -319,7 +327,7 @@ TEST(Unit3, basis) { Matrix62 actualH; Matrix62 expectedH = numericalDerivative11( - boost::bind(BasisTest, _1, boost::none), p); + std::bind(BasisTest, std::placeholders::_1, boost::none), p); // without H, first time EXPECT(assert_equal(expected, p.basis(), 1e-6)); @@ -348,7 +356,7 @@ TEST(Unit3, basis_derivatives) { p.basis(actualH); Matrix62 expectedH = numericalDerivative11( - boost::bind(BasisTest, _1, boost::none), p); + std::bind(BasisTest, std::placeholders::_1, boost::none), p); EXPECT(assert_equal(expectedH, actualH, 1e-5)); } } @@ -376,8 +384,8 @@ TEST(Unit3, retract) { TEST (Unit3, jacobian_retract) { Matrix22 H; Unit3 p; - boost::function f = - boost::bind(&Unit3::retract, p, _1, boost::none); + std::function f = + std::bind(&Unit3::retract, p, std::placeholders::_1, boost::none); { Vector2 v (-0.2, 0.1); p.retract(v, H); @@ -440,7 +448,7 @@ TEST (Unit3, FromPoint3) { Unit3 expected(point); EXPECT(assert_equal(expected, Unit3::FromPoint3(point, actualH), 1e-5)); Matrix expectedH = numericalDerivative11( - boost::bind(Unit3::FromPoint3, _1, boost::none), point); + std::bind(Unit3::FromPoint3, std::placeholders::_1, boost::none), point); EXPECT(assert_equal(expectedH, actualH, 1e-5)); } diff --git a/gtsam/linear/tests/testGaussianBayesNet.cpp b/gtsam/linear/tests/testGaussianBayesNet.cpp index c88bf87314..00a338e547 100644 --- a/gtsam/linear/tests/testGaussianBayesNet.cpp +++ b/gtsam/linear/tests/testGaussianBayesNet.cpp @@ -32,7 +32,7 @@ #include using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -270,11 +270,11 @@ TEST(GaussianBayesNet, ComputeSteepestDescentPoint) { // Compute the Hessian numerically Matrix hessian = numericalHessian( - boost::bind(&computeError, gbn, _1), Vector10::Zero()); + std::bind(&computeError, gbn, std::placeholders::_1), Vector10::Zero()); // Compute the gradient numerically Vector gradient = numericalGradient( - boost::bind(&computeError, gbn, _1), Vector10::Zero()); + std::bind(&computeError, gbn, std::placeholders::_1), Vector10::Zero()); // Compute the gradient using dense matrices Matrix augmentedHessian = GaussianFactorGraph(gbn).augmentedHessian(); diff --git a/gtsam/linear/tests/testGaussianBayesTree.cpp b/gtsam/linear/tests/testGaussianBayesTree.cpp index a6a60c19ce..c5601af271 100644 --- a/gtsam/linear/tests/testGaussianBayesTree.cpp +++ b/gtsam/linear/tests/testGaussianBayesTree.cpp @@ -21,7 +21,6 @@ #include #include // for operator += #include // for operator += -#include #include #include @@ -30,7 +29,7 @@ #include using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -260,11 +259,11 @@ TEST(GaussianBayesTree, ComputeSteepestDescentPointBT) { // Compute the Hessian numerically Matrix hessian = numericalHessian( - boost::bind(&computeError, bt, _1), Vector10::Zero()); + std::bind(&computeError, bt, std::placeholders::_1), Vector10::Zero()); // Compute the gradient numerically Vector gradient = numericalGradient( - boost::bind(&computeError, bt, _1), Vector10::Zero()); + std::bind(&computeError, bt, std::placeholders::_1), Vector10::Zero()); // Compute the gradient using dense matrices Matrix augmentedHessian = GaussianFactorGraph(bt).augmentedHessian(); diff --git a/gtsam/navigation/tests/testAHRSFactor.cpp b/gtsam/navigation/tests/testAHRSFactor.cpp index 828e264f46..a4d06d01a0 100644 --- a/gtsam/navigation/tests/testAHRSFactor.cpp +++ b/gtsam/navigation/tests/testAHRSFactor.cpp @@ -25,10 +25,9 @@ #include #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -175,17 +174,17 @@ TEST(AHRSFactor, Error) { // Expected Jacobians Matrix H1e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, _1, x2, bias), x1); + std::bind(&callEvaluateError, factor, std::placeholders::_1, x2, bias), x1); Matrix H2e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, _1, bias), x2); + std::bind(&callEvaluateError, factor, x1, std::placeholders::_1, bias), x2); Matrix H3e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, x2, _1), bias); + std::bind(&callEvaluateError, factor, x1, x2, std::placeholders::_1), bias); // Check rotation Jacobians Matrix RH1e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, _1, x2, bias), x1); + std::bind(&evaluateRotationError, factor, std::placeholders::_1, x2, bias), x1); Matrix RH2e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, _1, bias), x2); + std::bind(&evaluateRotationError, factor, x1, std::placeholders::_1, bias), x2); // Actual Jacobians Matrix H1a, H2a, H3a; @@ -234,19 +233,19 @@ TEST(AHRSFactor, ErrorWithBiases) { // Expected Jacobians Matrix H1e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, _1, x2, bias), x1); + std::bind(&callEvaluateError, factor, std::placeholders::_1, x2, bias), x1); Matrix H2e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, _1, bias), x2); + std::bind(&callEvaluateError, factor, x1, std::placeholders::_1, bias), x2); Matrix H3e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, x2, _1), bias); + std::bind(&callEvaluateError, factor, x1, x2, std::placeholders::_1), bias); // Check rotation Jacobians Matrix RH1e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, _1, x2, bias), x1); + std::bind(&evaluateRotationError, factor, std::placeholders::_1, x2, bias), x1); Matrix RH2e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, _1, bias), x2); + std::bind(&evaluateRotationError, factor, x1, std::placeholders::_1, bias), x2); Matrix RH3e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, x2, _1), bias); + std::bind(&evaluateRotationError, factor, x1, x2, std::placeholders::_1), bias); // Actual Jacobians Matrix H1a, H2a, H3a; @@ -269,7 +268,7 @@ TEST( AHRSFactor, PartialDerivativeExpmap ) { // Compute numerical derivatives Matrix expectedDelRdelBiasOmega = numericalDerivative11( - boost::bind(&evaluateRotation, measuredOmega, _1, deltaT), biasOmega); + std::bind(&evaluateRotation, measuredOmega, std::placeholders::_1, deltaT), biasOmega); const Matrix3 Jr = Rot3::ExpmapDerivative( (measuredOmega - biasOmega) * deltaT); @@ -294,7 +293,7 @@ TEST( AHRSFactor, PartialDerivativeLogmap ) { // Compute numerical derivatives Matrix expectedDelFdeltheta = numericalDerivative11( - boost::bind(&evaluateLogRotation, thetahat, _1), deltatheta); + std::bind(&evaluateLogRotation, thetahat, std::placeholders::_1), deltatheta); const Vector3 x = thetahat; // parametrization of so(3) const Matrix3 X = skewSymmetric(x); // element of Lie algebra so(3): X = x^ @@ -368,7 +367,7 @@ TEST( AHRSFactor, FirstOrderPreIntegratedMeasurements ) { // Compute numerical derivatives Matrix expectedDelRdelBias = numericalDerivative11( - boost::bind(&evaluatePreintegratedMeasurementsRotation, _1, + std::bind(&evaluatePreintegratedMeasurementsRotation, std::placeholders::_1, measuredOmegas, deltaTs, Vector3(M_PI / 100.0, 0.0, 0.0)), bias); Matrix expectedDelRdelBiasOmega = expectedDelRdelBias.rightCols(3); @@ -410,19 +409,19 @@ TEST( AHRSFactor, ErrorWithBiasesAndSensorBodyDisplacement ) { // Expected Jacobians Matrix H1e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, _1, x2, bias), x1); + std::bind(&callEvaluateError, factor, std::placeholders::_1, x2, bias), x1); Matrix H2e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, _1, bias), x2); + std::bind(&callEvaluateError, factor, x1, std::placeholders::_1, bias), x2); Matrix H3e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, x2, _1), bias); + std::bind(&callEvaluateError, factor, x1, x2, std::placeholders::_1), bias); // Check rotation Jacobians Matrix RH1e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, _1, x2, bias), x1); + std::bind(&evaluateRotationError, factor, std::placeholders::_1, x2, bias), x1); Matrix RH2e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, _1, bias), x2); + std::bind(&evaluateRotationError, factor, x1, std::placeholders::_1, bias), x2); Matrix RH3e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, x2, _1), bias); + std::bind(&evaluateRotationError, factor, x1, x2, std::placeholders::_1), bias); // Actual Jacobians Matrix H1a, H2a, H3a; @@ -459,8 +458,8 @@ TEST (AHRSFactor, predictTest) { // AHRSFactor::PreintegratedMeasurements::predict Matrix expectedH = numericalDerivative11( - boost::bind(&AHRSFactor::PreintegratedMeasurements::predict, - &pim, _1, boost::none), bias); + std::bind(&AHRSFactor::PreintegratedMeasurements::predict, + &pim, std::placeholders::_1, boost::none), bias); // Actual Jacobians Matrix H; diff --git a/gtsam/navigation/tests/testAttitudeFactor.cpp b/gtsam/navigation/tests/testAttitudeFactor.cpp index 2ab60fe6ae..d49907cbfd 100644 --- a/gtsam/navigation/tests/testAttitudeFactor.cpp +++ b/gtsam/navigation/tests/testAttitudeFactor.cpp @@ -25,7 +25,7 @@ #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -50,8 +50,9 @@ TEST( Rot3AttitudeFactor, Constructor ) { EXPECT(assert_equal((Vector) Z_2x1,factor.evaluateError(nRb),1e-5)); // Calculate numerical derivatives - Matrix expectedH = numericalDerivative11( - boost::bind(&Rot3AttitudeFactor::evaluateError, &factor, _1, boost::none), + Matrix expectedH = numericalDerivative11( + std::bind(&Rot3AttitudeFactor::evaluateError, &factor, + std::placeholders::_1, boost::none), nRb); // Use the factor to calculate the derivative @@ -117,7 +118,7 @@ TEST( Pose3AttitudeFactor, Constructor ) { // Calculate numerical derivatives Matrix expectedH = numericalDerivative11( - boost::bind(&Pose3AttitudeFactor::evaluateError, &factor, _1, + std::bind(&Pose3AttitudeFactor::evaluateError, &factor, std::placeholders::_1, boost::none), T); // Use the factor to calculate the derivative diff --git a/gtsam/navigation/tests/testGPSFactor.cpp b/gtsam/navigation/tests/testGPSFactor.cpp index b486272abf..b784c0c94c 100644 --- a/gtsam/navigation/tests/testGPSFactor.cpp +++ b/gtsam/navigation/tests/testGPSFactor.cpp @@ -27,7 +27,7 @@ #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; using namespace GeographicLib; @@ -72,7 +72,7 @@ TEST( GPSFactor, Constructor ) { // Calculate numerical derivatives Matrix expectedH = numericalDerivative11( - boost::bind(&GPSFactor::evaluateError, &factor, _1, boost::none), T); + std::bind(&GPSFactor::evaluateError, &factor, _1, boost::none), T); // Use the factor to calculate the derivative Matrix actualH; @@ -101,7 +101,7 @@ TEST( GPSFactor2, Constructor ) { // Calculate numerical derivatives Matrix expectedH = numericalDerivative11( - boost::bind(&GPSFactor2::evaluateError, &factor, _1, boost::none), T); + std::bind(&GPSFactor2::evaluateError, &factor, _1, boost::none), T); // Use the factor to calculate the derivative Matrix actualH; diff --git a/gtsam/navigation/tests/testImuBias.cpp b/gtsam/navigation/tests/testImuBias.cpp index e7da2c81c6..b486a4a98b 100644 --- a/gtsam/navigation/tests/testImuBias.cpp +++ b/gtsam/navigation/tests/testImuBias.cpp @@ -19,9 +19,8 @@ #include #include -#include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -128,8 +127,9 @@ TEST(ImuBias, operatorSubB) { TEST(ImuBias, Correct1) { Matrix aH1, aH2; const Vector3 measurement(1, 2, 3); - boost::function f = boost::bind( - &Bias::correctAccelerometer, _1, _2, boost::none, boost::none); + std::function f = + std::bind(&Bias::correctAccelerometer, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none); bias1.correctAccelerometer(measurement, aH1, aH2); EXPECT(assert_equal(numericalDerivative21(f, bias1, measurement), aH1)); EXPECT(assert_equal(numericalDerivative22(f, bias1, measurement), aH2)); @@ -139,8 +139,9 @@ TEST(ImuBias, Correct1) { TEST(ImuBias, Correct2) { Matrix aH1, aH2; const Vector3 measurement(1, 2, 3); - boost::function f = - boost::bind(&Bias::correctGyroscope, _1, _2, boost::none, boost::none); + std::function f = + std::bind(&Bias::correctGyroscope, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none); bias1.correctGyroscope(measurement, aH1, aH2); EXPECT(assert_equal(numericalDerivative21(f, bias1, measurement), aH1)); EXPECT(assert_equal(numericalDerivative22(f, bias1, measurement), aH2)); diff --git a/gtsam/navigation/tests/testImuFactor.cpp b/gtsam/navigation/tests/testImuFactor.cpp index f19862772c..801d87895d 100644 --- a/gtsam/navigation/tests/testImuFactor.cpp +++ b/gtsam/navigation/tests/testImuFactor.cpp @@ -146,9 +146,9 @@ TEST(ImuFactor, PreintegratedMeasurements) { Matrix9 aH1, aH2; Matrix96 aH3; actual.computeError(x1, x2, bias, aH1, aH2, aH3); - boost::function f = - boost::bind(&PreintegrationBase::computeError, actual, - boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, + std::function f = + std::bind(&PreintegrationBase::computeError, actual, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, boost::none, boost::none, boost::none); EXPECT(assert_equal(numericalDerivative31(f, x1, x2, bias), aH1, 1e-9)); EXPECT(assert_equal(numericalDerivative32(f, x1, x2, bias), aH2, 1e-9)); @@ -204,20 +204,20 @@ TEST(ImuFactor, PreintegrationBaseMethods) { Matrix96 actualH; pim.biasCorrectedDelta(kZeroBias, actualH); Matrix expectedH = numericalDerivative11( - boost::bind(&PreintegrationBase::biasCorrectedDelta, pim, - boost::placeholders::_1, boost::none), kZeroBias); + std::bind(&PreintegrationBase::biasCorrectedDelta, pim, + std::placeholders::_1, boost::none), kZeroBias); EXPECT(assert_equal(expectedH, actualH)); Matrix9 aH1; Matrix96 aH2; NavState predictedState = pim.predict(state1, kZeroBias, aH1, aH2); Matrix eH1 = numericalDerivative11( - boost::bind(&PreintegrationBase::predict, pim, boost::placeholders::_1, + std::bind(&PreintegrationBase::predict, pim, std::placeholders::_1, kZeroBias, boost::none, boost::none), state1); EXPECT(assert_equal(eH1, aH1)); Matrix eH2 = numericalDerivative11( - boost::bind(&PreintegrationBase::predict, pim, state1, - boost::placeholders::_1, boost::none, boost::none), kZeroBias); + std::bind(&PreintegrationBase::predict, pim, state1, + std::placeholders::_1, boost::none, boost::none), kZeroBias); EXPECT(assert_equal(eH2, aH2)); } @@ -278,12 +278,12 @@ TEST(ImuFactor, ErrorAndJacobians) { // Make sure rotation part is correct when error is interpreted as axis-angle // Jacobians are around zero, so the rotation part is the same as: Matrix H1Rot3 = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, boost::placeholders::_1, v1, x2, v2, kZeroBias), + std::bind(&evaluateRotationError, factor, std::placeholders::_1, v1, x2, v2, kZeroBias), x1); EXPECT(assert_equal(H1Rot3, H1a.topRows(3))); Matrix H3Rot3 = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, v1, boost::placeholders::_1, v2, kZeroBias), + std::bind(&evaluateRotationError, factor, x1, v1, std::placeholders::_1, v2, kZeroBias), x2); EXPECT(assert_equal(H3Rot3, H3a.topRows(3))); @@ -333,8 +333,8 @@ TEST(ImuFactor, ErrorAndJacobianWithBiases) { Matrix96 actualH; pim.biasCorrectedDelta(bias, actualH); Matrix expectedH = numericalDerivative11( - boost::bind(&PreintegrationBase::biasCorrectedDelta, pim, - boost::placeholders::_1, boost::none), bias); + std::bind(&PreintegrationBase::biasCorrectedDelta, pim, + std::placeholders::_1, boost::none), bias); EXPECT(assert_equal(expectedH, actualH)); // Create factor @@ -522,7 +522,7 @@ TEST(ImuFactor, ErrorWithBiasesAndSensorBodyDisplacement) { pim.correctMeasurementsBySensorPose(measuredAcc, measuredOmega, boost::none, D_correctedAcc_measuredOmega, boost::none); Matrix3 expectedD = numericalDerivative11( - boost::bind(correctedAcc, pim, measuredAcc, boost::placeholders::_1), + std::bind(correctedAcc, pim, measuredAcc, std::placeholders::_1), measuredOmega, 1e-6); EXPECT(assert_equal(expectedD, D_correctedAcc_measuredOmega, 1e-5)); @@ -534,15 +534,15 @@ TEST(ImuFactor, ErrorWithBiasesAndSensorBodyDisplacement) { // pim.updatedDeltaXij(measuredAcc, measuredOmega, dt, boost::none, G1, G2); // // Matrix93 expectedG1 = numericalDerivative21( -// boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, -// boost::placeholders::_1, boost::placeholders::_2, +// std::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, +// std::placeholders::_1, std::placeholders::_2, // dt, boost::none, boost::none, boost::none), measuredAcc, // measuredOmega, 1e-6); // EXPECT(assert_equal(expectedG1, G1, 1e-5)); // // Matrix93 expectedG2 = numericalDerivative22( -// boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, -// boost::placeholders::_1, boost::placeholders::_2, +// std::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, +// std::placeholders::_1, std::placeholders::_2, // dt, boost::none, boost::none, boost::none), measuredAcc, // measuredOmega, 1e-6); // EXPECT(assert_equal(expectedG2, G2, 1e-5)); diff --git a/gtsam/navigation/tests/testMagFactor.cpp b/gtsam/navigation/tests/testMagFactor.cpp index ad193b5036..5107b3b6b3 100644 --- a/gtsam/navigation/tests/testMagFactor.cpp +++ b/gtsam/navigation/tests/testMagFactor.cpp @@ -26,7 +26,7 @@ #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; using namespace GeographicLib; @@ -64,7 +64,7 @@ TEST( MagFactor, unrotate ) { Point3 expected(22735.5, 314.502, 44202.5); EXPECT( assert_equal(expected, MagFactor::unrotate(theta,nM,H),1e-1)); EXPECT( assert_equal(numericalDerivative11 // - (boost::bind(&MagFactor::unrotate, _1, nM, none), theta), H, 1e-6)); + (std::bind(&MagFactor::unrotate, _1, nM, none), theta), H, 1e-6)); } // ************************************************************************* @@ -76,35 +76,35 @@ TEST( MagFactor, Factors ) { MagFactor f(1, measured, s, dir, bias, model); EXPECT( assert_equal(Z_3x1,f.evaluateError(theta,H1),1e-5)); EXPECT( assert_equal((Matrix)numericalDerivative11 // - (boost::bind(&MagFactor::evaluateError, &f, _1, none), theta), H1, 1e-7)); + (std::bind(&MagFactor::evaluateError, &f, _1, none), theta), H1, 1e-7)); // MagFactor1 MagFactor1 f1(1, measured, s, dir, bias, model); EXPECT( assert_equal(Z_3x1,f1.evaluateError(nRb,H1),1e-5)); EXPECT( assert_equal(numericalDerivative11 // - (boost::bind(&MagFactor1::evaluateError, &f1, _1, none), nRb), H1, 1e-7)); + (std::bind(&MagFactor1::evaluateError, &f1, _1, none), nRb), H1, 1e-7)); // MagFactor2 MagFactor2 f2(1, 2, measured, nRb, model); EXPECT( assert_equal(Z_3x1,f2.evaluateError(scaled,bias,H1,H2),1e-5)); EXPECT( assert_equal(numericalDerivative11 // - (boost::bind(&MagFactor2::evaluateError, &f2, _1, bias, none, none), scaled),// + (std::bind(&MagFactor2::evaluateError, &f2, _1, bias, none, none), scaled),// H1, 1e-7)); EXPECT( assert_equal(numericalDerivative11 // - (boost::bind(&MagFactor2::evaluateError, &f2, scaled, _1, none, none), bias),// + (std::bind(&MagFactor2::evaluateError, &f2, scaled, _1, none, none), bias),// H2, 1e-7)); // MagFactor2 MagFactor3 f3(1, 2, 3, measured, nRb, model); EXPECT(assert_equal(Z_3x1,f3.evaluateError(s,dir,bias,H1,H2,H3),1e-5)); EXPECT(assert_equal((Matrix)numericalDerivative11 // - (boost::bind(&MagFactor3::evaluateError, &f3, _1, dir, bias, none, none, none), s),// + (std::bind(&MagFactor3::evaluateError, &f3, _1, dir, bias, none, none, none), s),// H1, 1e-7)); EXPECT(assert_equal(numericalDerivative11 // - (boost::bind(&MagFactor3::evaluateError, &f3, s, _1, bias, none, none, none), dir),// + (std::bind(&MagFactor3::evaluateError, &f3, s, _1, bias, none, none, none), dir),// H2, 1e-7)); EXPECT(assert_equal(numericalDerivative11 // - (boost::bind(&MagFactor3::evaluateError, &f3, s, dir, _1, none, none, none), bias),// + (std::bind(&MagFactor3::evaluateError, &f3, s, dir, _1, none, none, none), bias),// H3, 1e-7)); } diff --git a/gtsam/navigation/tests/testMagPoseFactor.cpp b/gtsam/navigation/tests/testMagPoseFactor.cpp index 1a3c5b2a97..204c1d38f9 100644 --- a/gtsam/navigation/tests/testMagPoseFactor.cpp +++ b/gtsam/navigation/tests/testMagPoseFactor.cpp @@ -17,9 +17,7 @@ #include #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; // ***************************************************************************** @@ -78,8 +76,11 @@ TEST(MagPoseFactor, JacobianPose2) { // Error should be zero at the groundtruth pose. MagPoseFactor f(Symbol('X', 0), measured2, scale, dir2, bias2, model2, boost::none); CHECK(gtsam::assert_equal(Z_2x1, f.evaluateError(n_P2_b, H2), 1e-5)); - CHECK(gtsam::assert_equal(gtsam::numericalDerivative11 // - (boost::bind(&MagPoseFactor::evaluateError, &f, _1, boost::none), n_P2_b), H2, 1e-7)); + CHECK(gtsam::assert_equal(gtsam::numericalDerivative11 // + (std::bind(&MagPoseFactor::evaluateError, &f, + std::placeholders::_1, boost::none), + n_P2_b), + H2, 1e-7)); } // ***************************************************************************** @@ -89,8 +90,11 @@ TEST(MagPoseFactor, JacobianPose3) { // Error should be zero at the groundtruth pose. MagPoseFactor f(Symbol('X', 0), measured3, scale, dir3, bias3, model3, boost::none); CHECK(gtsam::assert_equal(Z_3x1, f.evaluateError(n_P3_b, H3), 1e-5)); - CHECK(gtsam::assert_equal(gtsam::numericalDerivative11 // - (boost::bind(&MagPoseFactor::evaluateError, &f, _1, boost::none), n_P3_b), H3, 1e-7)); + CHECK(gtsam::assert_equal(gtsam::numericalDerivative11 // + (std::bind(&MagPoseFactor::evaluateError, &f, + std::placeholders::_1, boost::none), + n_P3_b), + H3, 1e-7)); } // ***************************************************************************** @@ -104,7 +108,7 @@ TEST(MagPoseFactor, body_P_sensor2) { MagPoseFactor f = MagPoseFactor(Symbol('X', 0), sM, scale, dir2, bias2, model2, body_P2_sensor); CHECK(gtsam::assert_equal(Z_2x1, f.evaluateError(n_P2_b, H2), 1e-5)); CHECK(gtsam::assert_equal(gtsam::numericalDerivative11 // - (boost::bind(&MagPoseFactor::evaluateError, &f, _1, boost::none), n_P2_b), H2, 1e-7)); + (std::bind(&MagPoseFactor::evaluateError, &f, std::placeholders::_1, boost::none), n_P2_b), H2, 1e-7)); } // ***************************************************************************** @@ -118,7 +122,7 @@ TEST(MagPoseFactor, body_P_sensor3) { MagPoseFactor f = MagPoseFactor(Symbol('X', 0), sM, scale, dir3, bias3, model3, body_P3_sensor); CHECK(gtsam::assert_equal(Z_3x1, f.evaluateError(n_P3_b, H3), 1e-5)); CHECK(gtsam::assert_equal(gtsam::numericalDerivative11 // - (boost::bind(&MagPoseFactor::evaluateError, &f, _1, boost::none), n_P3_b), H3, 1e-7)); + (std::bind(&MagPoseFactor::evaluateError, &f, std::placeholders::_1, boost::none), n_P3_b), H3, 1e-7)); } // ***************************************************************************** diff --git a/gtsam/navigation/tests/testManifoldPreintegration.cpp b/gtsam/navigation/tests/testManifoldPreintegration.cpp index 625689ed79..7796ccbda5 100644 --- a/gtsam/navigation/tests/testManifoldPreintegration.cpp +++ b/gtsam/navigation/tests/testManifoldPreintegration.cpp @@ -22,11 +22,10 @@ #include #include -#include #include "imuFactorTesting.h" -using namespace boost::placeholders; +using namespace std::placeholders; namespace testing { // Create default parameters with Z-down and above noise parameters @@ -43,21 +42,21 @@ static boost::shared_ptr Params() { TEST(ManifoldPreintegration, BiasCorrectionJacobians) { testing::SomeMeasurements measurements; - boost::function deltaRij = + std::function deltaRij = [=](const Vector3& a, const Vector3& w) { ManifoldPreintegration pim(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim); return pim.deltaRij(); }; - boost::function deltaPij = + std::function deltaPij = [=](const Vector3& a, const Vector3& w) { ManifoldPreintegration pim(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim); return pim.deltaPij(); }; - boost::function deltaVij = + std::function deltaVij = [=](const Vector3& a, const Vector3& w) { ManifoldPreintegration pim(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim); @@ -98,10 +97,12 @@ TEST(ManifoldPreintegration, computeError) { Matrix9 aH1, aH2; Matrix96 aH3; pim.computeError(x1, x2, bias, aH1, aH2, aH3); - boost::function f = - boost::bind(&ManifoldPreintegration::computeError, pim, _1, _2, _3, - boost::none, boost::none, boost::none); + std::function + f = std::bind(&ManifoldPreintegration::computeError, pim, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, + boost::none); // NOTE(frank): tolerance of 1e-3 on H1 because approximate away from 0 EXPECT(assert_equal(numericalDerivative31(f, x1, x2, bias), aH1, 1e-9)); EXPECT(assert_equal(numericalDerivative32(f, x1, x2, bias), aH2, 1e-9)); diff --git a/gtsam/navigation/tests/testNavState.cpp b/gtsam/navigation/tests/testNavState.cpp index 86c708f5e8..e7adb923d7 100644 --- a/gtsam/navigation/tests/testNavState.cpp +++ b/gtsam/navigation/tests/testNavState.cpp @@ -23,7 +23,7 @@ #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -39,9 +39,9 @@ static const Vector9 kZeroXi = Vector9::Zero(); /* ************************************************************************* */ TEST(NavState, Constructor) { - boost::function create = - boost::bind(&NavState::Create, _1, _2, _3, boost::none, boost::none, - boost::none); + std::function create = + std::bind(&NavState::Create, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, boost::none); Matrix aH1, aH2, aH3; EXPECT( assert_equal(kState1, @@ -59,9 +59,9 @@ TEST(NavState, Constructor) { /* ************************************************************************* */ TEST(NavState, Constructor2) { - boost::function construct = - boost::bind(&NavState::FromPoseVelocity, _1, _2, boost::none, - boost::none); + std::function construct = + std::bind(&NavState::FromPoseVelocity, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none); Matrix aH1, aH2; EXPECT( assert_equal(kState1, @@ -76,7 +76,7 @@ TEST( NavState, Attitude) { Rot3 actual = kState1.attitude(aH); EXPECT(assert_equal(actual, kAttitude)); eH = numericalDerivative11( - boost::bind(&NavState::attitude, _1, boost::none), kState1); + std::bind(&NavState::attitude, std::placeholders::_1, boost::none), kState1); EXPECT(assert_equal((Matrix )eH, aH)); } @@ -86,7 +86,8 @@ TEST( NavState, Position) { Point3 actual = kState1.position(aH); EXPECT(assert_equal(actual, kPosition)); eH = numericalDerivative11( - boost::bind(&NavState::position, _1, boost::none), kState1); + std::bind(&NavState::position, std::placeholders::_1, boost::none), + kState1); EXPECT(assert_equal((Matrix )eH, aH)); } @@ -96,7 +97,8 @@ TEST( NavState, Velocity) { Velocity3 actual = kState1.velocity(aH); EXPECT(assert_equal(actual, kVelocity)); eH = numericalDerivative11( - boost::bind(&NavState::velocity, _1, boost::none), kState1); + std::bind(&NavState::velocity, std::placeholders::_1, boost::none), + kState1); EXPECT(assert_equal((Matrix )eH, aH)); } @@ -106,7 +108,8 @@ TEST( NavState, BodyVelocity) { Velocity3 actual = kState1.bodyVelocity(aH); EXPECT(assert_equal(actual, kAttitude.unrotate(kVelocity))); eH = numericalDerivative11( - boost::bind(&NavState::bodyVelocity, _1, boost::none), kState1); + std::bind(&NavState::bodyVelocity, std::placeholders::_1, boost::none), + kState1); EXPECT(assert_equal((Matrix )eH, aH)); } @@ -137,8 +140,9 @@ TEST( NavState, Manifold ) { // Check retract derivatives Matrix9 aH1, aH2; kState1.retract(xi, aH1, aH2); - boost::function retract = - boost::bind(&NavState::retract, _1, _2, boost::none, boost::none); + std::function retract = + std::bind(&NavState::retract, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none); EXPECT(assert_equal(numericalDerivative21(retract, kState1, xi), aH1)); EXPECT(assert_equal(numericalDerivative22(retract, kState1, xi), aH2)); @@ -149,9 +153,9 @@ TEST( NavState, Manifold ) { EXPECT(assert_equal(numericalDerivative22(retract, state2, xi2), aH2)); // Check localCoordinates derivatives - boost::function local = - boost::bind(&NavState::localCoordinates, _1, _2, boost::none, - boost::none); + std::function local = + std::bind(&NavState::localCoordinates, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none); // from state1 to state2 kState1.localCoordinates(state2, aH1, aH2); EXPECT(assert_equal(numericalDerivative21(local, kState1, state2), aH1)); @@ -168,8 +172,9 @@ TEST( NavState, Manifold ) { /* ************************************************************************* */ static const double dt = 2.0; -boost::function coriolis = boost::bind( - &NavState::coriolis, _1, dt, kOmegaCoriolis, _2, boost::none); +std::function coriolis = + std::bind(&NavState::coriolis, std::placeholders::_1, dt, kOmegaCoriolis, + std::placeholders::_2, boost::none); TEST(NavState, Coriolis) { Matrix9 aH; @@ -244,9 +249,10 @@ TEST(NavState, CorrectPIM) { xi << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4, -0.1, -0.2, -0.3; double dt = 0.5; Matrix9 aH1, aH2; - boost::function correctPIM = - boost::bind(&NavState::correctPIM, _1, _2, dt, kGravity, kOmegaCoriolis, - false, boost::none, boost::none); + std::function correctPIM = + std::bind(&NavState::correctPIM, std::placeholders::_1, + std::placeholders::_2, dt, kGravity, kOmegaCoriolis, false, + boost::none, boost::none); kState1.correctPIM(xi, dt, kGravity, kOmegaCoriolis, false, aH1, aH2); EXPECT(assert_equal(numericalDerivative21(correctPIM, kState1, xi), aH1)); EXPECT(assert_equal(numericalDerivative22(correctPIM, kState1, xi), aH2)); diff --git a/gtsam/navigation/tests/testScenario.cpp b/gtsam/navigation/tests/testScenario.cpp index d0bae36900..0df51956bd 100644 --- a/gtsam/navigation/tests/testScenario.cpp +++ b/gtsam/navigation/tests/testScenario.cpp @@ -19,10 +19,9 @@ #include #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -148,7 +147,7 @@ TEST(Scenario, Accelerating) { { // Check acceleration in nav Matrix expected = numericalDerivative11( - boost::bind(&Scenario::velocity_n, scenario, _1), T); + std::bind(&Scenario::velocity_n, scenario, std::placeholders::_1), T); EXPECT(assert_equal(Vector3(expected), scenario.acceleration_n(T), 1e-9)); } diff --git a/gtsam/navigation/tests/testTangentPreintegration.cpp b/gtsam/navigation/tests/testTangentPreintegration.cpp index 9bb988b429..ada0590945 100644 --- a/gtsam/navigation/tests/testTangentPreintegration.cpp +++ b/gtsam/navigation/tests/testTangentPreintegration.cpp @@ -22,11 +22,10 @@ #include #include -#include #include "imuFactorTesting.h" -using namespace boost::placeholders; +using namespace std::placeholders; static const double kDt = 0.1; @@ -78,7 +77,7 @@ TEST(TangentPreintegration, UpdateEstimate2) { TEST(ImuFactor, BiasCorrectionJacobians) { testing::SomeMeasurements measurements; - boost::function preintegrated = + std::function preintegrated = [=](const Vector3& a, const Vector3& w) { TangentPreintegration pim(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim); @@ -105,10 +104,12 @@ TEST(TangentPreintegration, computeError) { Matrix9 aH1, aH2; Matrix96 aH3; pim.computeError(x1, x2, bias, aH1, aH2, aH3); - boost::function f = - boost::bind(&TangentPreintegration::computeError, pim, _1, _2, _3, - boost::none, boost::none, boost::none); + std::function + f = std::bind(&TangentPreintegration::computeError, pim, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, + boost::none); // NOTE(frank): tolerance of 1e-3 on H1 because approximate away from 0 EXPECT(assert_equal(numericalDerivative31(f, x1, x2, bias), aH1, 1e-9)); EXPECT(assert_equal(numericalDerivative32(f, x1, x2, bias), aH2, 1e-9)); @@ -121,7 +122,7 @@ TEST(TangentPreintegration, Compose) { TangentPreintegration pim(testing::Params()); testing::integrateMeasurements(measurements, &pim); - boost::function f = + std::function f = [pim](const Vector9& zeta01, const Vector9& zeta12) { return TangentPreintegration::Compose(zeta01, zeta12, pim.deltaTij()); }; diff --git a/gtsam/nonlinear/tests/testExpression.cpp b/gtsam/nonlinear/tests/testExpression.cpp index 8fcf84a113..7bb8021866 100644 --- a/gtsam/nonlinear/tests/testExpression.cpp +++ b/gtsam/nonlinear/tests/testExpression.cpp @@ -495,7 +495,7 @@ TEST(Expression, Subtract) { /* ************************************************************************* */ TEST(Expression, LinearExpression) { const Key key(67); - const boost::function f = [](const Point3& p) { return (Vector3)p; }; + const std::function f = [](const Point3& p) { return (Vector3)p; }; const Matrix3 kIdentity = I_3x3; const Expression linear_ = linearExpression(f, Point3_(key), kIdentity); diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index e9076a7d7a..b894f48169 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -34,7 +34,7 @@ #include using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace std; static double inf = std::numeric_limits::infinity(); @@ -336,7 +336,7 @@ TEST(Values, filter) { // Filter by key int i = 0; - Values::Filtered filtered = values.filter(boost::bind(std::greater_equal(), _1, 2)); + Values::Filtered filtered = values.filter(std::bind(std::greater_equal(), std::placeholders::_1, 2)); EXPECT_LONGS_EQUAL(2, (long)filtered.size()); for(const auto key_value: filtered) { if(i == 0) { @@ -364,7 +364,7 @@ TEST(Values, filter) { EXPECT(assert_equal(expectedSubValues1, actualSubValues1)); // ConstFilter by Key - Values::ConstFiltered constfiltered = values.filter(boost::bind(std::greater_equal(), _1, 2)); + Values::ConstFiltered constfiltered = values.filter(std::bind(std::greater_equal(), std::placeholders::_1, 2)); EXPECT_LONGS_EQUAL(2, (long)constfiltered.size()); Values fromconstfiltered(constfiltered); EXPECT(assert_equal(expectedSubValues1, fromconstfiltered)); diff --git a/gtsam/sam/tests/testRangeFactor.cpp b/gtsam/sam/tests/testRangeFactor.cpp index 2af5825db8..5f5d4f4dd0 100644 --- a/gtsam/sam/tests/testRangeFactor.cpp +++ b/gtsam/sam/tests/testRangeFactor.cpp @@ -28,7 +28,7 @@ #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -265,9 +265,9 @@ TEST( RangeFactor, Jacobian2D ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; H1Expected = numericalDerivative11( - boost::bind(&factorError2D, _1, point, factor), pose); + std::bind(&factorError2D, std::placeholders::_1, point, factor), pose); H2Expected = numericalDerivative11( - boost::bind(&factorError2D, pose, _1, factor), point); + std::bind(&factorError2D, pose, std::placeholders::_1, factor), point); // Verify the Jacobians are correct CHECK(assert_equal(H1Expected, H1Actual, 1e-9)); @@ -296,9 +296,9 @@ TEST( RangeFactor, Jacobian2DWithTransform ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; H1Expected = numericalDerivative11( - boost::bind(&factorErrorWithTransform2D, _1, point, factor), pose); + std::bind(&factorErrorWithTransform2D, std::placeholders::_1, point, factor), pose); H2Expected = numericalDerivative11( - boost::bind(&factorErrorWithTransform2D, pose, _1, factor), point); + std::bind(&factorErrorWithTransform2D, pose, std::placeholders::_1, factor), point); // Verify the Jacobians are correct CHECK(assert_equal(H1Expected, H1Actual, 1e-9)); @@ -323,9 +323,9 @@ TEST( RangeFactor, Jacobian3D ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; H1Expected = numericalDerivative11( - boost::bind(&factorError3D, _1, point, factor), pose); + std::bind(&factorError3D, std::placeholders::_1, point, factor), pose); H2Expected = numericalDerivative11( - boost::bind(&factorError3D, pose, _1, factor), point); + std::bind(&factorError3D, pose, std::placeholders::_1, factor), point); // Verify the Jacobians are correct CHECK(assert_equal(H1Expected, H1Actual, 1e-9)); @@ -355,9 +355,9 @@ TEST( RangeFactor, Jacobian3DWithTransform ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; H1Expected = numericalDerivative11( - boost::bind(&factorErrorWithTransform3D, _1, point, factor), pose); + std::bind(&factorErrorWithTransform3D, std::placeholders::_1, point, factor), pose); H2Expected = numericalDerivative11( - boost::bind(&factorErrorWithTransform3D, pose, _1, factor), point); + std::bind(&factorErrorWithTransform3D, pose, std::placeholders::_1, factor), point); // Verify the Jacobians are correct CHECK(assert_equal(H1Expected, H1Actual, 1e-9)); diff --git a/gtsam/sfm/tests/testTranslationFactor.cpp b/gtsam/sfm/tests/testTranslationFactor.cpp index 05ae76faa3..818f2bce51 100644 --- a/gtsam/sfm/tests/testTranslationFactor.cpp +++ b/gtsam/sfm/tests/testTranslationFactor.cpp @@ -20,10 +20,9 @@ #include #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -91,9 +90,9 @@ TEST(TranslationFactor, Jacobian) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; H1Expected = numericalDerivative11( - boost::bind(&factorError, _1, T2, factor), T1); + std::bind(&factorError, std::placeholders::_1, T2, factor), T1); H2Expected = numericalDerivative11( - boost::bind(&factorError, T1, _1, factor), T2); + std::bind(&factorError, T1, std::placeholders::_1, factor), T2); // Verify the Jacobians are correct EXPECT(assert_equal(H1Expected, H1Actual, 1e-9)); diff --git a/gtsam/slam/tests/testBetweenFactor.cpp b/gtsam/slam/tests/testBetweenFactor.cpp index a1f8774e5a..6897943ec1 100644 --- a/gtsam/slam/tests/testBetweenFactor.cpp +++ b/gtsam/slam/tests/testBetweenFactor.cpp @@ -14,7 +14,7 @@ #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace gtsam::symbol_shorthand; using namespace gtsam::noiseModel; @@ -35,15 +35,16 @@ TEST(BetweenFactor, Rot3) { Vector expected = Rot3::Logmap(measured.inverse() * R1.between(R2)); EXPECT(assert_equal(expected,actual/*, 1e-100*/)); // Uncomment to make unit test fail - Matrix numericalH1 = numericalDerivative21( - boost::function(boost::bind( - &BetweenFactor::evaluateError, factor, _1, _2, boost::none, - boost::none)), R1, R2, 1e-5); + Matrix numericalH1 = numericalDerivative21( + std::function(std::bind( + &BetweenFactor::evaluateError, factor, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none)), + R1, R2, 1e-5); EXPECT(assert_equal(numericalH1,actualH1, 1E-5)); Matrix numericalH2 = numericalDerivative22( - boost::function(boost::bind( - &BetweenFactor::evaluateError, factor, _1, _2, boost::none, + std::function(std::bind( + &BetweenFactor::evaluateError, factor, std::placeholders::_1, std::placeholders::_2, boost::none, boost::none)), R1, R2, 1e-5); EXPECT(assert_equal(numericalH2,actualH2, 1E-5)); } diff --git a/gtsam/slam/tests/testEssentialMatrixConstraint.cpp b/gtsam/slam/tests/testEssentialMatrixConstraint.cpp index fb2172107c..080239b350 100644 --- a/gtsam/slam/tests/testEssentialMatrixConstraint.cpp +++ b/gtsam/slam/tests/testEssentialMatrixConstraint.cpp @@ -23,10 +23,9 @@ #include #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -53,12 +52,14 @@ TEST( EssentialMatrixConstraint, test ) { CHECK(assert_equal(expected, actual, 1e-8)); // Calculate numerical derivatives - Matrix expectedH1 = numericalDerivative11( - boost::bind(&EssentialMatrixConstraint::evaluateError, &factor, _1, pose2, - boost::none, boost::none), pose1); - Matrix expectedH2 = numericalDerivative11( - boost::bind(&EssentialMatrixConstraint::evaluateError, &factor, pose1, _1, - boost::none, boost::none), pose2); + Matrix expectedH1 = numericalDerivative11( + std::bind(&EssentialMatrixConstraint::evaluateError, &factor, + std::placeholders::_1, pose2, boost::none, boost::none), + pose1); + Matrix expectedH2 = numericalDerivative11( + std::bind(&EssentialMatrixConstraint::evaluateError, &factor, pose1, + std::placeholders::_1, boost::none, boost::none), + pose2); // Use the factor to calculate the derivative Matrix actualH1; diff --git a/gtsam/slam/tests/testEssentialMatrixFactor.cpp b/gtsam/slam/tests/testEssentialMatrixFactor.cpp index 79a86865d1..03775a70f0 100644 --- a/gtsam/slam/tests/testEssentialMatrixFactor.cpp +++ b/gtsam/slam/tests/testEssentialMatrixFactor.cpp @@ -17,9 +17,7 @@ #include #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -104,8 +102,8 @@ TEST(EssentialMatrixFactor, factor) { TEST(EssentialMatrixFactor, ExpressionFactor) { Key key(1); for (size_t i = 0; i < 5; i++) { - boost::function)> f = - boost::bind(&EssentialMatrix::error, _1, vA(i), vB(i), _2); + std::function)> f = + std::bind(&EssentialMatrix::error, std::placeholders::_1, vA(i), vB(i), std::placeholders::_2); Expression E_(key); // leaf expression Expression expr(f, E_); // unary expression @@ -130,9 +128,9 @@ TEST(EssentialMatrixFactor, ExpressionFactor) { TEST(EssentialMatrixFactor, ExpressionFactorRotationOnly) { Key key(1); for (size_t i = 0; i < 5; i++) { - boost::function)> f = - boost::bind(&EssentialMatrix::error, _1, vA(i), vB(i), _2); - boost::function)> f = + std::bind(&EssentialMatrix::error, std::placeholders::_1, vA(i), vB(i), std::placeholders::_2); + std::function, OptionalJacobian<5, 2>)> g; diff --git a/gtsam/slam/tests/testOrientedPlane3Factor.cpp b/gtsam/slam/tests/testOrientedPlane3Factor.cpp index 022dc859ea..35c7504081 100644 --- a/gtsam/slam/tests/testOrientedPlane3Factor.cpp +++ b/gtsam/slam/tests/testOrientedPlane3Factor.cpp @@ -27,10 +27,9 @@ #include #include -#include using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace std; @@ -145,8 +144,9 @@ TEST( OrientedPlane3Factor, Derivatives ) { OrientedPlane3Factor factor(p.planeCoefficients(), noise, poseKey, planeKey); // Calculate numerical derivatives - boost::function f = boost::bind( - &OrientedPlane3Factor::evaluateError, factor, _1, _2, boost::none, boost::none); + std::function f = std::bind( + &OrientedPlane3Factor::evaluateError, factor, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none); Matrix numericalH1 = numericalDerivative21(f, poseLin, pLin); Matrix numericalH2 = numericalDerivative22(f, poseLin, pLin); @@ -184,15 +184,15 @@ TEST( OrientedPlane3DirectionPrior, Constructor ) { // Calculate numerical derivatives Matrix expectedH1 = numericalDerivative11( - boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1, + std::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, std::placeholders::_1, boost::none), T1); Matrix expectedH2 = numericalDerivative11( - boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1, + std::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, std::placeholders::_1, boost::none), T2); Matrix expectedH3 = numericalDerivative11( - boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1, + std::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, std::placeholders::_1, boost::none), T3); // Use the factor to calculate the derivative diff --git a/gtsam/slam/tests/testReferenceFrameFactor.cpp b/gtsam/slam/tests/testReferenceFrameFactor.cpp index 075710ae73..b5800a414b 100644 --- a/gtsam/slam/tests/testReferenceFrameFactor.cpp +++ b/gtsam/slam/tests/testReferenceFrameFactor.cpp @@ -16,8 +16,6 @@ #include -#include - #include #include @@ -32,7 +30,7 @@ using namespace std; using namespace boost; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; typedef gtsam::ReferenceFrameFactor PointReferenceFrameFactor; @@ -70,13 +68,13 @@ TEST( ReferenceFrameFactor, jacobians ) { Matrix numericalDT, numericalDL, numericalDF; numericalDF = numericalDerivative31( - boost::bind(evaluateError_, tc, _1, _2, _3), + std::bind(evaluateError_, tc, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3), global, trans, local, 1e-5); numericalDT = numericalDerivative32( - boost::bind(evaluateError_, tc, _1, _2, _3), + std::bind(evaluateError_, tc, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3), global, trans, local, 1e-5); numericalDL = numericalDerivative33( - boost::bind(evaluateError_, tc, _1, _2, _3), + std::bind(evaluateError_, tc, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3), global, trans, local, 1e-5); EXPECT(assert_equal(numericalDF, actualDF)); @@ -102,13 +100,13 @@ TEST( ReferenceFrameFactor, jacobians_zero ) { Matrix numericalDT, numericalDL, numericalDF; numericalDF = numericalDerivative31( - boost::bind(evaluateError_, tc, _1, _2, _3), + std::bind(evaluateError_, tc, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3), global, trans, local, 1e-5); numericalDT = numericalDerivative32( - boost::bind(evaluateError_, tc, _1, _2, _3), + std::bind(evaluateError_, tc, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3), global, trans, local, 1e-5); numericalDL = numericalDerivative33( - boost::bind(evaluateError_, tc, _1, _2, _3), + std::bind(evaluateError_, tc, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3), global, trans, local, 1e-5); EXPECT(assert_equal(numericalDF, actualDF)); diff --git a/gtsam/slam/tests/testRotateFactor.cpp b/gtsam/slam/tests/testRotateFactor.cpp index e4ecafd425..b8fd01730e 100644 --- a/gtsam/slam/tests/testRotateFactor.cpp +++ b/gtsam/slam/tests/testRotateFactor.cpp @@ -13,12 +13,11 @@ #include #include -#include #include using namespace std; using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; static const double kDegree = M_PI / 180; @@ -73,13 +72,13 @@ TEST (RotateFactor, test) { // Use numerical derivatives to calculate the expected Jacobian { expected = numericalDerivative11( - boost::bind(&RotateFactor::evaluateError, &f, _1, boost::none), iRc); + std::bind(&RotateFactor::evaluateError, &f, std::placeholders::_1, boost::none), iRc); f.evaluateError(iRc, actual); EXPECT(assert_equal(expected, actual, 1e-9)); } { expected = numericalDerivative11( - boost::bind(&RotateFactor::evaluateError, &f, _1, boost::none), R); + std::bind(&RotateFactor::evaluateError, &f, std::placeholders::_1, boost::none), R); f.evaluateError(R, actual); EXPECT(assert_equal(expected, actual, 1e-9)); } @@ -144,14 +143,14 @@ TEST (RotateDirectionsFactor, test) { // Use numerical derivatives to calculate the expected Jacobian { expected = numericalDerivative11( - boost::bind(&RotateDirectionsFactor::evaluateError, &f, _1, + std::bind(&RotateDirectionsFactor::evaluateError, &f, std::placeholders::_1, boost::none), iRc); f.evaluateError(iRc, actual); EXPECT(assert_equal(expected, actual, 1e-9)); } { expected = numericalDerivative11( - boost::bind(&RotateDirectionsFactor::evaluateError, &f, _1, + std::bind(&RotateDirectionsFactor::evaluateError, &f, std::placeholders::_1, boost::none), R); f.evaluateError(R, actual); EXPECT(assert_equal(expected, actual, 1e-9)); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 26caa6b75d..c7f220c102 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -27,11 +27,10 @@ #include #include #include -#include #include using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; static const double rankTol = 1.0; // Create a noise model for the pixel error @@ -132,8 +131,8 @@ TEST( SmartProjectionPoseFactor, noiseless ) { EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7); // Calculate expected derivative for point (easiest to check) - boost::function f = // - boost::bind(&SmartFactor::whitenedError, factor, cameras, _1); + std::function f = // + std::bind(&SmartFactor::whitenedError, factor, cameras, std::placeholders::_1); // Calculate using computeEP Matrix actualE; diff --git a/gtsam/slam/tests/testTriangulationFactor.cpp b/gtsam/slam/tests/testTriangulationFactor.cpp index 9fe087c2ff..ad88c88fcc 100644 --- a/gtsam/slam/tests/testTriangulationFactor.cpp +++ b/gtsam/slam/tests/testTriangulationFactor.cpp @@ -32,7 +32,7 @@ using namespace std; using namespace gtsam; using namespace boost::assign; -using namespace boost::placeholders; +using namespace std::placeholders; // Some common constants static const boost::shared_ptr sharedCal = // @@ -62,7 +62,7 @@ TEST( triangulation, TriangulationFactor ) { factor.evaluateError(landmark, HActual); Matrix HExpected = numericalDerivative11( - boost::bind(&Factor::evaluateError, &factor, _1, boost::none), landmark); + std::bind(&Factor::evaluateError, &factor, std::placeholders::_1, boost::none), landmark); // Verify the Jacobians are correct CHECK(assert_equal(HExpected, HActual, 1e-3)); @@ -86,13 +86,15 @@ TEST( triangulation, TriangulationFactorStereo ) { factor.evaluateError(landmark, HActual); Matrix HExpected = numericalDerivative11( - boost::bind(&Factor::evaluateError, &factor, _1, boost::none), landmark); + std::bind(&Factor::evaluateError, &factor, std::placeholders::_1, boost::none), landmark); // Verify the Jacobians are correct CHECK(assert_equal(HExpected, HActual, 1e-3)); // compare same problem against expression factor - Expression::UnaryFunction::type f = boost::bind(&StereoCamera::project2, camera2, _1, boost::none, _2); + Expression::UnaryFunction::type f = + std::bind(&StereoCamera::project2, camera2, std::placeholders::_1, + boost::none, std::placeholders::_2); Expression point_(pointKey); Expression project2_(f, point_); diff --git a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp index ede11c7fb5..882d5423ad 100644 --- a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp +++ b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp @@ -3,14 +3,13 @@ * @author Duy-Nguyen Ta */ -#include #include #include #include #include /* ************************************************************************* */ -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace gtsam::symbol_shorthand; @@ -58,19 +57,28 @@ TEST( Reconstruction, evaluateError) { assert_equal(Z_6x1, constraint.evaluateError(g2, g1, V1_g1, H1, H2, H3), tol)); Matrix numericalH1 = numericalDerivative31( - boost::function( - boost::bind(&Reconstruction::evaluateError, constraint, _1, _2, _3, - boost::none, boost::none, boost::none)), g2, g1, V1_g1, 1e-5); + std::function( + std::bind(&Reconstruction::evaluateError, constraint, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, + boost::none)), + g2, g1, V1_g1, 1e-5); Matrix numericalH2 = numericalDerivative32( - boost::function( - boost::bind(&Reconstruction::evaluateError, constraint, _1, _2, _3, - boost::none, boost::none, boost::none)), g2, g1, V1_g1, 1e-5); + std::function( + std::bind(&Reconstruction::evaluateError, constraint, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, + boost::none)), + g2, g1, V1_g1, 1e-5); Matrix numericalH3 = numericalDerivative33( - boost::function( - boost::bind(&Reconstruction::evaluateError, constraint, _1, _2, _3, - boost::none, boost::none, boost::none)), g2, g1, V1_g1, 1e-5); + std::function( + std::bind(&Reconstruction::evaluateError, constraint, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, + boost::none)), + g2, g1, V1_g1, 1e-5); EXPECT(assert_equal(numericalH1,H1,1e-5)); EXPECT(assert_equal(numericalH2,H2,1e-5)); @@ -111,22 +119,22 @@ TEST( DiscreteEulerPoincareHelicopter, evaluateError) { EXPECT(assert_equal(Z_6x1, constraint.evaluateError(expectedv2, V1_g1, g2, H1, H2, H3), 1e0)); Matrix numericalH1 = numericalDerivative31( - boost::function( - boost::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, _1, _2, _3, boost::none, boost::none, boost::none) + std::function( + std::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, boost::none, boost::none, boost::none) ), expectedv2, V1_g1, g2, 1e-5 ); Matrix numericalH2 = numericalDerivative32( - boost::function( - boost::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, _1, _2, _3, boost::none, boost::none, boost::none) + std::function( + std::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, boost::none, boost::none, boost::none) ), expectedv2, V1_g1, g2, 1e-5 ); Matrix numericalH3 = numericalDerivative33( - boost::function( - boost::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, _1, _2, _3, boost::none, boost::none, boost::none) + std::function( + std::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, boost::none, boost::none, boost::none) ), expectedv2, V1_g1, g2, 1e-5 ); diff --git a/gtsam_unstable/geometry/tests/testEvent.cpp b/gtsam_unstable/geometry/tests/testEvent.cpp index 3a599e6c5f..f1bbc39704 100644 --- a/gtsam_unstable/geometry/tests/testEvent.cpp +++ b/gtsam_unstable/geometry/tests/testEvent.cpp @@ -23,9 +23,7 @@ #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -67,11 +65,11 @@ TEST(Event, Derivatives) { Matrix13 actualH2; kToa(exampleEvent, microphoneAt0, actualH1, actualH2); Matrix expectedH1 = numericalDerivative11( - boost::bind(kToa, _1, microphoneAt0, boost::none, boost::none), + std::bind(kToa, std::placeholders::_1, microphoneAt0, boost::none, boost::none), exampleEvent); EXPECT(assert_equal(expectedH1, actualH1, 1e-8)); Matrix expectedH2 = numericalDerivative11( - boost::bind(kToa, exampleEvent, _1, boost::none, boost::none), + std::bind(kToa, exampleEvent, std::placeholders::_1, boost::none, boost::none), microphoneAt0); EXPECT(assert_equal(expectedH2, actualH2, 1e-8)); } diff --git a/gtsam_unstable/slam/tests/testBetweenFactorEM.cpp b/gtsam_unstable/slam/tests/testBetweenFactorEM.cpp index 70368cc0e1..4d6e1912a1 100644 --- a/gtsam_unstable/slam/tests/testBetweenFactorEM.cpp +++ b/gtsam_unstable/slam/tests/testBetweenFactorEM.cpp @@ -190,12 +190,12 @@ TEST (BetweenFactorEM, jacobian ) { // CHECK( assert_equal(H2_actual_stnd, H2_actual, 1e-8)); double stepsize = 1.0e-9; - Matrix H1_expected = gtsam::numericalDerivative11(boost::bind(&predictionError, _1, p2, key1, key2, f), p1, stepsize); - Matrix H2_expected = gtsam::numericalDerivative11(boost::bind(&predictionError, p1, _1, key1, key2, f), p2, stepsize); + Matrix H1_expected = gtsam::numericalDerivative11(std::bind(&predictionError, _1, p2, key1, key2, f), p1, stepsize); + Matrix H2_expected = gtsam::numericalDerivative11(std::bind(&predictionError, p1, _1, key1, key2, f), p2, stepsize); // try to check numerical derivatives of a standard between factor - Matrix H1_expected_stnd = gtsam::numericalDerivative11(boost::bind(&predictionError_standard, _1, p2, key1, key2, h), p1, stepsize); + Matrix H1_expected_stnd = gtsam::numericalDerivative11(std::bind(&predictionError_standard, _1, p2, key1, key2, h), p1, stepsize); // CHECK( assert_equal(H1_expected_stnd, H1_actual_stnd, 1e-5)); // // diff --git a/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp b/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp index 0eb8b274b3..59c4fdf536 100644 --- a/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp +++ b/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp @@ -10,10 +10,9 @@ #include #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace gtsam::symbol_shorthand; using namespace gtsam::noiseModel; @@ -68,15 +67,17 @@ TEST(BiasedGPSFactor, jacobian) { factor.evaluateError(pose,bias, actualH1, actualH2); Matrix numericalH1 = numericalDerivative21( - boost::function(boost::bind( - &BiasedGPSFactor::evaluateError, factor, _1, _2, boost::none, - boost::none)), pose, bias, 1e-5); + std::function(std::bind( + &BiasedGPSFactor::evaluateError, factor, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none)), + pose, bias, 1e-5); EXPECT(assert_equal(numericalH1,actualH1, 1E-5)); Matrix numericalH2 = numericalDerivative22( - boost::function(boost::bind( - &BiasedGPSFactor::evaluateError, factor, _1, _2, boost::none, - boost::none)), pose, bias, 1e-5); + std::function(std::bind( + &BiasedGPSFactor::evaluateError, factor, std::placeholders::_1, + std::placeholders::_2, boost::none, boost::none)), + pose, bias, 1e-5); EXPECT(assert_equal(numericalH2,actualH2, 1E-5)); } diff --git a/gtsam_unstable/slam/tests/testEquivInertialNavFactor_GlobalVel.cpp b/gtsam_unstable/slam/tests/testEquivInertialNavFactor_GlobalVel.cpp index 95b9b2f88f..644283512f 100644 --- a/gtsam_unstable/slam/tests/testEquivInertialNavFactor_GlobalVel.cpp +++ b/gtsam_unstable/slam/tests/testEquivInertialNavFactor_GlobalVel.cpp @@ -26,7 +26,7 @@ #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; diff --git a/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp b/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp index 74134612d8..8692cf5841 100644 --- a/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp +++ b/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp @@ -23,9 +23,7 @@ #include #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -108,9 +106,13 @@ TEST (GaussMarkovFactor, jacobian ) { // Calculate the Jacobian matrices H1 and H2 using the numerical derivative function Matrix numerical_H1, numerical_H2; numerical_H1 = numericalDerivative21( - boost::bind(&predictionError, _1, _2, factor), v1_upd, v2_upd); + std::bind(&predictionError, std::placeholders::_1, std::placeholders::_2, + factor), + v1_upd, v2_upd); numerical_H2 = numericalDerivative22( - boost::bind(&predictionError, _1, _2, factor), v1_upd, v2_upd); + std::bind(&predictionError, std::placeholders::_1, std::placeholders::_2, + factor), + v1_upd, v2_upd); // Verify they are equal for this choice of state CHECK( assert_equal(numerical_H1, computed_H1, 1e-9)); diff --git a/gtsam_unstable/slam/tests/testInertialNavFactor_GlobalVelocity.cpp b/gtsam_unstable/slam/tests/testInertialNavFactor_GlobalVelocity.cpp index aae59035be..e68b2fe5f4 100644 --- a/gtsam_unstable/slam/tests/testInertialNavFactor_GlobalVelocity.cpp +++ b/gtsam_unstable/slam/tests/testInertialNavFactor_GlobalVelocity.cpp @@ -16,7 +16,6 @@ */ #include -#include #include #include #include @@ -26,7 +25,7 @@ #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -251,7 +250,7 @@ Vector predictionErrorVel(const Pose3& p1, const Vector3& v1, // // Vector3 v(predictionRq(angles, q)); // -// J_expected = numericalDerivative11(boost::bind(&predictionRq, _1, q), angles); +// J_expected = numericalDerivative11(std::bind(&predictionRq, std::placeholders::_1, q), angles); // // cout<<"J_hyp"<( - boost::bind(&predictionErrorPose, _1, Vel1, Bias1, Pose2, Vel2, factor), + std::bind(&predictionErrorPose, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2, factor), Pose1); H2_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, Pose1, _1, Bias1, Pose2, Vel2, factor), + std::bind(&predictionErrorPose, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2, factor), Vel1); H3_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, Pose1, Vel1, _1, Pose2, Vel2, factor), + std::bind(&predictionErrorPose, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2, factor), Bias1); H4_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, _1, Vel2, factor), + std::bind(&predictionErrorPose, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2, factor), Pose2); H5_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, Pose2, _1, factor), + std::bind(&predictionErrorPose, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1, factor), Vel2); // Verify they are equal for this choice of state @@ -346,19 +345,19 @@ Vector predictionErrorVel(const Pose3& p1, const Vector3& v1, Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel, H5_expectedVel; H1_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, _1, Vel1, Bias1, Pose2, Vel2, factor), + std::bind(&predictionErrorVel, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2, factor), Pose1); H2_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, Pose1, _1, Bias1, Pose2, Vel2, factor), + std::bind(&predictionErrorVel, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2, factor), Vel1); H3_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, Pose1, Vel1, _1, Pose2, Vel2, factor), + std::bind(&predictionErrorVel, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2, factor), Bias1); H4_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, _1, Vel2, factor), + std::bind(&predictionErrorVel, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2, factor), Pose2); H5_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, Pose2, _1, factor), + std::bind(&predictionErrorVel, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1, factor), Vel2); // Verify they are equal for this choice of state @@ -644,19 +643,19 @@ Vector predictionErrorVel(const Pose3& p1, const Vector3& v1, Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose, H5_expectedPose; H1_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, _1, Vel1, Bias1, Pose2, Vel2, factor), + std::bind(&predictionErrorPose, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2, factor), Pose1); H2_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, Pose1, _1, Bias1, Pose2, Vel2, factor), + std::bind(&predictionErrorPose, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2, factor), Vel1); H3_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, Pose1, Vel1, _1, Pose2, Vel2, factor), + std::bind(&predictionErrorPose, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2, factor), Bias1); H4_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, _1, Vel2, factor), + std::bind(&predictionErrorPose, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2, factor), Pose2); H5_expectedPose = numericalDerivative11( - boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, Pose2, _1, factor), + std::bind(&predictionErrorPose, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1, factor), Vel2); // Verify they are equal for this choice of state @@ -678,19 +677,19 @@ Vector predictionErrorVel(const Pose3& p1, const Vector3& v1, Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel, H5_expectedVel; H1_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, _1, Vel1, Bias1, Pose2, Vel2, factor), + std::bind(&predictionErrorVel, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2, factor), Pose1); H2_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, Pose1, _1, Bias1, Pose2, Vel2, factor), + std::bind(&predictionErrorVel, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2, factor), Vel1); H3_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, Pose1, Vel1, _1, Pose2, Vel2, factor), + std::bind(&predictionErrorVel, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2, factor), Bias1); H4_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, _1, Vel2, factor), + std::bind(&predictionErrorVel, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2, factor), Pose2); H5_expectedVel = numericalDerivative11( - boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, Pose2, _1, factor), + std::bind(&predictionErrorVel, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1, factor), Vel2); // Verify they are equal for this choice of state diff --git a/gtsam_unstable/slam/tests/testLocalOrientedPlane3Factor.cpp b/gtsam_unstable/slam/tests/testLocalOrientedPlane3Factor.cpp index 6bbfb55ae1..b97d56c7ea 100644 --- a/gtsam_unstable/slam/tests/testLocalOrientedPlane3Factor.cpp +++ b/gtsam_unstable/slam/tests/testLocalOrientedPlane3Factor.cpp @@ -24,9 +24,7 @@ #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; using namespace std; @@ -143,8 +141,10 @@ TEST(LocalOrientedPlane3Factor, Derivatives) { LocalOrientedPlane3Factor factor(p, noise, poseKey, anchorPoseKey, planeKey); // Calculate numerical derivatives - auto f = boost::bind(&LocalOrientedPlane3Factor::evaluateError, factor, - _1, _2, _3, boost::none, boost::none, boost::none); + auto f = + std::bind(&LocalOrientedPlane3Factor::evaluateError, factor, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, boost::none); Matrix numericalH1 = numericalDerivative31(f, poseLin, anchorPoseLin, pLin); Matrix numericalH2 = numericalDerivative32 #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -83,7 +82,9 @@ TEST(PartialPriorFactor, JacobianPartialTranslation2) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose); + std::bind(&TestPartialPriorFactor2::evaluateError, &factor, + std::placeholders::_1, boost::none), + pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -99,13 +100,16 @@ TEST(PartialPriorFactor, JacobianFullTranslation2) { Pose2 measurement(-6.0, 3.5, 0.123); // Prior on x component of translation. - TestPartialPriorFactor2 factor(poseKey, { 0, 1 }, measurement.translation(), NM::Isotropic::Sigma(2, 0.25)); + TestPartialPriorFactor2 factor(poseKey, {0, 1}, measurement.translation(), + NM::Isotropic::Sigma(2, 0.25)); Pose2 pose = measurement; // Zero-error linearization point. // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose); + std::bind(&TestPartialPriorFactor2::evaluateError, &factor, + std::placeholders::_1, boost::none), + pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -127,7 +131,7 @@ TEST(PartialPriorFactor, JacobianTheta) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose); + std::bind(&TestPartialPriorFactor2::evaluateError, &factor, std::placeholders::_1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -178,7 +182,7 @@ TEST(PartialPriorFactor, JacobianAtIdentity3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); + std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -200,7 +204,7 @@ TEST(PartialPriorFactor, JacobianPartialTranslation3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); + std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -224,7 +228,7 @@ TEST(PartialPriorFactor, JacobianFullTranslation3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); + std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -248,7 +252,7 @@ TEST(PartialPriorFactor, JacobianTxTz3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); + std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -271,7 +275,7 @@ TEST(PartialPriorFactor, JacobianFullRotation3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); + std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; diff --git a/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp b/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp index 6f7725eed1..cd5bf1d9e9 100644 --- a/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp +++ b/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp @@ -22,10 +22,9 @@ #include #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -199,8 +198,14 @@ TEST( PoseBetweenFactor, Jacobian ) { Point3(-3.37493895, 6.14660244, -8.93650986)); // Calculate numerical derivatives - Matrix expectedH1 = numericalDerivative11(boost::bind(&TestPoseBetweenFactor::evaluateError, &factor, _1, pose2, boost::none, boost::none), pose1); - Matrix expectedH2 = numericalDerivative11(boost::bind(&TestPoseBetweenFactor::evaluateError, &factor, pose1, _1, boost::none, boost::none), pose2); + Matrix expectedH1 = numericalDerivative11( + std::bind(&TestPoseBetweenFactor::evaluateError, &factor, + std::placeholders::_1, pose2, boost::none, boost::none), + pose1); + Matrix expectedH2 = numericalDerivative11( + std::bind(&TestPoseBetweenFactor::evaluateError, &factor, pose1, + std::placeholders::_1, boost::none, boost::none), + pose2); // Use the factor to calculate the derivative Matrix actualH1; @@ -228,8 +233,14 @@ TEST( PoseBetweenFactor, JacobianWithTransform ) { Point3(-3.5257579, 6.02637531, -8.98382384)); // Calculate numerical derivatives - Matrix expectedH1 = numericalDerivative11(boost::bind(&TestPoseBetweenFactor::evaluateError, &factor, _1, pose2, boost::none, boost::none), pose1); - Matrix expectedH2 = numericalDerivative11(boost::bind(&TestPoseBetweenFactor::evaluateError, &factor, pose1, _1, boost::none, boost::none), pose2); + Matrix expectedH1 = numericalDerivative11( + std::bind(&TestPoseBetweenFactor::evaluateError, &factor, + std::placeholders::_1, pose2, boost::none, boost::none), + pose1); + Matrix expectedH2 = numericalDerivative11( + std::bind(&TestPoseBetweenFactor::evaluateError, &factor, pose1, + std::placeholders::_1, boost::none, boost::none), + pose2); // Use the factor to calculate the derivative Matrix actualH1; diff --git a/gtsam_unstable/slam/tests/testPosePriorFactor.cpp b/gtsam_unstable/slam/tests/testPosePriorFactor.cpp index cc26155172..dbbc02a8ba 100644 --- a/gtsam_unstable/slam/tests/testPosePriorFactor.cpp +++ b/gtsam_unstable/slam/tests/testPosePriorFactor.cpp @@ -22,10 +22,9 @@ #include #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -188,7 +187,10 @@ TEST( PosePriorFactor, Jacobian ) { Pose3 pose(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); // Calculate numerical derivatives - Matrix expectedH1 = numericalDerivative11(boost::bind(&TestPosePriorFactor::evaluateError, &factor, _1, boost::none), pose); + Matrix expectedH1 = numericalDerivative11( + std::bind(&TestPosePriorFactor::evaluateError, &factor, + std::placeholders::_1, boost::none), + pose); // Use the factor to calculate the derivative Matrix actualH1; @@ -212,7 +214,10 @@ TEST( PosePriorFactor, JacobianWithTransform ) { Point3(-4.74767676, 7.67044942, -11.00985)); // Calculate numerical derivatives - Matrix expectedH1 = numericalDerivative11(boost::bind(&TestPosePriorFactor::evaluateError, &factor, _1, boost::none), pose); + Matrix expectedH1 = numericalDerivative11( + std::bind(&TestPosePriorFactor::evaluateError, &factor, + std::placeholders::_1, boost::none), + pose); // Use the factor to calculate the derivative Matrix actualH1; diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h index 8f8563e9db..e0e5c45817 100644 --- a/gtsam_unstable/slam/tests/testPoseToPointFactor.h +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -63,7 +63,7 @@ TEST(PoseToPointFactor, jacobian) { PoseToPointFactor factor(pose_key, point_key, l_meas, noise); // Calculate numerical derivatives - auto f = boost::bind(&PoseToPointFactor::evaluateError, factor, _1, _2, + auto f = std::bind(&PoseToPointFactor::evaluateError, factor, _1, _2, boost::none, boost::none); Matrix numerical_H1 = numericalDerivative21(f, p, l); Matrix numerical_H2 = numericalDerivative22(f, p, l); diff --git a/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp b/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp index 8a65e5e571..c05f83a23b 100644 --- a/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp +++ b/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp @@ -28,9 +28,7 @@ #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -178,10 +176,13 @@ TEST( ProjectionFactorPPP, Jacobian ) { CHECK(assert_equal(H3Expected, H3Actual, 1e-3)); // Verify H2 with numerical derivative - Matrix H2Expected = numericalDerivative32( - boost::function( - boost::bind(&TestProjectionFactor::evaluateError, &factor, _1, _2, _3, - boost::none, boost::none, boost::none)), pose, Pose3(), point); + Matrix H2Expected = numericalDerivative32( + std::function( + std::bind(&TestProjectionFactor::evaluateError, &factor, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, + boost::none)), + pose, Pose3(), point); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); } @@ -214,9 +215,12 @@ TEST( ProjectionFactorPPP, JacobianWithTransform ) { // Verify H2 with numerical derivative Matrix H2Expected = numericalDerivative32( - boost::function( - boost::bind(&TestProjectionFactor::evaluateError, &factor, _1, _2, _3, - boost::none, boost::none, boost::none)), pose, body_P_sensor, point); + std::function( + std::bind(&TestProjectionFactor::evaluateError, &factor, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, boost::none, boost::none, + boost::none)), + pose, body_P_sensor, point); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); diff --git a/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp b/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp index 232f8de17e..6490dfc753 100644 --- a/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp +++ b/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp @@ -28,9 +28,7 @@ #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -138,12 +136,16 @@ TEST( ProjectionFactorPPPC, Jacobian ) { // Verify H2 and H4 with numerical derivatives Matrix H2Expected = numericalDerivative11( - boost::bind(&TestProjectionFactor::evaluateError, &factor, pose, _1, point, - *K1, boost::none, boost::none, boost::none, boost::none), Pose3()); + std::bind(&TestProjectionFactor::evaluateError, &factor, pose, + std::placeholders::_1, point, *K1, boost::none, boost::none, + boost::none, boost::none), + Pose3()); Matrix H4Expected = numericalDerivative11( - boost::bind(&TestProjectionFactor::evaluateError, &factor, pose, Pose3(), point, - _1, boost::none, boost::none, boost::none, boost::none), *K1); + std::bind(&TestProjectionFactor::evaluateError, &factor, pose, Pose3(), + point, std::placeholders::_1, boost::none, boost::none, + boost::none, boost::none), + *K1); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); CHECK(assert_equal(H4Expected, H4Actual, 1e-5)); @@ -174,12 +176,12 @@ TEST( ProjectionFactorPPPC, JacobianWithTransform ) { // Verify H2 and H4 with numerical derivatives Matrix H2Expected = numericalDerivative11( - boost::bind(&TestProjectionFactor::evaluateError, &factor, pose, _1, point, + std::bind(&TestProjectionFactor::evaluateError, &factor, pose, std::placeholders::_1, point, *K1, boost::none, boost::none, boost::none, boost::none), body_P_sensor); Matrix H4Expected = numericalDerivative11( - boost::bind(&TestProjectionFactor::evaluateError, &factor, pose, body_P_sensor, point, - _1, boost::none, boost::none, boost::none, boost::none), *K1); + std::bind(&TestProjectionFactor::evaluateError, &factor, pose, body_P_sensor, point, + std::placeholders::_1, boost::none, boost::none, boost::none, boost::none), *K1); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); CHECK(assert_equal(H4Expected, H4Actual, 1e-5)); diff --git a/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp b/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp index 2fda9debb8..25ca3339b7 100644 --- a/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp +++ b/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp @@ -5,14 +5,13 @@ * @author Alex Cunningham */ -#include #include #include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; SharedNoiseModel model1 = noiseModel::Unit::Create(1); @@ -37,10 +36,14 @@ TEST( testRelativeElevationFactor, level_zero_error ) { RelativeElevationFactor factor(poseKey, pointKey, measured, model1); Matrix actH1, actH2; EXPECT(assert_equal(Z_1x1, factor.evaluateError(pose1, point1, actH1, actH2))); - Matrix expH1 = numericalDerivative21( - boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); - Matrix expH2 = numericalDerivative22( - boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + Matrix expH1 = numericalDerivative21( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose1, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose1, point1, 1e-5); EXPECT(assert_equal(expH1, actH1, tol)); EXPECT(assert_equal(expH2, actH2, tol)); } @@ -52,10 +55,14 @@ TEST( testRelativeElevationFactor, level_positive ) { RelativeElevationFactor factor(poseKey, pointKey, measured, model1); Matrix actH1, actH2; EXPECT(assert_equal((Vector(1) << 2.0).finished(), factor.evaluateError(pose1, point1, actH1, actH2))); - Matrix expH1 = numericalDerivative21( - boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); - Matrix expH2 = numericalDerivative22( - boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + Matrix expH1 = numericalDerivative21( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose1, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose1, point1, 1e-5); EXPECT(assert_equal(expH1, actH1, tol)); EXPECT(assert_equal(expH2, actH2, tol)); } @@ -67,10 +74,14 @@ TEST( testRelativeElevationFactor, level_negative ) { RelativeElevationFactor factor(poseKey, pointKey, measured, model1); Matrix actH1, actH2; EXPECT(assert_equal((Vector(1) << 3.0).finished(), factor.evaluateError(pose1, point1, actH1, actH2))); - Matrix expH1 = numericalDerivative21( - boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); - Matrix expH2 = numericalDerivative22( - boost::bind(evalFactorError, factor, _1, _2), pose1, point1, 1e-5); + Matrix expH1 = numericalDerivative21( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose1, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose1, point1, 1e-5); EXPECT(assert_equal(expH1, actH1, tol)); EXPECT(assert_equal(expH2, actH2, tol)); } @@ -82,10 +93,14 @@ TEST( testRelativeElevationFactor, rotated_zero_error ) { RelativeElevationFactor factor(poseKey, pointKey, measured, model1); Matrix actH1, actH2; EXPECT(assert_equal(Z_1x1, factor.evaluateError(pose2, point1, actH1, actH2))); - Matrix expH1 = numericalDerivative21( - boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); - Matrix expH2 = numericalDerivative22( - boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + Matrix expH1 = numericalDerivative21( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose2, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose2, point1, 1e-5); EXPECT(assert_equal(expH1, actH1, tol)); EXPECT(assert_equal(expH2, actH2, tol)); } @@ -97,10 +112,14 @@ TEST( testRelativeElevationFactor, rotated_positive ) { RelativeElevationFactor factor(poseKey, pointKey, measured, model1); Matrix actH1, actH2; EXPECT(assert_equal((Vector(1) << 2.0).finished(), factor.evaluateError(pose2, point1, actH1, actH2))); - Matrix expH1 = numericalDerivative21( - boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); - Matrix expH2 = numericalDerivative22( - boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + Matrix expH1 = numericalDerivative21( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose2, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose2, point1, 1e-5); EXPECT(assert_equal(expH1, actH1, tol)); EXPECT(assert_equal(expH2, actH2, tol)); } @@ -112,10 +131,14 @@ TEST( testRelativeElevationFactor, rotated_negative1 ) { RelativeElevationFactor factor(poseKey, pointKey, measured, model1); Matrix actH1, actH2; EXPECT(assert_equal((Vector(1) << 3.0).finished(), factor.evaluateError(pose2, point1, actH1, actH2))); - Matrix expH1 = numericalDerivative21( - boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); - Matrix expH2 = numericalDerivative22( - boost::bind(evalFactorError, factor, _1, _2), pose2, point1, 1e-5); + Matrix expH1 = numericalDerivative21( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose2, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose2, point1, 1e-5); EXPECT(assert_equal(expH1, actH1, tol)); EXPECT(assert_equal(expH2, actH2, tol)); } @@ -127,10 +150,14 @@ TEST( testRelativeElevationFactor, rotated_negative2 ) { RelativeElevationFactor factor(poseKey, pointKey, measured, model1); Matrix actH1, actH2; EXPECT(assert_equal((Vector(1) << 3.0).finished(), factor.evaluateError(pose3, point1, actH1, actH2))); - Matrix expH1 = numericalDerivative21( - boost::bind(evalFactorError, factor, _1, _2), pose3, point1, 1e-5); - Matrix expH2 = numericalDerivative22( - boost::bind(evalFactorError, factor, _1, _2), pose3, point1, 1e-5); + Matrix expH1 = numericalDerivative21( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose3, point1, 1e-5); + Matrix expH2 = numericalDerivative22( + std::bind(evalFactorError, factor, std::placeholders::_1, + std::placeholders::_2), + pose3, point1, 1e-5); EXPECT(assert_equal(expH1, actH1, tol)); EXPECT(assert_equal(expH2, actH2, tol)); } diff --git a/gtsam_unstable/slam/tests/testTSAMFactors.cpp b/gtsam_unstable/slam/tests/testTSAMFactors.cpp index 77f82bca49..fbb21e191c 100644 --- a/gtsam_unstable/slam/tests/testTSAMFactors.cpp +++ b/gtsam_unstable/slam/tests/testTSAMFactors.cpp @@ -19,10 +19,9 @@ #include #include -#include #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -48,10 +47,10 @@ TEST( DeltaFactor, all ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; H1Expected = numericalDerivative11( - boost::bind(&DeltaFactor::evaluateError, &factor, _1, point, boost::none, + std::bind(&DeltaFactor::evaluateError, &factor, std::placeholders::_1, point, boost::none, boost::none), pose); H2Expected = numericalDerivative11( - boost::bind(&DeltaFactor::evaluateError, &factor, pose, _1, boost::none, + std::bind(&DeltaFactor::evaluateError, &factor, pose, std::placeholders::_1, boost::none, boost::none), point); // Verify the Jacobians are correct @@ -82,17 +81,17 @@ TEST( DeltaFactorBase, all ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected, H3Expected, H4Expected; H1Expected = numericalDerivative11( - boost::bind(&DeltaFactorBase::evaluateError, &factor, _1, pose, base2, + std::bind(&DeltaFactorBase::evaluateError, &factor, std::placeholders::_1, pose, base2, point, boost::none, boost::none, boost::none, boost::none), base1); H2Expected = numericalDerivative11( - boost::bind(&DeltaFactorBase::evaluateError, &factor, base1, _1, base2, + std::bind(&DeltaFactorBase::evaluateError, &factor, base1, std::placeholders::_1, base2, point, boost::none, boost::none, boost::none, boost::none), pose); H3Expected = numericalDerivative11( - boost::bind(&DeltaFactorBase::evaluateError, &factor, base1, pose, _1, + std::bind(&DeltaFactorBase::evaluateError, &factor, base1, pose, std::placeholders::_1, point, boost::none, boost::none, boost::none, boost::none), base2); H4Expected = numericalDerivative11( - boost::bind(&DeltaFactorBase::evaluateError, &factor, base1, pose, base2, - _1, boost::none, boost::none, boost::none, boost::none), point); + std::bind(&DeltaFactorBase::evaluateError, &factor, base1, pose, base2, + std::placeholders::_1, boost::none, boost::none, boost::none, boost::none), point); // Verify the Jacobians are correct EXPECT(assert_equal(H1Expected, H1Actual, 1e-9)); @@ -123,17 +122,17 @@ TEST( OdometryFactorBase, all ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected, H3Expected, H4Expected; H1Expected = numericalDerivative11( - boost::bind(&OdometryFactorBase::evaluateError, &factor, _1, pose1, base2, + std::bind(&OdometryFactorBase::evaluateError, &factor, std::placeholders::_1, pose1, base2, pose2, boost::none, boost::none, boost::none, boost::none), base1); H2Expected = numericalDerivative11( - boost::bind(&OdometryFactorBase::evaluateError, &factor, base1, _1, base2, + std::bind(&OdometryFactorBase::evaluateError, &factor, base1, std::placeholders::_1, base2, pose2, boost::none, boost::none, boost::none, boost::none), pose1); H3Expected = numericalDerivative11( - boost::bind(&OdometryFactorBase::evaluateError, &factor, base1, pose1, _1, + std::bind(&OdometryFactorBase::evaluateError, &factor, base1, pose1, std::placeholders::_1, pose2, boost::none, boost::none, boost::none, boost::none), base2); H4Expected = numericalDerivative11( - boost::bind(&OdometryFactorBase::evaluateError, &factor, base1, pose1, - base2, _1, boost::none, boost::none, boost::none, boost::none), + std::bind(&OdometryFactorBase::evaluateError, &factor, base1, pose1, + base2, std::placeholders::_1, boost::none, boost::none, boost::none, boost::none), pose2); // Verify the Jacobians are correct diff --git a/gtsam_unstable/slam/tests/testTransformBtwRobotsUnaryFactor.cpp b/gtsam_unstable/slam/tests/testTransformBtwRobotsUnaryFactor.cpp index d9e945b78c..36914f88f2 100644 --- a/gtsam_unstable/slam/tests/testTransformBtwRobotsUnaryFactor.cpp +++ b/gtsam_unstable/slam/tests/testTransformBtwRobotsUnaryFactor.cpp @@ -18,9 +18,7 @@ #include #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -233,7 +231,7 @@ TEST( TransformBtwRobotsUnaryFactor, Jacobian) Matrix H1_actual = H_actual[0]; double stepsize = 1.0e-9; - Matrix H1_expected = gtsam::numericalDerivative11(boost::bind(&predictionError, _1, key, g), orgA_T_orgB, stepsize); + Matrix H1_expected = gtsam::numericalDerivative11(std::bind(&predictionError, std::placeholders::_1, key, g), orgA_T_orgB, stepsize); // CHECK( assert_equal(H1_expected, H1_actual, 1e-5)); } @@ -287,12 +285,12 @@ TEST( TransformBtwRobotsUnaryFactor, Jacobian) //// CHECK( assert_equal(H2_actual_stnd, H2_actual, 1e-8)); // // double stepsize = 1.0e-9; -// Matrix H1_expected = gtsam::numericalDerivative11(boost::bind(&predictionError, _1, p2, keyA, keyB, f), p1, stepsize); -// Matrix H2_expected = gtsam::numericalDerivative11(boost::bind(&predictionError, p1, _1, keyA, keyB, f), p2, stepsize); +// Matrix H1_expected = gtsam::numericalDerivative11(std::bind(&predictionError, std::placeholders::_1, p2, keyA, keyB, f), p1, stepsize); +// Matrix H2_expected = gtsam::numericalDerivative11(std::bind(&predictionError, p1, std::placeholders::_1, keyA, keyB, f), p2, stepsize); // // // // try to check numerical derivatives of a standard between factor -// Matrix H1_expected_stnd = gtsam::numericalDerivative11(boost::bind(&predictionError_standard, _1, p2, keyA, keyB, h), p1, stepsize); +// Matrix H1_expected_stnd = gtsam::numericalDerivative11(std::bind(&predictionError_standard, std::placeholders::_1, p2, keyA, keyB, h), p1, stepsize); // CHECK( assert_equal(H1_expected_stnd, H1_actual_stnd, 1e-5)); // // diff --git a/gtsam_unstable/slam/tests/testTransformBtwRobotsUnaryFactorEM.cpp b/gtsam_unstable/slam/tests/testTransformBtwRobotsUnaryFactorEM.cpp index 2fd282091a..657a9fb348 100644 --- a/gtsam_unstable/slam/tests/testTransformBtwRobotsUnaryFactorEM.cpp +++ b/gtsam_unstable/slam/tests/testTransformBtwRobotsUnaryFactorEM.cpp @@ -18,9 +18,7 @@ #include #include -#include - -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -262,8 +260,10 @@ TEST( TransformBtwRobotsUnaryFactorEM, Jacobian) Matrix H1_actual = H_actual[0]; double stepsize = 1.0e-9; - Matrix H1_expected = gtsam::numericalDerivative11(boost::bind(&predictionError, _1, key, g), orgA_T_orgB, stepsize); -// CHECK( assert_equal(H1_expected, H1_actual, 1e-5)); + Matrix H1_expected = gtsam::numericalDerivative11( + std::bind(&predictionError, std::placeholders::_1, key, g), orgA_T_orgB, + stepsize); + // CHECK( assert_equal(H1_expected, H1_actual, 1e-5)); } /////* ************************************************************************** */ //TEST (TransformBtwRobotsUnaryFactorEM, jacobian ) { @@ -312,12 +312,12 @@ TEST( TransformBtwRobotsUnaryFactorEM, Jacobian) //// CHECK( assert_equal(H2_actual_stnd, H2_actual, 1e-8)); // // double stepsize = 1.0e-9; -// Matrix H1_expected = gtsam::numericalDerivative11(boost::bind(&predictionError, _1, p2, keyA, keyB, f), p1, stepsize); -// Matrix H2_expected = gtsam::numericalDerivative11(boost::bind(&predictionError, p1, _1, keyA, keyB, f), p2, stepsize); +// Matrix H1_expected = gtsam::numericalDerivative11(std::bind(&predictionError, std::placeholders::_1, p2, keyA, keyB, f), p1, stepsize); +// Matrix H2_expected = gtsam::numericalDerivative11(std::bind(&predictionError, p1, std::placeholders::_1, keyA, keyB, f), p2, stepsize); // // // // try to check numerical derivatives of a standard between factor -// Matrix H1_expected_stnd = gtsam::numericalDerivative11(boost::bind(&predictionError_standard, _1, p2, keyA, keyB, h), p1, stepsize); +// Matrix H1_expected_stnd = gtsam::numericalDerivative11(std::bind(&predictionError_standard, std::placeholders::_1, p2, keyA, keyB, h), p1, stepsize); // CHECK( assert_equal(H1_expected_stnd, H1_actual_stnd, 1e-5)); // // diff --git a/tests/testExpressionFactor.cpp b/tests/testExpressionFactor.cpp index 6bb5751bf6..e9eac22ebb 100644 --- a/tests/testExpressionFactor.cpp +++ b/tests/testExpressionFactor.cpp @@ -17,22 +17,19 @@ * @brief unit tests for Block Automatic Differentiation */ -#include -#include -#include -#include -#include +#include +#include #include #include +#include #include -#include - -#include +#include +#include +#include #include using boost::assign::list_of; -#include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; using namespace gtsam; @@ -621,9 +618,10 @@ TEST(ExpressionFactor, MultiplyWithInverseFunction) { Matrix3 A; const Vector Ab = f(a, b, H1, A); CHECK(assert_equal(A * b, Ab)); - CHECK(assert_equal(numericalDerivative11( - boost::bind(f, _1, b, boost::none, boost::none), a), - H1)); + CHECK(assert_equal( + numericalDerivative11( + std::bind(f, std::placeholders::_1, b, boost::none, boost::none), a), + H1)); Values values; values.insert(0, a); diff --git a/tests/testSimulated3D.cpp b/tests/testSimulated3D.cpp index 342c353bca..2bc381f7a4 100644 --- a/tests/testSimulated3D.cpp +++ b/tests/testSimulated3D.cpp @@ -26,7 +26,7 @@ #include -using namespace boost::placeholders; +using namespace std::placeholders; using namespace gtsam; // Convenience for named keys @@ -46,7 +46,7 @@ TEST( simulated3D, Values ) TEST( simulated3D, Dprior ) { Point3 x(1,-9, 7); - Matrix numerical = numericalDerivative11(boost::bind(simulated3D::prior, _1, boost::none),x); + Matrix numerical = numericalDerivative11(std::bind(simulated3D::prior, std::placeholders::_1, boost::none),x); Matrix computed; simulated3D::prior(x,computed); EXPECT(assert_equal(numerical,computed,1e-9)); @@ -55,13 +55,19 @@ TEST( simulated3D, Dprior ) /* ************************************************************************* */ TEST( simulated3D, DOdo ) { - Point3 x1(1,-9,7),x2(-5,6,7); - Matrix H1,H2; - simulated3D::odo(x1,x2,H1,H2); - Matrix A1 = numericalDerivative21(boost::bind(simulated3D::odo, _1, _2, boost::none, boost::none),x1,x2); - EXPECT(assert_equal(A1,H1,1e-9)); - Matrix A2 = numericalDerivative22(boost::bind(simulated3D::odo, _1, _2, boost::none, boost::none),x1,x2); - EXPECT(assert_equal(A2,H2,1e-9)); + Point3 x1(1, -9, 7), x2(-5, 6, 7); + Matrix H1, H2; + simulated3D::odo(x1, x2, H1, H2); + Matrix A1 = numericalDerivative21( + std::bind(simulated3D::odo, std::placeholders::_1, std::placeholders::_2, + boost::none, boost::none), + x1, x2); + EXPECT(assert_equal(A1, H1, 1e-9)); + Matrix A2 = numericalDerivative22( + std::bind(simulated3D::odo, std::placeholders::_1, std::placeholders::_2, + boost::none, boost::none), + x1, x2); + EXPECT(assert_equal(A2, H2, 1e-9)); }