diff --git a/.github/workflows/build-windows.yml b/.github/workflows/build-windows.yml index 5dfdcd0132..a9e794b3f9 100644 --- a/.github/workflows/build-windows.yml +++ b/.github/workflows/build-windows.yml @@ -26,7 +26,11 @@ jobs: windows-2019-cl, ] - build_type: [Debug, Release] + build_type: [ + Debug, + #TODO(Varun) The release build takes over 2.5 hours, need to figure out why. + # Release + ] build_unstable: [ON] include: #TODO This build fails, need to understand why. @@ -90,13 +94,18 @@ jobs: - name: Checkout uses: actions/checkout@v2 - - name: Build + - name: Configuration run: | cmake -E remove_directory build cmake -B build -S . -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF -DBOOST_ROOT="${env:BOOST_ROOT}" -DBOOST_INCLUDEDIR="${env:BOOST_ROOT}\boost\include" -DBOOST_LIBRARYDIR="${env:BOOST_ROOT}\lib" - cmake --build build --config ${{ matrix.build_type }} --target gtsam - cmake --build build --config ${{ matrix.build_type }} --target gtsam_unstable - cmake --build build --config ${{ matrix.build_type }} --target wrap - cmake --build build --config ${{ matrix.build_type }} --target check.base - cmake --build build --config ${{ matrix.build_type }} --target check.base_unstable - cmake --build build --config ${{ matrix.build_type }} --target check.linear + + - name: Build + run: | + # Since Visual Studio is a multi-generator, we need to use --config + # https://stackoverflow.com/a/24470998/1236990 + cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam + cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam_unstable + cmake --build build -j 4 --config ${{ matrix.build_type }} --target wrap + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.linear diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 7fafd95dfa..38d831e152 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -282,7 +282,7 @@ class GTSAM_EXPORT NoiseModelFactor: public NonlinearFactor { * which are objects in non-linear manifolds (Lie groups). */ template -class NoiseModelFactor1: public NoiseModelFactor { +class GTSAM_EXPORT NoiseModelFactor1: public NoiseModelFactor { public: @@ -366,7 +366,7 @@ class NoiseModelFactor1: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 2 * variables. To derive from this class, implement evaluateError(). */ template -class NoiseModelFactor2: public NoiseModelFactor { +class GTSAM_EXPORT NoiseModelFactor2: public NoiseModelFactor { public: @@ -441,7 +441,7 @@ class NoiseModelFactor2: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 3 * variables. To derive from this class, implement evaluateError(). */ template -class NoiseModelFactor3: public NoiseModelFactor { +class GTSAM_EXPORT NoiseModelFactor3: public NoiseModelFactor { public: @@ -518,7 +518,7 @@ class NoiseModelFactor3: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 4 * variables. To derive from this class, implement evaluateError(). */ template -class NoiseModelFactor4: public NoiseModelFactor { +class GTSAM_EXPORT NoiseModelFactor4: public NoiseModelFactor { public: @@ -599,7 +599,7 @@ class NoiseModelFactor4: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 5 * variables. To derive from this class, implement evaluateError(). */ template -class NoiseModelFactor5: public NoiseModelFactor { +class GTSAM_EXPORT NoiseModelFactor5: public NoiseModelFactor { public: @@ -684,7 +684,7 @@ class NoiseModelFactor5: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 6 * variables. To derive from this class, implement evaluateError(). */ template -class NoiseModelFactor6: public NoiseModelFactor { +class GTSAM_EXPORT NoiseModelFactor6: public NoiseModelFactor { public: diff --git a/gtsam/sfm/MFAS.h b/gtsam/sfm/MFAS.h index decfbed0f5..151b318ad8 100644 --- a/gtsam/sfm/MFAS.h +++ b/gtsam/sfm/MFAS.h @@ -48,7 +48,7 @@ namespace gtsam { unit translations in a projection direction. @addtogroup SFM */ -class MFAS { +class GTSAM_EXPORT MFAS { public: // used to represent edges between two nodes in the graph. When used in // translation averaging for global SfM diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 3802831411..6fe19299d6 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -45,7 +45,7 @@ namespace gtsam { * the value of a point, which is kept in the base class. */ template -class SmartFactorBase: public NonlinearFactor { +class GTSAM_EXPORT SmartFactorBase: public NonlinearFactor { private: typedef NonlinearFactor Base; diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index c7b1d54245..3cd69c46f3 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -41,11 +41,10 @@ namespace gtsam { * If the calibration should be optimized, as well, use SmartProjectionFactor instead! * @addtogroup SLAM */ -template -class SmartProjectionPoseFactor: public SmartProjectionFactor< - PinholePose > { - -private: +template +class GTSAM_EXPORT SmartProjectionPoseFactor + : public SmartProjectionFactor > { + private: typedef PinholePose Camera; typedef SmartProjectionFactor Base; typedef SmartProjectionPoseFactor This; @@ -156,7 +155,6 @@ class SmartProjectionPoseFactor: public SmartProjectionFactor< ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(K_); } - }; // end of class declaration diff --git a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h index 5264c8f4ba..7f71b282b0 100644 --- a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h +++ b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h @@ -9,6 +9,8 @@ #include #include +#include + #include namespace gtsam { @@ -32,9 +34,9 @@ namespace gtsam { * a local linearisation point for the plane. The plane is representated and * optimized in x1 frame in the optimization. */ -class LocalOrientedPlane3Factor: public NoiseModelFactor3 { -protected: +class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor + : public NoiseModelFactor3 { + protected: OrientedPlane3 measured_p_; typedef NoiseModelFactor3 Base; public: diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index fbc11503c5..53860efdc1 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -18,9 +18,11 @@ #pragma once -#include -#include #include +#include +#include +#include + #include namespace gtsam { @@ -30,28 +32,27 @@ namespace gtsam { * estimates the body pose, body-camera transform, 3D landmark, and calibration. * @addtogroup SLAM */ - template - class ProjectionFactorPPPC: public NoiseModelFactor4 { - protected: - - Point2 measured_; ///< 2D measurement +template +class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC + : public NoiseModelFactor4 { + protected: + Point2 measured_; ///< 2D measurement - // verbosity handling for Cheirality Exceptions - bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) - bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) + // verbosity handling for Cheirality Exceptions + bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) + bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) - public: + public: + /// shorthand for base class type + typedef NoiseModelFactor4 Base; - /// shorthand for base class type - typedef NoiseModelFactor4 Base; + /// shorthand for this class + typedef ProjectionFactorPPPC This; - /// shorthand for this class - typedef ProjectionFactorPPPC This; + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; - /// shorthand for a smart pointer to a factor - typedef boost::shared_ptr shared_ptr; - - /// Default constructor + /// Default constructor ProjectionFactorPPPC() : measured_(0.0, 0.0), throwCheirality_(false), verboseCheirality_(false) { } @@ -168,7 +169,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } - }; +}; /// traits template diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index c92653c13e..2aeaa48249 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h @@ -21,6 +21,7 @@ #include #include #include +#include #include @@ -40,7 +41,7 @@ namespace gtsam { * @addtogroup SLAM */ -class ProjectionFactorRollingShutter +class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter : public NoiseModelFactor3 { protected: // Keep a copy of measurement and calibration for I/O diff --git a/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h b/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h index 7660ff2363..bdab58a659 100644 --- a/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h +++ b/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h @@ -20,6 +20,7 @@ #include #include +#include namespace gtsam { /** @@ -41,7 +42,7 @@ namespace gtsam { * @addtogroup SLAM */ template -class SmartProjectionPoseFactorRollingShutter +class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter : public SmartProjectionFactor { public: typedef typename CAMERA::CalibrationType CALIBRATION; diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 52fd99356b..bac926b2cb 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -20,18 +20,18 @@ #pragma once -#include -#include - -#include #include #include -#include +#include #include +#include +#include +#include #include +#include -#include #include +#include #include namespace gtsam { @@ -49,8 +49,9 @@ typedef SmartProjectionParams SmartStereoProjectionParams; * If you'd like to store poses in values instead of cameras, use * SmartStereoProjectionPoseFactor instead */ -class SmartStereoProjectionFactor: public SmartFactorBase { -private: +class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactor + : public SmartFactorBase { + private: typedef SmartFactorBase Base; diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h b/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h index 25be48b0f5..923f809ccf 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h @@ -38,7 +38,8 @@ namespace gtsam { * This factor requires that values contain the involved poses and extrinsics (both are Pose3 variables). * @addtogroup SLAM */ -class SmartStereoProjectionFactorPP : public SmartStereoProjectionFactor { +class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactorPP + : public SmartStereoProjectionFactor { protected: /// shared pointer to calibration object (one for each camera) std::vector> K_all_; @@ -292,7 +293,6 @@ class SmartStereoProjectionFactorPP : public SmartStereoProjectionFactor { ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(K_all_); } - }; // end of class declaration diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 2a8180ac51..a46000a686 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -43,7 +43,8 @@ namespace gtsam { * This factor requires that values contains the involved poses (Pose3). * @addtogroup SLAM */ -class SmartStereoProjectionPoseFactor : public SmartStereoProjectionFactor { +class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionPoseFactor + : public SmartStereoProjectionFactor { protected: /// shared pointer to calibration object (one for each camera) std::vector> K_all_;