diff --git a/.github/workflows/build-windows.yml b/.github/workflows/build-windows.yml index cbe0c10f1..565a02756 100644 --- a/.github/workflows/build-windows.yml +++ b/.github/workflows/build-windows.yml @@ -99,26 +99,64 @@ jobs: 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" - name: Build + shell: cmd 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 + :: Since Visual Studio is a multi-generator, we need to use --config + :: https://stackoverflow.com/a/24470998/1236990 + cmake --build build -j4 --config ${{ matrix.build_type }} --target gtsam + cmake --build build -j4 --config ${{ matrix.build_type }} --target gtsam_unstable - # Run GTSAM tests - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.basis - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.discrete - #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.geometry - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.inference - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.linear - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.navigation - #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.nonlinear - #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.sam - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.sfm - #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.slam - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.symbolic + :: Target doesn't exist + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target wrap - # Run GTSAM_UNSTABLE tests - #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable + - name: Test + shell: cmd + run: | + :: Run GTSAM tests + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.base + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.basis + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.discrete + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.geometry + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.inference + + :: Compile. Fail with exception + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.linear + + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.navigation + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.sam + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.sfm + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.symbolic + + :: Compile. Fail with exception + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.hybrid + + :: Compile. Fail with exception + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.nonlinear + + :: Compilation error + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.slam + + + :: Run GTSAM_UNSTABLE tests + cmake --build build -j4 --config ${{ matrix.build_type }} --target check.base_unstable + + :: Compile. Fail with exception + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.geometry_unstable + + :: Compile. Fail with exception + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.linear_unstable + + :: Compile. Fail with exception + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.discrete_unstable + + :: Compile. Fail with exception + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.dynamics_unstable + + :: Compile. Fail with exception + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.nonlinear_unstable + + :: Compilation error + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.slam_unstable + + :: Compilation error + :: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.partition diff --git a/CMakeLists.txt b/CMakeLists.txt index ebe27443a..8b56ea9df 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -32,6 +32,14 @@ set (CMAKE_PROJECT_VERSION_PATCH ${GTSAM_VERSION_PATCH}) ############################################################################### # Gather information, perform checks, set defaults +if(MSVC) + set(MSVC_LINKER_FLAGS "/FORCE:MULTIPLE") + set(CMAKE_EXE_LINKER_FLAGS ${MSVC_LINKER_FLAGS}) + set(CMAKE_MODULE_LINKER_FLAGS ${MSVC_LINKER_FLAGS}) + set(CMAKE_SHARED_LINKER_FLAGS ${MSVC_LINKER_FLAGS}) + set(CMAKE_STATIC_LINKER_FLAGS ${MSVC_LINKER_FLAGS}) +endif() + set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${CMAKE_CURRENT_SOURCE_DIR}/cmake") include(GtsamMakeConfigFile) include(GNUInstallDirs) diff --git a/gtsam/basis/Basis.h b/gtsam/basis/Basis.h index 41cdeeaaa..0b2b3606b 100644 --- a/gtsam/basis/Basis.h +++ b/gtsam/basis/Basis.h @@ -80,7 +80,7 @@ using Weights = Eigen::Matrix; /* 1xN vector */ * * @ingroup basis */ -Matrix kroneckerProductIdentity(size_t M, const Weights& w); +Matrix GTSAM_EXPORT kroneckerProductIdentity(size_t M, const Weights& w); /** * CRTP Base class for function bases diff --git a/gtsam/discrete/SignatureParser.h b/gtsam/discrete/SignatureParser.h index e6b402e44..ddc548fc6 100644 --- a/gtsam/discrete/SignatureParser.h +++ b/gtsam/discrete/SignatureParser.h @@ -22,6 +22,8 @@ #include #include +#include + namespace gtsam { /** * @brief A simple parser that replaces the boost spirit parser. @@ -47,7 +49,7 @@ namespace gtsam { * * Also fails if the rows are not of the same size. */ -struct SignatureParser { +struct GTSAM_EXPORT SignatureParser { using Row = std::vector; using Table = std::vector; diff --git a/gtsam/geometry/Line3.h b/gtsam/geometry/Line3.h index b1a1e4f6e..def49d268 100644 --- a/gtsam/geometry/Line3.h +++ b/gtsam/geometry/Line3.h @@ -146,7 +146,7 @@ class GTSAM_EXPORT Line3 { * @param Dline - OptionalJacobian of transformed line with respect to l * @return Transformed line in camera frame */ - friend Line3 transformTo(const Pose3 &wTc, const Line3 &wL, + GTSAM_EXPORT friend Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian<4, 6> Dpose, OptionalJacobian<4, 4> Dline); }; diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index f1b38c5a6..aad81493f 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -36,7 +36,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ -class Pose2: public LieGroup { +class GTSAM_EXPORT Pose2: public LieGroup { public: @@ -112,10 +112,10 @@ public: /// @{ /** print with optional string */ - GTSAM_EXPORT void print(const std::string& s = "") const; + void print(const std::string& s = "") const; /** assert equality up to a tolerance */ - GTSAM_EXPORT bool equals(const Pose2& pose, double tol = 1e-9) const; + bool equals(const Pose2& pose, double tol = 1e-9) const; /// @} /// @name Group @@ -125,7 +125,7 @@ public: inline static Pose2 Identity() { return Pose2(); } /// inverse - GTSAM_EXPORT Pose2 inverse() const; + Pose2 inverse() const; /// compose syntactic sugar inline Pose2 operator*(const Pose2& p2) const { @@ -137,16 +137,16 @@ public: /// @{ ///Exponential map at identity - create a rotation from canonical coordinates \f$ [T_x,T_y,\theta] \f$ - GTSAM_EXPORT static Pose2 Expmap(const Vector3& xi, ChartJacobian H = {}); + static Pose2 Expmap(const Vector3& xi, ChartJacobian H = {}); ///Log map at identity - return the canonical coordinates \f$ [T_x,T_y,\theta] \f$ of this rotation - GTSAM_EXPORT static Vector3 Logmap(const Pose2& p, ChartJacobian H = {}); + static Vector3 Logmap(const Pose2& p, ChartJacobian H = {}); /** * Calculate Adjoint map * Ad_pose is 3*3 matrix that when applied to twist xi \f$ [T_x,T_y,\theta] \f$, returns Ad_pose(xi) */ - GTSAM_EXPORT Matrix3 AdjointMap() const; + Matrix3 AdjointMap() const; /// Apply AdjointMap to twist xi inline Vector3 Adjoint(const Vector3& xi) const { @@ -156,7 +156,7 @@ public: /** * Compute the [ad(w,v)] operator for SE2 as in [Kobilarov09siggraph], pg 19 */ - GTSAM_EXPORT static Matrix3 adjointMap(const Vector3& v); + static Matrix3 adjointMap(const Vector3& v); /** * Action of the adjointMap on a Lie-algebra vector y, with optional derivatives @@ -192,15 +192,15 @@ public: } /// Derivative of Expmap - GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& v); + static Matrix3 ExpmapDerivative(const Vector3& v); /// Derivative of Logmap - GTSAM_EXPORT static Matrix3 LogmapDerivative(const Pose2& v); + static Matrix3 LogmapDerivative(const Pose2& v); // Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP - struct ChartAtOrigin { - GTSAM_EXPORT static Pose2 Retract(const Vector3& v, ChartJacobian H = {}); - GTSAM_EXPORT static Vector3 Local(const Pose2& r, ChartJacobian H = {}); + struct GTSAM_EXPORT ChartAtOrigin { + static Pose2 Retract(const Vector3& v, ChartJacobian H = {}); + static Vector3 Local(const Pose2& r, ChartJacobian H = {}); }; using LieGroup::inverse; // version with derivative @@ -210,7 +210,7 @@ public: /// @{ /** Return point coordinates in pose coordinate frame */ - GTSAM_EXPORT Point2 transformTo(const Point2& point, + Point2 transformTo(const Point2& point, OptionalJacobian<2, 3> Dpose = {}, OptionalJacobian<2, 2> Dpoint = {}) const; @@ -222,7 +222,7 @@ public: Matrix transformTo(const Matrix& points) const; /** Return point coordinates in global frame */ - GTSAM_EXPORT Point2 transformFrom(const Point2& point, + Point2 transformFrom(const Point2& point, OptionalJacobian<2, 3> Dpose = {}, OptionalJacobian<2, 2> Dpoint = {}) const; @@ -273,14 +273,14 @@ public: } //// return transformation matrix - GTSAM_EXPORT Matrix3 matrix() const; + Matrix3 matrix() const; /** * Calculate bearing to a landmark * @param point 2D location of landmark * @return 2D rotation \f$ \in SO(2) \f$ */ - GTSAM_EXPORT Rot2 bearing(const Point2& point, + Rot2 bearing(const Point2& point, OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 2> H2={}) const; /** @@ -288,7 +288,7 @@ public: * @param point SO(2) location of other pose * @return 2D rotation \f$ \in SO(2) \f$ */ - GTSAM_EXPORT Rot2 bearing(const Pose2& pose, + Rot2 bearing(const Pose2& pose, OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 3> H2={}) const; /** @@ -296,7 +296,7 @@ public: * @param point 2D location of landmark * @return range (double) */ - GTSAM_EXPORT double range(const Point2& point, + double range(const Point2& point, OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 2> H2={}) const; @@ -305,7 +305,7 @@ public: * @param point 2D location of other pose * @return range (double) */ - GTSAM_EXPORT double range(const Pose2& point, + double range(const Pose2& point, OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 3> H2={}) const; diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 6c91d7468..8a807cc23 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -204,7 +204,7 @@ public: static Matrix6 LogmapDerivative(const Pose3& xi); // Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP - struct ChartAtOrigin { + struct GTSAM_EXPORT ChartAtOrigin { static Pose3 Retract(const Vector6& xi, ChartJacobian Hxi = {}); static Vector6 Local(const Pose3& pose, ChartJacobian Hpose = {}); }; diff --git a/gtsam/hybrid/HybridFactorGraph.h b/gtsam/hybrid/HybridFactorGraph.h index b8e7ff588..8b59fd4f9 100644 --- a/gtsam/hybrid/HybridFactorGraph.h +++ b/gtsam/hybrid/HybridFactorGraph.h @@ -35,7 +35,7 @@ using SharedFactor = std::shared_ptr; * Hybrid Factor Graph * Factor graph with utilities for hybrid factors. */ -class HybridFactorGraph : public FactorGraph { +class GTSAM_EXPORT HybridFactorGraph : public FactorGraph { public: using Base = FactorGraph; using This = HybridFactorGraph; ///< this class diff --git a/gtsam/hybrid/HybridSmoother.h b/gtsam/hybrid/HybridSmoother.h index 0767da12f..5c2e4f546 100644 --- a/gtsam/hybrid/HybridSmoother.h +++ b/gtsam/hybrid/HybridSmoother.h @@ -24,7 +24,7 @@ namespace gtsam { -class HybridSmoother { +class GTSAM_EXPORT HybridSmoother { private: HybridBayesNet hybridBayesNet_; HybridGaussianFactorGraph remainingFactorGraph_; diff --git a/gtsam/hybrid/tests/testHybridGaussianFactorGraph.cpp b/gtsam/hybrid/tests/testHybridGaussianFactorGraph.cpp index 1da897103..df38c171e 100644 --- a/gtsam/hybrid/tests/testHybridGaussianFactorGraph.cpp +++ b/gtsam/hybrid/tests/testHybridGaussianFactorGraph.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include "Switching.h" #include "TinyHybridExample.h" diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 86d44e072..c3df1b8a0 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -30,7 +30,7 @@ namespace gtsam { -class Ordering: public KeyVector { +class GTSAM_EXPORT Ordering: public KeyVector { protected: typedef KeyVector Base; @@ -44,8 +44,7 @@ public: typedef Ordering This; ///< Typedef to this class typedef std::shared_ptr shared_ptr; ///< shared_ptr to this class - /// Create an empty ordering - GTSAM_EXPORT + /// Create an empty ordering Ordering() { } @@ -99,7 +98,7 @@ public: } /// Compute a fill-reducing ordering using COLAMD from a VariableIndex. - static GTSAM_EXPORT Ordering Colamd(const VariableIndex& variableIndex); + static Ordering Colamd(const VariableIndex& variableIndex); /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details /// for note on performance). This internally builds a VariableIndex so if you already have a @@ -124,7 +123,7 @@ public: /// variables in \c constrainLast will be ordered in the same order specified in the KeyVector /// \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. - static GTSAM_EXPORT Ordering ColamdConstrainedLast( + static Ordering ColamdConstrainedLast( const VariableIndex& variableIndex, const KeyVector& constrainLast, bool forceOrder = false); @@ -152,7 +151,7 @@ public: /// KeyVector \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. - static GTSAM_EXPORT Ordering ColamdConstrainedFirst( + static Ordering ColamdConstrainedFirst( const VariableIndex& variableIndex, const KeyVector& constrainFirst, bool forceOrder = false); @@ -181,7 +180,7 @@ public: /// appear in \c groups in 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. - static GTSAM_EXPORT Ordering ColamdConstrained( + static Ordering ColamdConstrained( const VariableIndex& variableIndex, const FastMap& groups); /// Return a natural Ordering. Typically used by iterative solvers @@ -195,11 +194,11 @@ public: /// METIS Formatting function template - static GTSAM_EXPORT void CSRFormat(std::vector& xadj, + static void CSRFormat(std::vector& xadj, std::vector& adj, const FACTOR_GRAPH& graph); /// Compute an ordering determined by METIS from a VariableIndex - static GTSAM_EXPORT Ordering Metis(const MetisIndex& met); + static Ordering Metis(const MetisIndex& met); template static Ordering Metis(const FACTOR_GRAPH& graph) { @@ -241,18 +240,16 @@ public: /// @name Testable /// @{ - GTSAM_EXPORT void print(const std::string& str = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; - GTSAM_EXPORT bool equals(const Ordering& other, double tol = 1e-9) const; /// @} private: /// Internal COLAMD function - static GTSAM_EXPORT Ordering ColamdConstrained( + static Ordering ColamdConstrained( const VariableIndex& variableIndex, std::vector& cmember); #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION diff --git a/gtsam_unstable/linear/LPInitSolver.h b/gtsam_unstable/linear/LPInitSolver.h index 7e326117b..9db2a34f0 100644 --- a/gtsam_unstable/linear/LPInitSolver.h +++ b/gtsam_unstable/linear/LPInitSolver.h @@ -19,6 +19,7 @@ #pragma once +#include #include #include @@ -49,7 +50,7 @@ namespace gtsam { * inequality constraint, we can't conclude that the problem is infeasible. * However, whether it is infeasible or unbounded, we don't have a unique solution anyway. */ -class LPInitSolver { +class GTSAM_UNSTABLE_EXPORT LPInitSolver { private: const LP& lp_; diff --git a/gtsam_unstable/linear/QPSParser.h b/gtsam_unstable/linear/QPSParser.h index bd4254d0f..e751f34d2 100644 --- a/gtsam_unstable/linear/QPSParser.h +++ b/gtsam_unstable/linear/QPSParser.h @@ -18,12 +18,13 @@ #pragma once +#include #include #include namespace gtsam { -class QPSParser { +class GTSAM_UNSTABLE_EXPORT QPSParser { private: std::string fileName_;