Got rid or ifdefed many boost headers

release/4.3a0
Frank Dellaert 2023-02-05 19:30:01 -08:00
parent 8bd15b8792
commit fdf53b62c6
42 changed files with 26 additions and 62 deletions

View File

@ -52,7 +52,6 @@ using ConcurrentMapBase = gtsam::FastMap<KEY, VALUE>;
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/split_member.hpp> #include <boost/serialization/split_member.hpp>
#endif #endif
#include <boost/static_assert.hpp>
#include <gtsam/base/FastVector.h> #include <gtsam/base/FastVector.h>

View File

@ -20,7 +20,6 @@
#include <gtsam/base/FastDefaultAllocator.h> #include <gtsam/base/FastDefaultAllocator.h>
#include <list> #include <list>
#include <boost/utility/enable_if.hpp>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/version.hpp> #include <boost/serialization/version.hpp>

View File

@ -18,8 +18,8 @@
#pragma once #pragma once
#include <boost/version.hpp>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/version.hpp>
#if BOOST_VERSION >= 107400 #if BOOST_VERSION >= 107400
#include <boost/serialization/library_version_type.hpp> #include <boost/serialization/library_version_type.hpp>
#endif #endif

View File

@ -23,8 +23,6 @@
#include <gtsam/base/types.h> #include <gtsam/base/types.h>
#include <gtsam/base/Value.h> #include <gtsam/base/Value.h>
#include <boost/pool/pool_alloc.hpp>
#include <cmath> #include <cmath>
#include <iostream> #include <iostream>
#include <typeinfo> // operator typeid #include <typeinfo> // operator typeid

View File

@ -22,10 +22,13 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#ifdef GTSAM_USE_BOOST_FEATURES
#include <boost/concept_check.hpp> #include <boost/concept_check.hpp>
#include <boost/concept/requires.hpp> #include <boost/concept/requires.hpp>
#include <boost/type_traits/is_base_of.hpp> #include <boost/type_traits/is_base_of.hpp>
#include <boost/static_assert.hpp> #include <boost/static_assert.hpp>
#endif
#include <utility> #include <utility>
namespace gtsam { namespace gtsam {

View File

@ -23,9 +23,11 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/OptionalJacobian.h> #include <gtsam/base/OptionalJacobian.h>
#ifdef GTSAM_USE_BOOST_FEATURES
#include <boost/concept_check.hpp> #include <boost/concept_check.hpp>
#include <boost/concept/requires.hpp> #include <boost/concept/requires.hpp>
#include <boost/type_traits/is_base_of.hpp> #include <boost/type_traits/is_base_of.hpp>
#endif
namespace gtsam { namespace gtsam {

View File

@ -33,7 +33,10 @@
#pragma once #pragma once
#ifdef GTSAM_USE_BOOST_FEATURES
#include <boost/concept_check.hpp> #include <boost/concept_check.hpp>
#endif
#include <functional> #include <functional>
#include <iostream> #include <iostream>
#include <memory> #include <memory>

View File

@ -13,7 +13,10 @@
// to cause compilation errors. // to cause compilation errors.
#ifdef COMPILE_ERROR_NOT_IMPLEMENTED #ifdef COMPILE_ERROR_NOT_IMPLEMENTED
#ifdef GTSAM_USE_BOOST_FEATURES
#include <boost/static_assert.hpp> #include <boost/static_assert.hpp>
#endif
#define CONCEPT_NOT_IMPLEMENTED BOOST_STATIC_ASSERT_MSG(boost::false_type, \ #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."); "This method is required by the new concepts framework but has not been implemented yet.");

View File

@ -20,8 +20,10 @@
#pragma once #pragma once
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#ifdef GTSAM_USE_BOOST_FEATURES
#include <boost/concept/assert.hpp> #include <boost/concept/assert.hpp>
#include <boost/range/concepts.hpp> #include <boost/range/concepts.hpp>
#endif
#include <gtsam/config.h> // for GTSAM_USE_TBB #include <gtsam/config.h> // for GTSAM_USE_TBB
#include <cstddef> #include <cstddef>

View File

@ -19,8 +19,6 @@
#pragma once #pragma once
#include <boost/utility.hpp>
#include <gtsam/global_includes.h> #include <gtsam/global_includes.h>
#include <gtsam/linear/JacobianFactor.h> #include <gtsam/linear/JacobianFactor.h>
#include <gtsam/inference/Conditional.h> #include <gtsam/inference/Conditional.h>

View File

@ -22,8 +22,6 @@
#include <gtsam/linear/Preconditioner.h> #include <gtsam/linear/Preconditioner.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <boost/algorithm/string.hpp>
#include <algorithm> #include <algorithm>
#include <iostream> #include <iostream>
#include <stdexcept> #include <stdexcept>

View File

@ -25,9 +25,9 @@
#include <gtsam/linear/SubgraphBuilder.h> #include <gtsam/linear/SubgraphBuilder.h>
#include <gtsam/base/kruskal.h> #include <gtsam/base/kruskal.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/archive/text_iarchive.hpp> #include <boost/archive/text_iarchive.hpp>
#include <boost/archive/text_oarchive.hpp> #include <boost/archive/text_oarchive.hpp>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/vector.hpp> #include <boost/serialization/vector.hpp>
#endif #endif

View File

@ -24,8 +24,6 @@
#include <gtsam/base/types.h> #include <gtsam/base/types.h>
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
#include <boost/algorithm/string.hpp>
#include <stdexcept> #include <stdexcept>
using std::cout; using std::cout;

View File

@ -18,9 +18,6 @@
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <boost/bind/bind.hpp>
#include <boost/range/numeric.hpp>
using namespace std; using namespace std;
namespace gtsam { namespace gtsam {

View File

@ -18,7 +18,6 @@
#include <gtsam/linear/linearExceptions.h> #include <gtsam/linear/linearExceptions.h>
#include <gtsam/inference/Symbol.h> #include <gtsam/inference/Symbol.h>
#include <boost/lexical_cast.hpp>
namespace gtsam { namespace gtsam {

View File

@ -24,7 +24,6 @@
#include <gtsam/inference/Symbol.h> #include <gtsam/inference/Symbol.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <boost/bind/bind.hpp>
// STL/C++ // STL/C++
#include <iostream> #include <iostream>

View File

@ -25,8 +25,6 @@
#include <gtsam/linear/GaussianConditional.h> #include <gtsam/linear/GaussianConditional.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <boost/range/iterator_range.hpp>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -320,6 +320,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -329,6 +330,7 @@ private:
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(_PIM_); ar & BOOST_SERIALIZATION_NVP(_PIM_);
} }
#endif
}; };
// class ImuFactor2 // class ImuFactor2

View File

@ -20,7 +20,6 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
#include <functional> #include <functional>
#include "gtsam/base/Matrix.h" #include "gtsam/base/Matrix.h"
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>

View File

@ -21,8 +21,6 @@
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <gtsam/navigation/BarometricFactor.h> #include <gtsam/navigation/BarometricFactor.h>
#include <boost/bind/bind.hpp>
using namespace std::placeholders; using namespace std::placeholders;
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -30,7 +30,6 @@
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <boost/bind/bind.hpp>
#include <list> #include <list>
#include "imuFactorTesting.h" #include "imuFactorTesting.h"

View File

@ -20,8 +20,6 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <GeographicLib/LocalCartesian.hpp> #include <GeographicLib/LocalCartesian.hpp>

View File

@ -20,7 +20,6 @@
#include <gtsam/base/TestableAssertions.h> #include <gtsam/base/TestableAssertions.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
using namespace std::placeholders; using namespace std::placeholders;

View File

@ -288,6 +288,7 @@ private:
return expression(keys); return expression(keys);
} }
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
void serialize(ARCHIVE &ar, const unsigned int /*version*/) { void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
@ -295,6 +296,7 @@ private:
"ExpressionFactorN", "ExpressionFactorN",
boost::serialization::base_object<ExpressionFactor<T>>(*this)); boost::serialization::base_object<ExpressionFactor<T>>(*this));
} }
#endif
}; };
/// traits /// traits
template <typename T, typename... Args> template <typename T, typename... Args>

