diff --git a/gtsam/base/timing.h b/gtsam/base/timing.h index ec80baad3..557500e73 100644 --- a/gtsam/base/timing.h +++ b/gtsam/base/timing.h @@ -142,7 +142,7 @@ namespace gtsam { /** * Timing Entry, arranged in a tree */ - class GTSAM_EXPORT TimingOutline { + class TimingOutline { protected: size_t id_; size_t t_; @@ -174,21 +174,21 @@ namespace gtsam { public: /// Constructor - TimingOutline(const std::string& label, size_t myId); - size_t time() const; ///< time taken, including children + GTSAM_EXPORT TimingOutline(const std::string& label, size_t myId); + GTSAM_EXPORT size_t time() const; ///< time taken, including children double secs() const { return double(time()) / 1000000.0;} ///< time taken, in seconds, including children double self() const { return double(t_) / 1000000.0;} ///< self time only, in seconds double wall() const { return double(tWall_) / 1000000.0;} ///< wall time, in seconds double min() const { return double(tMin_) / 1000000.0;} ///< min time, in seconds double max() const { return double(tMax_) / 1000000.0;} ///< max time, in seconds double mean() const { return self() / double(n_); } ///< mean self time, in seconds - void print(const std::string& outline = "") const; - void print2(const std::string& outline = "", const double parentTotal = -1.0) const; - const boost::shared_ptr& + GTSAM_EXPORT void print(const std::string& outline = "") const; + GTSAM_EXPORT void print2(const std::string& outline = "", const double parentTotal = -1.0) const; + GTSAM_EXPORT const boost::shared_ptr& child(size_t child, const std::string& label, const boost::weak_ptr& thisPtr); - void tic(); - void toc(); - void finishedIteration(); + GTSAM_EXPORT void tic(); + GTSAM_EXPORT void toc(); + GTSAM_EXPORT void finishedIteration(); GTSAM_EXPORT friend void toc(size_t id, const char *label); }; // \TimingOutline diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 1f791935d..9d9b37d7a 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -29,8 +29,7 @@ namespace gtsam { -class GTSAM_EXPORT CheiralityException: public ThreadsafeException< - CheiralityException> { +class GTSAM_EXPORT CheiralityException: public ThreadsafeException { public: CheiralityException() : CheiralityException(std::numeric_limits::max()) {} diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index 891902da7..3235fdedd 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -23,7 +23,7 @@ namespace gtsam { * but here we choose instead to parameterize it as a (Rot3,Unit3) pair. * We can then non-linearly optimize immediately on this 5-dimensional manifold. */ -class GTSAM_EXPORT EssentialMatrix { +class EssentialMatrix { private: Rot3 R_; ///< Rotation Unit3 t_; ///< Translation @@ -48,12 +48,12 @@ class GTSAM_EXPORT EssentialMatrix { } /// Named constructor with derivatives - static EssentialMatrix FromRotationAndDirection(const Rot3& aRb, const Unit3& aTb, + GTSAM_EXPORT static EssentialMatrix FromRotationAndDirection(const Rot3& aRb, const Unit3& aTb, OptionalJacobian<5, 3> H1 = boost::none, OptionalJacobian<5, 2> H2 = boost::none); /// Named constructor converting a Pose3 with scale to EssentialMatrix (no scale) - static EssentialMatrix FromPose3(const Pose3& _1P2_, + GTSAM_EXPORT static EssentialMatrix FromPose3(const Pose3& _1P2_, OptionalJacobian<5, 6> H = boost::none); /// Random, using Rot3::Random and Unit3::Random @@ -70,7 +70,7 @@ class GTSAM_EXPORT EssentialMatrix { /// @{ /// print with optional string - void print(const std::string& s = "") const; + GTSAM_EXPORT void print(const std::string& s = "") const; /// assert equality up to a tolerance bool equals(const EssentialMatrix& other, double tol = 1e-8) const { @@ -138,7 +138,7 @@ class GTSAM_EXPORT EssentialMatrix { * @param Dpoint optional 3*3 Jacobian wrpt point * @return point in pose coordinates */ - Point3 transformTo(const Point3& p, + GTSAM_EXPORT Point3 transformTo(const Point3& p, OptionalJacobian<3, 5> DE = boost::none, OptionalJacobian<3, 3> Dpoint = boost::none) const; @@ -147,7 +147,7 @@ class GTSAM_EXPORT EssentialMatrix { * @param cRb rotation from body frame to camera frame * @param E essential matrix E in camera frame C */ - EssentialMatrix rotate(const Rot3& cRb, OptionalJacobian<5, 5> HE = + GTSAM_EXPORT EssentialMatrix rotate(const Rot3& cRb, OptionalJacobian<5, 5> HE = boost::none, OptionalJacobian<5, 3> HR = boost::none) const; /** @@ -160,7 +160,7 @@ class GTSAM_EXPORT EssentialMatrix { } /// epipolar error, algebraic - double error(const Vector3& vA, const Vector3& vB, + GTSAM_EXPORT double error(const Vector3& vA, const Vector3& vB, OptionalJacobian<1, 5> H = boost::none) const; /// @} diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index a4f6861cc..5f1c7d1bf 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -156,14 +156,14 @@ class GTSAM_EXPORT ExpmapFunctor { }; /// Functor that implements Exponential map *and* its derivatives -class GTSAM_EXPORT DexpFunctor : public ExpmapFunctor { +class DexpFunctor : public ExpmapFunctor { const Vector3 omega; double a, b; Matrix3 dexp_; public: /// Constructor with element of Lie algebra so(3) - DexpFunctor(const Vector3& omega, bool nearZeroApprox = false); + GTSAM_EXPORT DexpFunctor(const Vector3& omega, bool nearZeroApprox = false); // NOTE(luca): Right Jacobian for Exponential map in SO(3) - equation // (10.86) and following equations in G.S. Chirikjian, "Stochastic Models, @@ -174,11 +174,11 @@ class GTSAM_EXPORT DexpFunctor : public ExpmapFunctor { const Matrix3& dexp() const { return dexp_; } /// Multiplies with dexp(), with optional derivatives - Vector3 applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none, + GTSAM_EXPORT Vector3 applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none, OptionalJacobian<3, 3> H2 = boost::none) const; /// Multiplies with dexp().inverse(), with optional derivatives - Vector3 applyInvDexp(const Vector3& v, + GTSAM_EXPORT Vector3 applyInvDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none, OptionalJacobian<3, 3> H2 = boost::none) const; }; diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index f182df285..211698806 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -39,7 +39,7 @@ namespace gtsam { /// Represents a 3D point on a unit sphere. -class GTSAM_EXPORT Unit3 { +class Unit3 { private: @@ -94,11 +94,11 @@ public: } /// Named constructor from Point3 with optional Jacobian - static Unit3 FromPoint3(const Point3& point, // + GTSAM_EXPORT static Unit3 FromPoint3(const Point3& point, // OptionalJacobian<2, 3> H = boost::none); /// Random direction, using boost::uniform_on_sphere - static Unit3 Random(boost::mt19937 & rng); + GTSAM_EXPORT static Unit3 Random(boost::mt19937 & rng); /// @} @@ -108,7 +108,7 @@ public: friend std::ostream& operator<<(std::ostream& os, const Unit3& pair); /// The print fuction - void print(const std::string& s = std::string()) const; + GTSAM_EXPORT void print(const std::string& s = std::string()) const; /// The equals function with tolerance bool equals(const Unit3& s, double tol = 1e-9) const { @@ -125,16 +125,16 @@ public: * tangent to the sphere at the current direction. * Provides derivatives of the basis with the two basis vectors stacked up as a 6x1. */ - const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const; + GTSAM_EXPORT const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const; /// Return skew-symmetric associated with 3D point on unit sphere - Matrix3 skew() const; + GTSAM_EXPORT Matrix3 skew() const; /// Return unit-norm Point3 - Point3 point3(OptionalJacobian<3, 2> H = boost::none) const; + GTSAM_EXPORT Point3 point3(OptionalJacobian<3, 2> H = boost::none) const; /// Return unit-norm Vector - Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const; + GTSAM_EXPORT Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const; /// Return scaled direction as Point3 friend Point3 operator*(double s, const Unit3& d) { @@ -142,20 +142,20 @@ public: } /// Return dot product with q - double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, // + GTSAM_EXPORT double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, // OptionalJacobian<1,2> H2 = boost::none) const; /// Signed, vector-valued error between two directions /// @deprecated, errorVector has the proper derivatives, this confusingly has only the second. - Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const; + GTSAM_EXPORT Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const; /// Signed, vector-valued error between two directions /// NOTE(hayk): This method has zero derivatives if this (p) and q are orthogonal. - Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, // + GTSAM_EXPORT Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, // OptionalJacobian<2, 2> H_q = boost::none) const; /// Distance between two directions - double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const; + GTSAM_EXPORT double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const; /// Cross-product between two Unit3s Unit3 cross(const Unit3& q) const { @@ -188,10 +188,10 @@ public: }; /// The retract function - Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const; + GTSAM_EXPORT Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const; /// The local coordinates function - Vector2 localCoordinates(const Unit3& s) const; + GTSAM_EXPORT Vector2 localCoordinates(const Unit3& s) const; /// @} diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 851c5e4d3..ed61c75b5 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -386,7 +386,7 @@ private: /** * TriangulationResult is an optional point, along with the reasons why it is invalid. */ -class GTSAM_EXPORT TriangulationResult: public boost::optional { +class TriangulationResult: public boost::optional { enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT }; diff --git a/gtsam/inference/Key.h b/gtsam/inference/Key.h index ae3f3844b..8b13f0b4c 100644 --- a/gtsam/inference/Key.h +++ b/gtsam/inference/Key.h @@ -58,7 +58,7 @@ static const gtsam::KeyFormatter MultiRobotKeyFormatter = struct StreamedKey { const Key &key_; explicit StreamedKey(const Key &key) : key_(key) {} - friend std::ostream &operator<<(std::ostream &, const StreamedKey &); + GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const StreamedKey &); }; /** @@ -72,8 +72,8 @@ struct StreamedKey { class key_formatter { public: explicit key_formatter(KeyFormatter v) : formatter_(v) {} - friend std::ostream &operator<<(std::ostream &, const key_formatter &); - friend std::ostream &operator<<(std::ostream &, const StreamedKey &); + GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const key_formatter &); + GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const StreamedKey &); private: KeyFormatter formatter_; diff --git a/gtsam/linear/IterativeSolver.h b/gtsam/linear/IterativeSolver.h index f0fbfbfd2..758d2aec9 100644 --- a/gtsam/linear/IterativeSolver.h +++ b/gtsam/linear/IterativeSolver.h @@ -41,7 +41,7 @@ class VectorValues; /** * parameters for iterative linear solvers */ -class GTSAM_EXPORT IterativeOptimizationParameters { +class IterativeOptimizationParameters { public: @@ -63,27 +63,27 @@ public: inline Verbosity verbosity() const { return verbosity_; } - std::string getVerbosity() const; - void setVerbosity(const std::string &s); + GTSAM_EXPORT std::string getVerbosity() const; + GTSAM_EXPORT void setVerbosity(const std::string &s); /* matlab interface */ - void print() const; + GTSAM_EXPORT void print() const; /* virtual print function */ - virtual void print(std::ostream &os) const; + GTSAM_EXPORT virtual void print(std::ostream &os) const; /* for serialization */ friend std::ostream& operator<<(std::ostream &os, const IterativeOptimizationParameters &p); - static Verbosity verbosityTranslator(const std::string &s); - static std::string verbosityTranslator(Verbosity v); + GTSAM_EXPORT static Verbosity verbosityTranslator(const std::string &s); + GTSAM_EXPORT static std::string verbosityTranslator(Verbosity v); }; /** * Base class for Iterative Solvers like SubgraphSolver */ -class GTSAM_EXPORT IterativeSolver { +class IterativeSolver { public: typedef boost::shared_ptr shared_ptr; IterativeSolver() { @@ -92,12 +92,12 @@ public: } /* interface to the nonlinear optimizer, without metadata, damping and initial estimate */ - VectorValues optimize(const GaussianFactorGraph &gfg, + GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg, boost::optional = boost::none, boost::optional&> lambda = boost::none); /* interface to the nonlinear optimizer, without initial estimate */ - VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, + GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map &lambda); /* interface to the nonlinear optimizer that the subclasses have to implement */ diff --git a/gtsam/nonlinear/ISAM2Result.h b/gtsam/nonlinear/ISAM2Result.h index 3953c760b..e45b17e4a 100644 --- a/gtsam/nonlinear/ISAM2Result.h +++ b/gtsam/nonlinear/ISAM2Result.h @@ -38,7 +38,7 @@ namespace gtsam { * converging, and about how much work was required for the update. See member * variables for details and information about each entry. */ -struct GTSAM_EXPORT ISAM2Result { +struct ISAM2Result { /** The nonlinear error of all of the factors, \a including new factors and * variables added during the current call to ISAM2::update(). This error is * calculated using the following variable values: diff --git a/gtsam/nonlinear/ISAM2UpdateParams.h b/gtsam/nonlinear/ISAM2UpdateParams.h index 884ac7922..44519e3aa 100644 --- a/gtsam/nonlinear/ISAM2UpdateParams.h +++ b/gtsam/nonlinear/ISAM2UpdateParams.h @@ -29,7 +29,7 @@ namespace gtsam { * This struct is used by ISAM2::update() to pass additional parameters to * give the user a fine-grained control on how factors and relinearized, etc. */ -struct GTSAM_EXPORT ISAM2UpdateParams { +struct ISAM2UpdateParams { ISAM2UpdateParams() = default; /** Indices of factors to remove from system (default: empty) */ diff --git a/gtsam/nonlinear/LinearContainerFactor.h b/gtsam/nonlinear/LinearContainerFactor.h index 928b59e77..8a1f600ff 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -23,7 +23,7 @@ namespace gtsam { * This factor does have the ability to perform relinearization under small-angle and * linearity assumptions if a linearization point is added. */ -class GTSAM_EXPORT LinearContainerFactor : public NonlinearFactor { +class LinearContainerFactor : public NonlinearFactor { protected: GaussianFactor::shared_ptr factor_; @@ -33,7 +33,7 @@ protected: LinearContainerFactor() {} /** direct copy constructor */ - LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional& linearizationPoint); + GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional& linearizationPoint); // Some handy typedefs typedef NonlinearFactor Base; @@ -44,13 +44,13 @@ public: typedef boost::shared_ptr shared_ptr; /** Primary constructor: store a linear factor with optional linearization point */ - LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values()); + GTSAM_EXPORT LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values()); /** Primary constructor: store a linear factor with optional linearization point */ - LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values()); + GTSAM_EXPORT LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values()); /** Constructor from shared_ptr */ - LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values()); + GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values()); // Access @@ -59,10 +59,10 @@ public: // Testable /** print */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; + GTSAM_EXPORT void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; /** Check if two factors are equal */ - bool equals(const NonlinearFactor& f, double tol = 1e-9) const; + GTSAM_EXPORT bool equals(const NonlinearFactor& f, double tol = 1e-9) const; // NonlinearFactor @@ -74,10 +74,10 @@ public: * * @return nonlinear error if linearizationPoint present, zero otherwise */ - double error(const Values& c) const; + GTSAM_EXPORT double error(const Values& c) const; /** get the dimension of the factor: rows of linear factor */ - size_t dim() const; + GTSAM_EXPORT size_t dim() const; /** Extract the linearization point used in recalculating error */ const boost::optional& linearizationPoint() const { return linearizationPoint_; } @@ -98,17 +98,17 @@ public: * TODO: better approximation of relinearization * TODO: switchable modes for approximation technique */ - GaussianFactor::shared_ptr linearize(const Values& c) const; + GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values& c) const; /** * Creates an anti-factor directly */ - GaussianFactor::shared_ptr negateToGaussian() const; + GTSAM_EXPORT GaussianFactor::shared_ptr negateToGaussian() const; /** * Creates the equivalent anti-factor as another LinearContainerFactor. */ - NonlinearFactor::shared_ptr negateToNonlinear() const; + GTSAM_EXPORT NonlinearFactor::shared_ptr negateToNonlinear() const; /** * Creates a shared_ptr clone of the factor - needs to be specialized to allow @@ -127,31 +127,31 @@ public: /** * Simple checks whether this is a Jacobian or Hessian factor */ - bool isJacobian() const; - bool isHessian() const; + GTSAM_EXPORT bool isJacobian() const; + GTSAM_EXPORT bool isHessian() const; /** Casts to JacobianFactor */ - boost::shared_ptr toJacobian() const; + GTSAM_EXPORT boost::shared_ptr toJacobian() const; /** Casts to HessianFactor */ - boost::shared_ptr toHessian() const; + GTSAM_EXPORT boost::shared_ptr toHessian() const; /** * Utility function for converting linear graphs to nonlinear graphs * consisting of LinearContainerFactors. */ - static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph, + GTSAM_EXPORT static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph, const Values& linearizationPoint = Values()); #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - static NonlinearFactorGraph convertLinearGraph(const GaussianFactorGraph& linear_graph, + GTSAM_EXPORT static NonlinearFactorGraph convertLinearGraph(const GaussianFactorGraph& linear_graph, const Values& linearizationPoint = Values()) { return ConvertLinearGraph(linear_graph, linearizationPoint); } #endif protected: - void initializeLinearizationPoint(const Values& linearizationPoint); + GTSAM_EXPORT void initializeLinearizationPoint(const Values& linearizationPoint); private: diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.h b/gtsam/nonlinear/NonlinearOptimizerParams.h index 3018a14b9..180f4fb84 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.h +++ b/gtsam/nonlinear/NonlinearOptimizerParams.h @@ -31,7 +31,7 @@ namespace gtsam { /** The common parameters for Nonlinear optimizers. Most optimizers * deriving from NonlinearOptimizer also subclass the parameters. */ -class GTSAM_EXPORT NonlinearOptimizerParams { +class NonlinearOptimizerParams { public: /** See NonlinearOptimizerParams::verbosity */ enum Verbosity { @@ -52,7 +52,7 @@ public: virtual ~NonlinearOptimizerParams() { } - virtual void print(const std::string& str = "") const; + GTSAM_EXPORT virtual void print(const std::string& str = "") const; size_t getMaxIterations() const { return maxIterations; } double getRelativeErrorTol() const { return relativeErrorTol; } @@ -68,8 +68,8 @@ public: verbosity = verbosityTranslator(src); } - static Verbosity verbosityTranslator(const std::string &s) ; - static std::string verbosityTranslator(Verbosity value) ; + GTSAM_EXPORT static Verbosity verbosityTranslator(const std::string &s) ; + GTSAM_EXPORT static std::string verbosityTranslator(Verbosity value) ; /** See NonlinearOptimizerParams::linearSolverType */ enum LinearSolverType { @@ -144,10 +144,10 @@ public: } private: - std::string linearSolverTranslator(LinearSolverType linearSolverType) const; - LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const; - std::string orderingTypeTranslator(Ordering::OrderingType type) const; - Ordering::OrderingType orderingTypeTranslator(const std::string& type) const; + GTSAM_EXPORT std::string linearSolverTranslator(LinearSolverType linearSolverType) const; + GTSAM_EXPORT LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const; + GTSAM_EXPORT std::string orderingTypeTranslator(Ordering::OrderingType type) const; + GTSAM_EXPORT Ordering::OrderingType orderingTypeTranslator(const std::string& type) const; }; // For backward compatibility: diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 1048cd73a..4b0fceaf9 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -422,7 +422,7 @@ namespace gtsam { }; /* ************************************************************************* */ - class GTSAM_EXPORT ValuesKeyAlreadyExists : public std::exception { + class ValuesKeyAlreadyExists : public std::exception { protected: const Key key_; ///< The key that already existed @@ -440,11 +440,11 @@ namespace gtsam { Key key() const throw() { return key_; } /// The message to be displayed to the user - virtual const char* what() const throw(); + GTSAM_EXPORT virtual const char* what() const throw(); }; /* ************************************************************************* */ - class GTSAM_EXPORT ValuesKeyDoesNotExist : public std::exception { + class ValuesKeyDoesNotExist : public std::exception { protected: const char* operation_; ///< The operation that attempted to access the key const Key key_; ///< The key that does not exist @@ -463,11 +463,11 @@ namespace gtsam { Key key() const throw() { return key_; } /// The message to be displayed to the user - virtual const char* what() const throw(); + GTSAM_EXPORT virtual const char* what() const throw(); }; /* ************************************************************************* */ - class GTSAM_EXPORT ValuesIncorrectType : public std::exception { + class ValuesIncorrectType : public std::exception { protected: const Key key_; ///< The key requested const std::type_info& storedTypeId_; @@ -494,11 +494,11 @@ namespace gtsam { const std::type_info& requestedTypeId() const { return requestedTypeId_; } /// The message to be displayed to the user - virtual const char* what() const throw(); + GTSAM_EXPORT virtual const char* what() const throw(); }; /* ************************************************************************* */ - class GTSAM_EXPORT DynamicValuesMismatched : public std::exception { + class DynamicValuesMismatched : public std::exception { public: DynamicValuesMismatched() throw() {} @@ -511,7 +511,7 @@ namespace gtsam { }; /* ************************************************************************* */ - class GTSAM_EXPORT NoMatchFoundForFixed: public std::exception { + class NoMatchFoundForFixed: public std::exception { protected: const size_t M1_, N1_; @@ -528,7 +528,7 @@ namespace gtsam { virtual ~NoMatchFoundForFixed() throw () { } - virtual const char* what() const throw (); + GTSAM_EXPORT virtual const char* what() const throw (); }; /* ************************************************************************* */ diff --git a/gtsam/symbolic/SymbolicBayesNet.h b/gtsam/symbolic/SymbolicBayesNet.h index ab89a4dba..ca87b2bbc 100644 --- a/gtsam/symbolic/SymbolicBayesNet.h +++ b/gtsam/symbolic/SymbolicBayesNet.h @@ -27,7 +27,7 @@ namespace gtsam { /** Symbolic Bayes Net * \nosubgrouping */ - class GTSAM_EXPORT SymbolicBayesNet : public FactorGraph { + class SymbolicBayesNet : public FactorGraph { public: @@ -61,14 +61,14 @@ namespace gtsam { /// @{ /** Check equality */ - bool equals(const This& bn, double tol = 1e-9) const; + GTSAM_EXPORT bool equals(const This& bn, double tol = 1e-9) const; /// @} /// @name Standard Interface /// @{ - void saveGraph(const std::string &s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + GTSAM_EXPORT void saveGraph(const std::string &s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; /// @} diff --git a/gtsam/symbolic/SymbolicBayesTree.h b/gtsam/symbolic/SymbolicBayesTree.h index e28f28764..5f7bdde7e 100644 --- a/gtsam/symbolic/SymbolicBayesTree.h +++ b/gtsam/symbolic/SymbolicBayesTree.h @@ -30,7 +30,7 @@ namespace gtsam { /* ************************************************************************* */ /// A clique in a SymbolicBayesTree - class GTSAM_EXPORT SymbolicBayesTreeClique : + class SymbolicBayesTreeClique : public BayesTreeCliqueBase { public: @@ -45,7 +45,7 @@ namespace gtsam { /* ************************************************************************* */ /// A Bayes tree that represents the connectivity between variables but is not associated with any /// probability functions. - class GTSAM_EXPORT SymbolicBayesTree : + class SymbolicBayesTree : public BayesTree { private: @@ -59,7 +59,7 @@ namespace gtsam { SymbolicBayesTree() {} /** check equality */ - bool equals(const This& other, double tol = 1e-9) const; + GTSAM_EXPORT bool equals(const This& other, double tol = 1e-9) const; private: /** Serialization function */ diff --git a/gtsam_unstable/geometry/Event.h b/gtsam_unstable/geometry/Event.h index b22164117..fc186857f 100644 --- a/gtsam_unstable/geometry/Event.h +++ b/gtsam_unstable/geometry/Event.h @@ -22,6 +22,7 @@ #include #include #include +#include namespace gtsam { @@ -60,10 +61,10 @@ public: } /** print with optional string */ - GTSAM_EXPORT void print(const std::string& s = "") const; + GTSAM_UNSTABLE_EXPORT void print(const std::string& s = "") const; /** equals with an tolerance */ - GTSAM_EXPORT bool equals(const Event& other, double tol = 1e-9) const; + GTSAM_UNSTABLE_EXPORT bool equals(const Event& other, double tol = 1e-9) const; /// Updates a with tangent space delta inline Event retract(const Vector4& v) const { diff --git a/gtsam_unstable/geometry/Similarity3.h b/gtsam_unstable/geometry/Similarity3.h index a3d80c1d0..bf4937ed4 100644 --- a/gtsam_unstable/geometry/Similarity3.h +++ b/gtsam_unstable/geometry/Similarity3.h @@ -21,6 +21,7 @@ #include #include #include +#include namespace gtsam { @@ -49,59 +50,59 @@ public: /// @{ /// Default constructor - GTSAM_EXPORT Similarity3(); + GTSAM_UNSTABLE_EXPORT Similarity3(); /// Construct pure scaling - GTSAM_EXPORT Similarity3(double s); + GTSAM_UNSTABLE_EXPORT Similarity3(double s); /// Construct from GTSAM types - GTSAM_EXPORT Similarity3(const Rot3& R, const Point3& t, double s); + GTSAM_UNSTABLE_EXPORT Similarity3(const Rot3& R, const Point3& t, double s); /// Construct from Eigen types - GTSAM_EXPORT Similarity3(const Matrix3& R, const Vector3& t, double s); + GTSAM_UNSTABLE_EXPORT Similarity3(const Matrix3& R, const Vector3& t, double s); /// Construct from matrix [R t; 0 s^-1] - GTSAM_EXPORT Similarity3(const Matrix4& T); + GTSAM_UNSTABLE_EXPORT Similarity3(const Matrix4& T); /// @} /// @name Testable /// @{ /// Compare with tolerance - GTSAM_EXPORT bool equals(const Similarity3& sim, double tol) const; + GTSAM_UNSTABLE_EXPORT bool equals(const Similarity3& sim, double tol) const; /// Exact equality - GTSAM_EXPORT bool operator==(const Similarity3& other) const; + GTSAM_UNSTABLE_EXPORT bool operator==(const Similarity3& other) const; /// Print with optional string - GTSAM_EXPORT void print(const std::string& s) const; + GTSAM_UNSTABLE_EXPORT void print(const std::string& s) const; - GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity3& p); + GTSAM_UNSTABLE_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity3& p); /// @} /// @name Group /// @{ /// Return an identity transform - GTSAM_EXPORT static Similarity3 identity(); + GTSAM_UNSTABLE_EXPORT static Similarity3 identity(); /// Composition - GTSAM_EXPORT Similarity3 operator*(const Similarity3& T) const; + GTSAM_UNSTABLE_EXPORT Similarity3 operator*(const Similarity3& T) const; /// Return the inverse - GTSAM_EXPORT Similarity3 inverse() const; + GTSAM_UNSTABLE_EXPORT Similarity3 inverse() const; /// @} /// @name Group action on Point3 /// @{ /// Action on a point p is s*(R*p+t) - GTSAM_EXPORT Point3 transformFrom(const Point3& p, // + GTSAM_UNSTABLE_EXPORT Point3 transformFrom(const Point3& p, // OptionalJacobian<3, 7> H1 = boost::none, // OptionalJacobian<3, 3> H2 = boost::none) const; /** syntactic sugar for transformFrom */ - GTSAM_EXPORT Point3 operator*(const Point3& p) const; + GTSAM_UNSTABLE_EXPORT Point3 operator*(const Point3& p) const; /// @} /// @name Lie Group @@ -110,12 +111,12 @@ public: /** Log map at the identity * \f$ [R_x,R_y,R_z, t_x, t_y, t_z, \lambda] \f$ */ - GTSAM_EXPORT static Vector7 Logmap(const Similarity3& s, // + GTSAM_UNSTABLE_EXPORT static Vector7 Logmap(const Similarity3& s, // OptionalJacobian<7, 7> Hm = boost::none); /** Exponential map at the identity */ - GTSAM_EXPORT static Similarity3 Expmap(const Vector7& v, // + GTSAM_UNSTABLE_EXPORT static Similarity3 Expmap(const Vector7& v, // OptionalJacobian<7, 7> Hm = boost::none); /// Chart at the origin @@ -136,17 +137,17 @@ public: * @return 4*4 element of Lie algebra that can be exponentiated * TODO(frank): rename to Hat, make part of traits */ - GTSAM_EXPORT static Matrix4 wedge(const Vector7& xi); + GTSAM_UNSTABLE_EXPORT static Matrix4 wedge(const Vector7& xi); /// Project from one tangent space to another - GTSAM_EXPORT Matrix7 AdjointMap() const; + GTSAM_UNSTABLE_EXPORT Matrix7 AdjointMap() const; /// @} /// @name Standard interface /// @{ /// Calculate 4*4 matrix group equivalent - GTSAM_EXPORT const Matrix4 matrix() const; + GTSAM_UNSTABLE_EXPORT const Matrix4 matrix() const; /// Return a GTSAM rotation const Rot3& rotation() const { @@ -165,7 +166,7 @@ public: /// Convert to a rigid body pose (R, s*t) /// TODO(frank): why is this here? Red flag! Definitely don't have it as a cast. - GTSAM_EXPORT operator Pose3() const; + GTSAM_UNSTABLE_EXPORT operator Pose3() const; /// Dimensionality of tangent space = 7 DOF - used to autodetect sizes inline static size_t Dim() {