Windows Fixes (#904)
parent
7dee503739
commit
b47f46a6f5
|
@ -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
|
||||
|
|
|
@ -282,7 +282,7 @@ public:
|
|||
* which are objects in non-linear manifolds (Lie groups).
|
||||
*/
|
||||
template<class VALUE>
|
||||
class NoiseModelFactor1: public NoiseModelFactor {
|
||||
class GTSAM_EXPORT NoiseModelFactor1: public NoiseModelFactor {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -366,7 +366,7 @@ private:
|
|||
/** A convenient base class for creating your own NoiseModelFactor with 2
|
||||
* variables. To derive from this class, implement evaluateError(). */
|
||||
template<class VALUE1, class VALUE2>
|
||||
class NoiseModelFactor2: public NoiseModelFactor {
|
||||
class GTSAM_EXPORT NoiseModelFactor2: public NoiseModelFactor {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -441,7 +441,7 @@ private:
|
|||
/** A convenient base class for creating your own NoiseModelFactor with 3
|
||||
* variables. To derive from this class, implement evaluateError(). */
|
||||
template<class VALUE1, class VALUE2, class VALUE3>
|
||||
class NoiseModelFactor3: public NoiseModelFactor {
|
||||
class GTSAM_EXPORT NoiseModelFactor3: public NoiseModelFactor {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -518,7 +518,7 @@ private:
|
|||
/** A convenient base class for creating your own NoiseModelFactor with 4
|
||||
* variables. To derive from this class, implement evaluateError(). */
|
||||
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4>
|
||||
class NoiseModelFactor4: public NoiseModelFactor {
|
||||
class GTSAM_EXPORT NoiseModelFactor4: public NoiseModelFactor {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -599,7 +599,7 @@ private:
|
|||
/** A convenient base class for creating your own NoiseModelFactor with 5
|
||||
* variables. To derive from this class, implement evaluateError(). */
|
||||
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5>
|
||||
class NoiseModelFactor5: public NoiseModelFactor {
|
||||
class GTSAM_EXPORT NoiseModelFactor5: public NoiseModelFactor {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -684,7 +684,7 @@ private:
|
|||
/** A convenient base class for creating your own NoiseModelFactor with 6
|
||||
* variables. To derive from this class, implement evaluateError(). */
|
||||
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5, class VALUE6>
|
||||
class NoiseModelFactor6: public NoiseModelFactor {
|
||||
class GTSAM_EXPORT NoiseModelFactor6: public NoiseModelFactor {
|
||||
|
||||
public:
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -47,7 +47,7 @@ namespace gtsam {
|
|||
* @tparam CAMERA should behave like a PinholeCamera.
|
||||
*/
|
||||
template<class CAMERA>
|
||||
class SmartFactorBase: public NonlinearFactor {
|
||||
class GTSAM_EXPORT SmartFactorBase: public NonlinearFactor {
|
||||
|
||||
private:
|
||||
typedef NonlinearFactor Base;
|
||||
|
|
|
@ -41,11 +41,10 @@ namespace gtsam {
|
|||
* If the calibration should be optimized, as well, use SmartProjectionFactor instead!
|
||||
* @addtogroup SLAM
|
||||
*/
|
||||
template<class CALIBRATION>
|
||||
class SmartProjectionPoseFactor: public SmartProjectionFactor<
|
||||
PinholePose<CALIBRATION> > {
|
||||
|
||||
private:
|
||||
template <class CALIBRATION>
|
||||
class GTSAM_EXPORT SmartProjectionPoseFactor
|
||||
: public SmartProjectionFactor<PinholePose<CALIBRATION> > {
|
||||
private:
|
||||
typedef PinholePose<CALIBRATION> Camera;
|
||||
typedef SmartProjectionFactor<Camera> Base;
|
||||
typedef SmartProjectionPoseFactor<CALIBRATION> This;
|
||||
|
@ -156,7 +155,6 @@ public:
|
|||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar & BOOST_SERIALIZATION_NVP(K_);
|
||||
}
|
||||
|
||||
};
|
||||
// end of class declaration
|
||||
|
||||
|
|
|
@ -9,6 +9,8 @@
|
|||
|
||||
#include <gtsam/geometry/OrientedPlane3.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
|
||||
#include <string>
|
||||
|
||||
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<Pose3, Pose3,
|
||||
OrientedPlane3> {
|
||||
protected:
|
||||
class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor
|
||||
: public NoiseModelFactor3<Pose3, Pose3, OrientedPlane3> {
|
||||
protected:
|
||||
OrientedPlane3 measured_p_;
|
||||
typedef NoiseModelFactor3<Pose3, Pose3, OrientedPlane3> Base;
|
||||
public:
|
||||
|
|
|
@ -18,9 +18,11 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam/geometry/PinholeCamera.h>
|
||||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
#include <gtsam/geometry/PinholeCamera.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
|
||||
#include <boost/optional.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -30,28 +32,27 @@ namespace gtsam {
|
|||
* estimates the body pose, body-camera transform, 3D landmark, and calibration.
|
||||
* @addtogroup SLAM
|
||||
*/
|
||||
template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
|
||||
class ProjectionFactorPPPC: public NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> {
|
||||
protected:
|
||||
template <class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
|
||||
class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC
|
||||
: public NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> {
|
||||
protected:
|
||||
Point2 measured_; ///< 2D measurement
|
||||
|
||||
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:
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> Base;
|
||||
|
||||
public:
|
||||
/// shorthand for this class
|
||||
typedef ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> This;
|
||||
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> Base;
|
||||
/// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<This> shared_ptr;
|
||||
|
||||
/// shorthand for this class
|
||||
typedef ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> This;
|
||||
|
||||
/// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<This> 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<class POSE, class LANDMARK, class CALIBRATION>
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
#include <gtsam/geometry/CalibratedCamera.h>
|
||||
#include <gtsam/geometry/PinholeCamera.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
|
||||
#include <boost/optional.hpp>
|
||||
|
||||
|
@ -40,7 +41,7 @@ namespace gtsam {
|
|||
* @addtogroup SLAM
|
||||
*/
|
||||
|
||||
class ProjectionFactorRollingShutter
|
||||
class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter
|
||||
: public NoiseModelFactor3<Pose3, Pose3, Point3> {
|
||||
protected:
|
||||
// Keep a copy of measurement and calibration for I/O
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
|
||||
#include <gtsam/geometry/CameraSet.h>
|
||||
#include <gtsam/slam/SmartProjectionFactor.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
|
||||
namespace gtsam {
|
||||
/**
|
||||
|
@ -41,7 +42,7 @@ namespace gtsam {
|
|||
* @addtogroup SLAM
|
||||
*/
|
||||
template <class CAMERA>
|
||||
class SmartProjectionPoseFactorRollingShutter
|
||||
class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter
|
||||
: public SmartProjectionFactor<CAMERA> {
|
||||
private:
|
||||
typedef SmartProjectionFactor<CAMERA> Base;
|
||||
|
|
|
@ -20,18 +20,18 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/slam/SmartFactorBase.h>
|
||||
#include <gtsam/slam/SmartFactorParams.h>
|
||||
|
||||
#include <gtsam/geometry/triangulation.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/StereoCamera.h>
|
||||
#include <gtsam/slam/StereoFactor.h>
|
||||
#include <gtsam/geometry/triangulation.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/slam/SmartFactorBase.h>
|
||||
#include <gtsam/slam/SmartFactorParams.h>
|
||||
#include <gtsam/slam/StereoFactor.h>
|
||||
#include <gtsam/slam/dataset.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
|
||||
#include <boost/optional.hpp>
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <boost/optional.hpp>
|
||||
#include <vector>
|
||||
|
||||
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<StereoCamera> {
|
||||
private:
|
||||
class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactor
|
||||
: public SmartFactorBase<StereoCamera> {
|
||||
private:
|
||||
|
||||
typedef SmartFactorBase<StereoCamera> Base;
|
||||
|
||||
|
|
|
@ -40,7 +40,8 @@ namespace gtsam {
|
|||
* 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<boost::shared_ptr<Cal3_S2Stereo>> K_all_;
|
||||
|
@ -294,7 +295,6 @@ class SmartStereoProjectionFactorPP : public SmartStereoProjectionFactor {
|
|||
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar & BOOST_SERIALIZATION_NVP(K_all_);
|
||||
}
|
||||
|
||||
};
|
||||
// end of class declaration
|
||||
|
||||
|
|
|
@ -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<boost::shared_ptr<Cal3_S2Stereo>> K_all_;
|
||||
|
|
Loading…
Reference in New Issue