diff --git a/gtsam/base/deprecated/LieMatrix.h b/gtsam/base/deprecated/LieMatrix.h index e26f45511..9ee20a596 100644 --- a/gtsam/base/deprecated/LieMatrix.h +++ b/gtsam/base/deprecated/LieMatrix.h @@ -29,7 +29,7 @@ namespace gtsam { * we can directly add double, Vector, and Matrix into values now, because of * gtsam::traits. */ -struct LieMatrix : public Matrix { +struct GTSAM_EXPORT LieMatrix : public Matrix { /// @name Constructors /// @{ @@ -60,7 +60,7 @@ struct LieMatrix : public Matrix { /// @{ /** print @param s optional string naming the object */ - GTSAM_EXPORT void print(const std::string& name = "") const { + void print(const std::string& name = "") const { gtsam::print(matrix(), name); } /** equality up to tolerance */ diff --git a/gtsam/base/deprecated/LieVector.h b/gtsam/base/deprecated/LieVector.h index 4a85036e0..b271275c3 100644 --- a/gtsam/base/deprecated/LieVector.h +++ b/gtsam/base/deprecated/LieVector.h @@ -27,7 +27,7 @@ namespace gtsam { * we can directly add double, Vector, and Matrix into values now, because of * gtsam::traits. */ -struct LieVector : public Vector { +struct GTSAM_EXPORT LieVector : public Vector { enum { dimension = Eigen::Dynamic }; @@ -51,13 +51,13 @@ struct LieVector : public Vector { LieVector(double d) : Vector((Vector(1) << d).finished()) {} /** constructor with size and initial data, row order ! */ - GTSAM_EXPORT LieVector(size_t m, const double* const data) : Vector(m) { + LieVector(size_t m, const double* const data) : Vector(m) { for (size_t i = 0; i < m; i++) (*this)(i) = data[i]; } /// @name Testable /// @{ - GTSAM_EXPORT void print(const std::string& name="") const { + void print(const std::string& name="") const { gtsam::print(vector(), name); } bool equals(const LieVector& expected, double tol=1e-5) const { diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index db49448ec..3a0f56c30 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -27,7 +27,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class Cal3_S2Stereo { + class GTSAM_EXPORT Cal3_S2Stereo { private: Cal3_S2 K_; diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index beadba929..c52127a45 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 f3b99b2fb..2670a63f7 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: @@ -234,7 +234,7 @@ public: * \nosubgrouping */ template -class GTSAM_EXPORT PinholePose: public PinholeBaseK { +class PinholePose: public PinholeBaseK { private: diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 3657ebf05..30e902c2b 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -152,23 +152,23 @@ struct traits : public internal::VectorSpace { #endif // GTSAM_TYPEDEF_POINTS_TO_VECTORS /// Distance of the point from the origin, with Jacobian -double norm2(const Point2& p, OptionalJacobian<1, 2> H = boost::none); +GTSAM_EXPORT double norm2(const Point2& p, OptionalJacobian<1, 2> H = boost::none); /// distance between two points -double distance2(const Point2& p1, const Point2& q, +GTSAM_EXPORT double distance2(const Point2& p1, const Point2& q, OptionalJacobian<1, 2> H1 = boost::none, OptionalJacobian<1, 2> H2 = boost::none); // Convenience typedef typedef std::pair Point2Pair; -std::ostream &operator<<(std::ostream &os, const gtsam::Point2Pair &p); +GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const gtsam::Point2Pair &p); // For MATLAB wrapper typedef std::vector > Point2Vector; /// multiply with scalar inline Point2 operator*(double s, const Point2& p) { -return p * s; + return p * s; } /* @@ -185,7 +185,7 @@ return p * s; * @param tol: absolute tolerance below which we consider touching circles * @return optional Point2 with f and h, boost::none if no solution. */ -boost::optional circleCircleIntersection(double R_d, double r_d, double tol = 1e-9); +GTSAM_EXPORT boost::optional circleCircleIntersection(double R_d, double r_d, double tol = 1e-9); /* * @brief Circle-circle intersection, from the normalized radii solution. @@ -193,7 +193,7 @@ boost::optional circleCircleIntersection(double R_d, double r_d, double * @param c2 center of second circle * @return list of solutions (0,1, or 2). Identical circles will return empty list, as well. */ -std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); +GTSAM_EXPORT std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); /** * @brief Intersect 2 circles @@ -204,7 +204,7 @@ std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional * @param tol: absolute tolerance below which we consider touching circles * @return list of solutions (0,1, or 2). Identical circles will return empty list, as well. */ -std::list circleCircleIntersection(Point2 c1, double r1, +GTSAM_EXPORT std::list circleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9); } // \ namespace gtsam diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 99cb6c2e7..215161b3a 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -157,28 +157,28 @@ struct traits : public internal::VectorSpace {}; // Convenience typedef typedef std::pair Point3Pair; -std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p); +GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p); /// distance between two points -double distance3(const Point3& p1, const Point3& q, - OptionalJacobian<1, 3> H1 = boost::none, - OptionalJacobian<1, 3> H2 = boost::none); +GTSAM_EXPORT double distance3(const Point3& p1, const Point3& q, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none); /// Distance of the point from the origin, with Jacobian -double norm3(const Point3& p, OptionalJacobian<1, 3> H = boost::none); +GTSAM_EXPORT double norm3(const Point3& p, OptionalJacobian<1, 3> H = boost::none); /// normalize, with optional Jacobian -Point3 normalize(const Point3& p, OptionalJacobian<3, 3> H = boost::none); +GTSAM_EXPORT Point3 normalize(const Point3& p, OptionalJacobian<3, 3> H = boost::none); /// cross product @return this x q -Point3 cross(const Point3& p, const Point3& q, - OptionalJacobian<3, 3> H_p = boost::none, - OptionalJacobian<3, 3> H_q = boost::none); +GTSAM_EXPORT Point3 cross(const Point3& p, const Point3& q, + OptionalJacobian<3, 3> H_p = boost::none, + OptionalJacobian<3, 3> H_q = boost::none); /// dot product -double dot(const Point3& p, const Point3& q, - OptionalJacobian<1, 3> H_p = boost::none, - OptionalJacobian<1, 3> H_q = boost::none); +GTSAM_EXPORT double dot(const Point3& p, const Point3& q, + OptionalJacobian<1, 3> H_p = boost::none, + OptionalJacobian<1, 3> H_q = boost::none); template struct Range; diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index 53f2c2130..3b27d45c5 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -33,7 +33,7 @@ namespace gtsam { * We guarantee (all but first) constructors only generate from sub-manifold. * However, round-off errors in repeated composition could move off it... */ -class GTSAM_EXPORT SO3: public Matrix3, public LieGroup { +class SO3: public Matrix3, public LieGroup { protected: @@ -135,7 +135,7 @@ public: namespace so3 { /// Functor implementing Exponential map -class ExpmapFunctor { +class GTSAM_EXPORT ExpmapFunctor { protected: const double theta2; Matrix3 W, K, KK; @@ -156,7 +156,7 @@ class ExpmapFunctor { }; /// Functor that implements Exponential map *and* its derivatives -class DexpFunctor : public ExpmapFunctor { +class GTSAM_EXPORT DexpFunctor : public ExpmapFunctor { const Vector3 omega; double a, b; Matrix3 dexp_; 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/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 535572fe1..1fae470f9 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -29,7 +29,7 @@ namespace gtsam { /// Exception thrown by triangulateDLT when SVD returns rank < 3 -class TriangulationUnderconstrainedException: public std::runtime_error { +class GTSAM_EXPORT TriangulationUnderconstrainedException: public std::runtime_error { public: TriangulationUnderconstrainedException() : std::runtime_error("Triangulation Underconstrained Exception.") { @@ -37,7 +37,7 @@ public: }; /// Exception thrown by triangulateDLT when landmark is behind one or more of the cameras -class TriangulationCheiralityException: public std::runtime_error { +class GTSAM_EXPORT TriangulationCheiralityException: public std::runtime_error { public: TriangulationCheiralityException() : std::runtime_error( @@ -323,7 +323,7 @@ Point3 triangulatePoint3( (cameras, measurements, rank_tol, optimize); } -struct TriangulationParameters { +struct GTSAM_EXPORT TriangulationParameters { double rankTolerance; ///< threshold to decide whether triangulation is result.degenerate ///< (the rank is the number of singular values of the triangulation matrix which are larger than rankTolerance) @@ -386,7 +386,7 @@ private: /** * TriangulationResult is an optional point, along with the reasons why it is invalid. */ -class TriangulationResult: public boost::optional { +class GTSAM_EXPORT TriangulationResult: public boost::optional { enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT }; diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 5fc82f0a3..ff1a53025 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 ccf5db5c3..ee1369f6b 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; @@ -180,7 +180,7 @@ private: * * @addtogroup SLAM */ -class ImuFactor: public NoiseModelFactor5 { private: @@ -289,7 +289,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 025278c81..54320417d 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 @@ -68,7 +68,7 @@ public: * 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 1c673bff5..7bff82365 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 da49e4ddd..2c0811ae6 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: /** diff --git a/gtsam/slam/SmartFactorParams.h b/gtsam/slam/SmartFactorParams.h index 761703f8b..e8a1fa7ab 100644 --- a/gtsam/slam/SmartFactorParams.h +++ b/gtsam/slam/SmartFactorParams.h @@ -39,7 +39,7 @@ enum DegeneracyMode { /* * Parameters for the smart (stereo) projection factors */ -struct GTSAM_EXPORT SmartProjectionParams { +struct SmartProjectionParams { LinearizationMode linearizationMode; ///< How to linearize the factor DegeneracyMode degeneracyMode; ///< How to linearize the factor