diff --git a/gtsam/geometry/SimpleCamera.h b/gtsam/geometry/SimpleCamera.h index fe493c075..a7e021394 100644 --- a/gtsam/geometry/SimpleCamera.h +++ b/gtsam/geometry/SimpleCamera.h @@ -31,7 +31,7 @@ typedef gtsam::PinholeCamera PinholeCameraCal3_S2; * @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x * Use PinholeCameraCal3_S2 instead */ -class SimpleCamera : public PinholeCameraCal3_S2 { +class GTSAM_EXPORT SimpleCamera : public PinholeCameraCal3_S2 { typedef PinholeCamera Base; typedef boost::shared_ptr shared_ptr; diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 2ad3c17dd..84458f521 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -27,7 +27,7 @@ namespace gtsam { /// All bias models live in the imuBias namespace namespace imuBias { -class ConstantBias { +class GTSAM_EXPORT ConstantBias { private: Vector3 biasAcc_; Vector3 biasGyro_; diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 532abdac0..e713fcb99 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -68,7 +68,7 @@ typedef ManifoldPreintegration PreintegrationType; * * @addtogroup SLAM */ -class PreintegratedImuMeasurements: public PreintegrationType { +class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType { friend class ImuFactor; friend class ImuFactor2; @@ -176,7 +176,7 @@ private: * * @addtogroup SLAM */ -class ImuFactor: public NoiseModelFactor5 { private: @@ -285,7 +285,7 @@ private: * ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity. * @addtogroup SLAM */ -class ImuFactor2 : public NoiseModelFactor3 { +class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3 { private: typedef ImuFactor2 This; diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 92d3f4814..22897b9d4 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -30,7 +30,7 @@ namespace gtsam { * IMU pre-integration on NavSatet manifold. * This corresponds to the original RSS paper (with one difference: V is rotated) */ -class ManifoldPreintegration : public PreintegrationBase { +class GTSAM_EXPORT ManifoldPreintegration : public PreintegrationBase { protected: /** diff --git a/gtsam/navigation/NavState.h b/gtsam/navigation/NavState.h index a1544735d..e9afcd3ac 100644 --- a/gtsam/navigation/NavState.h +++ b/gtsam/navigation/NavState.h @@ -31,7 +31,7 @@ typedef Vector3 Velocity3; * Navigation state: Pose (rotation, translation) + velocity * NOTE(frank): it does not make sense to make this a Lie group, but it is a 9D manifold */ -class NavState { +class GTSAM_EXPORT NavState { private: // TODO(frank): diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 88d9c6437..c03cab88a 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -28,7 +28,7 @@ namespace gtsam { /// Parameters for pre-integration: /// Usage: Create just a single Params and pass a shared pointer to the constructor -struct PreintegratedRotationParams { +struct GTSAM_EXPORT PreintegratedRotationParams { Matrix3 gyroscopeCovariance; ///< continuous-time "Covariance" of gyroscope measurements boost::optional omegaCoriolis; ///< Coriolis constant boost::optional body_P_sensor; ///< The pose of the sensor in the body frame @@ -63,7 +63,7 @@ struct PreintegratedRotationParams { * classes (in AHRSFactor, ImuFactor, and CombinedImuFactor). * It includes the definitions of the preintegrated rotation. */ -class PreintegratedRotation { +class GTSAM_EXPORT PreintegratedRotation { public: typedef PreintegratedRotationParams Params; diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 06be4642d..cf5465c05 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -55,7 +55,7 @@ struct PoseVelocityBias { * It includes the definitions of the preintegrated variables and the methods * to access, print, and compare them. */ -class PreintegrationBase { +class GTSAM_EXPORT PreintegrationBase { public: typedef imuBias::ConstantBias Bias; typedef PreintegrationParams Params; diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index f2b2c0fef..831da0a12 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -23,7 +23,7 @@ namespace gtsam { /// Parameters for pre-integration: /// Usage: Create just a single Params and pass a shared pointer to the constructor -struct PreintegrationParams: PreintegratedRotationParams { +struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { Matrix3 accelerometerCovariance; ///< continuous-time "Covariance" of accelerometer Matrix3 integrationCovariance; ///< continuous-time "Covariance" describing integration uncertainty bool use2ndOrderCoriolis; ///< Whether to use second order Coriolis integration diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index dddafad7a..f5e3f7960 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -25,7 +25,7 @@ namespace gtsam { * Integrate on the 9D tangent space of the NavState manifold. * See extensive discussion in ImuFactor.lyx */ -class TangentPreintegration : public PreintegrationBase { +class GTSAM_EXPORT TangentPreintegration : public PreintegrationBase { protected: /**