diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 61e9f09098..dcb830f24b 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 b4999af7c8..7b92be5d50 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: diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 38d831e152..7fafd95dfa 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 GTSAM_EXPORT NoiseModelFactor1: public NoiseModelFactor { +class NoiseModelFactor1: public NoiseModelFactor { public: @@ -366,7 +366,7 @@ class GTSAM_EXPORT NoiseModelFactor1: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 2 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor2: public NoiseModelFactor { +class NoiseModelFactor2: public NoiseModelFactor { public: @@ -441,7 +441,7 @@ class GTSAM_EXPORT NoiseModelFactor2: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 3 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor3: public NoiseModelFactor { +class NoiseModelFactor3: public NoiseModelFactor { public: @@ -518,7 +518,7 @@ class GTSAM_EXPORT NoiseModelFactor3: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 4 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor4: public NoiseModelFactor { +class NoiseModelFactor4: public NoiseModelFactor { public: @@ -599,7 +599,7 @@ class GTSAM_EXPORT NoiseModelFactor4: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 5 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor5: public NoiseModelFactor { +class NoiseModelFactor5: public NoiseModelFactor { public: @@ -684,7 +684,7 @@ class GTSAM_EXPORT NoiseModelFactor5: public NoiseModelFactor { /** A convenient base class for creating your own NoiseModelFactor with 6 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor6: public NoiseModelFactor { +class NoiseModelFactor6: public NoiseModelFactor { public: diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 16712c429f..ca158cc1d3 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -47,7 +47,7 @@ namespace gtsam { * @tparam CAMERA should behave like a PinholeCamera. */ template -class GTSAM_EXPORT SmartFactorBase: public NonlinearFactor { +class SmartFactorBase: public NonlinearFactor { private: typedef NonlinearFactor Base; diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 5cdfb2ab7c..61f110d3a8 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -49,7 +49,7 @@ typedef SmartProjectionParams SmartStereoProjectionParams; * If you'd like to store poses in values instead of cameras, use * SmartStereoProjectionPoseFactor instead */ -class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactor +class SmartStereoProjectionFactor : public SmartFactorBase { private: