From 9f30d225fe65c63136e3f6d17e82714cb59fe259 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Tue, 16 May 2017 14:15:01 -0700 Subject: [PATCH 01/27] fixing compile issues on vc++14 --- CMakeLists.txt | 2 +- gtsam/discrete/DiscreteConditional.cpp | 24 +++++++++++++----------- 2 files changed, 14 insertions(+), 12 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 77434d135..9aa8b701a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -116,7 +116,7 @@ if(MSVC) endif() endif() -find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time timer chrono) +find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time timer chrono regex) # Required components if(NOT Boost_SERIALIZATION_LIBRARY OR NOT Boost_SYSTEM_LIBRARY OR NOT Boost_FILESYSTEM_LIBRARY OR diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index 4a918ef02..f12cd2567 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -87,17 +87,19 @@ bool DiscreteConditional::equals(const DiscreteFactor& other, Potentials::ADT DiscreteConditional::choose(const Values& parentsValues) const { ADT pFS(*this); Key j; size_t value; - for(Key key: parents()) - try { - j = (key); - value = parentsValues.at(j); - pFS = pFS.choose(j, value); - } catch (exception&) { - cout << "Key: " << j << " Value: " << value << endl; - parentsValues.print("parentsValues: "); -// pFS.print("pFS: "); - throw runtime_error("DiscreteConditional::choose: parent value missing"); - }; + for(Key key: parents()) { + try { + j = (key); + value = parentsValues.at(j); + pFS = pFS.choose(j, value); + } catch (exception&) { + cout << "Key: " << j << " Value: " << value << endl; + parentsValues.print("parentsValues: "); + // pFS.print("pFS: "); + throw runtime_error("DiscreteConditional::choose: parent value missing"); + }; + } + return pFS; } From 6a5beab4d48f3bf479dfab5291433d100033ae1a Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Tue, 16 May 2017 17:42:30 -0700 Subject: [PATCH 02/27] fixing compile issue on vc++14 --- gtsam/base/GenericValue.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 5b59f4872..bf186470e 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -167,10 +167,10 @@ public: // implicit assignment operator for (const GenericValue& rhs) works fine here /// Assignment operator, protected because only the Value or DERIVED /// assignment operators should be used. - // DerivedValue& operator=(const DerivedValue& rhs) { - // // Nothing to do, do not call base class assignment operator - // return *this; - // } + GenericValue& operator=(const GenericValue& rhs) { + // Nothing to do, do not call base class assignment operator + return *this; + } private: From 3f98942e9a5cf4dbefd358dd6ee7191d79e92f6c Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Wed, 17 May 2017 14:30:17 -0700 Subject: [PATCH 03/27] a few tmp fix to bypass eigen errors, should not be permanent solutions --- CMakeLists.txt | 3 +++ gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9aa8b701a..6db1f6681 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -251,6 +251,9 @@ else() endif() +# tmp mute eigen static assert to avoid errors in shared lib +add_definitions(-DEIGEN_NO_STATIC_ASSERT) + ############################################################################### # Global compile options diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h index 9f71956ff..be2c67c5f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h @@ -380,7 +380,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type */ EIGEN_STRONG_INLINE void conservativeResize(Index size) { - internal::conservative_resize_like_impl::run(*this, size); + internal::conservative_resize_like_impl::run(*this, size, 1); } /** Resizes the matrix to \a rows x \a cols of \c other, while leaving old values untouched. From 89ca6fb92542a92e1d50d4ac5cb5b1b159c8fba8 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Thu, 18 May 2017 11:39:51 -0700 Subject: [PATCH 04/27] fixing windows compile issues --- gtsam/geometry/SimpleCamera.h | 2 +- gtsam/navigation/ImuBias.h | 2 +- gtsam/navigation/ImuFactor.h | 6 +++--- gtsam/navigation/ManifoldPreintegration.h | 2 +- gtsam/navigation/NavState.h | 2 +- gtsam/navigation/PreintegratedRotation.h | 4 ++-- gtsam/navigation/PreintegrationBase.h | 2 +- gtsam/navigation/PreintegrationParams.h | 2 +- gtsam/navigation/TangentPreintegration.h | 2 +- 9 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtsam/geometry/SimpleCamera.h b/gtsam/geometry/SimpleCamera.h index fe493c075..a7e021394 100644 --- a/gtsam/geometry/SimpleCamera.h +++ b/gtsam/geometry/SimpleCamera.h @@ -31,7 +31,7 @@ typedef gtsam::PinholeCamera PinholeCameraCal3_S2; * @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x * Use PinholeCameraCal3_S2 instead */ -class SimpleCamera : public PinholeCameraCal3_S2 { +class GTSAM_EXPORT SimpleCamera : public PinholeCameraCal3_S2 { typedef PinholeCamera Base; typedef boost::shared_ptr shared_ptr; diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 2ad3c17dd..84458f521 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -27,7 +27,7 @@ namespace gtsam { /// All bias models live in the imuBias namespace namespace imuBias { -class ConstantBias { +class GTSAM_EXPORT ConstantBias { private: Vector3 biasAcc_; Vector3 biasGyro_; diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 532abdac0..e713fcb99 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -68,7 +68,7 @@ typedef ManifoldPreintegration PreintegrationType; * * @addtogroup SLAM */ -class PreintegratedImuMeasurements: public PreintegrationType { +class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType { friend class ImuFactor; friend class ImuFactor2; @@ -176,7 +176,7 @@ private: * * @addtogroup SLAM */ -class ImuFactor: public NoiseModelFactor5 { private: @@ -285,7 +285,7 @@ private: * ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity. * @addtogroup SLAM */ -class ImuFactor2 : public NoiseModelFactor3 { +class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3 { private: typedef ImuFactor2 This; diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 92d3f4814..22897b9d4 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -30,7 +30,7 @@ namespace gtsam { * IMU pre-integration on NavSatet manifold. * This corresponds to the original RSS paper (with one difference: V is rotated) */ -class ManifoldPreintegration : public PreintegrationBase { +class GTSAM_EXPORT ManifoldPreintegration : public PreintegrationBase { protected: /** diff --git a/gtsam/navigation/NavState.h b/gtsam/navigation/NavState.h index a1544735d..e9afcd3ac 100644 --- a/gtsam/navigation/NavState.h +++ b/gtsam/navigation/NavState.h @@ -31,7 +31,7 @@ typedef Vector3 Velocity3; * Navigation state: Pose (rotation, translation) + velocity * NOTE(frank): it does not make sense to make this a Lie group, but it is a 9D manifold */ -class NavState { +class GTSAM_EXPORT NavState { private: // TODO(frank): diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 88d9c6437..c03cab88a 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -28,7 +28,7 @@ namespace gtsam { /// Parameters for pre-integration: /// Usage: Create just a single Params and pass a shared pointer to the constructor -struct PreintegratedRotationParams { +struct GTSAM_EXPORT PreintegratedRotationParams { Matrix3 gyroscopeCovariance; ///< continuous-time "Covariance" of gyroscope measurements boost::optional omegaCoriolis; ///< Coriolis constant boost::optional body_P_sensor; ///< The pose of the sensor in the body frame @@ -63,7 +63,7 @@ struct PreintegratedRotationParams { * classes (in AHRSFactor, ImuFactor, and CombinedImuFactor). * It includes the definitions of the preintegrated rotation. */ -class PreintegratedRotation { +class GTSAM_EXPORT PreintegratedRotation { public: typedef PreintegratedRotationParams Params; diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 06be4642d..cf5465c05 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -55,7 +55,7 @@ struct PoseVelocityBias { * It includes the definitions of the preintegrated variables and the methods * to access, print, and compare them. */ -class PreintegrationBase { +class GTSAM_EXPORT PreintegrationBase { public: typedef imuBias::ConstantBias Bias; typedef PreintegrationParams Params; diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index f2b2c0fef..831da0a12 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -23,7 +23,7 @@ namespace gtsam { /// Parameters for pre-integration: /// Usage: Create just a single Params and pass a shared pointer to the constructor -struct PreintegrationParams: PreintegratedRotationParams { +struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { Matrix3 accelerometerCovariance; ///< continuous-time "Covariance" of accelerometer Matrix3 integrationCovariance; ///< continuous-time "Covariance" describing integration uncertainty bool use2ndOrderCoriolis; ///< Whether to use second order Coriolis integration diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index dddafad7a..f5e3f7960 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -25,7 +25,7 @@ namespace gtsam { * Integrate on the 9D tangent space of the NavState manifold. * See extensive discussion in ImuFactor.lyx */ -class TangentPreintegration : public PreintegrationBase { +class GTSAM_EXPORT TangentPreintegration : public PreintegrationBase { protected: /** From ed4a99f6209efe58accd8ba2139cc9145ceb1143 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Thu, 18 May 2017 11:56:52 -0700 Subject: [PATCH 05/27] fixing vc++14 compile issues --- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index a5707ce89..e36630104 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -30,7 +30,7 @@ namespace gtsam { * \nosubgrouping */ template -class GTSAM_EXPORT PinholeCamera: public PinholeBaseK { +class PinholeCamera: public PinholeBaseK { public: diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 43ba78ea2..4db1ee8c3 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -31,7 +31,7 @@ namespace gtsam { * \nosubgrouping */ template -class GTSAM_EXPORT PinholeBaseK: public PinholeBase { +class PinholeBaseK: public PinholeBase { private: @@ -222,7 +222,7 @@ private: * \nosubgrouping */ template -class GTSAM_EXPORT PinholePose: public PinholeBaseK { +class PinholePose: public PinholeBaseK { private: From 6b3608cf9ae954d71c2af349bc080239a674b5a7 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Thu, 18 May 2017 12:32:29 -0700 Subject: [PATCH 06/27] fixing vc++14 compile issues --- gtsam/geometry/CameraSet.h | 12 ++++++------ gtsam/geometry/Point3.h | 24 ++++++++++++------------ gtsam/geometry/triangulation.h | 8 ++++---- gtsam/slam/SmartFactorParams.h | 2 +- 4 files changed, 23 insertions(+), 23 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 18f311a23..026bcdd9e 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -209,11 +209,11 @@ public: bool diagonalDamping = false) { if (E.cols() == 2) { Matrix2 P2; - ComputePointCovariance(P2, E, lambda, diagonalDamping); + ComputePointCovariance<2>(P2, E, lambda, diagonalDamping); return P2; } else { Matrix3 P3; - ComputePointCovariance(P3, E, lambda, diagonalDamping); + ComputePointCovariance<3>(P3, E, lambda, diagonalDamping); return P3; } } @@ -227,12 +227,12 @@ public: bool diagonalDamping = false) { if (E.cols() == 2) { Matrix2 P; - ComputePointCovariance(P, E, lambda, diagonalDamping); - return SchurComplement(Fblocks, E, P, b); + ComputePointCovariance<2>(P, E, lambda, diagonalDamping); + return SchurComplement<2>(Fblocks, E, P, b); } else { Matrix3 P; - ComputePointCovariance(P, E, lambda, diagonalDamping); - return SchurComplement(Fblocks, E, P, b); + ComputePointCovariance<3>(P, E, lambda, diagonalDamping); + return SchurComplement<3>(Fblocks, E, P, b); } } diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 99cb6c2e7..215161b3a 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -157,28 +157,28 @@ struct traits : public internal::VectorSpace {}; // Convenience typedef typedef std::pair Point3Pair; -std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p); +GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p); /// distance between two points -double distance3(const Point3& p1, const Point3& q, - OptionalJacobian<1, 3> H1 = boost::none, - OptionalJacobian<1, 3> H2 = boost::none); +GTSAM_EXPORT double distance3(const Point3& p1, const Point3& q, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none); /// Distance of the point from the origin, with Jacobian -double norm3(const Point3& p, OptionalJacobian<1, 3> H = boost::none); +GTSAM_EXPORT double norm3(const Point3& p, OptionalJacobian<1, 3> H = boost::none); /// normalize, with optional Jacobian -Point3 normalize(const Point3& p, OptionalJacobian<3, 3> H = boost::none); +GTSAM_EXPORT Point3 normalize(const Point3& p, OptionalJacobian<3, 3> H = boost::none); /// cross product @return this x q -Point3 cross(const Point3& p, const Point3& q, - OptionalJacobian<3, 3> H_p = boost::none, - OptionalJacobian<3, 3> H_q = boost::none); +GTSAM_EXPORT Point3 cross(const Point3& p, const Point3& q, + OptionalJacobian<3, 3> H_p = boost::none, + OptionalJacobian<3, 3> H_q = boost::none); /// dot product -double dot(const Point3& p, const Point3& q, - OptionalJacobian<1, 3> H_p = boost::none, - OptionalJacobian<1, 3> H_q = boost::none); +GTSAM_EXPORT double dot(const Point3& p, const Point3& q, + OptionalJacobian<1, 3> H_p = boost::none, + OptionalJacobian<1, 3> H_q = boost::none); template struct Range; diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index fdfe32e8b..e49e93d5a 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -28,7 +28,7 @@ namespace gtsam { /// Exception thrown by triangulateDLT when SVD returns rank < 3 -class TriangulationUnderconstrainedException: public std::runtime_error { +class GTSAM_EXPORT TriangulationUnderconstrainedException: public std::runtime_error { public: TriangulationUnderconstrainedException() : std::runtime_error("Triangulation Underconstrained Exception.") { @@ -36,7 +36,7 @@ public: }; /// Exception thrown by triangulateDLT when landmark is behind one or more of the cameras -class TriangulationCheiralityException: public std::runtime_error { +class GTSAM_EXPORT TriangulationCheiralityException: public std::runtime_error { public: TriangulationCheiralityException() : std::runtime_error( @@ -319,7 +319,7 @@ Point3 triangulatePoint3( (cameras, measurements, rank_tol, optimize); } -struct TriangulationParameters { +struct GTSAM_EXPORT TriangulationParameters { double rankTolerance; ///< threshold to decide whether triangulation is result.degenerate ///< (the rank is the number of singular values of the triangulation matrix which are larger than rankTolerance) @@ -382,7 +382,7 @@ private: /** * TriangulationResult is an optional point, along with the reasons why it is invalid. */ -class TriangulationResult: public boost::optional { +class GTSAM_EXPORT TriangulationResult: public boost::optional { enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT }; diff --git a/gtsam/slam/SmartFactorParams.h b/gtsam/slam/SmartFactorParams.h index 761703f8b..e8a1fa7ab 100644 --- a/gtsam/slam/SmartFactorParams.h +++ b/gtsam/slam/SmartFactorParams.h @@ -39,7 +39,7 @@ enum DegeneracyMode { /* * Parameters for the smart (stereo) projection factors */ -struct GTSAM_EXPORT SmartProjectionParams { +struct SmartProjectionParams { LinearizationMode linearizationMode; ///< How to linearize the factor DegeneracyMode degeneracyMode; ///< How to linearize the factor From eb1e75fd27c72cc2ed42ae64c8fa1e05194ac20a Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Thu, 18 May 2017 14:46:46 -0700 Subject: [PATCH 07/27] fixing vc++14 compile issues --- gtsam/base/deprecated/LieMatrix.h | 4 ++-- gtsam/base/deprecated/LieVector.h | 6 +++--- gtsam/geometry/Cal3_S2Stereo.h | 2 +- gtsam/geometry/Point2.h | 14 +++++++------- gtsam/geometry/SO3.h | 4 ++-- gtsam/geometry/tests/testCameraSet.cpp | 6 +++--- gtsam/geometry/tests/testOrientedPlane3.cpp | 2 -- 7 files changed, 18 insertions(+), 20 deletions(-) diff --git a/gtsam/base/deprecated/LieMatrix.h b/gtsam/base/deprecated/LieMatrix.h index e26f45511..9ee20a596 100644 --- a/gtsam/base/deprecated/LieMatrix.h +++ b/gtsam/base/deprecated/LieMatrix.h @@ -29,7 +29,7 @@ namespace gtsam { * we can directly add double, Vector, and Matrix into values now, because of * gtsam::traits. */ -struct LieMatrix : public Matrix { +struct GTSAM_EXPORT LieMatrix : public Matrix { /// @name Constructors /// @{ @@ -60,7 +60,7 @@ struct LieMatrix : public Matrix { /// @{ /** print @param s optional string naming the object */ - GTSAM_EXPORT void print(const std::string& name = "") const { + void print(const std::string& name = "") const { gtsam::print(matrix(), name); } /** equality up to tolerance */ diff --git a/gtsam/base/deprecated/LieVector.h b/gtsam/base/deprecated/LieVector.h index 4a85036e0..b271275c3 100644 --- a/gtsam/base/deprecated/LieVector.h +++ b/gtsam/base/deprecated/LieVector.h @@ -27,7 +27,7 @@ namespace gtsam { * we can directly add double, Vector, and Matrix into values now, because of * gtsam::traits. */ -struct LieVector : public Vector { +struct GTSAM_EXPORT LieVector : public Vector { enum { dimension = Eigen::Dynamic }; @@ -51,13 +51,13 @@ struct LieVector : public Vector { LieVector(double d) : Vector((Vector(1) << d).finished()) {} /** constructor with size and initial data, row order ! */ - GTSAM_EXPORT LieVector(size_t m, const double* const data) : Vector(m) { + LieVector(size_t m, const double* const data) : Vector(m) { for (size_t i = 0; i < m; i++) (*this)(i) = data[i]; } /// @name Testable /// @{ - GTSAM_EXPORT void print(const std::string& name="") const { + void print(const std::string& name="") const { gtsam::print(vector(), name); } bool equals(const LieVector& expected, double tol=1e-5) const { diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index db49448ec..3a0f56c30 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -27,7 +27,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class Cal3_S2Stereo { + class GTSAM_EXPORT Cal3_S2Stereo { private: Cal3_S2 K_; diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index fb250df6d..cfd7b4500 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -152,23 +152,23 @@ struct traits : public internal::VectorSpace { #endif // GTSAM_TYPEDEF_POINTS_TO_VECTORS /// Distance of the point from the origin, with Jacobian -double norm2(const Point2& p, OptionalJacobian<1, 2> H = boost::none); +GTSAM_EXPORT double norm2(const Point2& p, OptionalJacobian<1, 2> H = boost::none); /// distance between two points -double distance2(const Point2& p1, const Point2& q, +GTSAM_EXPORT double distance2(const Point2& p1, const Point2& q, OptionalJacobian<1, 2> H1 = boost::none, OptionalJacobian<1, 2> H2 = boost::none); // Convenience typedef typedef std::pair Point2Pair; -std::ostream &operator<<(std::ostream &os, const gtsam::Point2Pair &p); +GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const gtsam::Point2Pair &p); // For MATLAB wrapper typedef std::vector Point2Vector; /// multiply with scalar inline Point2 operator*(double s, const Point2& p) { -return p * s; + return p * s; } /* @@ -185,7 +185,7 @@ return p * s; * @param tol: absolute tolerance below which we consider touching circles * @return optional Point2 with f and h, boost::none if no solution. */ -boost::optional circleCircleIntersection(double R_d, double r_d, double tol = 1e-9); +GTSAM_EXPORT boost::optional circleCircleIntersection(double R_d, double r_d, double tol = 1e-9); /* * @brief Circle-circle intersection, from the normalized radii solution. @@ -193,7 +193,7 @@ boost::optional circleCircleIntersection(double R_d, double r_d, double * @param c2 center of second circle * @return list of solutions (0,1, or 2). Identical circles will return empty list, as well. */ -std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); +GTSAM_EXPORT std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); /** * @brief Intersect 2 circles @@ -204,7 +204,7 @@ std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional * @param tol: absolute tolerance below which we consider touching circles * @return list of solutions (0,1, or 2). Identical circles will return empty list, as well. */ -std::list circleCircleIntersection(Point2 c1, double r1, +GTSAM_EXPORT std::list circleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9); } // \ namespace gtsam diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index 53f2c2130..e9d257acb 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -135,7 +135,7 @@ public: namespace so3 { /// Functor implementing Exponential map -class ExpmapFunctor { +class GTSAM_EXPORT ExpmapFunctor { protected: const double theta2; Matrix3 W, K, KK; @@ -156,7 +156,7 @@ class ExpmapFunctor { }; /// Functor that implements Exponential map *and* its derivatives -class DexpFunctor : public ExpmapFunctor { +class GTSAM_EXPORT DexpFunctor : public ExpmapFunctor { const Vector3 omega; double a, b; Matrix3 dexp_; diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 01f784ae0..de7fe4625 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -89,7 +89,7 @@ TEST(CameraSet, Pinhole) { Vector4 b = actualV; Vector v = Ft * (b - E * P * Et * b); schur << Ft * F - Ft * E * P * Et * F, v, v.transpose(), 30; - SymmetricBlockMatrix actualReduced = Set::SchurComplement(Fs, E, P, b); + SymmetricBlockMatrix actualReduced = Set::SchurComplement<3>(Fs, E, P, b); EXPECT(assert_equal(schur, actualReduced.selfadjointView())); // Check Schur complement update, same order, should just double @@ -98,14 +98,14 @@ TEST(CameraSet, Pinhole) { allKeys.push_back(2); keys.push_back(1); keys.push_back(2); - Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys, actualReduced); + Set::UpdateSchurComplement<3>(Fs, E, P, b, allKeys, keys, actualReduced); EXPECT(assert_equal((Matrix )(2.0 * schur), actualReduced.selfadjointView())); // Check Schur complement update, keys reversed FastVector keys2; keys2.push_back(2); keys2.push_back(1); - Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys2, actualReduced); + Set::UpdateSchurComplement<3>(Fs, E, P, b, allKeys, keys2, actualReduced); Vector4 reverse_b; reverse_b << b.tail<2>(), b.head<2>(); Vector reverse_v = Ft * (reverse_b - E * P * Et * reverse_b); diff --git a/gtsam/geometry/tests/testOrientedPlane3.cpp b/gtsam/geometry/tests/testOrientedPlane3.cpp index b3d87f18c..a1531e07c 100644 --- a/gtsam/geometry/tests/testOrientedPlane3.cpp +++ b/gtsam/geometry/tests/testOrientedPlane3.cpp @@ -120,8 +120,6 @@ TEST(OrientedPlane3, localCoordinates_retract) { maxXiLimit << M_PI, M_PI, 10.0; for (size_t i = 0; i < numIterations; i++) { - sleep(0); - // Create a Plane OrientedPlane3 p1(randomVector(minPlaneLimit, maxPlaneLimit)); Vector v12 = randomVector(minXiLimit, maxXiLimit); From 0f80f9bf41e30103907b012374305915eaedbce4 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Fri, 19 May 2017 18:51:14 -0700 Subject: [PATCH 08/27] static lib and examples compiles --- CMakeLists.txt | 2 +- cmake/dllexport.h.in | 29 ++++++++++++++++++----------- gtsam/CMakeLists.txt | 4 ++-- 3 files changed, 21 insertions(+), 14 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6db1f6681..115c8bb49 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -128,7 +128,7 @@ option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF) # Allow for not using the timer libraries on boost < 1.48 (GTSAM timing code falls back to old timer library) set(GTSAM_BOOST_LIBRARIES ${Boost_SERIALIZATION_LIBRARY} ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY} - ${Boost_THREAD_LIBRARY} ${Boost_DATE_TIME_LIBRARY}) + ${Boost_THREAD_LIBRARY} ${Boost_DATE_TIME_LIBRARY} ${Boost_REGEX_LIBRARY}) if (GTSAM_DISABLE_NEW_TIMERS) message("WARNING: GTSAM timing instrumentation manually disabled") add_definitions(-DGTSAM_DISABLE_NEW_TIMERS) diff --git a/cmake/dllexport.h.in b/cmake/dllexport.h.in index 023f06f57..6539e869e 100644 --- a/cmake/dllexport.h.in +++ b/cmake/dllexport.h.in @@ -26,21 +26,28 @@ // class __declspec(dllexport) MyClass { ... }; // When included while compiling other code against GTSAM: // class __declspec(dllimport) MyClass { ... }; + +#pragma once + +// Whether GTSAM is compiled as static or DLL in windows. +// This will be used to decide whether include __declspec(dllimport) or not in headers +// TODO: replace GTSAM by @library_name@ +#cmakedefine GTSAM_BUILD_STATIC_LIBRARY + #ifdef _WIN32 -# ifdef @library_name@_EXPORTS -# define @library_name@_EXPORT __declspec(dllexport) -# define @library_name@_EXTERN_EXPORT __declspec(dllexport) extern -# else -# ifndef @library_name@_IMPORT_STATIC +# ifdef @library_name@_BUILD_STATIC_LIBRARY +# define @library_name@_EXPORT +# define @library_name@_EXTERN_EXPORT extern +# else /* @library_name@_BUILD_STATIC_LIBRARY */ +# ifdef @library_name@_EXPORTS +# define @library_name@_EXPORT __declspec(dllexport) +# define @library_name@_EXTERN_EXPORT __declspec(dllexport) extern +# else /* @library_name@_EXPORTS */ # define @library_name@_EXPORT __declspec(dllimport) # define @library_name@_EXTERN_EXPORT __declspec(dllimport) -# else /* @library_name@_IMPORT_STATIC */ -# define @library_name@_EXPORT -# define @library_name@_EXTERN_EXPORT extern -# endif /* @library_name@_IMPORT_STATIC */ -# endif /* @library_name@_EXPORTS */ +# endif /* @library_name@_EXPORTS */ +# endif /* @library_name@_BUILD_STATIC_LIBRARY */ #else /* _WIN32 */ # define @library_name@_EXPORT # define @library_name@_EXTERN_EXPORT extern #endif - diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 8c1d8bb43..7cf801e74 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -110,8 +110,8 @@ if (GTSAM_BUILD_STATIC_LIBRARY) SOVERSION ${gtsam_soversion}) if(WIN32) # Add 'lib' prefix to static library to avoid filename collision with shared library set_target_properties(gtsam PROPERTIES - PREFIX "lib" - COMPILE_DEFINITIONS GTSAM_IMPORT_STATIC) + PREFIX "lib") + #COMPILE_DEFINITIONS GTSAM_IMPORT_STATIC) endif() install(TARGETS gtsam EXPORT GTSAM-exports ARCHIVE DESTINATION lib) list(APPEND GTSAM_EXPORTED_TARGETS gtsam) From bf0c9dccaa739542d1ec25392d044579e755bd1c Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 22 Oct 2018 19:10:52 -0400 Subject: [PATCH 09/27] cmake changes --- CMakeLists.txt | 3 +++ gtsam/3rdparty/metis/CMakeLists.txt | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 115c8bb49..b3e038efe 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -108,6 +108,7 @@ set(CPACK_GENERATOR "TGZ" CACHE STRING "CPack Default Binary Generator") # If using Boost shared libs, disable auto linking if(MSVC) + set(Boost_USE_STATIC_LIBS ON) # only find static libs # Some libraries, at least Boost Program Options, rely on this to export DLL symbols # Disable autolinking if(NOT Boost_USE_STATIC_LIBS) @@ -319,6 +320,8 @@ include_directories(BEFORE if(MSVC) add_definitions(-D_CRT_SECURE_NO_WARNINGS -D_SCL_SECURE_NO_WARNINGS) add_definitions(/wd4251 /wd4275 /wd4251 /wd4661 /wd4344 /wd4503) # Disable non-DLL-exported base class and other warnings + add_definitions(/wd4244) # Disable loss of precision which is thrown all over our Eigen + add_definitions(/bigobj) # Allow large object files for template-based code endif() # GCC 4.8+ complains about local typedefs which we use for shared_ptr etc. diff --git a/gtsam/3rdparty/metis/CMakeLists.txt b/gtsam/3rdparty/metis/CMakeLists.txt index dd21338a4..f864e02ac 100644 --- a/gtsam/3rdparty/metis/CMakeLists.txt +++ b/gtsam/3rdparty/metis/CMakeLists.txt @@ -23,7 +23,7 @@ set(GKLIB_PATH ${PROJECT_SOURCE_DIR}/GKlib CACHE PATH "path to GKlib") set(METIS_SHARED TRUE CACHE BOOL "build a shared library") if(MSVC) - set(METIS_INSTALL FALSE) + set(METIS_INSTALL TRUE) else() set(METIS_INSTALL FALSE) endif() From 1c8578d52f6ebf7a50e79d253b4da6b1255acbd5 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 23 Oct 2018 12:18:25 -0400 Subject: [PATCH 10/27] Ignore MSVC 2017 files --- .gitignore | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.gitignore b/.gitignore index 2682a6748..42bd27466 100644 --- a/.gitignore +++ b/.gitignore @@ -17,3 +17,5 @@ cython/gtsam.so cython/gtsam_wrapper.pxd .vscode .env +/.vs/ +/CMakeSettings.json From 846a2619df1c3271bfab0afe996d479ae1fae296 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 23 Oct 2018 22:50:30 -0400 Subject: [PATCH 11/27] Don't export because has templated methods. Might need to revisit and export individual non-templated methods. --- gtsam/geometry/SO3.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index e9d257acb..3b27d45c5 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -33,7 +33,7 @@ namespace gtsam { * We guarantee (all but first) constructors only generate from sub-manifold. * However, round-off errors in repeated composition could move off it... */ -class GTSAM_EXPORT SO3: public Matrix3, public LieGroup { +class SO3: public Matrix3, public LieGroup { protected: From 9b7f80f25cf69cde11de6eeda8093f969bcc6247 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 23 Oct 2018 22:51:44 -0400 Subject: [PATCH 12/27] GenericValue stores a T. So, it potentially has to be aligned. We check this requirement and call Eigen's aligning operator if so. --- gtsam/base/GenericValue.h | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index f98b3669e..1b59b6c1d 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -187,7 +187,14 @@ public: ar & boost::serialization::make_nvp("GenericValue", boost::serialization::base_object(*this)); ar & boost::serialization::make_nvp("value", value_); - } + + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + } /// use this macro instead of BOOST_CLASS_EXPORT for GenericValues #define GTSAM_VALUE_EXPORT(Type) BOOST_CLASS_EXPORT(gtsam::GenericValue) From a7678698d37abe33ab83c842e3f1fa84d6fda209 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 23 Oct 2018 23:20:17 -0400 Subject: [PATCH 13/27] Fixed some warnings --- gtsam/linear/HessianFactor.cpp | 2 +- gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp | 2 +- gtsam/nonlinear/internal/LevenbergMarquardtState.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/linear/HessianFactor.cpp b/gtsam/linear/HessianFactor.cpp index 29b2b8591..428fb6cde 100644 --- a/gtsam/linear/HessianFactor.cpp +++ b/gtsam/linear/HessianFactor.cpp @@ -486,7 +486,7 @@ boost::shared_ptr HessianFactor::eliminateCholesky(const Or // Erase the eliminated keys in this factor keys_.erase(begin(), begin() + nFrontals); - } catch (const CholeskyFailed& e) { + } catch (const CholeskyFailed&) { throw IndeterminantLinearSystemException(keys.front()); } diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 5f29c3bdf..b9579661d 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -148,7 +148,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear, // ============ Solve is where most computation happens !! ================= delta = solve(dampedSystem, params_); systemSolvedSuccessfully = true; - } catch (const IndeterminantLinearSystemException& e) { + } catch (const IndeterminantLinearSystemException&) { systemSolvedSuccessfully = false; } diff --git a/gtsam/nonlinear/internal/LevenbergMarquardtState.h b/gtsam/nonlinear/internal/LevenbergMarquardtState.h index bd5465dda..8ab2e7466 100644 --- a/gtsam/nonlinear/internal/LevenbergMarquardtState.h +++ b/gtsam/nonlinear/internal/LevenbergMarquardtState.h @@ -147,7 +147,7 @@ struct LevenbergMarquardtState : public NonlinearOptimizerState { CachedModel* item = getCachedModel(dim); item->A.diagonal() = sqrtHessianDiagonal.at(key); // use diag(hessian) damped += boost::make_shared(key, item->A, item->b, item->model); - } catch (const std::out_of_range& e) { + } catch (const std::out_of_range&) { continue; // Don't attempt any damping if no key found in diagonal } } From 1c2cd7045e9852aadd5689354c4d8384fbf7f063 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 23 Oct 2018 23:37:36 -0400 Subject: [PATCH 14/27] Fixed alignment warnings on windows by adding EIGEN_MAKE_ALIGNED_OPERATOR_NEW --- gtsam/geometry/BearingRange.h | 3 +++ gtsam/geometry/OrientedPlane3.h | 3 +++ gtsam/navigation/AttitudeFactor.h | 6 ++++++ gtsam/slam/BetweenFactor.h | 3 +++ gtsam/slam/EssentialMatrixConstraint.h | 3 +++ gtsam/slam/PriorFactor.h | 3 +++ 6 files changed, 21 insertions(+) diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index b1e003864..33a799c1a 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -94,6 +94,9 @@ struct BearingRange } friend class boost::serialization::access; + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // Declare this to be both Testable and a Manifold diff --git a/gtsam/geometry/OrientedPlane3.h b/gtsam/geometry/OrientedPlane3.h index e425a4b81..4bca8d138 100644 --- a/gtsam/geometry/OrientedPlane3.h +++ b/gtsam/geometry/OrientedPlane3.h @@ -156,6 +156,9 @@ public: } /// @} + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; template<> struct traits : public internal::Manifold< diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 21f74ac06..4ae6078e9 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -129,6 +129,9 @@ private: ar & BOOST_SERIALIZATION_NVP(nZ_); ar & BOOST_SERIALIZATION_NVP(bRef_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; /// traits @@ -213,6 +216,9 @@ private: ar & BOOST_SERIALIZATION_NVP(nZ_); ar & BOOST_SERIALIZATION_NVP(bRef_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; /// traits diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index f3fd49fa7..7af43e986 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -122,6 +122,9 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // \class BetweenFactor /// traits diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 92a78279b..9aa8f8b83 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -103,6 +103,9 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measuredE_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // \class EssentialMatrixConstraint diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index 9a3a4a47a..c8ed378d8 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -104,6 +104,9 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(prior_); } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam From c93cd7e5f1d8a4999052383de07676aa4e28b84a Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 2 Nov 2018 23:26:20 -0400 Subject: [PATCH 15/27] Removed unnecessary (I think) aligned new operators. --- gtsam/geometry/BearingRange.h | 3 --- gtsam/geometry/CalibratedCamera.h | 7 ------- gtsam/geometry/OrientedPlane3.h | 3 --- gtsam/geometry/Pose3.h | 4 ---- 4 files changed, 17 deletions(-) diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index 33a799c1a..b1e003864 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -94,9 +94,6 @@ struct BearingRange } friend class boost::serialization::access; - -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // Declare this to be both Testable and a Manifold diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index db9caf13b..acb3cacaf 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -229,10 +229,6 @@ private: void serialize(Archive & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_NVP(pose_); } - -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - }; // end of class PinholeBase @@ -416,9 +412,6 @@ private: } /// @} - -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // manifold traits diff --git a/gtsam/geometry/OrientedPlane3.h b/gtsam/geometry/OrientedPlane3.h index 4bca8d138..e425a4b81 100644 --- a/gtsam/geometry/OrientedPlane3.h +++ b/gtsam/geometry/OrientedPlane3.h @@ -156,9 +156,6 @@ public: } /// @} - -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; template<> struct traits : public internal::Manifold< diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 3229cbbbe..d70295f58 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -326,10 +326,6 @@ public: ar & BOOST_SERIALIZATION_NVP(t_); } /// @} - - public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - }; // Pose3 class From d7ca1862690a379668055f269c46a5e90a8f2743 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 2 Nov 2018 23:29:52 -0400 Subject: [PATCH 16/27] Straightforward conditional aligned new operator --- gtsam/base/GenericValue.h | 16 +++++++--------- gtsam/slam/BetweenFactor.h | 6 ++++-- gtsam/slam/PriorFactor.h | 4 +++- 3 files changed, 14 insertions(+), 12 deletions(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 1b59b6c1d..229050448 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -187,20 +187,18 @@ public: ar & boost::serialization::make_nvp("GenericValue", boost::serialization::base_object(*this)); ar & boost::serialization::make_nvp("value", value_); - - // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html - enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; - - public: - - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) } + + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) +}; + /// use this macro instead of BOOST_CLASS_EXPORT for GenericValues #define GTSAM_VALUE_EXPORT(Type) BOOST_CLASS_EXPORT(gtsam::GenericValue) -}; - // traits template struct traits > diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 7af43e986..89291fac5 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -123,8 +123,10 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(measured_); } - public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 }; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // \class BetweenFactor /// traits diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index c8ed378d8..3c5c42ccc 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -105,8 +105,10 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(prior_); } + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; } /// namespace gtsam From 2d0ba69fa489c00d5d80a21f7372c2024df60f1d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 2 Nov 2018 23:31:28 -0400 Subject: [PATCH 17/27] Config-dependent aligned new operator --- gtsam/geometry/Pose2.h | 6 ++++++ gtsam/geometry/Rot3.h | 6 ++++-- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 1ba384857..f03e0852e 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -278,6 +278,12 @@ private: ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(r_); } + +#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS +public: + // Make sure Pose2 is aligned if it contains a Vector2 + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#endif }; // Pose2 /** specialization for pose2 wedge function (generic template in Lie.h) */ diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 263301122..985c521a2 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -508,9 +508,11 @@ namespace gtsam { #endif } - public: +#ifdef GTSAM_USE_QUATERNIONS + // only align if quaternion, Matrix3 has no alignment requirements + public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW - +#endif }; /** From 8900739bd39583c52c6e6786cb3114b8f1c83d79 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 3 Nov 2018 00:21:36 -0400 Subject: [PATCH 18/27] Conditional aligned new, but not sure it has effect since inherits from pair --- gtsam/base/Manifold.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index b30edb3df..f89680b7c 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -209,6 +209,12 @@ public: v << v1, v2; return v; } + + // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html + enum { NeedsToAlign = (sizeof(M1) % 16) == 0 || (sizeof(M2) % 16) == 0 + }; +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Define any direct product group to be a model of the multiplicative Group concept From 142797723067a765c53378b6440aa4bb6d04be1b Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 3 Nov 2018 10:20:31 -0400 Subject: [PATCH 19/27] Undo Eigen change (needed to remove GTSAM_EXPORT in SO3 to do this) --- gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h index 9e4981586..77f4f6066 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h @@ -431,7 +431,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResize(Index size) { - internal::conservative_resize_like_impl::run(*this, size, 1); + internal::conservative_resize_like_impl::run(*this, size); } /** Resizes the matrix to \a rows x \a cols of \c other, while leaving old values untouched. From e38a3156c34d31b5d1286095bef467dfa8054e4f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 4 Nov 2018 12:37:43 -0500 Subject: [PATCH 20/27] Adding a pre-compiled header for MSVC --- cmake/GtsamAddPch.cmake | 27 +++++++++++++++++ gtsam/CMakeLists.txt | 28 ++++++++--------- gtsam/precompiled_header.cpp | 19 ++++++++++++ gtsam/precompiled_header.h | 59 ++++++++++++++++++++++++++++++++++++ 4 files changed, 119 insertions(+), 14 deletions(-) create mode 100644 cmake/GtsamAddPch.cmake create mode 100644 gtsam/precompiled_header.cpp create mode 100644 gtsam/precompiled_header.h diff --git a/cmake/GtsamAddPch.cmake b/cmake/GtsamAddPch.cmake new file mode 100644 index 000000000..cb872e361 --- /dev/null +++ b/cmake/GtsamAddPch.cmake @@ -0,0 +1,27 @@ +############################################################################### +# Macro: +# +# gtsamAddPch(precompiledHeader precompiledSource sources) +# +# Adds a precompiled header to compile all sources with. Currently only on MSVC. +# Inspired by https://stackoverflow.com/questions/148570/ +# +# Arguments: +# precompiledHeader: the header file that includes headers to be precompiled. +# precompiledSource: the source file that simply includes that header above. +# sources: the list of source files to apply this to. +# +macro(gtsamAddPch precompiledHeader precompiledSource sources) + get_filename_component(pchBasename ${precompiledHeader} NAME_WE) + SET(precompiledBinary "${CMAKE_CURRENT_BINARY_DIR}/${pchBasename}.pch") + IF(MSVC) + message(STATUS "Adding precompiled header for MSVC") + set_source_files_properties(${precompiledSource} + PROPERTIES COMPILE_FLAGS "/Yc\"${precompiledHeader}\" /Fp\"${precompiledBinary}\"" + OBJECT_OUTPUTS "${precompiledBinary}") + set_source_files_properties(${sources} + PROPERTIES COMPILE_FLAGS "/Yu\"${precompiledHeader}\" /FI\"${precompiledHeader}\" /Fp\"${precompiledBinary}\"" + OBJECT_DEPENDS "${precompiledBinary}") + ENDIF(MSVC) +endmacro(gtsamAddPch) + diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 10092f195..6a3d08eb8 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -65,20 +65,19 @@ foreach(subdir ${gtsam_subdirs}) endforeach(subdir) # To add additional sources to gtsam when building the full library (static or shared) -# Add the subfolder with _srcs appended to the end to this list -set(gtsam_srcs - ${3rdparty_srcs} - ${base_srcs} - ${geometry_srcs} - ${inference_srcs} - ${symbolic_srcs} - ${discrete_srcs} - ${linear_srcs} - ${nonlinear_srcs} - ${slam_srcs} - ${navigation_srcs} - ${gtsam_core_headers} -) +# append the subfolder with _srcs appended to the end to this list +set(gtsam_srcs ${3rdparty_srcs}) +foreach(subdir ${gtsam_subdirs}) + list(APPEND gtsam_srcs ${${subdir}_srcs}) +endforeach(subdir) +list(APPEND gtsam_srcs ${gtsam_core_headers}) + +IF(MSVC) + # Add precompiled header to sources + include(gtsamAddPch) + gtsamAddPch("precompiled_header.h" "precompiled_header.cpp" ${gtsam_srcs}) + list(INSERT gtsam_srcs 0 "precompiled_header.cpp") +ENDIF(MSVC) # Generate and install config and dllexport files configure_file(config.h.in config.h) @@ -155,6 +154,7 @@ if(MSVC) APPEND PROPERTY COMPILE_FLAGS "/bigobj") endif() + # Create the matlab toolbox for the gtsam library if (GTSAM_INSTALL_MATLAB_TOOLBOX) # Set up codegen diff --git a/gtsam/precompiled_header.cpp b/gtsam/precompiled_header.cpp new file mode 100644 index 000000000..83bc6231a --- /dev/null +++ b/gtsam/precompiled_header.cpp @@ -0,0 +1,19 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + + /** + * @file precompiled_header.cpp + * @brief We need exactly one compilation unit that includes the precompiled headers + * @author Frank Dellaert + * @date November 2018 + */ + +#include "precompiled_header.h" \ No newline at end of file diff --git a/gtsam/precompiled_header.h b/gtsam/precompiled_header.h new file mode 100644 index 000000000..c1b159802 --- /dev/null +++ b/gtsam/precompiled_header.h @@ -0,0 +1,59 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + + /** + * @file precompiled_header.h> + * @brief Include headers that will be included nearly everywhere + * @author Frank Dellaert + * @date November 2018 + */ + +#pragma once + +// All headers in base: +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + From 7e566aeb16479183bcc8476a65bf9467104732d4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 5 Nov 2018 00:15:21 -0500 Subject: [PATCH 21/27] Resolve alignment conflict --- gtsam/geometry/Pose3.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index d70295f58..725a888ca 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -326,6 +326,12 @@ public: ar & BOOST_SERIALIZATION_NVP(t_); } /// @} + +#ifdef GTSAM_USE_QUATERNIONS + // Align if we are using Quaternions + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#endif }; // Pose3 class From 68f1cbdb08af182b96a717b6aa15bd141e810201 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 6 Nov 2018 00:18:45 -0500 Subject: [PATCH 22/27] Refactored templates so we can get rid of FactorGraph include for faster/tighter compile --- gtsam/inference/Ordering.h | 35 ++++++++++++++++++----------------- 1 file changed, 18 insertions(+), 17 deletions(-) diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index ae7a10f44..30cc54c06 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -11,8 +11,10 @@ /** * @file Ordering.h + * @brief Variable ordering for the elimination algorithm * @author Richard Roberts * @author Andrew Melim + * @author Frank Dellaert * @date Sep 2, 2010 */ @@ -21,7 +23,6 @@ #include #include #include -#include #include #include @@ -77,8 +78,8 @@ public: /// Compute a fill-reducing ordering using COLAMD from a factor graph (see details for note on /// performance). This internally builds a VariableIndex so if you already have a VariableIndex, /// it is faster to use COLAMD(const VariableIndex&) - template - static Ordering Colamd(const FactorGraph& graph) { + template + static Ordering Colamd(const FACTOR_GRAPH& graph) { if (graph.empty()) return Ordering(); else @@ -96,8 +97,8 @@ public: /// constrainLast will be ordered in the same order specified in the vector \c /// constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. - template - static Ordering ColamdConstrainedLast(const FactorGraph& graph, + template + static Ordering ColamdConstrainedLast(const FACTOR_GRAPH& graph, const std::vector& constrainLast, bool forceOrder = false) { if (graph.empty()) return Ordering(); @@ -123,8 +124,8 @@ public: /// constrainFirst will be ordered in the same order specified in the vector \c /// constrainFirst. If \c forceOrder is false, the variables in \c constrainFirst will be /// ordered before all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. - template - static Ordering ColamdConstrainedFirst(const FactorGraph& graph, + template + static Ordering ColamdConstrainedFirst(const FACTOR_GRAPH& graph, const std::vector& constrainFirst, bool forceOrder = false) { if (graph.empty()) return Ordering(); @@ -152,8 +153,8 @@ public: /// arbitrary order. Any variables not present in \c groups will be assigned to group 0. This /// function simply fills the \c cmember argument to CCOLAMD with the supplied indices, see the /// CCOLAMD documentation for more information. - template - static Ordering ColamdConstrained(const FactorGraph& graph, + template + static Ordering ColamdConstrained(const FACTOR_GRAPH& graph, const FastMap& groups) { if (graph.empty()) return Ordering(); @@ -172,8 +173,8 @@ public: const VariableIndex& variableIndex, const FastMap& groups); /// Return a natural Ordering. Typically used by iterative solvers - template - static Ordering Natural(const FactorGraph &fg) { + template + static Ordering Natural(const FACTOR_GRAPH &fg) { KeySet src = fg.keys(); std::vector keys(src.begin(), src.end()); std::stable_sort(keys.begin(), keys.end()); @@ -181,15 +182,15 @@ public: } /// METIS Formatting function - template + template static GTSAM_EXPORT void CSRFormat(std::vector& xadj, - std::vector& adj, const FactorGraph& graph); + std::vector& adj, const FACTOR_GRAPH& graph); /// Compute an ordering determined by METIS from a VariableIndex static GTSAM_EXPORT Ordering Metis(const MetisIndex& met); - template - static Ordering Metis(const FactorGraph& graph) { + template + static Ordering Metis(const FACTOR_GRAPH& graph) { return Metis(MetisIndex(graph)); } @@ -197,9 +198,9 @@ public: /// @name Named Constructors @{ - template + template static Ordering Create(OrderingType orderingType, - const FactorGraph& graph) { + const FACTOR_GRAPH& graph) { if (graph.empty()) return Ordering(); From 7d4ec362792b647be35d4ce62c8fe1eeb8159309 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 6 Nov 2018 00:19:54 -0500 Subject: [PATCH 23/27] Removed some offending headers in pch --- gtsam/base/testLie.h | 4 ++-- gtsam/precompiled_header.h | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/gtsam/base/testLie.h b/gtsam/base/testLie.h index 1906ec439..63eb8674d 100644 --- a/gtsam/base/testLie.h +++ b/gtsam/base/testLie.h @@ -10,8 +10,8 @@ * -------------------------------------------------------------------------- */ /* - * @file chartTesting.h - * @brief + * @file testLie.h + * @brief Test utilities for Lie groups * @date November, 2014 * @author Paul Furgale */ diff --git a/gtsam/precompiled_header.h b/gtsam/precompiled_header.h index c1b159802..37ab01cf2 100644 --- a/gtsam/precompiled_header.h +++ b/gtsam/precompiled_header.h @@ -18,7 +18,10 @@ #pragma once -// All headers in base: +// All headers in base, except: +// treeTraversal-inst.h: very specific to only a few compilation units +// numericalDerivative.h : includes things in linear, nonlinear :-( +// testLie.h: includes numericalDerivative #include #include #include @@ -38,7 +41,6 @@ #include #include #include -#include #include #include #include @@ -46,10 +48,8 @@ #include #include #include -#include #include #include -#include #include #include #include From c1840f3d245c65c47600a6600ca50111125bf055 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 8 Nov 2018 09:51:01 -0500 Subject: [PATCH 24/27] Removed TODO, superfluous comments --- cmake/dllexport.h.in | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/cmake/dllexport.h.in b/cmake/dllexport.h.in index 6539e869e..55683a496 100644 --- a/cmake/dllexport.h.in +++ b/cmake/dllexport.h.in @@ -31,23 +31,22 @@ // Whether GTSAM is compiled as static or DLL in windows. // This will be used to decide whether include __declspec(dllimport) or not in headers -// TODO: replace GTSAM by @library_name@ #cmakedefine GTSAM_BUILD_STATIC_LIBRARY #ifdef _WIN32 # ifdef @library_name@_BUILD_STATIC_LIBRARY # define @library_name@_EXPORT # define @library_name@_EXTERN_EXPORT extern -# else /* @library_name@_BUILD_STATIC_LIBRARY */ +# else # ifdef @library_name@_EXPORTS # define @library_name@_EXPORT __declspec(dllexport) # define @library_name@_EXTERN_EXPORT __declspec(dllexport) extern -# else /* @library_name@_EXPORTS */ +# else # define @library_name@_EXPORT __declspec(dllimport) # define @library_name@_EXTERN_EXPORT __declspec(dllimport) -# endif /* @library_name@_EXPORTS */ -# endif /* @library_name@_BUILD_STATIC_LIBRARY */ -#else /* _WIN32 */ +# endif +# endif +#else # define @library_name@_EXPORT # define @library_name@_EXTERN_EXPORT extern #endif From 8d61e3a4d95b89b6b700cf29455926ecc86ca0bb Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 8 Nov 2018 09:51:23 -0500 Subject: [PATCH 25/27] Restored to (nonsensical?) state it was before --- gtsam/3rdparty/metis/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/3rdparty/metis/CMakeLists.txt b/gtsam/3rdparty/metis/CMakeLists.txt index f864e02ac..dd21338a4 100644 --- a/gtsam/3rdparty/metis/CMakeLists.txt +++ b/gtsam/3rdparty/metis/CMakeLists.txt @@ -23,7 +23,7 @@ set(GKLIB_PATH ${PROJECT_SOURCE_DIR}/GKlib CACHE PATH "path to GKlib") set(METIS_SHARED TRUE CACHE BOOL "build a shared library") if(MSVC) - set(METIS_INSTALL TRUE) + set(METIS_INSTALL FALSE) else() set(METIS_INSTALL FALSE) endif() From 85a2c8e5bf00db63a7fff05ac7937aebb077c169 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 8 Nov 2018 09:51:46 -0500 Subject: [PATCH 26/27] Restored flag, builds fine --- gtsam/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 6a3d08eb8..4d1007d19 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -108,8 +108,8 @@ if (GTSAM_BUILD_STATIC_LIBRARY) SOVERSION ${gtsam_soversion}) if(WIN32) # Add 'lib' prefix to static library to avoid filename collision with shared library set_target_properties(gtsam PROPERTIES - PREFIX "lib") - #COMPILE_DEFINITIONS GTSAM_IMPORT_STATIC) + PREFIX "lib" + COMPILE_DEFINITIONS GTSAM_IMPORT_STATIC) endif() install(TARGETS gtsam EXPORT GTSAM-exports ARCHIVE DESTINATION lib) list(APPEND GTSAM_EXPORTED_TARGETS gtsam) From 1becaab652a0a25c07f3455465129aef575ec5c1 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 8 Nov 2018 09:52:12 -0500 Subject: [PATCH 27/27] Added comment --- CMakeLists.txt | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 740ef7416..45a57827d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -111,11 +111,12 @@ set(CPACK_GENERATOR "TGZ" CACHE STRING "CPack Default Binary Generator") # BOOST_ROOT: path to install prefix for boost # Boost_NO_SYSTEM_PATHS: set to true to keep the find script from ignoring BOOST_ROOT -# If using Boost shared libs, disable auto linking if(MSVC) - set(Boost_USE_STATIC_LIBS ON) # only find static libs - # Some libraries, at least Boost Program Options, rely on this to export DLL symbols - # Disable autolinking + # By default, boost only builds static libraries on windows + set(Boost_USE_STATIC_LIBS ON) # only find static libs + # If we ever reset above on windows and, ... + # If we use Boost shared libs, disable auto linking. + # Some libraries, at least Boost Program Options, rely on this to export DLL symbols. if(NOT Boost_USE_STATIC_LIBS) add_definitions(-DBOOST_ALL_NO_LIB) add_definitions(-DBOOST_ALL_DYN_LINK) @@ -257,8 +258,13 @@ else() endif() -# tmp mute eigen static assert to avoid errors in shared lib -add_definitions(-DEIGEN_NO_STATIC_ASSERT) +if (MSVC) + if (NOT GTSAM_BUILD_STATIC_LIBRARY) + # mute eigen static assert to avoid errors in shared lib + add_definitions(-DEIGEN_NO_STATIC_ASSERT) + endif() + add_definitions(/wd4244) # Disable loss of precision which is thrown all over our Eigen +endif() ############################################################################### # Global compile options @@ -325,7 +331,6 @@ include_directories(BEFORE if(MSVC) add_definitions(-D_CRT_SECURE_NO_WARNINGS -D_SCL_SECURE_NO_WARNINGS) add_definitions(/wd4251 /wd4275 /wd4251 /wd4661 /wd4344 /wd4503) # Disable non-DLL-exported base class and other warnings - add_definitions(/wd4244) # Disable loss of precision which is thrown all over our Eigen add_definitions(/bigobj) # Allow large object files for template-based code endif()