diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index a3a14c6c3..013947bbd 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -29,7 +29,7 @@ #include #include -#include +#include #include #include @@ -489,7 +489,7 @@ struct MultiplyWithInverseFunction { // The function phi should calculate f(a)*b, with derivatives in a and b. // Naturally, the derivative in b is f(a). - typedef boost::function, OptionalJacobian)> Operator; diff --git a/gtsam/base/Testable.h b/gtsam/base/Testable.h index e8cdbd8e0..6062c7ae1 100644 --- a/gtsam/base/Testable.h +++ b/gtsam/base/Testable.h @@ -34,8 +34,9 @@ #pragma once #include -#include +#include #include +#include #include #define GTSAM_PRINT(x)((x).print(#x)) @@ -119,10 +120,10 @@ namespace gtsam { * Binary predicate on shared pointers */ template - struct equals_star : public std::function&, const boost::shared_ptr&)> { + struct equals_star : public std::function&, const std::shared_ptr&)> { double tol_; equals_star(double tol = 1e-9) : tol_(tol) {} - bool operator()(const boost::shared_ptr& expected, const boost::shared_ptr& actual) { + bool operator()(const std::shared_ptr& expected, const std::shared_ptr& actual) { if (!actual && !expected) return true; return actual && expected && traits::Equals(*actual,*expected, tol_); } diff --git a/gtsam/base/lieProxies.h b/gtsam/base/lieProxies.h index 820fc7333..c811eb58a 100644 --- a/gtsam/base/lieProxies.h +++ b/gtsam/base/lieProxies.h @@ -24,7 +24,7 @@ * * These should not be used outside of tests, as they are just remappings * of the original functions. We use these to avoid needing to do - * too much boost::bind magic or writing a bunch of separate proxy functions. + * too much std::bind magic or writing a bunch of separate proxy functions. * * Don't expect all classes to work for all of these functions. */ diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index c624c900e..05b60033f 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -18,8 +18,7 @@ // \callgraph #pragma once -#include -#include +#include #include #include @@ -38,13 +37,13 @@ namespace gtsam { * for a function with one relevant param and an optional derivative: * Foo bar(const Obj& a, boost::optional H1) * Use boost.bind to restructure: - * boost::bind(bar, boost::placeholders::_1, boost::none) + * std::bind(bar, std::placeholders::_1, boost::none) * This syntax will fix the optional argument to boost::none, while using the first argument provided * * For member functions, such as below, with an instantiated copy instanceOfSomeClass * Foo SomeClass::bar(const Obj& a) * Use boost bind as follows to create a function pointer that uses the member function: - * boost::bind(&SomeClass::bar, ref(instanceOfSomeClass), boost::placeholders::_1) + * std::bind(&SomeClass::bar, ref(instanceOfSomeClass), std::placeholders::_1) * * For additional details, see the documentation: * http://www.boost.org/doc/libs/release/libs/bind/bind.html @@ -69,7 +68,7 @@ struct FixedSizeMatrix { template ::dimension> typename Eigen::Matrix numericalGradient( - boost::function h, const X& x, double delta = 1e-5) { + std::function h, const X& x, double delta = 1e-5) { double factor = 1.0 / (2.0 * delta); BOOST_STATIC_ASSERT_MSG( @@ -109,7 +108,7 @@ typename Eigen::Matrix numericalGradient( template ::dimension> // TODO Should compute fixed-size matrix typename internal::FixedSizeMatrix::type numericalDerivative11( - boost::function h, const X& x, double delta = 1e-5) { + std::function h, const X& x, double delta = 1e-5) { typedef typename internal::FixedSizeMatrix::type Matrix; BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), @@ -150,7 +149,7 @@ typename internal::FixedSizeMatrix::type numericalDerivative11( template typename internal::FixedSizeMatrix::type numericalDerivative11(Y (*h)(const X&), const X& x, double delta = 1e-5) { - return numericalDerivative11(boost::bind(h, boost::placeholders::_1), x, + return numericalDerivative11(std::bind(h, std::placeholders::_1), x, delta); } @@ -164,14 +163,14 @@ typename internal::FixedSizeMatrix::type numericalDerivative11(Y (*h)(const * @tparam int N is the dimension of the X1 input value if variable dimension type but known at test time */ template::dimension> -typename internal::FixedSizeMatrix::type numericalDerivative21(const boost::function& h, +typename internal::FixedSizeMatrix::type numericalDerivative21(const std::function& h, const X1& x1, const X2& x2, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::placeholders::_1, boost::cref(x2)), x1, delta); + std::bind(h, std::placeholders::_1, std::cref(x2)), x1, delta); } /** use a raw C++ function pointer */ @@ -179,7 +178,7 @@ template typename internal::FixedSizeMatrix::type numericalDerivative21(Y (*h)(const X1&, const X2&), const X1& x1, const X2& x2, double delta = 1e-5) { return numericalDerivative21( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2), x1, x2, + std::bind(h, std::placeholders::_1, std::placeholders::_2), x1, x2, delta); } @@ -193,14 +192,14 @@ typename internal::FixedSizeMatrix::type numericalDerivative21(Y (*h)(cons * @tparam int N is the dimension of the X2 input value if variable dimension type but known at test time */ template::dimension> -typename internal::FixedSizeMatrix::type numericalDerivative22(boost::function h, +typename internal::FixedSizeMatrix::type numericalDerivative22(std::function h, const X1& x1, const X2& x2, double delta = 1e-5) { // BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), // "Template argument X1 must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X2 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::placeholders::_1), x2, delta); + std::bind(h, std::cref(x1), std::placeholders::_1), x2, delta); } /** use a raw C++ function pointer */ @@ -208,7 +207,7 @@ template typename internal::FixedSizeMatrix::type numericalDerivative22(Y (*h)(const X1&, const X2&), const X1& x1, const X2& x2, double delta = 1e-5) { return numericalDerivative22( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2), x1, x2, + std::bind(h, std::placeholders::_1, std::placeholders::_2), x1, x2, delta); } @@ -225,14 +224,14 @@ typename internal::FixedSizeMatrix::type numericalDerivative22(Y (*h)(cons */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative31( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::placeholders::_1, boost::cref(x2), boost::cref(x3)), + std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3)), x1, delta); } @@ -240,8 +239,8 @@ template typename internal::FixedSizeMatrix::type numericalDerivative31(Y (*h)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalDerivative31( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3), x1, x2, x3, delta); } @@ -258,14 +257,14 @@ typename internal::FixedSizeMatrix::type numericalDerivative31(Y (*h)(cons */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative32( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X2 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::placeholders::_1, boost::cref(x3)), + std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3)), x2, delta); } @@ -273,8 +272,8 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative32(Y (*h)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalDerivative32( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3), x1, x2, x3, delta); } @@ -291,14 +290,14 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative32(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative33( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X3 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::placeholders::_1), + std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1), x3, delta); } @@ -306,8 +305,8 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative33(Y (*h)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalDerivative33( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3), x1, x2, x3, delta); } @@ -324,15 +323,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative33(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative41( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::placeholders::_1, boost::cref(x2), boost::cref(x3), - boost::cref(x4)), + std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3), + std::cref(x4)), x1, delta); } @@ -340,8 +339,8 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative41(Y (*h)(const X1&, const X2&, const X3&, const X4&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { return numericalDerivative41( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4), x1, x2, x3, x4); } @@ -358,15 +357,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative41(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative42( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X2 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::placeholders::_1, boost::cref(x3), - boost::cref(x4)), + std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3), + std::cref(x4)), x2, delta); } @@ -374,8 +373,8 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative42(Y (*h)(const X1&, const X2&, const X3&, const X4&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { return numericalDerivative42( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4), x1, x2, x3, x4); } @@ -392,15 +391,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative42(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative43( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X3 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::placeholders::_1, - boost::cref(x4)), + std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1, + std::cref(x4)), x3, delta); } @@ -408,8 +407,8 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative43(Y (*h)(const X1&, const X2&, const X3&, const X4&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { return numericalDerivative43( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4), x1, x2, x3, x4); } @@ -426,15 +425,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative43(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative44( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X4 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), - boost::placeholders::_1), + std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), + std::placeholders::_1), x4, delta); } @@ -442,8 +441,8 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative44(Y (*h)(const X1&, const X2&, const X3&, const X4&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { return numericalDerivative44( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4), x1, x2, x3, x4); } @@ -461,15 +460,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative44(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative51( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::placeholders::_1, boost::cref(x2), boost::cref(x3), - boost::cref(x4), boost::cref(x5)), + std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3), + std::cref(x4), std::cref(x5)), x1, delta); } @@ -477,9 +476,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative51(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { return numericalDerivative51( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5), x1, x2, x3, x4, x5); } @@ -497,15 +496,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative51(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative52( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::placeholders::_1, boost::cref(x3), - boost::cref(x4), boost::cref(x5)), + std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3), + std::cref(x4), std::cref(x5)), x2, delta); } @@ -513,9 +512,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative52(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { return numericalDerivative52( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5), x1, x2, x3, x4, x5); } @@ -533,15 +532,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative52(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative53( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::placeholders::_1, - boost::cref(x4), boost::cref(x5)), + std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1, + std::cref(x4), std::cref(x5)), x3, delta); } @@ -549,9 +548,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative53(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { return numericalDerivative53( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5), x1, x2, x3, x4, x5); } @@ -569,15 +568,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative53(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative54( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), - boost::placeholders::_1, boost::cref(x5)), + std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), + std::placeholders::_1, std::cref(x5)), x4, delta); } @@ -585,9 +584,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative54(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { return numericalDerivative54( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5), x1, x2, x3, x4, x5); } @@ -605,15 +604,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative54(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative55( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), - boost::cref(x4), boost::placeholders::_1), + std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), + std::cref(x4), std::placeholders::_1), x5, delta); } @@ -621,9 +620,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative55(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { return numericalDerivative55( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5), x1, x2, x3, x4, x5); } @@ -642,15 +641,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative55(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative61( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::placeholders::_1, boost::cref(x2), boost::cref(x3), - boost::cref(x4), boost::cref(x5), boost::cref(x6)), + std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3), + std::cref(x4), std::cref(x5), std::cref(x6)), x1, delta); } @@ -658,9 +657,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative61(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { return numericalDerivative61( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5, boost::placeholders::_6), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5, std::placeholders::_6), x1, x2, x3, x4, x5, x6); } @@ -679,15 +678,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative61(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative62( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::placeholders::_1, boost::cref(x3), - boost::cref(x4), boost::cref(x5), boost::cref(x6)), + std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3), + std::cref(x4), std::cref(x5), std::cref(x6)), x2, delta); } @@ -695,9 +694,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative62(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { return numericalDerivative62( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5, boost::placeholders::_6), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5, std::placeholders::_6), x1, x2, x3, x4, x5, x6); } @@ -716,15 +715,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative62(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative63( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::placeholders::_1, - boost::cref(x4), boost::cref(x5), boost::cref(x6)), + std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1, + std::cref(x4), std::cref(x5), std::cref(x6)), x3, delta); } @@ -732,9 +731,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative63(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { return numericalDerivative63( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5, boost::placeholders::_6), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5, std::placeholders::_6), x1, x2, x3, x4, x5, x6); } @@ -753,15 +752,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative63(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative64( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), - boost::placeholders::_1, boost::cref(x5), boost::cref(x6)), + std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), + std::placeholders::_1, std::cref(x5), std::cref(x6)), x4, delta); } @@ -769,9 +768,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative64(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { return numericalDerivative64( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5, boost::placeholders::_6), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5, std::placeholders::_6), x1, x2, x3, x4, x5, x6); } @@ -790,15 +789,15 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative64(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative65( - boost::function h, const X1& x1, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), - boost::cref(x4), boost::placeholders::_1, boost::cref(x6)), + std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), + std::cref(x4), std::placeholders::_1, std::cref(x6)), x5, delta); } @@ -806,9 +805,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative65(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { return numericalDerivative65( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5, boost::placeholders::_6), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5, std::placeholders::_6), x1, x2, x3, x4, x5, x6); } @@ -827,7 +826,7 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative65(Y (* */ template::dimension> typename internal::FixedSizeMatrix::type numericalDerivative66( - boost::function h, + std::function h, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), @@ -835,8 +834,8 @@ typename internal::FixedSizeMatrix::type numericalDerivative66( BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X1 must be a manifold type."); return numericalDerivative11( - boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), - boost::cref(x4), boost::cref(x5), boost::placeholders::_1), + std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), + std::cref(x4), std::cref(x5), std::placeholders::_1), x6, delta); } @@ -844,9 +843,9 @@ template inline typename internal::FixedSizeMatrix::type numericalDerivative66(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&), const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { return numericalDerivative66( - boost::bind(h, boost::placeholders::_1, boost::placeholders::_2, - boost::placeholders::_3, boost::placeholders::_4, - boost::placeholders::_5, boost::placeholders::_6), + std::bind(h, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, + std::placeholders::_5, std::placeholders::_6), x1, x2, x3, x4, x5, x6); } @@ -859,22 +858,22 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative66(Y (* * @return n*n Hessian matrix computed via central differencing */ template -inline typename internal::FixedSizeMatrix::type numericalHessian(boost::function f, const X& x, +inline typename internal::FixedSizeMatrix::type numericalHessian(std::function f, const X& x, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X must be a manifold type."); typedef Eigen::Matrix::dimension, 1> VectorD; - typedef boost::function F; - typedef boost::function G; + typedef std::function F; + typedef std::function G; G ng = static_cast(numericalGradient ); return numericalDerivative11( - boost::bind(ng, f, boost::placeholders::_1, delta), x, delta); + std::bind(ng, f, std::placeholders::_1, delta), x, delta); } template inline typename internal::FixedSizeMatrix::type numericalHessian(double (*f)(const X&), const X& x, double delta = 1e-5) { - return numericalHessian(boost::function(f), x, delta); + return numericalHessian(std::function(f), x, delta); } /** Helper class that computes the derivative of f w.r.t. x1, centered about @@ -882,86 +881,86 @@ inline typename internal::FixedSizeMatrix::type numericalHessian(double (*f */ template class G_x1 { - const boost::function& f_; + const std::function& f_; X1 x1_; double delta_; public: typedef typename internal::FixedSizeMatrix::type Vector; - G_x1(const boost::function& f, const X1& x1, + G_x1(const std::function& f, const X1& x1, double delta) : f_(f), x1_(x1), delta_(delta) { } Vector operator()(const X2& x2) { return numericalGradient( - boost::bind(f_, boost::placeholders::_1, boost::cref(x2)), x1_, delta_); + std::bind(f_, std::placeholders::_1, std::cref(x2)), x1_, delta_); } }; template inline typename internal::FixedSizeMatrix::type numericalHessian212( - boost::function f, const X1& x1, const X2& x2, + std::function f, const X1& x1, const X2& x2, double delta = 1e-5) { typedef typename internal::FixedSizeMatrix::type Vector; G_x1 g_x1(f, x1, delta); return numericalDerivative11( - boost::function( - boost::bind(boost::ref(g_x1), boost::placeholders::_1)), + std::function( + std::bind(std::ref(g_x1), std::placeholders::_1)), x2, delta); } template inline typename internal::FixedSizeMatrix::type numericalHessian212(double (*f)(const X1&, const X2&), const X1& x1, const X2& x2, double delta = 1e-5) { - return numericalHessian212(boost::function(f), + return numericalHessian212(std::function(f), x1, x2, delta); } template inline typename internal::FixedSizeMatrix::type numericalHessian211( - boost::function f, const X1& x1, const X2& x2, + std::function f, const X1& x1, const X2& x2, double delta = 1e-5) { typedef typename internal::FixedSizeMatrix::type Vector; - Vector (*numGrad)(boost::function, const X1&, + Vector (*numGrad)(std::function, const X1&, double) = &numericalGradient; - boost::function f2( - boost::bind(f, boost::placeholders::_1, boost::cref(x2))); + std::function f2( + std::bind(f, std::placeholders::_1, std::cref(x2))); return numericalDerivative11( - boost::function( - boost::bind(numGrad, f2, boost::placeholders::_1, delta)), + std::function( + std::bind(numGrad, f2, std::placeholders::_1, delta)), x1, delta); } template inline typename internal::FixedSizeMatrix::type numericalHessian211(double (*f)(const X1&, const X2&), const X1& x1, const X2& x2, double delta = 1e-5) { - return numericalHessian211(boost::function(f), + return numericalHessian211(std::function(f), x1, x2, delta); } template inline typename internal::FixedSizeMatrix::type numericalHessian222( - boost::function f, const X1& x1, const X2& x2, + std::function f, const X1& x1, const X2& x2, double delta = 1e-5) { typedef typename internal::FixedSizeMatrix::type Vector; - Vector (*numGrad)(boost::function, const X2&, + Vector (*numGrad)(std::function, const X2&, double) = &numericalGradient; - boost::function f2( - boost::bind(f, boost::cref(x1), boost::placeholders::_1)); + std::function f2( + std::bind(f, std::cref(x1), std::placeholders::_1)); return numericalDerivative11( - boost::function( - boost::bind(numGrad, f2, boost::placeholders::_1, delta)), + std::function( + std::bind(numGrad, f2, std::placeholders::_1, delta)), x2, delta); } template inline typename internal::FixedSizeMatrix::type numericalHessian222(double (*f)(const X1&, const X2&), const X1& x1, const X2& x2, double delta = 1e-5) { - return numericalHessian222(boost::function(f), + return numericalHessian222(std::function(f), x1, x2, delta); } @@ -971,17 +970,17 @@ inline typename internal::FixedSizeMatrix::type numericalHessian222(doubl /* **************************************************************** */ template inline typename internal::FixedSizeMatrix::type numericalHessian311( - boost::function f, const X1& x1, + std::function f, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { typedef typename internal::FixedSizeMatrix::type Vector; - Vector (*numGrad)(boost::function, const X1&, + Vector (*numGrad)(std::function, const X1&, double) = &numericalGradient; - boost::function f2(boost::bind( - f, boost::placeholders::_1, boost::cref(x2), boost::cref(x3))); + std::function f2(std::bind( + f, std::placeholders::_1, std::cref(x2), std::cref(x3))); return numericalDerivative11( - boost::function( - boost::bind(numGrad, f2, boost::placeholders::_1, delta)), + std::function( + std::bind(numGrad, f2, std::placeholders::_1, delta)), x1, delta); } @@ -989,24 +988,24 @@ template inline typename internal::FixedSizeMatrix::type numericalHessian311(double (*f)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian311( - boost::function(f), x1, x2, x3, + std::function(f), x1, x2, x3, delta); } /* **************************************************************** */ template inline typename internal::FixedSizeMatrix::type numericalHessian322( - boost::function f, const X1& x1, + std::function f, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { typedef typename internal::FixedSizeMatrix::type Vector; - Vector (*numGrad)(boost::function, const X2&, + Vector (*numGrad)(std::function, const X2&, double) = &numericalGradient; - boost::function f2(boost::bind( - f, boost::cref(x1), boost::placeholders::_1, boost::cref(x3))); + std::function f2(std::bind( + f, std::cref(x1), std::placeholders::_1, std::cref(x3))); return numericalDerivative11( - boost::function( - boost::bind(numGrad, f2, boost::placeholders::_1, delta)), + std::function( + std::bind(numGrad, f2, std::placeholders::_1, delta)), x2, delta); } @@ -1014,24 +1013,24 @@ template inline typename internal::FixedSizeMatrix::type numericalHessian322(double (*f)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian322( - boost::function(f), x1, x2, x3, + std::function(f), x1, x2, x3, delta); } /* **************************************************************** */ template inline typename internal::FixedSizeMatrix::type numericalHessian333( - boost::function f, const X1& x1, + std::function f, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { typedef typename internal::FixedSizeMatrix::type Vector; - Vector (*numGrad)(boost::function, const X3&, + Vector (*numGrad)(std::function, const X3&, double) = &numericalGradient; - boost::function f2(boost::bind( - f, boost::cref(x1), boost::cref(x2), boost::placeholders::_1)); + std::function f2(std::bind( + f, std::cref(x1), std::cref(x2), std::placeholders::_1)); return numericalDerivative11( - boost::function( - boost::bind(numGrad, f2, boost::placeholders::_1, delta)), + std::function( + std::bind(numGrad, f2, std::placeholders::_1, delta)), x3, delta); } @@ -1039,41 +1038,41 @@ template inline typename internal::FixedSizeMatrix::type numericalHessian333(double (*f)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian333( - boost::function(f), x1, x2, x3, + std::function(f), x1, x2, x3, delta); } /* **************************************************************** */ template inline typename internal::FixedSizeMatrix::type numericalHessian312( - boost::function f, const X1& x1, + std::function f, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian212( - boost::function( - boost::bind(f, boost::placeholders::_1, boost::placeholders::_2, - boost::cref(x3))), + std::function( + std::bind(f, std::placeholders::_1, std::placeholders::_2, + std::cref(x3))), x1, x2, delta); } template inline typename internal::FixedSizeMatrix::type numericalHessian313( - boost::function f, const X1& x1, + std::function f, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian212( - boost::function( - boost::bind(f, boost::placeholders::_1, boost::cref(x2), - boost::placeholders::_2)), + std::function( + std::bind(f, std::placeholders::_1, std::cref(x2), + std::placeholders::_2)), x1, x3, delta); } template inline typename internal::FixedSizeMatrix::type numericalHessian323( - boost::function f, const X1& x1, + std::function f, const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian212( - boost::function( - boost::bind(f, boost::cref(x1), boost::placeholders::_1, - boost::placeholders::_2)), + std::function( + std::bind(f, std::cref(x1), std::placeholders::_1, + std::placeholders::_2)), x2, x3, delta); } @@ -1082,7 +1081,7 @@ template inline typename internal::FixedSizeMatrix::type numericalHessian312(double (*f)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian312( - boost::function(f), x1, x2, x3, + std::function(f), x1, x2, x3, delta); } @@ -1090,7 +1089,7 @@ template inline typename internal::FixedSizeMatrix::type numericalHessian313(double (*f)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian313( - boost::function(f), x1, x2, x3, + std::function(f), x1, x2, x3, delta); } @@ -1098,7 +1097,7 @@ template inline typename internal::FixedSizeMatrix::type numericalHessian323(double (*f)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) { return numericalHessian323( - boost::function(f), x1, x2, x3, + std::function(f), x1, x2, x3, delta); } diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 80b226e3a..439889ebf 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -450,7 +450,7 @@ namespace gtsam { template template DecisionTree::DecisionTree(const DecisionTree& other, - const std::map& map, boost::function op) { + const std::map& map, std::function op) { root_ = convert(other.root_, map, op); } @@ -568,7 +568,7 @@ namespace gtsam { template typename DecisionTree::NodePtr DecisionTree::convert( const typename DecisionTree::NodePtr& f, const std::map& map, - boost::function op) { + std::function op) { typedef DecisionTree MX; typedef typename MX::Leaf MXLeaf; diff --git a/gtsam/discrete/DecisionTree.h b/gtsam/discrete/DecisionTree.h index ecf03ad5d..0ee0b8be0 100644 --- a/gtsam/discrete/DecisionTree.h +++ b/gtsam/discrete/DecisionTree.h @@ -20,10 +20,12 @@ #pragma once #include + #include +#include #include -#include #include +#include namespace gtsam { @@ -38,8 +40,8 @@ namespace gtsam { public: /** Handy typedefs for unary and binary function types */ - typedef boost::function Unary; - typedef boost::function Binary; + typedef std::function Unary; + typedef std::function Binary; /** A label annotated with cardinality */ typedef std::pair LabelC; @@ -107,7 +109,7 @@ namespace gtsam { /** Convert to a different type */ template NodePtr convert(const typename DecisionTree::NodePtr& f, const std::map& map, boost::function op); + L>& map, std::function op); /** Default constructor */ DecisionTree(); @@ -143,7 +145,7 @@ namespace gtsam { /** Convert from a different type */ template DecisionTree(const DecisionTree& other, - const std::map& map, boost::function op); + const std::map& map, std::function op); /// @} /// @name Testable diff --git a/gtsam/geometry/Cyclic.h b/gtsam/geometry/Cyclic.h index 0b81ff0f9..35578ffe0 100644 --- a/gtsam/geometry/Cyclic.h +++ b/gtsam/geometry/Cyclic.h @@ -17,7 +17,9 @@ #include #include -#include // for cout :-( + +#include +#include // for cout :-( namespace gtsam { diff --git a/gtsam/inference/EliminateableFactorGraph.h b/gtsam/inference/EliminateableFactorGraph.h index 316ca8ee4..edc4883e7 100644 --- a/gtsam/inference/EliminateableFactorGraph.h +++ b/gtsam/inference/EliminateableFactorGraph.h @@ -19,7 +19,7 @@ #pragma once #include -#include +#include #include #include @@ -86,7 +86,7 @@ namespace gtsam { typedef std::pair, boost::shared_ptr<_FactorType> > EliminationResult; /// The function type that does a single dense elimination step on a subgraph. - typedef boost::function Eliminate; + typedef std::function Eliminate; /// Typedef for an optional variable index as an argument to elimination functions typedef boost::optional OptionalVariableIndex; diff --git a/gtsam/inference/LabeledSymbol.cpp b/gtsam/inference/LabeledSymbol.cpp index 17ff6fd22..6a1739e20 100644 --- a/gtsam/inference/LabeledSymbol.cpp +++ b/gtsam/inference/LabeledSymbol.cpp @@ -15,15 +15,12 @@ * @author: Alex Cunningham */ -#include - -#include -#include - -#include - #include +#include +#include +#include + namespace gtsam { using namespace std; @@ -109,17 +106,37 @@ bool LabeledSymbol::operator!=(gtsam::Key comp) const { /* ************************************************************************* */ static LabeledSymbol make(gtsam::Key key) { return LabeledSymbol(key);} -boost::function LabeledSymbol::TypeTest(unsigned char c) { - return boost::bind(&LabeledSymbol::chr, boost::bind(make, boost::placeholders::_1)) == c; +std::function LabeledSymbol::TypeTest(unsigned char c) { + // Use lambda function to check equality + auto equals = [](unsigned char s, unsigned char c) { return s == c; }; + return std::bind( + equals, + std::bind(&LabeledSymbol::chr, std::bind(make, std::placeholders::_1)), + c); } -boost::function LabeledSymbol::LabelTest(unsigned char label) { - return boost::bind(&LabeledSymbol::label, boost::bind(make, boost::placeholders::_1)) == label; +std::function LabeledSymbol::LabelTest(unsigned char label) { + // Use lambda function to check equality + auto equals = [](unsigned char s, unsigned char c) { return s == c; }; + return std::bind( + equals, + std::bind(&LabeledSymbol::label, std::bind(make, std::placeholders::_1)), + label); } -boost::function LabeledSymbol::TypeLabelTest(unsigned char c, unsigned char label) { - return boost::bind(&LabeledSymbol::chr, boost::bind(make, boost::placeholders::_1)) == c && - boost::bind(&LabeledSymbol::label, boost::bind(make, boost::placeholders::_1)) == label; +std::function LabeledSymbol::TypeLabelTest(unsigned char c, unsigned char label) { + // Use lambda functions for && and == + auto logical_and = [](bool is_type, bool is_label) { return is_type == is_label; }; + auto equals = [](unsigned char s, unsigned char c) { return s == c; }; + return std::bind(logical_and, + std::bind(equals, + std::bind(&LabeledSymbol::chr, + std::bind(make, std::placeholders::_1)), + c), + std::bind(equals, + std::bind(&LabeledSymbol::label, + std::bind(make, std::placeholders::_1)), + label)); } /* ************************************************************************* */ diff --git a/gtsam/inference/LabeledSymbol.h b/gtsam/inference/LabeledSymbol.h index 15a2a2501..5aee4a0e2 100644 --- a/gtsam/inference/LabeledSymbol.h +++ b/gtsam/inference/LabeledSymbol.h @@ -19,8 +19,8 @@ #pragma once +#include #include -#include namespace gtsam { @@ -89,13 +89,13 @@ public: */ // Checks only the type - static boost::function TypeTest(unsigned char c); + static std::function TypeTest(unsigned char c); // Checks only the robot ID (label_) - static boost::function LabelTest(unsigned char label); + static std::function LabelTest(unsigned char label); // Checks both type and the robot ID - static boost::function TypeLabelTest(unsigned char c, unsigned char label); + static std::function TypeLabelTest(unsigned char c, unsigned char label); // Converts to upper/lower versions of labels LabeledSymbol upper() const { return LabeledSymbol(c_, toupper(label_), j_); } diff --git a/gtsam/inference/Symbol.cpp b/gtsam/inference/Symbol.cpp index 61e397f40..925ba9ce3 100644 --- a/gtsam/inference/Symbol.cpp +++ b/gtsam/inference/Symbol.cpp @@ -62,8 +62,11 @@ Symbol::operator std::string() const { static Symbol make(gtsam::Key key) { return Symbol(key);} -boost::function Symbol::ChrTest(unsigned char c) { - return boost::bind(&Symbol::chr, boost::bind(make, boost::placeholders::_1)) == c; +std::function Symbol::ChrTest(unsigned char c) { + auto equals = [](unsigned char s, unsigned char c) { return s == c; }; + return std::bind( + equals, std::bind(&Symbol::chr, std::bind(make, std::placeholders::_1)), + c); } GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const Symbol &symbol) { diff --git a/gtsam/inference/Symbol.h b/gtsam/inference/Symbol.h index 89fb0d161..017d5134a 100644 --- a/gtsam/inference/Symbol.h +++ b/gtsam/inference/Symbol.h @@ -18,11 +18,12 @@ #pragma once -#include #include +#include + #include -#include #include +#include namespace gtsam { @@ -114,7 +115,7 @@ public: * Values::filter() function to retrieve all key-value pairs with the * requested character. */ - static boost::function ChrTest(unsigned char c); + static std::function ChrTest(unsigned char c); /// Output stream operator that can be used with key_formatter (see Key.h). GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const Symbol &); diff --git a/gtsam/linear/VectorValues.cpp b/gtsam/linear/VectorValues.cpp index f72799c0a..6a2514b35 100644 --- a/gtsam/linear/VectorValues.cpp +++ b/gtsam/linear/VectorValues.cpp @@ -38,8 +38,8 @@ namespace gtsam { { // Merge using predicate for comparing first of pair merge(first.begin(), first.end(), second.begin(), second.end(), inserter(values_, values_.end()), - boost::bind(&less::operator(), less(), boost::bind(&KeyValuePair::first, boost::placeholders::_1), - boost::bind(&KeyValuePair::first, boost::placeholders::_2))); + std::bind(&less::operator(), less(), std::bind(&KeyValuePair::first, std::placeholders::_1), + std::bind(&KeyValuePair::first, std::placeholders::_2))); if(size() != first.size() + second.size()) throw invalid_argument("Requested to merge two VectorValues that have one or more variables in common."); } diff --git a/gtsam/nonlinear/Expression-inl.h b/gtsam/nonlinear/Expression-inl.h index 85f2f14bc..cf2462dfc 100644 --- a/gtsam/nonlinear/Expression-inl.h +++ b/gtsam/nonlinear/Expression-inl.h @@ -83,8 +83,8 @@ template Expression::Expression(const Expression& expression, T (A::*method)(typename MakeOptionalJacobian::type) const) : root_( - new internal::UnaryExpression(boost::bind(method, - boost::placeholders::_1, boost::placeholders::_2), + new internal::UnaryExpression(std::bind(method, + std::placeholders::_1, std::placeholders::_2), expression)) { } @@ -97,9 +97,9 @@ Expression::Expression(const Expression& expression1, const Expression& expression2) : root_( new internal::BinaryExpression( - boost::bind(method, boost::placeholders::_1, - boost::placeholders::_2, boost::placeholders::_3, - boost::placeholders::_4), + std::bind(method, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3, + std::placeholders::_4), expression1, expression2)) { } @@ -114,10 +114,10 @@ Expression::Expression(const Expression& expression1, const Expression& expression2, const Expression& expression3) : root_( new internal::TernaryExpression( - boost::bind(method, boost::placeholders::_1, - boost::placeholders::_2, boost::placeholders::_3, - boost::placeholders::_4, boost::placeholders::_5, - boost::placeholders::_6), + std::bind(method, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3, + std::placeholders::_4, std::placeholders::_5, + std::placeholders::_6), expression1, expression2, expression3)) { } @@ -255,9 +255,9 @@ template Expression operator*(const Expression& expression1, const Expression& expression2) { return Expression( - boost::bind(internal::apply_compose(), boost::placeholders::_1, - boost::placeholders::_2, boost::placeholders::_3, - boost::placeholders::_4), + std::bind(internal::apply_compose(), std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3, + std::placeholders::_4), expression1, expression2); } diff --git a/gtsam/nonlinear/Expression.h b/gtsam/nonlinear/Expression.h index bda457595..eb828760d 100644 --- a/gtsam/nonlinear/Expression.h +++ b/gtsam/nonlinear/Expression.h @@ -68,20 +68,20 @@ public: // Expression::BinaryFunction,Point3>::type template struct UnaryFunction { - typedef boost::function< + typedef std::function< T(const A1&, typename MakeOptionalJacobian::type)> type; }; template struct BinaryFunction { - typedef boost::function< + typedef std::function< T(const A1&, const A2&, typename MakeOptionalJacobian::type, typename MakeOptionalJacobian::type)> type; }; template struct TernaryFunction { - typedef boost::function< + typedef std::function< T(const A1&, const A2&, const A3&, typename MakeOptionalJacobian::type, typename MakeOptionalJacobian::type, @@ -239,7 +239,7 @@ class BinarySumExpression : public Expression { */ template Expression linearExpression( - const boost::function& f, const Expression& expression, + const std::function& f, const Expression& expression, const Eigen::Matrix::dimension, traits::dimension>& dTdA) { // Use lambda to endow f with a linear Jacobian typename Expression::template UnaryFunction::type g = diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index f10ba93ae..6b9972156 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -69,7 +69,7 @@ public: /** * Function that compares two values */ - typedef boost::function CompareFunction; + typedef std::function CompareFunction; CompareFunction compare_; // bool (*compare_)(const T& a, const T& b); @@ -87,8 +87,8 @@ public: * Constructor - forces exact evaluation */ NonlinearEquality(Key j, const T& feasible, - const CompareFunction &_compare = boost::bind(traits::Equals, - boost::placeholders::_1, boost::placeholders::_2, 1e-9)) : + const CompareFunction &_compare = std::bind(traits::Equals, + std::placeholders::_1, std::placeholders::_2, 1e-9)) : Base(noiseModel::Constrained::All(traits::GetDimension(feasible)), j), feasible_(feasible), allow_error_(false), error_gain_(0.0), // compare_(_compare) { @@ -98,8 +98,8 @@ public: * Constructor - allows inexact evaluation */ NonlinearEquality(Key j, const T& feasible, double error_gain, - const CompareFunction &_compare = boost::bind(traits::Equals, - boost::placeholders::_1, boost::placeholders::_2, 1e-9)) : + const CompareFunction &_compare = std::bind(traits::Equals, + std::placeholders::_1, std::placeholders::_2, 1e-9)) : Base(noiseModel::Constrained::All(traits::GetDimension(feasible)), j), feasible_(feasible), allow_error_(true), error_gain_(error_gain), // compare_(_compare) { diff --git a/gtsam/nonlinear/Values-inl.h b/gtsam/nonlinear/Values-inl.h index eca7416c9..8ebdcab17 100644 --- a/gtsam/nonlinear/Values-inl.h +++ b/gtsam/nonlinear/Values-inl.h @@ -103,7 +103,7 @@ namespace gtsam { boost::transform_iterator< KeyValuePair(*)(Values::KeyValuePair), boost::filter_iterator< - boost::function, + std::function, Values::iterator> > iterator; @@ -113,7 +113,7 @@ namespace gtsam { boost::transform_iterator< ConstKeyValuePair(*)(Values::ConstKeyValuePair), boost::filter_iterator< - boost::function, + std::function, Values::const_iterator> > const_const_iterator; @@ -134,7 +134,7 @@ namespace gtsam { private: Filtered( - const boost::function& filter, + const std::function& filter, Values& values) : begin_( boost::make_transform_iterator( @@ -205,7 +205,7 @@ namespace gtsam { const_iterator begin_; const_iterator end_; ConstFiltered( - const boost::function& filter, + const std::function& filter, const Values& values) { // We remove the const from values to create a non-const Filtered // view, then pull the const_iterators out of it. @@ -236,35 +236,35 @@ namespace gtsam { /* ************************************************************************* */ Values::Filtered - inline Values::filter(const boost::function& filterFcn) { + inline Values::filter(const std::function& filterFcn) { return filter(filterFcn); } /* ************************************************************************* */ template Values::Filtered - Values::filter(const boost::function& filterFcn) { - return Filtered(boost::bind(&filterHelper, filterFcn, - boost::placeholders::_1), *this); + Values::filter(const std::function& filterFcn) { + return Filtered(std::bind(&filterHelper, filterFcn, + std::placeholders::_1), *this); } /* ************************************************************************* */ Values::ConstFiltered - inline Values::filter(const boost::function& filterFcn) const { + inline Values::filter(const std::function& filterFcn) const { return filter(filterFcn); } /* ************************************************************************* */ template Values::ConstFiltered - Values::filter(const boost::function& filterFcn) const { - return ConstFiltered(boost::bind(&filterHelper, - filterFcn, boost::placeholders::_1), *this); + Values::filter(const std::function& filterFcn) const { + return ConstFiltered(std::bind(&filterHelper, + filterFcn, std::placeholders::_1), *this); } /* ************************************************************************* */ template<> - inline bool Values::filterHelper(const boost::function filter, + inline bool Values::filterHelper(const std::function filter, const ConstKeyValuePair& key_value) { // Filter and check the type return filter(key_value.key); diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 3b447ede1..33e9e7d82 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -108,19 +108,19 @@ namespace gtsam { /// Mutable forward iterator, with value type KeyValuePair typedef boost::transform_iterator< - boost::function1, KeyValueMap::iterator> iterator; + std::function, KeyValueMap::iterator> iterator; /// Const forward iterator, with value type ConstKeyValuePair typedef boost::transform_iterator< - boost::function1, KeyValueMap::const_iterator> const_iterator; + std::function, KeyValueMap::const_iterator> const_iterator; /// Mutable reverse iterator, with value type KeyValuePair typedef boost::transform_iterator< - boost::function1, KeyValueMap::reverse_iterator> reverse_iterator; + std::function, KeyValueMap::reverse_iterator> reverse_iterator; /// Const reverse iterator, with value type ConstKeyValuePair typedef boost::transform_iterator< - boost::function1, KeyValueMap::const_reverse_iterator> const_reverse_iterator; + std::function, KeyValueMap::const_reverse_iterator> const_reverse_iterator; typedef KeyValuePair value_type; @@ -321,7 +321,7 @@ namespace gtsam { * the original Values class. */ Filtered - filter(const boost::function& filterFcn); + filter(const std::function& filterFcn); /** * Return a filtered view of this Values class, without copying any data. @@ -344,7 +344,7 @@ namespace gtsam { */ template Filtered - filter(const boost::function& filterFcn = &_truePredicate); + filter(const std::function& filterFcn = &_truePredicate); /** * Return a filtered view of this Values class, without copying any data. @@ -360,7 +360,7 @@ namespace gtsam { * the original Values class. */ ConstFiltered - filter(const boost::function& filterFcn) const; + filter(const std::function& filterFcn) const; /** * Return a filtered view of this Values class, without copying any data. @@ -382,7 +382,7 @@ namespace gtsam { */ template ConstFiltered - filter(const boost::function& filterFcn = &_truePredicate) const; + filter(const std::function& filterFcn = &_truePredicate) const; // Count values of given type \c ValueType template @@ -399,7 +399,7 @@ namespace gtsam { // Filters based on ValueType (if not Value) and also based on the user- // supplied \c filter function. template - static bool filterHelper(const boost::function filter, const ConstKeyValuePair& key_value) { + static bool filterHelper(const std::function filter, const ConstKeyValuePair& key_value) { BOOST_STATIC_ASSERT((!boost::is_same::value)); // Filter and check the type return filter(key_value.key) && (dynamic_cast*>(&key_value.value)); diff --git a/gtsam/nonlinear/internal/ExpressionNode.h b/gtsam/nonlinear/internal/ExpressionNode.h index 2a1a07fb0..f6afb287e 100644 --- a/gtsam/nonlinear/internal/ExpressionNode.h +++ b/gtsam/nonlinear/internal/ExpressionNode.h @@ -57,7 +57,7 @@ T upAligned(T value, unsigned requiredAlignment = TraceAlignment) { * Expression node. The superclass for objects that do the heavy lifting * An Expression has a pointer to an ExpressionNode underneath * allowing Expressions to have polymorphic behaviour even though they - * are passed by value. This is the same way boost::function works. + * are passed by value. This is the same way std::function works. * http://loki-lib.sourceforge.net/html/a00652.html */ template diff --git a/gtsam_unstable/base/BTree.h b/gtsam_unstable/base/BTree.h index 96424324b..9d854a169 100644 --- a/gtsam_unstable/base/BTree.h +++ b/gtsam_unstable/base/BTree.h @@ -20,7 +20,7 @@ #include #include #include -#include +#include namespace gtsam { @@ -260,7 +260,7 @@ namespace gtsam { } /** iterate over tree */ - void iter(boost::function f) const { + void iter(std::function f) const { if (!root_) return; left().iter(f); f(key(), value()); @@ -269,7 +269,7 @@ namespace gtsam { /** map key-values in tree over function f that computes a new value */ template - BTree map(boost::function f) const { + BTree map(std::function f) const { if (empty()) return BTree (); std::pair xd(key(), f(key(), value())); return BTree (left().map(f), xd, right().map(f)); @@ -282,7 +282,7 @@ namespace gtsam { * The associated values are passed to [f] in reverse sort order */ template - ACC fold(boost::function f, + ACC fold(std::function f, const ACC& a) const { if (!root_) return a; ACC ar = right().fold(f, a); // fold over right subtree diff --git a/gtsam_unstable/base/DSF.h b/gtsam_unstable/base/DSF.h index c7b8cd417..4ad7d3ea8 100644 --- a/gtsam_unstable/base/DSF.h +++ b/gtsam_unstable/base/DSF.h @@ -122,7 +122,7 @@ public: } // maps f over all keys, must be invertible - DSF map(boost::function func) const { + DSF map(std::function func) const { DSF t; for(const KeyLabel& pair: (Tree)*this) t = t.add(func(pair.first), func(pair.second)); diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index 337f2bc43..9f00f81d6 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -91,9 +91,9 @@ public: z.segment(3, 3).operator=(gyro_); // Strange syntax to work around ambiguous operator error with clang z.tail(3).operator=(x2.t()); // Strange syntax to work around ambiguous operator error with clang if (H1) *H1 = numericalDerivative21( - boost::bind(This::predict_proxy, boost::placeholders::_1, boost::placeholders::_2, dt_), x1, x2, 1e-5); + std::bind(This::predict_proxy, std::placeholders::_1, std::placeholders::_2, dt_), x1, x2, 1e-5); if (H2) *H2 = numericalDerivative22( - boost::bind(This::predict_proxy, boost::placeholders::_1, boost::placeholders::_2, dt_), x1, x2, 1e-5); + std::bind(This::predict_proxy, std::placeholders::_1, std::placeholders::_2, dt_), x1, x2, 1e-5); return z - predict_proxy(x1, x2, dt_); } diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index e082dee82..9a742b4f0 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -81,9 +81,9 @@ public: boost::optional H2 = boost::none) const override { const Vector6 meas = z(); if (H1) *H1 = numericalDerivative21( - boost::bind(This::predict_proxy, boost::placeholders::_1, boost::placeholders::_2, dt_, meas), x1, x2, 1e-5); + std::bind(This::predict_proxy, std::placeholders::_1, std::placeholders::_2, dt_, meas), x1, x2, 1e-5); if (H2) *H2 = numericalDerivative22( - boost::bind(This::predict_proxy, boost::placeholders::_1, boost::placeholders::_2, dt_, meas), x1, x2, 1e-5); + std::bind(This::predict_proxy, std::placeholders::_1, std::placeholders::_2, dt_, meas), x1, x2, 1e-5); return predict_proxy(x1, x2, dt_, meas); } diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index 976f448c5..bf3b95c0f 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -166,24 +166,24 @@ public: boost::optional H3 = boost::none) const { if (H1) { (*H1) = numericalDerivative31( - boost::function( - boost::bind(&DiscreteEulerPoincareHelicopter::computeError, *this, _1, _2, _3) + std::function( + std::bind(&DiscreteEulerPoincareHelicopter::computeError, *this, _1, _2, _3) ), xik, xik_1, gk, 1e-5 ); } if (H2) { (*H2) = numericalDerivative32( - boost::function( - boost::bind(&DiscreteEulerPoincareHelicopter::computeError, *this, _1, _2, _3) + std::function( + std::bind(&DiscreteEulerPoincareHelicopter::computeError, *this, _1, _2, _3) ), xik, xik_1, gk, 1e-5 ); } if (H3) { (*H3) = numericalDerivative33( - boost::function( - boost::bind(&DiscreteEulerPoincareHelicopter::computeError, *this, _1, _2, _3) + std::function( + std::bind(&DiscreteEulerPoincareHelicopter::computeError, *this, _1, _2, _3) ), xik, xik_1, gk, 1e-5 ); diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index 840b7bba7..d24d06e79 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -86,11 +86,11 @@ public: boost::optional H1=boost::none, boost::optional H2=boost::none) const override { if (H1) *H1 = gtsam::numericalDerivative21( - boost::bind(VelocityConstraint::evaluateError_, boost::placeholders::_1, - boost::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5); + std::bind(VelocityConstraint::evaluateError_, std::placeholders::_1, + std::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5); if (H2) *H2 = gtsam::numericalDerivative22( - boost::bind(VelocityConstraint::evaluateError_, boost::placeholders::_1, - boost::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5); + std::bind(VelocityConstraint::evaluateError_, std::placeholders::_1, + std::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5); return evaluateError_(x1, x2, dt_, integration_mode_); } diff --git a/gtsam_unstable/linear/QPSParser.cpp b/gtsam_unstable/linear/QPSParser.cpp index 88697e075..c755f2451 100644 --- a/gtsam_unstable/linear/QPSParser.cpp +++ b/gtsam_unstable/linear/QPSParser.cpp @@ -24,7 +24,6 @@ #include #include -#include #include #include #include @@ -40,7 +39,7 @@ #include using boost::fusion::at_c; -using namespace boost::placeholders; +using namespace std::placeholders; using namespace std; namespace bf = boost::fusion; @@ -412,50 +411,50 @@ typedef qi::grammar> base_grammar; struct QPSParser::MPSGrammar : base_grammar { typedef std::vector Chars; QPSVisitor *rqp_; - boost::function const &)> setName; - boost::function const &)> + std::function const &)> setName; + std::function const &)> addRow; - boost::function const &)> rhsSingle; - boost::function)> rhsDouble; - boost::function const &)> rangeSingle; - boost::function)> rangeDouble; - boost::function)> colSingle; - boost::function const &)> colDouble; - boost::function const &)> addQuadTerm; - boost::function const &)> addBound; - boost::function const &)> addFreeBound; MPSGrammar(QPSVisitor *rqp) : base_grammar(start), rqp_(rqp), - setName(boost::bind(&QPSVisitor::setName, rqp, ::_1)), - addRow(boost::bind(&QPSVisitor::addRow, rqp, ::_1)), - rhsSingle(boost::bind(&QPSVisitor::addRHS, rqp, ::_1)), - rhsDouble(boost::bind(&QPSVisitor::addRHSDouble, rqp, ::_1)), - rangeSingle(boost::bind(&QPSVisitor::addRangeSingle, rqp, ::_1)), - rangeDouble(boost::bind(&QPSVisitor::addRangeDouble, rqp, ::_1)), - colSingle(boost::bind(&QPSVisitor::addColumn, rqp, ::_1)), - colDouble(boost::bind(&QPSVisitor::addColumnDouble, rqp, ::_1)), - addQuadTerm(boost::bind(&QPSVisitor::addQuadTerm, rqp, ::_1)), - addBound(boost::bind(&QPSVisitor::addBound, rqp, ::_1)), - addFreeBound(boost::bind(&QPSVisitor::addFreeBound, rqp, ::_1)) { + setName(std::bind(&QPSVisitor::setName, rqp, std::placeholders::_1)), + addRow(std::bind(&QPSVisitor::addRow, rqp, std::placeholders::_1)), + rhsSingle(std::bind(&QPSVisitor::addRHS, rqp, std::placeholders::_1)), + rhsDouble(std::bind(&QPSVisitor::addRHSDouble, rqp, std::placeholders::_1)), + rangeSingle(std::bind(&QPSVisitor::addRangeSingle, rqp, std::placeholders::_1)), + rangeDouble(std::bind(&QPSVisitor::addRangeDouble, rqp, std::placeholders::_1)), + colSingle(std::bind(&QPSVisitor::addColumn, rqp, std::placeholders::_1)), + colDouble(std::bind(&QPSVisitor::addColumnDouble, rqp, std::placeholders::_1)), + addQuadTerm(std::bind(&QPSVisitor::addQuadTerm, rqp, std::placeholders::_1)), + addBound(std::bind(&QPSVisitor::addBound, rqp, std::placeholders::_1)), + addFreeBound(std::bind(&QPSVisitor::addFreeBound, rqp, std::placeholders::_1)) { using namespace boost::spirit; using namespace boost::spirit::qi; character = lexeme[alnum | '_' | '-' | '.']; diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index a6638c1d7..cabbfdbe8 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -309,12 +309,12 @@ public: // Jacobian w.r.t. Pose1 if (H1){ Matrix H1_Pose = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, - this, boost::placeholders::_1, Vel1, Bias1, Pose2, Vel2), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, + this, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2), Pose1); Matrix H1_Vel = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, - this, boost::placeholders::_1, Vel1, Bias1, Pose2, Vel2), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, + this, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2), Pose1); *H1 = stack(2, &H1_Pose, &H1_Vel); } @@ -323,12 +323,12 @@ public: if (H2){ if (Vel1.size()!=3) throw std::runtime_error("Frank's hack to make this compile will not work if size != 3"); Matrix H2_Pose = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, - this, Pose1, boost::placeholders::_1, Bias1, Pose2, Vel2), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, + this, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2), Vel1); Matrix H2_Vel = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, - this, Pose1, boost::placeholders::_1, Bias1, Pose2, Vel2), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, + this, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2), Vel1); *H2 = stack(2, &H2_Pose, &H2_Vel); } @@ -336,12 +336,12 @@ public: // Jacobian w.r.t. IMUBias1 if (H3){ Matrix H3_Pose = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, - this, Pose1, Vel1, boost::placeholders::_1, Pose2, Vel2), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, + this, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2), Bias1); Matrix H3_Vel = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, - this, Pose1, Vel1, boost::placeholders::_1, Pose2, Vel2), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, + this, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2), Bias1); *H3 = stack(2, &H3_Pose, &H3_Vel); } @@ -349,12 +349,12 @@ public: // Jacobian w.r.t. Pose2 if (H4){ Matrix H4_Pose = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, - this, Pose1, Vel1, Bias1, boost::placeholders::_1, Vel2), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, + this, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2), Pose2); Matrix H4_Vel = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, - this, Pose1, Vel1, Bias1, boost::placeholders::_1, Vel2), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, + this, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2), Pose2); *H4 = stack(2, &H4_Pose, &H4_Vel); } @@ -363,12 +363,12 @@ public: if (H5){ if (Vel2.size()!=3) throw std::runtime_error("Frank's hack to make this compile will not work if size != 3"); Matrix H5_Pose = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, - this, Pose1, Vel1, Bias1, Pose2, boost::placeholders::_1), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluatePoseError, + this, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1), Vel2); Matrix H5_Vel = numericalDerivative11( - boost::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, - this, Pose1, Vel1, Bias1, Pose2, boost::placeholders::_1), + std::bind(&EquivInertialNavFactor_GlobalVel::evaluateVelocityError, + this, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1), Vel2); *H5 = stack(2, &H5_Pose, &H5_Vel); } @@ -469,43 +469,43 @@ public: Matrix I_3x3 = I_3x3; Matrix H_pos_pos = numericalDerivative11( - boost::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, - boost::placeholders::_1, delta_vel_in_t0), + std::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, + std::placeholders::_1, delta_vel_in_t0), delta_pos_in_t0); Matrix H_pos_vel = numericalDerivative11( - boost::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, - delta_pos_in_t0, boost::placeholders::_1), + std::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, + delta_pos_in_t0, std::placeholders::_1), delta_vel_in_t0); Matrix H_pos_angles = Z_3x3; Matrix H_pos_bias = collect(2, &Z_3x3, &Z_3x3); Matrix H_vel_vel = numericalDerivative11( - boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, - msr_acc_t, msr_dt, delta_angles, boost::placeholders::_1, + std::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, + msr_acc_t, msr_dt, delta_angles, std::placeholders::_1, flag_use_body_P_sensor, body_P_sensor, Bias_t0), delta_vel_in_t0); Matrix H_vel_angles = numericalDerivative11( - boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, - msr_acc_t, msr_dt, boost::placeholders::_1, delta_vel_in_t0, + std::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, + msr_acc_t, msr_dt, std::placeholders::_1, delta_vel_in_t0, flag_use_body_P_sensor, body_P_sensor, Bias_t0), delta_angles); Matrix H_vel_bias = numericalDerivative11( - boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, + std::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, delta_angles, delta_vel_in_t0, flag_use_body_P_sensor, body_P_sensor, - boost::placeholders::_1), + std::placeholders::_1), Bias_t0); Matrix H_vel_pos = Z_3x3; Matrix H_angles_angles = numericalDerivative11( - boost::bind(&PreIntegrateIMUObservations_delta_angles, msr_gyro_t, - msr_dt, boost::placeholders::_1, flag_use_body_P_sensor, + std::bind(&PreIntegrateIMUObservations_delta_angles, msr_gyro_t, + msr_dt, std::placeholders::_1, flag_use_body_P_sensor, body_P_sensor, Bias_t0), delta_angles); Matrix H_angles_bias = numericalDerivative11( - boost::bind(&PreIntegrateIMUObservations_delta_angles, msr_gyro_t, + std::bind(&PreIntegrateIMUObservations_delta_angles, msr_gyro_t, msr_dt, delta_angles, flag_use_body_P_sensor, body_P_sensor, - boost::placeholders::_1), + std::placeholders::_1), Bias_t0); Matrix H_angles_pos = Z_3x3; Matrix H_angles_vel = Z_3x3; diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index 40dc81c9a..0e2aebd7f 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -278,29 +278,29 @@ public: // TODO: Write analytical derivative calculations // Jacobian w.r.t. Pose1 if (H1){ - Matrix H1_Pose = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, _1, Vel1, Pose2, Vel2), Pose1); - Matrix H1_Vel = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, _1, Vel1, Pose2, Vel2), Pose1); + Matrix H1_Pose = numericalDerivative11(std::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, _1, Vel1, Pose2, Vel2), Pose1); + Matrix H1_Vel = numericalDerivative11(std::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, _1, Vel1, Pose2, Vel2), Pose1); *H1 = stack(2, &H1_Pose, &H1_Vel); } // Jacobian w.r.t. Vel1 if (H2){ - Matrix H2_Pose = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, _1, Pose2, Vel2), Vel1); - Matrix H2_Vel = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, _1, Pose2, Vel2), Vel1); + Matrix H2_Pose = numericalDerivative11(std::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, _1, Pose2, Vel2), Vel1); + Matrix H2_Vel = numericalDerivative11(std::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, _1, Pose2, Vel2), Vel1); *H2 = stack(2, &H2_Pose, &H2_Vel); } // Jacobian w.r.t. Pose2 if (H3){ - Matrix H3_Pose = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, Vel1, _1, Vel2), Pose2); - Matrix H3_Vel = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, Vel1, _1, Vel2), Pose2); + Matrix H3_Pose = numericalDerivative11(std::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, Vel1, _1, Vel2), Pose2); + Matrix H3_Vel = numericalDerivative11(std::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, Vel1, _1, Vel2), Pose2); *H3 = stack(2, &H3_Pose, &H3_Vel); } // Jacobian w.r.t. Vel2 if (H4){ - Matrix H4_Pose = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, Vel1, Pose2, _1), Vel2); - Matrix H4_Vel = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, Vel1, Pose2, _1), Vel2); + Matrix H4_Pose = numericalDerivative11(std::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, Vel1, Pose2, _1), Vel2); + Matrix H4_Vel = numericalDerivative11(std::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, Vel1, Pose2, _1), Vel2); *H4 = stack(2, &H4_Pose, &H4_Vel); } @@ -372,15 +372,15 @@ public: Matrix Z_3x3 = Z_3x3; Matrix I_3x3 = I_3x3; - Matrix H_pos_pos = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, _1, delta_vel_in_t0), delta_pos_in_t0); - Matrix H_pos_vel = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, delta_pos_in_t0, _1), delta_vel_in_t0); + Matrix H_pos_pos = numericalDerivative11(std::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, _1, delta_vel_in_t0), delta_pos_in_t0); + Matrix H_pos_vel = numericalDerivative11(std::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, delta_pos_in_t0, _1), delta_vel_in_t0); Matrix H_pos_angles = Z_3x3; - Matrix H_vel_vel = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, delta_angles, _1, flag_use_body_P_sensor, body_P_sensor), delta_vel_in_t0); - Matrix H_vel_angles = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, _1, delta_vel_in_t0, flag_use_body_P_sensor, body_P_sensor), delta_angles); + Matrix H_vel_vel = numericalDerivative11(std::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, delta_angles, _1, flag_use_body_P_sensor, body_P_sensor), delta_vel_in_t0); + Matrix H_vel_angles = numericalDerivative11(std::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, _1, delta_vel_in_t0, flag_use_body_P_sensor, body_P_sensor), delta_angles); Matrix H_vel_pos = Z_3x3; - Matrix H_angles_angles = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_angles, msr_gyro_t, msr_dt, _1, flag_use_body_P_sensor, body_P_sensor), delta_angles); + Matrix H_angles_angles = numericalDerivative11(std::bind(&PreIntegrateIMUObservations_delta_angles, msr_gyro_t, msr_dt, _1, flag_use_body_P_sensor, body_P_sensor), delta_angles); Matrix H_angles_pos = Z_3x3; Matrix H_angles_vel = Z_3x3; diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index 3f526e934..0828fbd08 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -236,12 +236,12 @@ public: // Jacobian w.r.t. Pose1 if (H1){ Matrix H1_Pose = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, - this, boost::placeholders::_1, Vel1, Bias1, Pose2, Vel2), + std::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, + this, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2), Pose1); Matrix H1_Vel = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, - this, boost::placeholders::_1, Vel1, Bias1, Pose2, Vel2), + std::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, + this, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2), Pose1); *H1 = stack(2, &H1_Pose, &H1_Vel); } @@ -250,12 +250,12 @@ public: if (H2){ if (Vel1.size()!=3) throw std::runtime_error("Frank's hack to make this compile will not work if size != 3"); Matrix H2_Pose = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, - this, Pose1, boost::placeholders::_1, Bias1, Pose2, Vel2), + std::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, + this, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2), Vel1); Matrix H2_Vel = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, - this, Pose1, boost::placeholders::_1, Bias1, Pose2, Vel2), + std::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, + this, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2), Vel1); *H2 = stack(2, &H2_Pose, &H2_Vel); } @@ -263,12 +263,12 @@ public: // Jacobian w.r.t. IMUBias1 if (H3){ Matrix H3_Pose = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, - this, Pose1, Vel1, boost::placeholders::_1, Pose2, Vel2), + std::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, + this, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2), Bias1); Matrix H3_Vel = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, - this, Pose1, Vel1, boost::placeholders::_1, Pose2, Vel2), + std::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, + this, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2), Bias1); *H3 = stack(2, &H3_Pose, &H3_Vel); } @@ -276,12 +276,12 @@ public: // Jacobian w.r.t. Pose2 if (H4){ Matrix H4_Pose = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, - this, Pose1, Vel1, Bias1, boost::placeholders::_1, Vel2), + std::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, + this, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2), Pose2); Matrix H4_Vel = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, - this, Pose1, Vel1, Bias1, boost::placeholders::_1, Vel2), + std::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, + this, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2), Pose2); *H4 = stack(2, &H4_Pose, &H4_Vel); } @@ -290,12 +290,12 @@ public: if (H5){ if (Vel2.size()!=3) throw std::runtime_error("Frank's hack to make this compile will not work if size != 3"); Matrix H5_Pose = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, - this, Pose1, Vel1, Bias1, Pose2, boost::placeholders::_1), + std::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, + this, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1), Vel2); Matrix H5_Vel = gtsam::numericalDerivative11( - boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, - this, Pose1, Vel1, Bias1, Pose2, boost::placeholders::_1), + std::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, + this, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1), Vel2); *H5 = stack(2, &H5_Pose, &H5_Vel); } diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index a9dcb8cef..40c09416c 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -108,14 +108,14 @@ public: if (H1) { (*H1) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant1::inverseDepthError, this, - boost::placeholders::_1, landmark), + std::bind(&InvDepthFactorVariant1::inverseDepthError, this, + std::placeholders::_1, landmark), pose); } if (H2) { (*H2) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant1::inverseDepthError, this, pose, - boost::placeholders::_1), landmark); + std::bind(&InvDepthFactorVariant1::inverseDepthError, this, pose, + std::placeholders::_1), landmark); } return inverseDepthError(pose, landmark); diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index d1fc92b90..b1169580e 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -111,13 +111,13 @@ public: if (H1) { (*H1) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant2::inverseDepthError, this, - boost::placeholders::_1, landmark), pose); + std::bind(&InvDepthFactorVariant2::inverseDepthError, this, + std::placeholders::_1, landmark), pose); } if (H2) { (*H2) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant2::inverseDepthError, this, pose, - boost::placeholders::_1), landmark); + std::bind(&InvDepthFactorVariant2::inverseDepthError, this, pose, + std::placeholders::_1), landmark); } return inverseDepthError(pose, landmark); diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index 4595a934b..98f2db2f3 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -111,14 +111,14 @@ public: if(H1) { (*H1) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant3a::inverseDepthError, this, - boost::placeholders::_1, landmark), + std::bind(&InvDepthFactorVariant3a::inverseDepthError, this, + std::placeholders::_1, landmark), pose); } if(H2) { (*H2) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant3a::inverseDepthError, this, pose, - boost::placeholders::_1), + std::bind(&InvDepthFactorVariant3a::inverseDepthError, this, pose, + std::placeholders::_1), landmark); } @@ -238,20 +238,20 @@ public: if(H1) (*H1) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, - boost::placeholders::_1, pose2, landmark), + std::bind(&InvDepthFactorVariant3b::inverseDepthError, this, + std::placeholders::_1, pose2, landmark), pose1); if(H2) (*H2) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1, - boost::placeholders::_1, landmark), + std::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1, + std::placeholders::_1, landmark), pose2); if(H3) (*H3) = numericalDerivative11( - boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1, - pose2, boost::placeholders::_1), + std::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1, + pose2, std::placeholders::_1), landmark); return inverseDepthError(pose1, pose2, landmark);