Missing DLL EXPORT macros
							parent
							
								
									7aeb153da8
								
							
						
					
					
						commit
						c5681d8e59
					
				|  | @ -32,7 +32,7 @@ namespace gtsam { | |||
| //******************************************************************************
 | ||||
| namespace so3 { | ||||
| 
 | ||||
| Matrix99 Dcompose(const SO3& Q) { | ||||
| GTSAM_EXPORT Matrix99 Dcompose(const SO3& Q) { | ||||
|   Matrix99 H; | ||||
|   auto R = Q.matrix(); | ||||
|   H << I_3x3 * R(0, 0), I_3x3 * R(1, 0), I_3x3 * R(2, 0),  //
 | ||||
|  | @ -41,7 +41,7 @@ Matrix99 Dcompose(const SO3& Q) { | |||
|   return H; | ||||
| } | ||||
| 
 | ||||
| Matrix3 compose(const Matrix3& M, const SO3& R, OptionalJacobian<9, 9> H) { | ||||
| GTSAM_EXPORT Matrix3 compose(const Matrix3& M, const SO3& R, OptionalJacobian<9, 9> H) { | ||||
|   Matrix3 MR = M * R.matrix(); | ||||
|   if (H) *H = Dcompose(R); | ||||
|   return MR; | ||||
|  | @ -134,12 +134,14 @@ Vector3 DexpFunctor::applyInvDexp(const Vector3& v, OptionalJacobian<3, 3> H1, | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::AxisAngle(const Vector3& axis, double theta) { | ||||
|   return so3::ExpmapFunctor(axis, theta).expmap(); | ||||
| } | ||||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::ClosestTo(const Matrix3& M) { | ||||
|   Eigen::JacobiSVD<Matrix3> svd(M, Eigen::ComputeFullU | Eigen::ComputeFullV); | ||||
|   const auto& U = svd.matrixU(); | ||||
|  | @ -150,6 +152,7 @@ SO3 SO3::ClosestTo(const Matrix3& M) { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::ChordalMean(const std::vector<SO3>& rotations) { | ||||
|   // See Hartley13ijcv:
 | ||||
|   // Cost function C(R) = \sum sqr(|R-R_i|_F)
 | ||||
|  | @ -163,6 +166,7 @@ SO3 SO3::ChordalMean(const std::vector<SO3>& rotations) { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix3 SO3::Hat(const Vector3& xi) { | ||||
|   // skew symmetric matrix X = xi^
 | ||||
|   Matrix3 Y = Z_3x3; | ||||
|  | @ -174,6 +178,7 @@ Matrix3 SO3::Hat(const Vector3& xi) { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector3 SO3::Vee(const Matrix3& X) { | ||||
|   Vector3 xi; | ||||
|   xi(0) = -X(1, 2); | ||||
|  | @ -184,12 +189,14 @@ Vector3 SO3::Vee(const Matrix3& X) { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix3 SO3::AdjointMap() const { | ||||
|   return matrix_; | ||||
| } | ||||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H) { | ||||
|   if (H) { | ||||
|     so3::DexpFunctor impl(omega); | ||||
|  | @ -201,6 +208,7 @@ SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H) { | |||
| } | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix3 SO3::ExpmapDerivative(const Vector3& omega) { | ||||
|   return so3::DexpFunctor(omega).dexp(); | ||||
| } | ||||
|  | @ -217,6 +225,7 @@ Matrix3 SO3::ExpmapDerivative(const Vector3& omega) { | |||
|  omega) | ||||
|  */ | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix3 SO3::LogmapDerivative(const Vector3& omega) { | ||||
|   using std::cos; | ||||
|   using std::sin; | ||||
|  | @ -234,6 +243,7 @@ Matrix3 SO3::LogmapDerivative(const Vector3& omega) { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector3 SO3::Logmap(const SO3& Q, ChartJacobian H) { | ||||
|   using std::sin; | ||||
|   using std::sqrt; | ||||
|  | @ -281,11 +291,13 @@ Vector3 SO3::Logmap(const SO3& Q, ChartJacobian H) { | |||
| // Chart at origin for SO3 is *not* Cayley but actual Expmap/Logmap
 | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::ChartAtOrigin::Retract(const Vector3& omega, ChartJacobian H) { | ||||
|   return Expmap(omega, H); | ||||
| } | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector3 SO3::ChartAtOrigin::Local(const SO3& R, ChartJacobian H) { | ||||
|   return Logmap(R, H); | ||||
| } | ||||
|  | @ -307,6 +319,7 @@ static const Matrix93 P3 = | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector9 SO3::vec(OptionalJacobian<9, 3> H) const { | ||||
|   const Matrix3& R = matrix_; | ||||
|   if (H) { | ||||
|  |  | |||
|  | @ -24,6 +24,7 @@ | |||
| 
 | ||||
| #include <gtsam/base/Lie.h> | ||||
| #include <gtsam/base/Matrix.h> | ||||
| #include <gtsam/dllexport.h> | ||||
| 
 | ||||
| #include <cmath> | ||||
| #include <vector> | ||||
|  | @ -36,18 +37,23 @@ using SO3 = SO<3>; | |||
| // They are *defined* in SO3.cpp.
 | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::AxisAngle(const Vector3& axis, double theta); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::ClosestTo(const Matrix3& M); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::ChordalMean(const std::vector<SO3>& rotations); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix3 SO3::Hat(const Vector3& xi);  ///< make skew symmetric matrix
 | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector3 SO3::Vee(const Matrix3& X);  ///< inverse of Hat
 | ||||
| 
 | ||||
| /// Adjoint map
 | ||||
|  | @ -59,10 +65,12 @@ Matrix3 SO3::AdjointMap() const; | |||
|  * \f$ [R_x,R_y,R_z] \f$ using Rodrigues' formula | ||||
|  */ | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H); | ||||
| 
 | ||||
| /// Derivative of Expmap
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix3 SO3::ExpmapDerivative(const Vector3& omega); | ||||
| 
 | ||||
| /**
 | ||||
|  | @ -70,20 +78,25 @@ Matrix3 SO3::ExpmapDerivative(const Vector3& omega); | |||
|  * \f$ [R_x,R_y,R_z] \f$ of this rotation | ||||
|  */ | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector3 SO3::Logmap(const SO3& R, ChartJacobian H); | ||||
| 
 | ||||
| /// Derivative of Logmap
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix3 SO3::LogmapDerivative(const Vector3& omega); | ||||
| 
 | ||||
| // Chart at origin for SO3 is *not* Cayley but actual Expmap/Logmap
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO3 SO3::ChartAtOrigin::Retract(const Vector3& omega, ChartJacobian H); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector3 SO3::ChartAtOrigin::Local(const SO3& R, ChartJacobian H); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector9 SO3::vec(OptionalJacobian<9, 3> H) const; | ||||
| 
 | ||||
| /** Serialization function */ | ||||
|  | @ -107,11 +120,11 @@ namespace so3 { | |||
|  * Compose general matrix with an SO(3) element. | ||||
|  * We only provide the 9*9 derivative in the first argument M. | ||||
|  */ | ||||
| Matrix3 compose(const Matrix3& M, const SO3& R, | ||||
| GTSAM_EXPORT Matrix3 compose(const Matrix3& M, const SO3& R, | ||||
|                 OptionalJacobian<9, 9> H = boost::none); | ||||
| 
 | ||||
| /// (constant) Jacobian of compose wrpt M
 | ||||
| Matrix99 Dcompose(const SO3& R); | ||||
| GTSAM_EXPORT Matrix99 Dcompose(const SO3& R); | ||||
| 
 | ||||
| // Below are two functors that allow for saving computation when exponential map
 | ||||
| // and its derivatives are needed at the same location in so<3>. The second
 | ||||
|  |  | |||
|  | @ -50,6 +50,7 @@ namespace gtsam { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix4 SO4::Hat(const Vector6& xi) { | ||||
|   // skew symmetric matrix X = xi^
 | ||||
|   // Unlike Luca, makes upper-left the SO(3) subgroup.
 | ||||
|  | @ -65,6 +66,7 @@ Matrix4 SO4::Hat(const Vector6& xi) { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector6 SO4::Vee(const Matrix4& X) { | ||||
|   Vector6 xi; | ||||
|   xi(5) = -X(0, 1); | ||||
|  | @ -81,6 +83,7 @@ Vector6 SO4::Vee(const Matrix4& X) { | |||
|  * "SOME REMARKS ON THE EXPONENTIAL MAP ON THE GROUPS SO(n) AND SE(n)" by | ||||
|  * Ramona-Andreaa Rohan */ | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO4 SO4::Expmap(const Vector6& xi, ChartJacobian H) { | ||||
|   using namespace std; | ||||
|   if (H) throw std::runtime_error("SO4::Expmap Jacobian"); | ||||
|  | @ -151,6 +154,7 @@ static const Eigen::Matrix<double, 16, 6> P4 = | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix6 SO4::AdjointMap() const { | ||||
|   // Elaborate way of calculating the AdjointMap
 | ||||
|   // TODO(frank): find a closed form solution. In SO(3) is just R :-/
 | ||||
|  | @ -166,6 +170,7 @@ Matrix6 SO4::AdjointMap() const { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO4::VectorN2 SO4::vec(OptionalJacobian<16, 6> H) const { | ||||
|   const Matrix& Q = matrix_; | ||||
|   if (H) { | ||||
|  | @ -178,6 +183,7 @@ SO4::VectorN2 SO4::vec(OptionalJacobian<16, 6> H) const { | |||
| 
 | ||||
| ///******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO4 SO4::ChartAtOrigin::Retract(const Vector6& xi, ChartJacobian H) { | ||||
|   if (H) throw std::runtime_error("SO4::ChartAtOrigin::Retract Jacobian"); | ||||
|   gttic(SO4_Retract); | ||||
|  | @ -187,6 +193,7 @@ SO4 SO4::ChartAtOrigin::Retract(const Vector6& xi, ChartJacobian H) { | |||
| 
 | ||||
| //******************************************************************************
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector6 SO4::ChartAtOrigin::Local(const SO4& Q, ChartJacobian H) { | ||||
|   if (H) throw std::runtime_error("SO4::ChartAtOrigin::Retract Jacobian"); | ||||
|   const Matrix4& R = Q.matrix(); | ||||
|  | @ -195,7 +202,7 @@ Vector6 SO4::ChartAtOrigin::Local(const SO4& Q, ChartJacobian H) { | |||
| } | ||||
| 
 | ||||
| //******************************************************************************
 | ||||
| Matrix3 topLeft(const SO4& Q, OptionalJacobian<9, 6> H) { | ||||
| GTSAM_EXPORT Matrix3 topLeft(const SO4& Q, OptionalJacobian<9, 6> H) { | ||||
|   const Matrix4& R = Q.matrix(); | ||||
|   const Matrix3 M = R.topLeftCorner<3, 3>(); | ||||
|   if (H) { | ||||
|  | @ -209,7 +216,7 @@ Matrix3 topLeft(const SO4& Q, OptionalJacobian<9, 6> H) { | |||
| } | ||||
| 
 | ||||
| //******************************************************************************
 | ||||
| Matrix43 stiefel(const SO4& Q, OptionalJacobian<12, 6> H) { | ||||
| GTSAM_EXPORT Matrix43 stiefel(const SO4& Q, OptionalJacobian<12, 6> H) { | ||||
|   const Matrix4& R = Q.matrix(); | ||||
|   const Matrix43 M = R.leftCols<3>(); | ||||
|   if (H) { | ||||
|  |  | |||
|  | @ -25,6 +25,7 @@ | |||
| #include <gtsam/base/Lie.h> | ||||
| #include <gtsam/base/Manifold.h> | ||||
| #include <gtsam/base/Matrix.h> | ||||
| #include <gtsam/dllexport.h> | ||||
| 
 | ||||
| #include <boost/random/mersenne_twister.hpp> | ||||
| 
 | ||||
|  | @ -41,36 +42,43 @@ using SO4 = SO<4>; | |||
| // They are *defined* in SO4.cpp.
 | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix4 SO4::Hat(const TangentVector &xi); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector6 SO4::Vee(const Matrix4 &X); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO4 SO4::Expmap(const Vector6 &xi, ChartJacobian H); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix6 SO4::AdjointMap() const; | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO4::VectorN2 SO4::vec(OptionalJacobian<16, 6> H) const; | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| SO4 SO4::ChartAtOrigin::Retract(const Vector6 &omega, ChartJacobian H); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector6 SO4::ChartAtOrigin::Local(const SO4 &Q, ChartJacobian H); | ||||
| 
 | ||||
| /**
 | ||||
|  * Project to top-left 3*3 matrix. Note this is *not* in general \in SO(3). | ||||
|  */ | ||||
| Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = boost::none); | ||||
| GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = boost::none); | ||||
| 
 | ||||
| /**
 | ||||
|  * Project to Stiefel manifold of 4*3 orthonormal 3-frames in R^4, i.e., pi(Q) | ||||
|  * -> S \in St(3,4). | ||||
|  */ | ||||
| Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = boost::none); | ||||
| GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = boost::none); | ||||
| 
 | ||||
| /** Serialization function */ | ||||
| template <class Archive> | ||||
|  |  | |||
|  | @ -21,6 +21,7 @@ | |||
| namespace gtsam { | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix SOn::Hat(const Vector& xi) { | ||||
|   size_t n = AmbientDim(xi.size()); | ||||
|   if (n < 2) throw std::invalid_argument("SO<N>::Hat: n<2 not supported"); | ||||
|  | @ -49,6 +50,7 @@ Matrix SOn::Hat(const Vector& xi) { | |||
| } | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector SOn::Vee(const Matrix& X) { | ||||
|   const size_t n = X.rows(); | ||||
|   if (n < 2) throw std::invalid_argument("SO<N>::Hat: n<2 not supported"); | ||||
|  |  | |||
|  | @ -20,6 +20,7 @@ | |||
| 
 | ||||
| #include <gtsam/base/Lie.h> | ||||
| #include <gtsam/base/Manifold.h> | ||||
| #include <gtsam/dllexport.h> | ||||
| 
 | ||||
| #include <Eigen/Core> | ||||
| #include <boost/random.hpp> | ||||
|  | @ -297,9 +298,11 @@ using SOn = SO<Eigen::Dynamic>; | |||
|  */ | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Matrix SOn::Hat(const Vector& xi); | ||||
| 
 | ||||
| template <> | ||||
| GTSAM_EXPORT | ||||
| Vector SOn::Vee(const Matrix& X); | ||||
| 
 | ||||
| /*
 | ||||
|  |  | |||
|  | @ -66,7 +66,7 @@ boost::function<bool(Key)> Symbol::ChrTest(unsigned char c) { | |||
|   return bind(&Symbol::chr, bind(make, _1)) == c; | ||||
| } | ||||
| 
 | ||||
| std::ostream &operator<<(std::ostream &os, const Symbol &symbol) { | ||||
| GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const Symbol &symbol) { | ||||
|   os << StreamedKey(symbol); | ||||
|   return os; | ||||
| } | ||||
|  |  | |||
|  | @ -113,7 +113,7 @@ public: | |||
|   static boost::function<bool(Key)> ChrTest(unsigned char c); | ||||
| 
 | ||||
|   /// Output stream operator that can be used with key_formatter (see Key.h).
 | ||||
|   friend std::ostream &operator<<(std::ostream &, const Symbol &); | ||||
|   GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const Symbol &); | ||||
| 
 | ||||
| private: | ||||
| 
 | ||||
|  |  | |||
|  | @ -49,16 +49,16 @@ struct GTSAM_EXPORT SlotEntry { | |||
| class Scatter : public FastVector<SlotEntry> { | ||||
|  public: | ||||
|   /// Default Constructor
 | ||||
|   Scatter() {} | ||||
|    GTSAM_EXPORT Scatter() {} | ||||
| 
 | ||||
|   /// Construct from gaussian factor graph, without ordering
 | ||||
|   explicit Scatter(const GaussianFactorGraph& gfg); | ||||
|    GTSAM_EXPORT explicit Scatter(const GaussianFactorGraph& gfg); | ||||
| 
 | ||||
|   /// Construct from gaussian factor graph, with (partial or complete) ordering
 | ||||
|   explicit Scatter(const GaussianFactorGraph& gfg, const Ordering& ordering); | ||||
|    GTSAM_EXPORT explicit Scatter(const GaussianFactorGraph& gfg, const Ordering& ordering); | ||||
| 
 | ||||
|   /// Add a key/dim pair
 | ||||
|   void add(Key key, size_t dim); | ||||
|    GTSAM_EXPORT void add(Key key, size_t dim); | ||||
| 
 | ||||
|  private: | ||||
|   /// Find the SlotEntry with the right key (linear time worst case)
 | ||||
|  |  | |||
|  | @ -129,7 +129,7 @@ namespace gtsam { | |||
|   } | ||||
| 
 | ||||
|   /* ************************************************************************* */ | ||||
|   ostream& operator<<(ostream& os, const VectorValues& v) { | ||||
|   GTSAM_EXPORT ostream& operator<<(ostream& os, const VectorValues& v) { | ||||
|     // Change print depending on whether we are using TBB
 | ||||
| #ifdef GTSAM_USE_TBB | ||||
|     map<Key, Vector> sorted; | ||||
|  |  | |||
|  | @ -230,7 +230,7 @@ namespace gtsam { | |||
|     const_iterator find(Key j) const { return values_.find(j); } | ||||
| 
 | ||||
|     /// overload operator << to print to stringstream
 | ||||
|     friend std::ostream& operator<<(std::ostream&, const VectorValues&); | ||||
|     GTSAM_EXPORT friend std::ostream& operator<<(std::ostream&, const VectorValues&); | ||||
| 
 | ||||
|     /** print required by Testable for unit testing */ | ||||
|     void print(const std::string& str = "VectorValues", | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue