Got rid or ifdefed many boost headers
parent
8bd15b8792
commit
fdf53b62c6
|
@ -52,7 +52,6 @@ using ConcurrentMapBase = gtsam::FastMap<KEY, VALUE>;
|
|||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/split_member.hpp>
|
||||
#endif
|
||||
#include <boost/static_assert.hpp>
|
||||
|
||||
#include <gtsam/base/FastVector.h>
|
||||
|
||||
|
|
|
@ -20,7 +20,6 @@
|
|||
|
||||
#include <gtsam/base/FastDefaultAllocator.h>
|
||||
#include <list>
|
||||
#include <boost/utility/enable_if.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/version.hpp>
|
||||
|
|
|
@ -18,8 +18,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <boost/version.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/version.hpp>
|
||||
#if BOOST_VERSION >= 107400
|
||||
#include <boost/serialization/library_version_type.hpp>
|
||||
#endif
|
||||
|
|
|
@ -23,8 +23,6 @@
|
|||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/base/Value.h>
|
||||
|
||||
#include <boost/pool/pool_alloc.hpp>
|
||||
|
||||
#include <cmath>
|
||||
#include <iostream>
|
||||
#include <typeinfo> // operator typeid
|
||||
|
|
|
@ -22,10 +22,13 @@
|
|||
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/concept_check.hpp>
|
||||
#include <boost/concept/requires.hpp>
|
||||
#include <boost/type_traits/is_base_of.hpp>
|
||||
#include <boost/static_assert.hpp>
|
||||
#endif
|
||||
|
||||
#include <utility>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -23,9 +23,11 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/OptionalJacobian.h>
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/concept_check.hpp>
|
||||
#include <boost/concept/requires.hpp>
|
||||
#include <boost/type_traits/is_base_of.hpp>
|
||||
#endif
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
|
|
@ -33,7 +33,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/concept_check.hpp>
|
||||
#endif
|
||||
|
||||
#include <functional>
|
||||
#include <iostream>
|
||||
#include <memory>
|
||||
|
|
|
@ -13,7 +13,10 @@
|
|||
// to cause compilation errors.
|
||||
#ifdef COMPILE_ERROR_NOT_IMPLEMENTED
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/static_assert.hpp>
|
||||
#endif
|
||||
|
||||
#define CONCEPT_NOT_IMPLEMENTED BOOST_STATIC_ASSERT_MSG(boost::false_type, \
|
||||
"This method is required by the new concepts framework but has not been implemented yet.");
|
||||
|
||||
|
|
|
@ -20,8 +20,10 @@
|
|||
#pragma once
|
||||
|
||||
#include <gtsam/dllexport.h>
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/concept/assert.hpp>
|
||||
#include <boost/range/concepts.hpp>
|
||||
#endif
|
||||
#include <gtsam/config.h> // for GTSAM_USE_TBB
|
||||
|
||||
#include <cstddef>
|
||||
|
|
|
@ -19,8 +19,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <boost/utility.hpp>
|
||||
|
||||
#include <gtsam/global_includes.h>
|
||||
#include <gtsam/linear/JacobianFactor.h>
|
||||
#include <gtsam/inference/Conditional.h>
|
||||
|
|
|
@ -22,8 +22,6 @@
|
|||
#include <gtsam/linear/Preconditioner.h>
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
|
||||
#include <boost/algorithm/string.hpp>
|
||||
|
||||
#include <algorithm>
|
||||
#include <iostream>
|
||||
#include <stdexcept>
|
||||
|
|
|
@ -25,9 +25,9 @@
|
|||
#include <gtsam/linear/SubgraphBuilder.h>
|
||||
#include <gtsam/base/kruskal.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/archive/text_iarchive.hpp>
|
||||
#include <boost/archive/text_oarchive.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/vector.hpp>
|
||||
#endif
|
||||
|
||||
|
|
|
@ -24,8 +24,6 @@
|
|||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/base/Vector.h>
|
||||
|
||||
#include <boost/algorithm/string.hpp>
|
||||
|
||||
#include <stdexcept>
|
||||
|
||||
using std::cout;
|
||||
|
|
|
@ -18,9 +18,6 @@
|
|||
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <boost/range/numeric.hpp>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -18,7 +18,6 @@
|
|||
|
||||
#include <gtsam/linear/linearExceptions.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <boost/lexical_cast.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
|
|
@ -24,7 +24,6 @@
|
|||
#include <gtsam/inference/Symbol.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
// STL/C++
|
||||
#include <iostream>
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
#include <gtsam/linear/GaussianConditional.h>
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
|
||||
#include <boost/range/iterator_range.hpp>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
|
@ -320,6 +320,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -329,6 +330,7 @@ private:
|
|||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(_PIM_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
// class ImuFactor2
|
||||
|
||||
|
|
|
@ -20,7 +20,6 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <functional>
|
||||
#include "gtsam/base/Matrix.h"
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
|
|
@ -21,8 +21,6 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/navigation/BarometricFactor.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace std::placeholders;
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
|
|
@ -30,7 +30,6 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <list>
|
||||
|
||||
#include "imuFactorTesting.h"
|
||||
|
|
|
@ -20,8 +20,6 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <GeographicLib/LocalCartesian.hpp>
|
||||
|
|
|
@ -20,7 +20,6 @@
|
|||
#include <gtsam/base/TestableAssertions.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace std::placeholders;
|
||||
|
|
|
@ -288,6 +288,7 @@ private:
|
|||
return expression(keys);
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
|
||||
|
@ -295,6 +296,7 @@ private:
|
|||
"ExpressionFactorN",
|
||||
boost::serialization::base_object<ExpressionFactor<T>>(*this));
|
||||
}
|
||||
#endif
|
||||
};
|
||||
/// traits
|
||||
template <typename T, typename... Args>
|
||||
|
|
|
@ -21,8 +21,6 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Manifold.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <limits>
|
||||
#include <iostream>
|
||||
#include <cmath>
|
||||
|
@ -346,6 +344,7 @@ class NonlinearEquality2 : public NoiseModelFactorN<T, T> {
|
|||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -354,6 +353,7 @@ class NonlinearEquality2 : public NoiseModelFactorN<T, T> {
|
|||
ar& boost::serialization::make_nvp(
|
||||
"NoiseModelFactor2", boost::serialization::base_object<Base>(*this));
|
||||
}
|
||||
#endif
|
||||
};
|
||||
// \NonlinearEquality2
|
||||
|
||||
|
|
|
@ -25,11 +25,8 @@
|
|||
#pragma once
|
||||
|
||||
#include <utility>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <gtsam/nonlinear/Values.h> // Only so Eclipse finds class definition
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <stdexcept>
|
||||
#include <limits>
|
||||
#include <type_traits>
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace std::placeholders;
|
||||
using namespace std;
|
||||
|
|
|
@ -36,7 +36,6 @@
|
|||
#include <gtsam/base/Vector.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
|
||||
#include <boost/none.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
|
|
@ -27,8 +27,6 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
|
||||
#include <boost/math/special_functions.hpp>
|
||||
|
||||
#include <utility>
|
||||
|
||||
using namespace std;
|
||||
|
|
|
@ -19,7 +19,6 @@
|
|||
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam/geometry/CalibratedCamera.h>
|
||||
#include <boost/lexical_cast.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -86,7 +85,7 @@ public:
|
|||
if (model && model->dim() != traits<Measurement>::dimension)
|
||||
throw std::invalid_argument(
|
||||
"TriangulationFactor must be created with "
|
||||
+ boost::lexical_cast<std::string>((int) traits<Measurement>::dimension)
|
||||
+ std::to_string((int) traits<Measurement>::dimension)
|
||||
+ "-dimensional noise model.");
|
||||
}
|
||||
|
||||
|
|
|
@ -19,17 +19,16 @@
|
|||
#include <gtsam/slam/lago.h>
|
||||
|
||||
#include <gtsam/slam/InitializePose.h>
|
||||
#include <gtsam/nonlinear/PriorFactor.h>
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/nonlinear/PriorFactor.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
#include <gtsam/base/kruskal.h>
|
||||
|
||||
#include <boost/math/special_functions.hpp>
|
||||
|
||||
#include <iostream>
|
||||
#include <stack>
|
||||
#include <cmath>
|
||||
|
||||
using namespace std;
|
||||
|
||||
|
@ -188,7 +187,7 @@ GaussianFactorGraph buildLinearOrientationGraph(
|
|||
///cout << "REG: key1= " << DefaultKeyFormatter(key1) << " key2= " << DefaultKeyFormatter(key2) << endl;
|
||||
double k2pi_noise = key1_DeltaTheta_key2 + orientationsToRoot.at(key1)
|
||||
- orientationsToRoot.at(key2); // this coincides to summing up measurements along the cycle induced by the chord
|
||||
double k = boost::math::round(k2pi_noise / (2 * M_PI));
|
||||
double k = std::round(k2pi_noise / (2 * M_PI));
|
||||
//if (k2pi_noise - 2*k*M_PI > 1e-5) cout << k2pi_noise - 2*k*M_PI << endl; // for debug
|
||||
Vector deltaThetaRegularized = (Vector(1)
|
||||
<< key1_DeltaTheta_key2 - 2 * k * M_PI).finished();
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace std::placeholders;
|
||||
|
|
|
@ -10,8 +10,6 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dynamics/PoseRTV.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
|
|
@ -10,8 +10,6 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dynamics/PoseRTV.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
|
|
@ -10,8 +10,6 @@
|
|||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dynamics/PoseRTV.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
namespace dynamics {
|
||||
|
|
|
@ -27,8 +27,6 @@
|
|||
// Using numerical derivative to calculate d(Pose3::Expmap)/dw
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <ostream>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -26,8 +26,6 @@
|
|||
// Using numerical derivative to calculate d(Pose3::Expmap)/dw
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
#include <ostream>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -17,8 +17,6 @@
|
|||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
|
|
@ -18,8 +18,6 @@
|
|||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
|
|
@ -17,8 +17,6 @@
|
|||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
|
|
|
@ -22,7 +22,6 @@
|
|||
#include <gtsam/inference/Key.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <boost/bind/bind.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <iostream>
|
||||
|
||||
|
|
Loading…
Reference in New Issue