View File

@ -21,8 +21,6 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/Manifold.h> #include <gtsam/base/Manifold.h>
#include <boost/bind/bind.hpp>
#include <limits> #include <limits>
#include <iostream> #include <iostream>
#include <cmath> #include <cmath>
@ -346,6 +344,7 @@ class NonlinearEquality2 : public NoiseModelFactorN<T, T> {
GTSAM_MAKE_ALIGNED_OPERATOR_NEW GTSAM_MAKE_ALIGNED_OPERATOR_NEW
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -354,6 +353,7 @@ class NonlinearEquality2 : public NoiseModelFactorN<T, T> {
ar& boost::serialization::make_nvp( ar& boost::serialization::make_nvp(
"NoiseModelFactor2", boost::serialization::base_object<Base>(*this)); "NoiseModelFactor2", boost::serialization::base_object<Base>(*this));
} }
#endif
}; };
// \NonlinearEquality2 // \NonlinearEquality2

View File

@ -25,11 +25,8 @@
#pragma once #pragma once
#include <utility> #include <utility>
#include <boost/bind/bind.hpp>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <boost/bind/bind.hpp>
#include <gtsam/nonlinear/Values.h> // Only so Eclipse finds class definition #include <gtsam/nonlinear/Values.h> // Only so Eclipse finds class definition
namespace gtsam { namespace gtsam {

View File

@ -25,7 +25,6 @@
#include <gtsam/base/TestableAssertions.h> #include <gtsam/base/TestableAssertions.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <boost/bind/bind.hpp>
#include <stdexcept> #include <stdexcept>
#include <limits> #include <limits>
#include <type_traits> #include <type_traits>

View File

@ -25,7 +25,6 @@
#include <gtsam/base/TestableAssertions.h> #include <gtsam/base/TestableAssertions.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <boost/bind/bind.hpp>
using namespace std::placeholders; using namespace std::placeholders;
using namespace std; using namespace std;

View File

@ -36,7 +36,6 @@
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/none.hpp>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif

View File

@ -27,8 +27,6 @@
#include <gtsam/geometry/Pose3.h> #include <gtsam/geometry/Pose3.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/math/special_functions.hpp>
#include <utility> #include <utility>
using namespace std; using namespace std;

View File

@ -19,7 +19,6 @@
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/geometry/CalibratedCamera.h> #include <gtsam/geometry/CalibratedCamera.h>
#include <boost/lexical_cast.hpp>
namespace gtsam { namespace gtsam {
@ -86,7 +85,7 @@ public:
if (model && model->dim() != traits<Measurement>::dimension) if (model && model->dim() != traits<Measurement>::dimension)
throw std::invalid_argument( throw std::invalid_argument(
"TriangulationFactor must be created with " "TriangulationFactor must be created with "
+ boost::lexical_cast<std::string>((int) traits<Measurement>::dimension) + std::to_string((int) traits<Measurement>::dimension)
+ "-dimensional noise model."); + "-dimensional noise model.");
} }

View File

@ -19,17 +19,16 @@
#include <gtsam/slam/lago.h> #include <gtsam/slam/lago.h>
#include <gtsam/slam/InitializePose.h> #include <gtsam/slam/InitializePose.h>
#include <gtsam/nonlinear/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h> #include <gtsam/slam/BetweenFactor.h>
#include <gtsam/inference/Symbol.h> #include <gtsam/nonlinear/PriorFactor.h>
#include <gtsam/geometry/Pose2.h> #include <gtsam/geometry/Pose2.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <gtsam/base/kruskal.h> #include <gtsam/base/kruskal.h>
#include <boost/math/special_functions.hpp>
#include <iostream> #include <iostream>
#include <stack> #include <stack>
#include <cmath>
using namespace std; using namespace std;
@ -188,7 +187,7 @@ GaussianFactorGraph buildLinearOrientationGraph(
///cout << "REG: key1= " << DefaultKeyFormatter(key1) << " key2= " << DefaultKeyFormatter(key2) << endl; ///cout << "REG: key1= " << DefaultKeyFormatter(key1) << " key2= " << DefaultKeyFormatter(key2) << endl;
double k2pi_noise = key1_DeltaTheta_key2 + orientationsToRoot.at(key1) 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 - 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 //if (k2pi_noise - 2*k*M_PI > 1e-5) cout << k2pi_noise - 2*k*M_PI << endl; // for debug
Vector deltaThetaRegularized = (Vector(1) Vector deltaThetaRegularized = (Vector(1)
<< key1_DeltaTheta_key2 - 2 * k * M_PI).finished(); << key1_DeltaTheta_key2 - 2 * k * M_PI).finished();

View File

@ -25,8 +25,6 @@
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <boost/bind/bind.hpp>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
using namespace std::placeholders; using namespace std::placeholders;

View File

@ -10,8 +10,6 @@
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam_unstable/dynamics/PoseRTV.h> #include <gtsam_unstable/dynamics/PoseRTV.h>
#include <boost/bind/bind.hpp>
namespace gtsam { namespace gtsam {
/** /**

View File

@ -10,8 +10,6 @@
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam_unstable/dynamics/PoseRTV.h> #include <gtsam_unstable/dynamics/PoseRTV.h>
#include <boost/bind/bind.hpp>
namespace gtsam { namespace gtsam {
/** /**

View File

@ -10,8 +10,6 @@
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam_unstable/dynamics/PoseRTV.h> #include <gtsam_unstable/dynamics/PoseRTV.h>
#include <boost/bind/bind.hpp>
namespace gtsam { namespace gtsam {
namespace dynamics { namespace dynamics {

View File

@ -27,8 +27,6 @@
// Using numerical derivative to calculate d(Pose3::Expmap)/dw // Using numerical derivative to calculate d(Pose3::Expmap)/dw
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
#include <ostream> #include <ostream>
namespace gtsam { namespace gtsam {

View File

@ -26,8 +26,6 @@
// Using numerical derivative to calculate d(Pose3::Expmap)/dw // Using numerical derivative to calculate d(Pose3::Expmap)/dw
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
#include <ostream> #include <ostream>
namespace gtsam { namespace gtsam {

View File

@ -17,8 +17,6 @@
#include <gtsam/geometry/Point2.h> #include <gtsam/geometry/Point2.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
namespace gtsam { namespace gtsam {
/** /**

View File

@ -18,8 +18,6 @@
#include <gtsam/geometry/Point2.h> #include <gtsam/geometry/Point2.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
namespace gtsam { namespace gtsam {
/** /**

View File

@ -17,8 +17,6 @@
#include <gtsam/geometry/Point2.h> #include <gtsam/geometry/Point2.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
namespace gtsam { namespace gtsam {
/** /**

View File

@ -22,7 +22,6 @@
#include <gtsam/inference/Key.h> #include <gtsam/inference/Key.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <boost/bind/bind.hpp>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <iostream> #include <iostream>