fixing windows compile issues

release/4.3a0
Jing Dong 2017-05-18 11:39:51 -07:00
parent 3f98942e9a
commit 89ca6fb925
9 changed files with 12 additions and 12 deletions

View File

@ -31,7 +31,7 @@ typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
* @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x * @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x
* Use PinholeCameraCal3_S2 instead * Use PinholeCameraCal3_S2 instead
*/ */
class SimpleCamera : public PinholeCameraCal3_S2 { class GTSAM_EXPORT SimpleCamera : public PinholeCameraCal3_S2 {
typedef PinholeCamera<Cal3_S2> Base; typedef PinholeCamera<Cal3_S2> Base;
typedef boost::shared_ptr<SimpleCamera> shared_ptr; typedef boost::shared_ptr<SimpleCamera> shared_ptr;

View File

@ -27,7 +27,7 @@ namespace gtsam {
/// All bias models live in the imuBias namespace /// All bias models live in the imuBias namespace
namespace imuBias { namespace imuBias {
class ConstantBias { class GTSAM_EXPORT ConstantBias {
private: private:
Vector3 biasAcc_; Vector3 biasAcc_;
Vector3 biasGyro_; Vector3 biasGyro_;

View File

@ -68,7 +68,7 @@ typedef ManifoldPreintegration PreintegrationType;
* *
* @addtogroup SLAM * @addtogroup SLAM
*/ */
class PreintegratedImuMeasurements: public PreintegrationType { class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {
friend class ImuFactor; friend class ImuFactor;
friend class ImuFactor2; friend class ImuFactor2;
@ -176,7 +176,7 @@ private:
* *
* @addtogroup SLAM * @addtogroup SLAM
*/ */
class ImuFactor: public NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3, class GTSAM_EXPORT ImuFactor: public NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3,
imuBias::ConstantBias> { imuBias::ConstantBias> {
private: private:
@ -285,7 +285,7 @@ private:
* ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity. * ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity.
* @addtogroup SLAM * @addtogroup SLAM
*/ */
class ImuFactor2 : public NoiseModelFactor3<NavState, NavState, imuBias::ConstantBias> { class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3<NavState, NavState, imuBias::ConstantBias> {
private: private:
typedef ImuFactor2 This; typedef ImuFactor2 This;

View File

@ -30,7 +30,7 @@ namespace gtsam {
* IMU pre-integration on NavSatet manifold. * IMU pre-integration on NavSatet manifold.
* This corresponds to the original RSS paper (with one difference: V is rotated) * This corresponds to the original RSS paper (with one difference: V is rotated)
*/ */
class ManifoldPreintegration : public PreintegrationBase { class GTSAM_EXPORT ManifoldPreintegration : public PreintegrationBase {
protected: protected:
/** /**

View File

@ -31,7 +31,7 @@ typedef Vector3 Velocity3;
* Navigation state: Pose (rotation, translation) + velocity * 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 * 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: private:
// TODO(frank): // TODO(frank):

View File

@ -28,7 +28,7 @@ namespace gtsam {
/// Parameters for pre-integration: /// Parameters for pre-integration:
/// Usage: Create just a single Params and pass a shared pointer to the constructor /// 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 Matrix3 gyroscopeCovariance; ///< continuous-time "Covariance" of gyroscope measurements
boost::optional<Vector3> omegaCoriolis; ///< Coriolis constant boost::optional<Vector3> omegaCoriolis; ///< Coriolis constant
boost::optional<Pose3> body_P_sensor; ///< The pose of the sensor in the body frame boost::optional<Pose3> body_P_sensor; ///< The pose of the sensor in the body frame
@ -63,7 +63,7 @@ struct PreintegratedRotationParams {
* classes (in AHRSFactor, ImuFactor, and CombinedImuFactor). * classes (in AHRSFactor, ImuFactor, and CombinedImuFactor).
* It includes the definitions of the preintegrated rotation. * It includes the definitions of the preintegrated rotation.
*/ */
class PreintegratedRotation { class GTSAM_EXPORT PreintegratedRotation {
public: public:
typedef PreintegratedRotationParams Params; typedef PreintegratedRotationParams Params;

View File

@ -55,7 +55,7 @@ struct PoseVelocityBias {
* It includes the definitions of the preintegrated variables and the methods * It includes the definitions of the preintegrated variables and the methods
* to access, print, and compare them. * to access, print, and compare them.
*/ */
class PreintegrationBase { class GTSAM_EXPORT PreintegrationBase {
public: public:
typedef imuBias::ConstantBias Bias; typedef imuBias::ConstantBias Bias;
typedef PreintegrationParams Params; typedef PreintegrationParams Params;

View File

@ -23,7 +23,7 @@ namespace gtsam {
/// Parameters for pre-integration: /// Parameters for pre-integration:
/// Usage: Create just a single Params and pass a shared pointer to the constructor /// 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 accelerometerCovariance; ///< continuous-time "Covariance" of accelerometer
Matrix3 integrationCovariance; ///< continuous-time "Covariance" describing integration uncertainty Matrix3 integrationCovariance; ///< continuous-time "Covariance" describing integration uncertainty
bool use2ndOrderCoriolis; ///< Whether to use second order Coriolis integration bool use2ndOrderCoriolis; ///< Whether to use second order Coriolis integration

View File

@ -25,7 +25,7 @@ namespace gtsam {
* Integrate on the 9D tangent space of the NavState manifold. * Integrate on the 9D tangent space of the NavState manifold.
* See extensive discussion in ImuFactor.lyx * See extensive discussion in ImuFactor.lyx
*/ */
class TangentPreintegration : public PreintegrationBase { class GTSAM_EXPORT TangentPreintegration : public PreintegrationBase {
protected: protected:
/** /**