Skip to content

Commit

Permalink
Merge pull request #1584 from talregev/TalR/fix/windows_tests
Browse files Browse the repository at this point in the history
  • Loading branch information
dellaert authored Jul 27, 2023
2 parents ba42f4e + 8ac72e8 commit 4b0f386
Show file tree
Hide file tree
Showing 13 changed files with 107 additions and 56 deletions.
73 changes: 57 additions & 16 deletions .github/workflows/build-windows.yml
Original file line number Diff line number Diff line change
Expand Up @@ -99,26 +99,67 @@ 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: bash
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 -j4 --config ${{ matrix.build_type }} --target gtsam
cmake --build build -j4 --config ${{ matrix.build_type }} --target gtsam_unstable
# Target doesn't exist
# cmake --build build -j4 --config ${{ matrix.build_type }} --target wrap
- name: Test
shell: bash
run: |
# 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
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
# Compilation error
# 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 -j 4 --config ${{ matrix.build_type }} --target check.base_unstable
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
8 changes: 8 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion gtsam/basis/Basis.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ using Weights = Eigen::Matrix<double, 1, -1>; /* 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
Expand Down
4 changes: 3 additions & 1 deletion gtsam/discrete/SignatureParser.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#include <string>
#include <vector>

#include <gtsam/dllexport.h>

namespace gtsam {
/**
* @brief A simple parser that replaces the boost spirit parser.
Expand All @@ -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<double>;
using Table = std::vector<Row>;

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Line3.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
};
Expand Down
40 changes: 20 additions & 20 deletions gtsam/geometry/Pose2.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace gtsam {
* @ingroup geometry
* \nosubgrouping
*/
class Pose2: public LieGroup<Pose2, 3> {
class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {

public:

Expand Down Expand Up @@ -112,10 +112,10 @@ class Pose2: public LieGroup<Pose2, 3> {
/// @{

/** 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
Expand All @@ -125,7 +125,7 @@ class Pose2: public LieGroup<Pose2, 3> {
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 {
Expand All @@ -137,16 +137,16 @@ class Pose2: public LieGroup<Pose2, 3> {
/// @{

///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 {
Expand All @@ -156,7 +156,7 @@ class Pose2: public LieGroup<Pose2, 3> {
/**
* 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
Expand Down Expand Up @@ -192,15 +192,15 @@ class Pose2: public LieGroup<Pose2, 3> {
}

/// 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<Pose2, 3>::inverse; // version with derivative
Expand All @@ -210,7 +210,7 @@ class Pose2: public LieGroup<Pose2, 3> {
/// @{

/** 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;

Expand All @@ -222,7 +222,7 @@ class Pose2: public LieGroup<Pose2, 3> {
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;

Expand Down Expand Up @@ -273,30 +273,30 @@ class Pose2: public LieGroup<Pose2, 3> {
}

//// 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;

/**
* Calculate bearing to another pose
* @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;

/**
* Calculate range to a landmark
* @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;

Expand All @@ -305,7 +305,7 @@ class Pose2: public LieGroup<Pose2, 3> {
* @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;

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Pose3.h
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ class GTSAM_EXPORT Pose3: public LieGroup<Pose3, 6> {
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 = {});
};
Expand Down
2 changes: 1 addition & 1 deletion gtsam/hybrid/HybridFactorGraph.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ using SharedFactor = std::shared_ptr<Factor>;
* Hybrid Factor Graph
* Factor graph with utilities for hybrid factors.
*/
class HybridFactorGraph : public FactorGraph<Factor> {
class GTSAM_EXPORT HybridFactorGraph : public FactorGraph<Factor> {
public:
using Base = FactorGraph<Factor>;
using This = HybridFactorGraph; ///< this class
Expand Down
2 changes: 1 addition & 1 deletion gtsam/hybrid/HybridSmoother.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

namespace gtsam {

class HybridSmoother {
class GTSAM_EXPORT HybridSmoother {
private:
HybridBayesNet hybridBayesNet_;
HybridGaussianFactorGraph remainingFactorGraph_;
Expand Down
1 change: 1 addition & 0 deletions gtsam/hybrid/tests/testHybridGaussianFactorGraph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <iostream>
#include <iterator>
#include <vector>
#include <numeric>

#include "Switching.h"
#include "TinyHybridExample.h"
Expand Down
Loading

0 comments on commit 4b0f386

Please sign in to comment.