update boost::bind usage
use <boost/bind/bind.hpp> instead of deprecated <boost/bind.hpp> use boost::placeholders:: scope in appropriate files remove and add <boost/bind/bind.hpp> in appropriate filesrelease/4.3a0
parent
4b76601c00
commit
650e432f52
|
@ -19,14 +19,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/function.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#endif
|
||||
#include <boost/bind.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
#include <gtsam/linear/JacobianFactor.h>
|
||||
|
@ -45,13 +38,13 @@ namespace gtsam {
|
|||
* for a function with one relevant param and an optional derivative:
|
||||
* Foo bar(const Obj& a, boost::optional<Matrix&> H1)
|
||||
* Use boost.bind to restructure:
|
||||
* boost::bind(bar, _1, boost::none)
|
||||
* boost::bind(bar, boost::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), _1)
|
||||
* boost::bind(&SomeClass::bar, ref(instanceOfSomeClass), boost::placeholders::_1)
|
||||
*
|
||||
* For additional details, see the documentation:
|
||||
* http://www.boost.org/doc/libs/release/libs/bind/bind.html
|
||||
|
@ -157,7 +150,7 @@ typename internal::FixedSizeMatrix<Y, X>::type numericalDerivative11(
|
|||
template<class Y, class X>
|
||||
typename internal::FixedSizeMatrix<Y,X>::type numericalDerivative11(Y (*h)(const X&), const X& x,
|
||||
double delta = 1e-5) {
|
||||
return numericalDerivative11<Y, X>(boost::bind(h, _1), x, delta);
|
||||
return numericalDerivative11<Y, X>(boost::bind(h, boost::placeholders::_1), x, delta);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -176,13 +169,14 @@ typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative21(const boost
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, _1, boost::cref(x2)), x1, delta);
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, boost::placeholders::_1, boost::cref(x2)), x1, delta);
|
||||
}
|
||||
|
||||
/** use a raw C++ function pointer */
|
||||
template<class Y, class X1, class X2>
|
||||
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative21(Y (*h)(const X1&, const X2&), const X1& x1,
|
||||
const X2& x2, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative21<Y, X1, X2>(boost::bind(h, _1, _2), x1, x2, delta);
|
||||
}
|
||||
|
||||
|
@ -202,13 +196,14 @@ typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative22(boost::func
|
|||
// "Template argument X1 must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value),
|
||||
"Template argument X2 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), _1), x2, delta);
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), boost::placeholders::_1), x2, delta);
|
||||
}
|
||||
|
||||
/** use a raw C++ function pointer */
|
||||
template<class Y, class X1, class X2>
|
||||
typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative22(Y (*h)(const X1&, const X2&), const X1& x1,
|
||||
const X2& x2, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative22<Y, X1, X2>(boost::bind(h, _1, _2), x1, x2, delta);
|
||||
}
|
||||
|
||||
|
@ -231,12 +226,13 @@ typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative31(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, _1, boost::cref(x2), boost::cref(x3)), x1, delta);
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, boost::placeholders::_1, boost::cref(x2), boost::cref(x3)), x1, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3>
|
||||
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative31(Y (*h)(const X1&, const X2&, const X3&),
|
||||
const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative31<Y, X1, X2, X3>(boost::bind(h, _1, _2, _3), x1,
|
||||
x2, x3, delta);
|
||||
}
|
||||
|
@ -260,12 +256,13 @@ typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative32(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value),
|
||||
"Template argument X2 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), _1, boost::cref(x3)), x2, delta);
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), boost::placeholders::_1, boost::cref(x3)), x2, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3>
|
||||
inline typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative32(Y (*h)(const X1&, const X2&, const X3&),
|
||||
const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative32<Y, X1, X2, X3>(boost::bind(h, _1, _2, _3), x1,
|
||||
x2, x3, delta);
|
||||
}
|
||||
|
@ -289,12 +286,13 @@ typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative33(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X3>::structure_category>::value),
|
||||
"Template argument X3 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X3, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), _1), x3, delta);
|
||||
return numericalDerivative11<Y, X3, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::placeholders::_1), x3, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3>
|
||||
inline typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative33(Y (*h)(const X1&, const X2&, const X3&),
|
||||
const X1& x1, const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative33<Y, X1, X2, X3>(boost::bind(h, _1, _2, _3), x1,
|
||||
x2, x3, delta);
|
||||
}
|
||||
|
@ -318,12 +316,13 @@ typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative41(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, _1, boost::cref(x2), boost::cref(x3), boost::cref(x4)), x1, delta);
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, boost::placeholders::_1, boost::cref(x2), boost::cref(x3), boost::cref(x4)), x1, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4>
|
||||
inline typename internal::FixedSizeMatrix<Y,X1>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative41<Y, X1, X2, X3, X4>(boost::bind(h, _1, _2, _3, _4), x1, x2, x3, x4);
|
||||
}
|
||||
|
||||
|
@ -346,12 +345,13 @@ typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative42(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value),
|
||||
"Template argument X2 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), _1, boost::cref(x3), boost::cref(x4)), x2, delta);
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), boost::placeholders::_1, boost::cref(x3), boost::cref(x4)), x2, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4>
|
||||
inline typename internal::FixedSizeMatrix<Y,X2>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative42<Y, X1, X2, X3, X4>(boost::bind(h, _1, _2, _3, _4), x1, x2, x3, x4);
|
||||
}
|
||||
|
||||
|
@ -374,12 +374,13 @@ typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative43(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X3>::structure_category>::value),
|
||||
"Template argument X3 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X3, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), _1, boost::cref(x4)), x3, delta);
|
||||
return numericalDerivative11<Y, X3, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::placeholders::_1, boost::cref(x4)), x3, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4>
|
||||
inline typename internal::FixedSizeMatrix<Y,X3>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative43<Y, X1, X2, X3, X4>(boost::bind(h, _1, _2, _3, _4), x1, x2, x3, x4);
|
||||
}
|
||||
|
||||
|
@ -402,12 +403,13 @@ typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative44(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X4>::structure_category>::value),
|
||||
"Template argument X4 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X4, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), _1), x4, delta);
|
||||
return numericalDerivative11<Y, X4, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::placeholders::_1), x4, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4>
|
||||
inline typename internal::FixedSizeMatrix<Y,X4>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative44<Y, X1, X2, X3, X4>(boost::bind(h, _1, _2, _3, _4), x1, x2, x3, x4);
|
||||
}
|
||||
|
||||
|
@ -431,12 +433,13 @@ typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative51(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, _1, boost::cref(x2), boost::cref(x3), boost::cref(x4), boost::cref(x5)), x1, delta);
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, boost::placeholders::_1, boost::cref(x2), boost::cref(x3), boost::cref(x4), boost::cref(x5)), x1, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5>
|
||||
inline typename internal::FixedSizeMatrix<Y,X1>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative51<Y, X1, X2, X3, X4, X5>(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5);
|
||||
}
|
||||
|
||||
|
@ -460,12 +463,13 @@ typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative52(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), _1, boost::cref(x3), boost::cref(x4), boost::cref(x5)), x2, delta);
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), boost::placeholders::_1, boost::cref(x3), boost::cref(x4), boost::cref(x5)), x2, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5>
|
||||
inline typename internal::FixedSizeMatrix<Y,X2>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative52<Y, X1, X2, X3, X4, X5>(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5);
|
||||
}
|
||||
|
||||
|
@ -489,12 +493,13 @@ typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative53(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X3, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), _1, boost::cref(x4), boost::cref(x5)), x3, delta);
|
||||
return numericalDerivative11<Y, X3, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::placeholders::_1, boost::cref(x4), boost::cref(x5)), x3, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5>
|
||||
inline typename internal::FixedSizeMatrix<Y,X3>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative53<Y, X1, X2, X3, X4, X5>(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5);
|
||||
}
|
||||
|
||||
|
@ -518,12 +523,13 @@ typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative54(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X4, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), _1, boost::cref(x5)), x4, delta);
|
||||
return numericalDerivative11<Y, X4, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::placeholders::_1, boost::cref(x5)), x4, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5>
|
||||
inline typename internal::FixedSizeMatrix<Y,X4>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative54<Y, X1, X2, X3, X4, X5>(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5);
|
||||
}
|
||||
|
||||
|
@ -547,12 +553,13 @@ typename internal::FixedSizeMatrix<Y,X5>::type numericalDerivative55(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X5, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::cref(x4), _1), x5, delta);
|
||||
return numericalDerivative11<Y, X5, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::cref(x4), boost::placeholders::_1), x5, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5>
|
||||
inline typename internal::FixedSizeMatrix<Y,X5>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative55<Y, X1, X2, X3, X4, X5>(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5);
|
||||
}
|
||||
|
||||
|
@ -577,12 +584,13 @@ typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative61(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, _1, boost::cref(x2), boost::cref(x3), boost::cref(x4), boost::cref(x5), boost::cref(x6)), x1, delta);
|
||||
return numericalDerivative11<Y, X1, N>(boost::bind(h, boost::placeholders::_1, boost::cref(x2), boost::cref(x3), boost::cref(x4), boost::cref(x5), boost::cref(x6)), x1, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5, class X6>
|
||||
inline typename internal::FixedSizeMatrix<Y,X1>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative61<Y, X1, X2, X3, X4, X5, X6>(boost::bind(h, _1, _2, _3, _4, _5, _6), x1, x2, x3, x4, x5, x6);
|
||||
}
|
||||
|
||||
|
@ -607,12 +615,13 @@ typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative62(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), _1, boost::cref(x3), boost::cref(x4), boost::cref(x5), boost::cref(x6)), x2, delta);
|
||||
return numericalDerivative11<Y, X2, N>(boost::bind(h, boost::cref(x1), boost::placeholders::_1, boost::cref(x3), boost::cref(x4), boost::cref(x5), boost::cref(x6)), x2, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5, class X6>
|
||||
inline typename internal::FixedSizeMatrix<Y,X2>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative62<Y, X1, X2, X3, X4, X5, X6>(boost::bind(h, _1, _2, _3, _4, _5, _6), x1, x2, x3, x4, x5, x6);
|
||||
}
|
||||
|
||||
|
@ -637,12 +646,13 @@ typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative63(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X3, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), _1, boost::cref(x4), boost::cref(x5), boost::cref(x6)), x3, delta);
|
||||
return numericalDerivative11<Y, X3, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::placeholders::_1, boost::cref(x4), boost::cref(x5), boost::cref(x6)), x3, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5, class X6>
|
||||
inline typename internal::FixedSizeMatrix<Y,X3>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative63<Y, X1, X2, X3, X4, X5, X6>(boost::bind(h, _1, _2, _3, _4, _5, _6), x1, x2, x3, x4, x5, x6);
|
||||
}
|
||||
|
||||
|
@ -667,12 +677,13 @@ typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative64(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X4, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), _1, boost::cref(x5), boost::cref(x6)), x4, delta);
|
||||
return numericalDerivative11<Y, X4, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::placeholders::_1, boost::cref(x5), boost::cref(x6)), x4, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5, class X6>
|
||||
inline typename internal::FixedSizeMatrix<Y,X4>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative64<Y, X1, X2, X3, X4, X5>(boost::bind(h, _1, _2, _3, _4, _5, _6), x1, x2, x3, x4, x5, x6);
|
||||
}
|
||||
|
||||
|
@ -697,12 +708,13 @@ typename internal::FixedSizeMatrix<Y,X5>::type numericalDerivative65(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X5, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::cref(x4), _1, boost::cref(x6)), x5, delta);
|
||||
return numericalDerivative11<Y, X5, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::cref(x4), boost::placeholders::_1, boost::cref(x6)), x5, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5, class X6>
|
||||
inline typename internal::FixedSizeMatrix<Y,X5>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative65<Y, X1, X2, X3, X4, X5, X6>(boost::bind(h, _1, _2, _3, _4, _5, _6), x1, x2, x3, x4, x5, x6);
|
||||
}
|
||||
|
||||
|
@ -728,12 +740,13 @@ typename internal::FixedSizeMatrix<Y, X6>::type numericalDerivative66(
|
|||
"Template argument Y must be a manifold type.");
|
||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
|
||||
"Template argument X1 must be a manifold type.");
|
||||
return numericalDerivative11<Y, X6, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::cref(x4), boost::cref(x5), _1), x6, delta);
|
||||
return numericalDerivative11<Y, X6, N>(boost::bind(h, boost::cref(x1), boost::cref(x2), boost::cref(x3), boost::cref(x4), boost::cref(x5), boost::placeholders::_1), x6, delta);
|
||||
}
|
||||
|
||||
template<class Y, class X1, class X2, class X3, class X4, class X5, class X6>
|
||||
inline typename internal::FixedSizeMatrix<Y,X6>::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) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalDerivative66<Y, X1, X2, X3, X4, X5, X6>(boost::bind(h, _1, _2, _3, _4, _5, _6), x1, x2, x3, x4, x5, x6);
|
||||
}
|
||||
|
||||
|
@ -754,7 +767,7 @@ inline typename internal::FixedSizeMatrix<X,X>::type numericalHessian(boost::fun
|
|||
typedef boost::function<double(const X&)> F;
|
||||
typedef boost::function<VectorD(F, const X&, double)> G;
|
||||
G ng = static_cast<G>(numericalGradient<X> );
|
||||
return numericalDerivative11<VectorD, X>(boost::bind(ng, f, _1, delta), x,
|
||||
return numericalDerivative11<VectorD, X>(boost::bind(ng, f, boost::placeholders::_1, delta), x,
|
||||
delta);
|
||||
}
|
||||
|
||||
|
@ -780,7 +793,7 @@ public:
|
|||
f_(f), x1_(x1), delta_(delta) {
|
||||
}
|
||||
Vector operator()(const X2& x2) {
|
||||
return numericalGradient<X1>(boost::bind(f_, _1, boost::cref(x2)), x1_, delta_);
|
||||
return numericalGradient<X1>(boost::bind(f_, boost::placeholders::_1, boost::cref(x2)), x1_, delta_);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -792,7 +805,7 @@ inline typename internal::FixedSizeMatrix<X1,X2>::type numericalHessian212(
|
|||
G_x1<X1, X2> g_x1(f, x1, delta);
|
||||
return numericalDerivative11<Vector, X2>(
|
||||
boost::function<Vector(const X2&)>(
|
||||
boost::bind<Vector>(boost::ref(g_x1), _1)), x2, delta);
|
||||
boost::bind<Vector>(boost::ref(g_x1), boost::placeholders::_1)), x2, delta);
|
||||
}
|
||||
|
||||
template<class X1, class X2>
|
||||
|
@ -807,6 +820,7 @@ inline typename internal::FixedSizeMatrix<X1,X1>::type numericalHessian211(
|
|||
boost::function<double(const X1&, const X2&)> f, const X1& x1, const X2& x2,
|
||||
double delta = 1e-5) {
|
||||
|
||||
using namespace boost::placeholders;
|
||||
typedef typename internal::FixedSizeMatrix<X1>::type Vector;
|
||||
|
||||
Vector (*numGrad)(boost::function<double(const X1&)>, const X1&,
|
||||
|
@ -829,6 +843,7 @@ template<class X1, class X2>
|
|||
inline typename internal::FixedSizeMatrix<X2,X2>::type numericalHessian222(
|
||||
boost::function<double(const X1&, const X2&)> f, const X1& x1, const X2& x2,
|
||||
double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
typedef typename internal::FixedSizeMatrix<X2>::type Vector;
|
||||
Vector (*numGrad)(boost::function<double(const X2&)>, const X2&,
|
||||
double) = &numericalGradient<X2>;
|
||||
|
@ -854,6 +869,7 @@ template<class X1, class X2, class X3>
|
|||
inline typename internal::FixedSizeMatrix<X1,X1>::type numericalHessian311(
|
||||
boost::function<double(const X1&, const X2&, const X3&)> f, const X1& x1,
|
||||
const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
typedef typename internal::FixedSizeMatrix<X1>::type Vector;
|
||||
Vector (*numGrad)(boost::function<double(const X1&)>, const X1&,
|
||||
double) = &numericalGradient<X1>;
|
||||
|
@ -877,6 +893,7 @@ template<class X1, class X2, class X3>
|
|||
inline typename internal::FixedSizeMatrix<X2,X2>::type numericalHessian322(
|
||||
boost::function<double(const X1&, const X2&, const X3&)> f, const X1& x1,
|
||||
const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
typedef typename internal::FixedSizeMatrix<X2>::type Vector;
|
||||
Vector (*numGrad)(boost::function<double(const X2&)>, const X2&,
|
||||
double) = &numericalGradient<X2>;
|
||||
|
@ -900,6 +917,7 @@ template<class X1, class X2, class X3>
|
|||
inline typename internal::FixedSizeMatrix<X3,X3>::type numericalHessian333(
|
||||
boost::function<double(const X1&, const X2&, const X3&)> f, const X1& x1,
|
||||
const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
typedef typename internal::FixedSizeMatrix<X3>::type Vector;
|
||||
Vector (*numGrad)(boost::function<double(const X3&)>, const X3&,
|
||||
double) = &numericalGradient<X3>;
|
||||
|
@ -923,6 +941,7 @@ template<class X1, class X2, class X3>
|
|||
inline typename internal::FixedSizeMatrix<X1,X2>::type numericalHessian312(
|
||||
boost::function<double(const X1&, const X2&, const X3&)> f, const X1& x1,
|
||||
const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalHessian212<X1, X2>(
|
||||
boost::function<double(const X1&, const X2&)>(boost::bind(f, _1, _2, boost::cref(x3))),
|
||||
x1, x2, delta);
|
||||
|
@ -932,6 +951,7 @@ template<class X1, class X2, class X3>
|
|||
inline typename internal::FixedSizeMatrix<X1,X3>::type numericalHessian313(
|
||||
boost::function<double(const X1&, const X2&, const X3&)> f, const X1& x1,
|
||||
const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalHessian212<X1, X3>(
|
||||
boost::function<double(const X1&, const X3&)>(boost::bind(f, _1, boost::cref(x2), _2)),
|
||||
x1, x3, delta);
|
||||
|
@ -941,6 +961,7 @@ template<class X1, class X2, class X3>
|
|||
inline typename internal::FixedSizeMatrix<X2,X3>::type numericalHessian323(
|
||||
boost::function<double(const X1&, const X2&, const X3&)> f, const X1& x1,
|
||||
const X2& x2, const X3& x3, double delta = 1e-5) {
|
||||
using namespace boost::placeholders;
|
||||
return numericalHessian212<X2, X3>(
|
||||
boost::function<double(const X2&, const X3&)>(boost::bind(f, boost::cref(x1), _1, _2)),
|
||||
x2, x3, delta);
|
||||
|
|
|
@ -20,10 +20,12 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <iostream>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -20,7 +20,6 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
|
|
@ -9,9 +9,12 @@
|
|||
#include <gtsam/geometry/CalibratedCamera.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <sstream>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -21,8 +21,10 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::assign;
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
using namespace std;
|
||||
using boost::none;
|
||||
|
|
|
@ -22,11 +22,13 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <cmath>
|
||||
#include <iostream>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -20,7 +20,6 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
|
|
@ -17,8 +17,11 @@
|
|||
#include <gtsam/geometry/Point3.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
|
||||
GTSAM_CONCEPT_TESTABLE_INST(Point3)
|
||||
|
|
|
@ -22,6 +22,8 @@
|
|||
|
||||
#include <boost/assign/std/vector.hpp> // for operator +=
|
||||
using namespace boost::assign;
|
||||
#include <boost/bind/bind.hpp>
|
||||
using namespace boost::placeholders;
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <cmath>
|
||||
|
|
|
@ -20,8 +20,10 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/testLie.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -30,9 +30,10 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/function.hpp>
|
||||
#include <boost/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
using namespace std;
|
||||
using symbol_shorthand::X;
|
||||
|
|
|
@ -31,13 +31,14 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <cmath>
|
||||
#include <random>
|
||||
|
||||
using namespace boost::assign;
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
using namespace std;
|
||||
using gtsam::symbol_shorthand::U;
|
||||
|
|
|
@ -18,7 +18,6 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <boost/bind.hpp>
|
||||
#include <stack>
|
||||
|
||||
#include <gtsam/base/timing.h>
|
||||
|
|
|
@ -23,8 +23,6 @@
|
|||
|
||||
#include <gtsam/inference/FactorGraph.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <algorithm>
|
||||
#include <iostream> // for cout :-(
|
||||
|
|
|
@ -29,7 +29,6 @@
|
|||
#include <Eigen/Core> // for Eigen::aligned_allocator
|
||||
|
||||
#include <boost/assign/list_inserter.hpp>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/vector.hpp>
|
||||
|
|
|
@ -17,8 +17,8 @@
|
|||
|
||||
#include <iostream>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/format.hpp>
|
||||
#include <boost/bind.hpp>
|
||||
|
||||
#include <boost/lexical_cast.hpp>
|
||||
|
||||
|
@ -110,16 +110,16 @@ bool LabeledSymbol::operator!=(gtsam::Key comp) const {
|
|||
static LabeledSymbol make(gtsam::Key key) { return LabeledSymbol(key);}
|
||||
|
||||
boost::function<bool(gtsam::Key)> LabeledSymbol::TypeTest(unsigned char c) {
|
||||
return boost::bind(&LabeledSymbol::chr, boost::bind(make, _1)) == c;
|
||||
return boost::bind(&LabeledSymbol::chr, boost::bind(make, boost::placeholders::_1)) == c;
|
||||
}
|
||||
|
||||
boost::function<bool(gtsam::Key)> LabeledSymbol::LabelTest(unsigned char label) {
|
||||
return boost::bind(&LabeledSymbol::label, boost::bind(make, _1)) == label;
|
||||
return boost::bind(&LabeledSymbol::label, boost::bind(make, boost::placeholders::_1)) == label;
|
||||
}
|
||||
|
||||
boost::function<bool(gtsam::Key)> LabeledSymbol::TypeLabelTest(unsigned char c, unsigned char label) {
|
||||
return boost::bind(&LabeledSymbol::chr, boost::bind(make, _1)) == c &&
|
||||
boost::bind(&LabeledSymbol::label, boost::bind(make, _1)) == label;
|
||||
return boost::bind(&LabeledSymbol::chr, boost::bind(make, boost::placeholders::_1)) == c &&
|
||||
boost::bind(&LabeledSymbol::label, boost::bind(make, boost::placeholders::_1)) == label;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -18,8 +18,8 @@
|
|||
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/format.hpp>
|
||||
#include <boost/bind.hpp>
|
||||
|
||||
#include <limits.h>
|
||||
#include <list>
|
||||
|
@ -63,7 +63,7 @@ Symbol::operator std::string() const {
|
|||
static Symbol make(gtsam::Key key) { return Symbol(key);}
|
||||
|
||||
boost::function<bool(Key)> Symbol::ChrTest(unsigned char c) {
|
||||
return bind(&Symbol::chr, bind(make, _1)) == c;
|
||||
return boost::bind(&Symbol::chr, boost::bind(make, boost::placeholders::_1)) == c;
|
||||
}
|
||||
|
||||
GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const Symbol &symbol) {
|
||||
|
|
|
@ -20,7 +20,6 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/bind.hpp>
|
||||
#include <utility>
|
||||
|
||||
#include <gtsam/base/treeTraversal-inst.h>
|
||||
|
|
|
@ -32,14 +32,6 @@
|
|||
#include <boost/format.hpp>
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <boost/tuple/tuple.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#endif
|
||||
#include <boost/bind.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
#include <boost/assign/list_of.hpp>
|
||||
#include <boost/range/adaptor/transformed.hpp>
|
||||
#include <boost/range/adaptor/map.hpp>
|
||||
|
|
|
@ -35,14 +35,6 @@
|
|||
#include <boost/format.hpp>
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <boost/array.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#endif
|
||||
#include <boost/bind.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
#include <boost/range/algorithm/copy.hpp>
|
||||
#include <boost/range/adaptor/indirected.hpp>
|
||||
#include <boost/range/adaptor/map.hpp>
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/range/combine.hpp>
|
||||
#include <boost/range/numeric.hpp>
|
||||
#include <boost/range/adaptor/transformed.hpp>
|
||||
|
@ -38,7 +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<Key>::operator(), less<Key>(), boost::bind(&KeyValuePair::first, _1), boost::bind(&KeyValuePair::first, _2)));
|
||||
boost::bind(&less<Key>::operator(), less<Key>(), boost::bind(&KeyValuePair::first, boost::placeholders::_1),
|
||||
boost::bind(&KeyValuePair::first, boost::placeholders::_2)));
|
||||
if(size() != first.size() + second.size())
|
||||
throw invalid_argument("Requested to merge two VectorValues that have one or more variables in common.");
|
||||
}
|
||||
|
|
|
@ -26,6 +26,8 @@
|
|||
#include <boost/assign/list_of.hpp>
|
||||
#include <boost/assign/std/list.hpp> // for operator +=
|
||||
using namespace boost::assign;
|
||||
#include <boost/bind/bind.hpp>
|
||||
using namespace boost::placeholders;
|
||||
|
||||
// STL/C++
|
||||
#include <iostream>
|
||||
|
|
|
@ -22,6 +22,8 @@
|
|||
#include <boost/assign/std/list.hpp> // for operator +=
|
||||
#include <boost/assign/std/set.hpp> // for operator +=
|
||||
using namespace boost::assign;
|
||||
#include <boost/bind/bind.hpp>
|
||||
using namespace boost::placeholders;
|
||||
|
||||
#include <gtsam/base/debug.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
|
|
@ -25,9 +25,10 @@
|
|||
#include <gtsam/base/debug.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <list>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -21,8 +21,11 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/serialization.h>
|
||||
#include <gtsam/base/serializationTestHelpers.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -29,7 +29,6 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <list>
|
||||
|
||||
#include "imuFactorTesting.h"
|
||||
|
|
|
@ -20,11 +20,14 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <GeographicLib/Config.h>
|
||||
#include <GeographicLib/LocalCartesian.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace GeographicLib;
|
||||
|
|
|
@ -19,8 +19,9 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <list>
|
||||
|
||||
#include "imuFactorTesting.h"
|
||||
|
@ -147,7 +147,8 @@ TEST(ImuFactor, PreintegratedMeasurements) {
|
|||
Matrix96 aH3;
|
||||
actual.computeError(x1, x2, bias, aH1, aH2, aH3);
|
||||
boost::function<Vector9(const NavState&, const NavState&, const Bias&)> f =
|
||||
boost::bind(&PreintegrationBase::computeError, actual, _1, _2, _3,
|
||||
boost::bind(&PreintegrationBase::computeError, actual,
|
||||
boost::placeholders::_1, boost::placeholders::_2, boost::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));
|
||||
|
@ -203,20 +204,20 @@ TEST(ImuFactor, PreintegrationBaseMethods) {
|
|||
Matrix96 actualH;
|
||||
pim.biasCorrectedDelta(kZeroBias, actualH);
|
||||
Matrix expectedH = numericalDerivative11<Vector9, Bias>(
|
||||
boost::bind(&PreintegrationBase::biasCorrectedDelta, pim, _1,
|
||||
boost::none), kZeroBias);
|
||||
boost::bind(&PreintegrationBase::biasCorrectedDelta, pim,
|
||||
boost::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<NavState, NavState>(
|
||||
boost::bind(&PreintegrationBase::predict, pim, _1, kZeroBias, boost::none,
|
||||
boost::none), state1);
|
||||
boost::bind(&PreintegrationBase::predict, pim, boost::placeholders::_1,
|
||||
kZeroBias, boost::none, boost::none), state1);
|
||||
EXPECT(assert_equal(eH1, aH1));
|
||||
Matrix eH2 = numericalDerivative11<NavState, Bias>(
|
||||
boost::bind(&PreintegrationBase::predict, pim, state1, _1, boost::none,
|
||||
boost::none), kZeroBias);
|
||||
boost::bind(&PreintegrationBase::predict, pim, state1,
|
||||
boost::placeholders::_1, boost::none, boost::none), kZeroBias);
|
||||
EXPECT(assert_equal(eH2, aH2));
|
||||
}
|
||||
|
||||
|
@ -277,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<Rot3, Pose3>(
|
||||
boost::bind(&evaluateRotationError, factor, _1, v1, x2, v2, kZeroBias),
|
||||
boost::bind(&evaluateRotationError, factor, boost::placeholders::_1, v1, x2, v2, kZeroBias),
|
||||
x1);
|
||||
EXPECT(assert_equal(H1Rot3, H1a.topRows(3)));
|
||||
|
||||
Matrix H3Rot3 = numericalDerivative11<Rot3, Pose3>(
|
||||
boost::bind(&evaluateRotationError, factor, x1, v1, _1, v2, kZeroBias),
|
||||
boost::bind(&evaluateRotationError, factor, x1, v1, boost::placeholders::_1, v2, kZeroBias),
|
||||
x2);
|
||||
EXPECT(assert_equal(H3Rot3, H3a.topRows(3)));
|
||||
|
||||
|
@ -332,8 +333,8 @@ TEST(ImuFactor, ErrorAndJacobianWithBiases) {
|
|||
Matrix96 actualH;
|
||||
pim.biasCorrectedDelta(bias, actualH);
|
||||
Matrix expectedH = numericalDerivative11<Vector9, Bias>(
|
||||
boost::bind(&PreintegrationBase::biasCorrectedDelta, pim, _1,
|
||||
boost::none), bias);
|
||||
boost::bind(&PreintegrationBase::biasCorrectedDelta, pim,
|
||||
boost::placeholders::_1, boost::none), bias);
|
||||
EXPECT(assert_equal(expectedH, actualH));
|
||||
|
||||
// Create factor
|
||||
|
@ -521,7 +522,8 @@ TEST(ImuFactor, ErrorWithBiasesAndSensorBodyDisplacement) {
|
|||
pim.correctMeasurementsBySensorPose(measuredAcc, measuredOmega,
|
||||
boost::none, D_correctedAcc_measuredOmega, boost::none);
|
||||
Matrix3 expectedD = numericalDerivative11<Vector3, Vector3>(
|
||||
boost::bind(correctedAcc, pim, measuredAcc, _1), measuredOmega, 1e-6);
|
||||
boost::bind(correctedAcc, pim, measuredAcc, boost::placeholders::_1),
|
||||
measuredOmega, 1e-6);
|
||||
EXPECT(assert_equal(expectedD, D_correctedAcc_measuredOmega, 1e-5));
|
||||
|
||||
double dt = 0.1;
|
||||
|
@ -532,13 +534,15 @@ TEST(ImuFactor, ErrorWithBiasesAndSensorBodyDisplacement) {
|
|||
// pim.updatedDeltaXij(measuredAcc, measuredOmega, dt, boost::none, G1, G2);
|
||||
//
|
||||
// Matrix93 expectedG1 = numericalDerivative21<NavState, Vector3, Vector3>(
|
||||
// boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, _1, _2,
|
||||
// boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim,
|
||||
// boost::placeholders::_1, boost::placeholders::_2,
|
||||
// dt, boost::none, boost::none, boost::none), measuredAcc,
|
||||
// measuredOmega, 1e-6);
|
||||
// EXPECT(assert_equal(expectedG1, G1, 1e-5));
|
||||
//
|
||||
// Matrix93 expectedG2 = numericalDerivative22<NavState, Vector3, Vector3>(
|
||||
// boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, _1, _2,
|
||||
// boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim,
|
||||
// boost::placeholders::_1, boost::placeholders::_2,
|
||||
// dt, boost::none, boost::none, boost::none), measuredAcc,
|
||||
// measuredOmega, 1e-6);
|
||||
// EXPECT(assert_equal(expectedG2, G2, 1e-5));
|
||||
|
|
|
@ -20,10 +20,13 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <GeographicLib/LocalCartesian.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace GeographicLib;
|
||||
|
|
|
@ -17,6 +17,9 @@
|
|||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/navigation/MagPoseFactor.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
|
||||
// *****************************************************************************
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include <gtsam/nonlinear/expressionTesting.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include "imuFactorTesting.h"
|
||||
|
||||
|
@ -98,7 +98,9 @@ TEST(ManifoldPreintegration, computeError) {
|
|||
pim.computeError(x1, x2, bias, aH1, aH2, aH3);
|
||||
boost::function<Vector9(const NavState&, const NavState&,
|
||||
const imuBias::ConstantBias&)> f =
|
||||
boost::bind(&ManifoldPreintegration::computeError, pim, _1, _2, _3,
|
||||
boost::bind(&ManifoldPreintegration::computeError, pim,
|
||||
boost::placeholders::_1, boost::placeholders::_2,
|
||||
boost::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));
|
||||
|
|
|
@ -19,8 +19,11 @@
|
|||
#include <gtsam/navigation/NavState.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -19,9 +19,10 @@
|
|||
#include <gtsam/navigation/Scenario.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <cmath>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include <gtsam/nonlinear/expressionTesting.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include "imuFactorTesting.h"
|
||||
|
||||
|
@ -105,7 +105,9 @@ TEST(TangentPreintegration, computeError) {
|
|||
pim.computeError(x1, x2, bias, aH1, aH2, aH3);
|
||||
boost::function<Vector9(const NavState&, const NavState&,
|
||||
const imuBias::ConstantBias&)> f =
|
||||
boost::bind(&TangentPreintegration::computeError, pim, _1, _2, _3,
|
||||
boost::bind(&TangentPreintegration::computeError, pim,
|
||||
boost::placeholders::_1, boost::placeholders::_2,
|
||||
boost::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));
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
|
||||
#include <gtsam/nonlinear/internal/ExpressionNode.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/tuple/tuple.hpp>
|
||||
#include <boost/range/adaptor/map.hpp>
|
||||
#include <boost/range/algorithm.hpp>
|
||||
|
@ -82,7 +83,8 @@ template<typename A>
|
|||
Expression<T>::Expression(const Expression<A>& expression,
|
||||
T (A::*method)(typename MakeOptionalJacobian<T, A>::type) const) :
|
||||
root_(
|
||||
new internal::UnaryExpression<T, A>(boost::bind(method, _1, _2),
|
||||
new internal::UnaryExpression<T, A>(boost::bind(method,
|
||||
boost::placeholders::_1, boost::placeholders::_2),
|
||||
expression)) {
|
||||
}
|
||||
|
||||
|
@ -95,7 +97,10 @@ Expression<T>::Expression(const Expression<A1>& expression1,
|
|||
const Expression<A2>& expression2) :
|
||||
root_(
|
||||
new internal::BinaryExpression<T, A1, A2>(
|
||||
boost::bind(method, _1, _2, _3, _4), expression1, expression2)) {
|
||||
boost::bind(method, boost::placeholders::_1,
|
||||
boost::placeholders::_2, boost::placeholders::_3,
|
||||
boost::placeholders::_4),
|
||||
expression1, expression2)) {
|
||||
}
|
||||
|
||||
/// Construct a binary method expression
|
||||
|
@ -109,8 +114,11 @@ Expression<T>::Expression(const Expression<A1>& expression1,
|
|||
const Expression<A2>& expression2, const Expression<A3>& expression3) :
|
||||
root_(
|
||||
new internal::TernaryExpression<T, A1, A2, A3>(
|
||||
boost::bind(method, _1, _2, _3, _4, _5, _6), expression1,
|
||||
expression2, expression3)) {
|
||||
boost::bind(method, boost::placeholders::_1,
|
||||
boost::placeholders::_2, boost::placeholders::_3,
|
||||
boost::placeholders::_4, boost::placeholders::_5,
|
||||
boost::placeholders::_6),
|
||||
expression1, expression2, expression3)) {
|
||||
}
|
||||
|
||||
template<typename T>
|
||||
|
@ -247,8 +255,10 @@ template<typename T>
|
|||
Expression<T> operator*(const Expression<T>& expression1,
|
||||
const Expression<T>& expression2) {
|
||||
return Expression<T>(
|
||||
boost::bind(internal::apply_compose<T>(), _1, _2, _3, _4), expression1,
|
||||
expression2);
|
||||
boost::bind(internal::apply_compose<T>(), boost::placeholders::_1,
|
||||
boost::placeholders::_2, boost::placeholders::_3,
|
||||
boost::placeholders::_4),
|
||||
expression1, expression2);
|
||||
}
|
||||
|
||||
/// Construct an array of leaves
|
||||
|
|
|
@ -24,7 +24,6 @@
|
|||
#include <gtsam/base/OptionalJacobian.h>
|
||||
#include <gtsam/base/VectorSpace.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <map>
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Manifold.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <limits>
|
||||
#include <iostream>
|
||||
|
@ -87,7 +87,8 @@ public:
|
|||
* Constructor - forces exact evaluation
|
||||
*/
|
||||
NonlinearEquality(Key j, const T& feasible,
|
||||
const CompareFunction &_compare = boost::bind(traits<T>::Equals,_1,_2,1e-9)) :
|
||||
const CompareFunction &_compare = boost::bind(traits<T>::Equals,
|
||||
boost::placeholders::_1,boost::placeholders::_2,1e-9)) :
|
||||
Base(noiseModel::Constrained::All(traits<T>::GetDimension(feasible)),
|
||||
j), feasible_(feasible), allow_error_(false), error_gain_(0.0), //
|
||||
compare_(_compare) {
|
||||
|
@ -97,7 +98,8 @@ public:
|
|||
* Constructor - allows inexact evaluation
|
||||
*/
|
||||
NonlinearEquality(Key j, const T& feasible, double error_gain,
|
||||
const CompareFunction &_compare = boost::bind(traits<T>::Equals,_1,_2,1e-9)) :
|
||||
const CompareFunction &_compare = boost::bind(traits<T>::Equals,
|
||||
boost::placeholders::_1,boost::placeholders::_2,1e-9)) :
|
||||
Base(noiseModel::Constrained::All(traits<T>::GetDimension(feasible)),
|
||||
j), feasible_(feasible), allow_error_(true), error_gain_(error_gain), //
|
||||
compare_(_compare) {
|
||||
|
|
|
@ -26,6 +26,8 @@
|
|||
|
||||
#include <utility>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <gtsam/nonlinear/Values.h> // Only so Eclipse finds class definition
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -242,7 +244,8 @@ namespace gtsam {
|
|||
template<class ValueType>
|
||||
Values::Filtered<ValueType>
|
||||
Values::filter(const boost::function<bool(Key)>& filterFcn) {
|
||||
return Filtered<ValueType>(boost::bind(&filterHelper<ValueType>, filterFcn, _1), *this);
|
||||
return Filtered<ValueType>(boost::bind(&filterHelper<ValueType>, filterFcn,
|
||||
boost::placeholders::_1), *this);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -255,7 +258,8 @@ namespace gtsam {
|
|||
template<class ValueType>
|
||||
Values::ConstFiltered<ValueType>
|
||||
Values::filter(const boost::function<bool(Key)>& filterFcn) const {
|
||||
return ConstFiltered<ValueType>(boost::bind(&filterHelper<ValueType>, filterFcn, _1), *this);
|
||||
return ConstFiltered<ValueType>(boost::bind(&filterHelper<ValueType>,
|
||||
filterFcn, boost::placeholders::_1), *this);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -25,14 +25,6 @@
|
|||
#include <gtsam/nonlinear/Values.h>
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#endif
|
||||
#include <boost/bind.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
#include <boost/iterator/transform_iterator.hpp>
|
||||
|
||||
#include <list>
|
||||
|
|
|
@ -29,15 +29,6 @@
|
|||
#include <gtsam/inference/Key.h>
|
||||
#include <boost/iterator/transform_iterator.hpp>
|
||||
#include <boost/iterator/filter_iterator.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#pragma GCC diagnostic ignored "-Wunused-local-typedefs"
|
||||
#endif
|
||||
#include <boost/bind.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
#include <boost/ptr_container/serialize_ptr_map.hpp>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
|
||||
|
|
|
@ -29,6 +29,8 @@
|
|||
#include <boost/assign/std/vector.hpp>
|
||||
#include <boost/assign/list_of.hpp>
|
||||
using namespace boost::assign;
|
||||
#include <boost/bind/bind.hpp>
|
||||
using namespace boost::placeholders;
|
||||
#include <stdexcept>
|
||||
#include <limits>
|
||||
#include <type_traits>
|
||||
|
|
|
@ -26,8 +26,9 @@
|
|||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -20,8 +20,10 @@
|
|||
#include <gtsam/geometry/Point3.h>
|
||||
#include <gtsam/sfm/TranslationFactor.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -9,8 +9,11 @@
|
|||
#include <gtsam/geometry/Rot3.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
using namespace gtsam::symbol_shorthand;
|
||||
using namespace gtsam::noiseModel;
|
||||
|
|
|
@ -22,8 +22,11 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -17,8 +17,10 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -27,9 +27,10 @@
|
|||
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
#include <boost/assign/std.hpp>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::assign;
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
using namespace std;
|
||||
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include <iostream>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
|
@ -32,6 +32,7 @@
|
|||
|
||||
using namespace std;
|
||||
using namespace boost;
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
|
||||
typedef gtsam::ReferenceFrameFactor<gtsam::Point2, gtsam::Pose2> PointReferenceFrameFactor;
|
||||
|
|
|
@ -12,12 +12,13 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <vector>
|
||||
|
||||
using namespace std;
|
||||
using namespace boost::assign;
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
|
||||
static const double kDegree = M_PI / 180;
|
||||
|
|
|
@ -27,9 +27,11 @@
|
|||
#include <gtsam/base/serializationTestHelpers.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/assign/std/map.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <iostream>
|
||||
|
||||
using namespace boost::assign;
|
||||
using namespace boost::placeholders;
|
||||
|
||||
static const double rankTol = 1.0;
|
||||
// Create a noise model for the pixel error
|
||||
|
|
|
@ -27,10 +27,12 @@
|
|||
|
||||
#include <boost/assign.hpp>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace boost::assign;
|
||||
using namespace boost::placeholders;
|
||||
|
||||
// Some common constants
|
||||
static const boost::shared_ptr<Cal3_S2> sharedCal = //
|
||||
|
|
|
@ -10,6 +10,8 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dynamics/PoseRTV.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
@ -89,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<Vector9, PoseRTV, PoseRTV>(
|
||||
boost::bind(This::predict_proxy, _1, _2, dt_), x1, x2, 1e-5);
|
||||
boost::bind(This::predict_proxy, boost::placeholders::_1, boost::placeholders::_2, dt_), x1, x2, 1e-5);
|
||||
if (H2) *H2 = numericalDerivative22<Vector9, PoseRTV, PoseRTV>(
|
||||
boost::bind(This::predict_proxy, _1, _2, dt_), x1, x2, 1e-5);
|
||||
boost::bind(This::predict_proxy, boost::placeholders::_1, boost::placeholders::_2, dt_), x1, x2, 1e-5);
|
||||
return z - predict_proxy(x1, x2, dt_);
|
||||
}
|
||||
|
||||
|
|
|
@ -10,6 +10,8 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dynamics/PoseRTV.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
@ -79,9 +81,9 @@ public:
|
|||
boost::optional<Matrix&> H2 = boost::none) const override {
|
||||
const Vector6 meas = z();
|
||||
if (H1) *H1 = numericalDerivative21<Vector6, PoseRTV, PoseRTV>(
|
||||
boost::bind(This::predict_proxy, _1, _2, dt_, meas), x1, x2, 1e-5);
|
||||
boost::bind(This::predict_proxy, boost::placeholders::_1, boost::placeholders::_2, dt_, meas), x1, x2, 1e-5);
|
||||
if (H2) *H2 = numericalDerivative22<Vector6, PoseRTV, PoseRTV>(
|
||||
boost::bind(This::predict_proxy, _1, _2, dt_, meas), x1, x2, 1e-5);
|
||||
boost::bind(This::predict_proxy, boost::placeholders::_1, boost::placeholders::_2, dt_, meas), x1, x2, 1e-5);
|
||||
return predict_proxy(x1, x2, dt_, meas);
|
||||
}
|
||||
|
||||
|
|
|
@ -10,6 +10,8 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dynamics/PoseRTV.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
namespace dynamics {
|
||||
|
@ -84,9 +86,11 @@ public:
|
|||
boost::optional<gtsam::Matrix&> H1=boost::none,
|
||||
boost::optional<gtsam::Matrix&> H2=boost::none) const override {
|
||||
if (H1) *H1 = gtsam::numericalDerivative21<gtsam::Vector,PoseRTV,PoseRTV>(
|
||||
boost::bind(VelocityConstraint::evaluateError_, _1, _2, dt_, integration_mode_), x1, x2, 1e-5);
|
||||
boost::bind(VelocityConstraint::evaluateError_, boost::placeholders::_1,
|
||||
boost::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5);
|
||||
if (H2) *H2 = gtsam::numericalDerivative22<gtsam::Vector,PoseRTV,PoseRTV>(
|
||||
boost::bind(VelocityConstraint::evaluateError_, _1, _2, dt_, integration_mode_), x1, x2, 1e-5);
|
||||
boost::bind(VelocityConstraint::evaluateError_, boost::placeholders::_1,
|
||||
boost::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5);
|
||||
return evaluateError_(x1, x2, dt_, integration_mode_);
|
||||
}
|
||||
|
||||
|
|
|
@ -3,12 +3,14 @@
|
|||
* @author Duy-Nguyen Ta
|
||||
*/
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam_unstable/dynamics/SimpleHelicopter.h>
|
||||
|
||||
/* ************************************************************************* */
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
using namespace gtsam::symbol_shorthand;
|
||||
|
||||
|
|
|
@ -24,7 +24,6 @@
|
|||
#include <gtsam_unstable/geometry/Event.h>
|
||||
#include <gtsam_unstable/slam/TOAFactor.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/format.hpp>
|
||||
|
||||
#include <vector>
|
||||
|
|
|
@ -23,8 +23,9 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -24,6 +24,7 @@
|
|||
#include <gtsam_unstable/linear/QPSParser.h>
|
||||
#include <gtsam_unstable/linear/QPSParserException.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/fusion/include/vector.hpp>
|
||||
#include <boost/fusion/sequence.hpp>
|
||||
#include <boost/lambda/lambda.hpp>
|
||||
|
@ -39,6 +40,7 @@
|
|||
#include <vector>
|
||||
|
||||
using boost::fusion::at_c;
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
|
||||
namespace bf = boost::fusion;
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
// Using numerical derivative to calculate d(Pose3::Expmap)/dw
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/optional.hpp>
|
||||
|
||||
#include <ostream>
|
||||
|
@ -304,6 +305,8 @@ public:
|
|||
boost::optional<Matrix&> H4 = boost::none,
|
||||
boost::optional<Matrix&> H5 = boost::none) const override {
|
||||
|
||||
using namespace boost::placeholders;
|
||||
|
||||
// TODO: Write analytical derivative calculations
|
||||
// Jacobian w.r.t. Pose1
|
||||
if (H1){
|
||||
|
@ -420,6 +423,8 @@ public:
|
|||
// Note: all delta terms refer to an IMU\sensor system at t0
|
||||
// Note: Earth-related terms are not accounted here but are incorporated in predict functions.
|
||||
|
||||
using namespace boost::placeholders;
|
||||
|
||||
POSE body_P_sensor = POSE();
|
||||
bool flag_use_body_P_sensor = false;
|
||||
if (p_body_P_sensor){
|
||||
|
|
|
@ -26,6 +26,7 @@
|
|||
// Using numerical derivative to calculate d(Pose3::Expmap)/dw
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/optional.hpp>
|
||||
|
||||
#include <ostream>
|
||||
|
@ -234,38 +235,38 @@ public:
|
|||
// TODO: Write analytical derivative calculations
|
||||
// Jacobian w.r.t. Pose1
|
||||
if (H1){
|
||||
Matrix H1_Pose = gtsam::numericalDerivative11<POSE, POSE>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, _1, Vel1, Bias1, Pose2, Vel2), Pose1);
|
||||
Matrix H1_Vel = gtsam::numericalDerivative11<VELOCITY, POSE>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, _1, Vel1, Bias1, Pose2, Vel2), Pose1);
|
||||
Matrix H1_Pose = gtsam::numericalDerivative11<POSE, POSE>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, boost::placeholders::_1, Vel1, Bias1, Pose2, Vel2), Pose1);
|
||||
Matrix H1_Vel = gtsam::numericalDerivative11<VELOCITY, POSE>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, boost::placeholders::_1, Vel1, Bias1, Pose2, Vel2), Pose1);
|
||||
*H1 = stack(2, &H1_Pose, &H1_Vel);
|
||||
}
|
||||
|
||||
// Jacobian w.r.t. Vel1
|
||||
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<POSE, Vector3>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, Pose1, _1, Bias1, Pose2, Vel2), Vel1);
|
||||
Matrix H2_Vel = gtsam::numericalDerivative11<Vector3, Vector3>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, Pose1, _1, Bias1, Pose2, Vel2), Vel1);
|
||||
Matrix H2_Pose = gtsam::numericalDerivative11<POSE, Vector3>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, Pose1, boost::placeholders::_1, Bias1, Pose2, Vel2), Vel1);
|
||||
Matrix H2_Vel = gtsam::numericalDerivative11<Vector3, Vector3>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, Pose1, boost::placeholders::_1, Bias1, Pose2, Vel2), Vel1);
|
||||
*H2 = stack(2, &H2_Pose, &H2_Vel);
|
||||
}
|
||||
|
||||
// Jacobian w.r.t. IMUBias1
|
||||
if (H3){
|
||||
Matrix H3_Pose = gtsam::numericalDerivative11<POSE, IMUBIAS>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, Pose1, Vel1, _1, Pose2, Vel2), Bias1);
|
||||
Matrix H3_Vel = gtsam::numericalDerivative11<VELOCITY, IMUBIAS>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, Pose1, Vel1, _1, Pose2, Vel2), Bias1);
|
||||
Matrix H3_Pose = gtsam::numericalDerivative11<POSE, IMUBIAS>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, Pose1, Vel1, boost::placeholders::_1, Pose2, Vel2), Bias1);
|
||||
Matrix H3_Vel = gtsam::numericalDerivative11<VELOCITY, IMUBIAS>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, Pose1, Vel1, boost::placeholders::_1, Pose2, Vel2), Bias1);
|
||||
*H3 = stack(2, &H3_Pose, &H3_Vel);
|
||||
}
|
||||
|
||||
// Jacobian w.r.t. Pose2
|
||||
if (H4){
|
||||
Matrix H4_Pose = gtsam::numericalDerivative11<POSE, POSE>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, Pose1, Vel1, Bias1, _1, Vel2), Pose2);
|
||||
Matrix H4_Vel = gtsam::numericalDerivative11<VELOCITY, POSE>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, Pose1, Vel1, Bias1, _1, Vel2), Pose2);
|
||||
Matrix H4_Pose = gtsam::numericalDerivative11<POSE, POSE>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, Pose1, Vel1, Bias1, boost::placeholders::_1, Vel2), Pose2);
|
||||
Matrix H4_Vel = gtsam::numericalDerivative11<VELOCITY, POSE>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, Pose1, Vel1, Bias1, boost::placeholders::_1, Vel2), Pose2);
|
||||
*H4 = stack(2, &H4_Pose, &H4_Vel);
|
||||
}
|
||||
|
||||
// Jacobian w.r.t. Vel2
|
||||
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<POSE, Vector3>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, Pose1, Vel1, Bias1, Pose2, _1), Vel2);
|
||||
Matrix H5_Vel = gtsam::numericalDerivative11<Vector3, Vector3>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, Pose1, Vel1, Bias1, Pose2, _1), Vel2);
|
||||
Matrix H5_Pose = gtsam::numericalDerivative11<POSE, Vector3>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluatePoseError, this, Pose1, Vel1, Bias1, Pose2, boost::placeholders::_1), Vel2);
|
||||
Matrix H5_Vel = gtsam::numericalDerivative11<Vector3, Vector3>(boost::bind(&InertialNavFactor_GlobalVelocity::evaluateVelocityError, this, Pose1, Vel1, Bias1, Pose2, boost::placeholders::_1), Vel2);
|
||||
*H5 = stack(2, &H5_Pose, &H5_Vel);
|
||||
}
|
||||
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
@ -106,13 +108,13 @@ public:
|
|||
|
||||
if (H1) {
|
||||
(*H1) = numericalDerivative11<Vector, Pose3>(
|
||||
boost::bind(&InvDepthFactorVariant1::inverseDepthError, this, _1,
|
||||
boost::bind(&InvDepthFactorVariant1::inverseDepthError, this, boost::placeholders::_1,
|
||||
landmark), pose);
|
||||
}
|
||||
if (H2) {
|
||||
(*H2) = numericalDerivative11<Vector, Vector6>(
|
||||
boost::bind(&InvDepthFactorVariant1::inverseDepthError, this, pose,
|
||||
_1), landmark);
|
||||
boost::placeholders::_1), landmark);
|
||||
}
|
||||
|
||||
return inverseDepthError(pose, landmark);
|
||||
|
|
|
@ -18,6 +18,8 @@
|
|||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
@ -109,13 +111,13 @@ public:
|
|||
|
||||
if (H1) {
|
||||
(*H1) = numericalDerivative11<Vector, Pose3>(
|
||||
boost::bind(&InvDepthFactorVariant2::inverseDepthError, this, _1,
|
||||
landmark), pose);
|
||||
boost::bind(&InvDepthFactorVariant2::inverseDepthError, this,
|
||||
boost::placeholders::_1, landmark), pose);
|
||||
}
|
||||
if (H2) {
|
||||
(*H2) = numericalDerivative11<Vector, Vector3>(
|
||||
boost::bind(&InvDepthFactorVariant2::inverseDepthError, this, pose,
|
||||
_1), landmark);
|
||||
boost::placeholders::_1), landmark);
|
||||
}
|
||||
|
||||
return inverseDepthError(pose, landmark);
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
@ -108,10 +110,10 @@ public:
|
|||
boost::optional<Matrix&> H2=boost::none) const override {
|
||||
|
||||
if(H1) {
|
||||
(*H1) = numericalDerivative11<Vector,Pose3>(boost::bind(&InvDepthFactorVariant3a::inverseDepthError, this, _1, landmark), pose);
|
||||
(*H1) = numericalDerivative11<Vector,Pose3>(boost::bind(&InvDepthFactorVariant3a::inverseDepthError, this, boost::placeholders::_1, landmark), pose);
|
||||
}
|
||||
if(H2) {
|
||||
(*H2) = numericalDerivative11<Vector,Vector3>(boost::bind(&InvDepthFactorVariant3a::inverseDepthError, this, pose, _1), landmark);
|
||||
(*H2) = numericalDerivative11<Vector,Vector3>(boost::bind(&InvDepthFactorVariant3a::inverseDepthError, this, pose, boost::placeholders::_1), landmark);
|
||||
}
|
||||
|
||||
return inverseDepthError(pose, landmark);
|
||||
|
@ -229,13 +231,13 @@ public:
|
|||
boost::optional<Matrix&> H3=boost::none) const override {
|
||||
|
||||
if(H1)
|
||||
(*H1) = numericalDerivative11<Vector,Pose3>(boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, _1, pose2, landmark), pose1);
|
||||
(*H1) = numericalDerivative11<Vector,Pose3>(boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, boost::placeholders::_1, pose2, landmark), pose1);
|
||||
|
||||
if(H2)
|
||||
(*H2) = numericalDerivative11<Vector,Pose3>(boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1, _1, landmark), pose2);
|
||||
(*H2) = numericalDerivative11<Vector,Pose3>(boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1, boost::placeholders::_1, landmark), pose2);
|
||||
|
||||
if(H3)
|
||||
(*H3) = numericalDerivative11<Vector,Vector3>(boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1, pose2, _1), landmark);
|
||||
(*H3) = numericalDerivative11<Vector,Vector3>(boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1, pose2, boost::placeholders::_1), landmark);
|
||||
|
||||
return inverseDepthError(pose1, pose2, landmark);
|
||||
}
|
||||
|
|
|
@ -9,8 +9,11 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam_unstable/slam/BiasedGPSFactor.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
using namespace gtsam::symbol_shorthand;
|
||||
using namespace gtsam::noiseModel;
|
||||
|
|
|
@ -21,9 +21,12 @@
|
|||
#include <gtsam/nonlinear/Values.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <iostream>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -23,6 +23,9 @@
|
|||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/deprecated/LieVector.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -16,6 +16,7 @@
|
|||
*/
|
||||
|
||||
#include <iostream>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/navigation/ImuBias.h>
|
||||
#include <gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h>
|
||||
|
@ -25,6 +26,7 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -24,8 +24,9 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
using namespace std;
|
||||
|
||||
|
|
|
@ -15,8 +15,11 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -21,8 +21,11 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -21,8 +21,11 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -28,8 +28,9 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -28,8 +28,9 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -5,12 +5,14 @@
|
|||
* @author Alex Cunningham
|
||||
*/
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <gtsam_unstable/slam/RelativeElevationFactor.h>
|
||||
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
|
||||
SharedNoiseModel model1 = noiseModel::Unit::Create(1);
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
#include <gtsam_unstable/slam/TOAFactor.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/format.hpp>
|
||||
|
||||
using namespace std;
|
||||
|
|
|
@ -18,8 +18,11 @@
|
|||
|
||||
#include <gtsam_unstable/slam/TSAMFactors.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -18,7 +18,9 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -18,7 +18,9 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -29,14 +29,6 @@
|
|||
#include <gtsam/linear/GaussianBayesTree.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#endif
|
||||
#include <boost/bind.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
#include <boost/assign/list_of.hpp> // for 'list_of()'
|
||||
#include <functional>
|
||||
#include <boost/iterator/counting_iterator.hpp>
|
||||
|
|
|
@ -31,6 +31,8 @@
|
|||
|
||||
#include <boost/assign/list_of.hpp>
|
||||
using boost::assign::list_of;
|
||||
#include <boost/bind/bind.hpp>
|
||||
using namespace boost::placeholders;
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
|
|
@ -21,10 +21,12 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <iostream>
|
||||
|
||||
using namespace boost::placeholders;
|
||||
using namespace gtsam;
|
||||
|
||||
// Convenience for named keys
|
||||
|
|
Loading…
Reference in New Issue