diff --git a/Using-GTSAM-EXPORT.md b/Using-GTSAM-EXPORT.md new file mode 100644 index 0000000000..41eccc178d --- /dev/null +++ b/Using-GTSAM-EXPORT.md @@ -0,0 +1,37 @@ +# Using GTSAM_EXPORT + +To create a DLL in windows, the `GTSAM_EXPORT` keyword has been created and needs to be applied to different methods and classes in the code to expose this code outside of the DLL. However, there are several intricacies that make this more difficult than it sounds. In general, if you follow the following three rules, GTSAM_EXPORT should work properly. The rest of the document also describes (1) the common error message encountered when you are not following these rules and (2) the reasoning behind these usage rules. + +## Usage Rules +1. Put `GTSAM_EXPORT` in front of any function that you want exported in the DLL _if and only if_ that function is declared in a .cpp file, not just a .h file. +2. Use `GTSAM_EXPORT` in a class definition (i.e. `class GSTAM_EXPORT MyClass {...}`) only if: + * At least one of the functions inside that class is declared in a .cpp file and not just the .h file. + * You can `GTSAM_EXPORT` any class it inherits from as well. (Note that this implictly requires the class does not derive from a "header-only" class. Note that Eigen is a "header-only" library, so if your class derives from Eigen, _do not_ use `GTSAM_EXPORT` in the class definition!) +3. If you have defined a class using `GTSAM_EXPORT`, do not use `GTSAM_EXPORT` in any of its individual function declarations. (Note that you _can_ put `GTSAM_EXPORT` in the definition of individual functions within a class as long as you don't put `GTSAM_EXPORT` in the class definition.) + +## When is GTSAM_EXPORT being used incorrectly +Unfortunately, using `GTSAM_EXPORT` incorrectly often does not cause a compiler or linker error in the library that is being compiled, but only when you try to use that DLL in a different library. For example, an error in gtsam/base will often show up when compiling the check_base_program or the MATLAB wrapper, but not when compiling/linking gtsam itself. The most common errors will say something like: + +``` +Error LNK2019 unresolved external symbol "public: void __cdecl gtsam::SO3::print(class std::basic_string,class std::allocator > const &)const " (?print@SO3@gtsam@@QEBAXAEBV?$basic_string@DU?$char_traits@D@std@@V?$allocator@D@2@@std@@@Z) referenced in function "public: static void __cdecl gtsam::Testable::Print(class gtsam::SO3 const &,class std::basic_string,class std::allocator > const &)" (?Print@?$Testable@VSO3@gtsam@@@gtsam@@SAXAEBVSO3@2@AEBV?$basic_string@DU?$char_traits@D@std@@V?$allocator@D@2@@std@@@Z) check_geometry_program C:\AFIT\lib\gtsam\build\gtsam\geometry\tests\testSO3.obj +``` + +Let's analyze this error statement. First, there is an unresolved symbol `gtsam::SO3::print`. This can occur because _either_ `GTSAM_EXPORT` was not added to the print function definition when it should have been, _OR_ because `GTSAM_EXPORT` was added to the print function definition when it is fully declared in the header. This error was detected while compiling `check_geometry_program` and pulling in `...\testSO3.obj`. Specifically, within the function call `gtsam::Testable::Print (...)`. Note that this error did _not_ occur when compiling the library that actually has SO3 inside of it. + +## But Why? +I believe that how the compiler/linker interacts with GTSAM_EXPORT can be explained by understanding the rules that MSVC operates under. + +But first, we need to understand exactly what `GTSAM_EXPORT` is. `GTSAM_EXPORT` is a `#define` macro that is created by CMAKE when GTSAM is being compiled on a Windows machine. Inside the GTSAM project, GTSAM export will be set to a "dllexport" command. A "dllexport" command tells the compiler that this function should go into the DLL and be visible externally. In any other library, `GTSAM_EXPORT` will be set to a "dllimport" command, telling the linker it should find this function in a DLL somewhere. This leads to the first rule the compiler uses. (Note that I say "compiler rules" when the rules may actually be in the linker, but I am conflating the two terms here when I speak of the "compiler rules".) + +***Compiler Rule #1*** If a `dllimport` command is used in defining a function or class, that function or class _must_ be found in a DLL. + +Rule #1 doesn't seem very bad, until you combine it with rule #2 + +***Compiler Rule #2*** Anything declared in a header file is not included in a DLL. + +When these two rules are combined, you get some very confusing results. For example, a class which is completely defined in a header (e.g. LieMatrix) cannot use `GTSAM_EXPORT` in its definition. If LieMatrix is defined with `GTSAM_EXPORT`, then the compiler _must_ find LieMatrix in a DLL. Because LieMatrix is a header-only class, however, it can't find it, leading to a very confusing "I can't find this symbol" type of error. Note that the linker says it can't find the symbol even though the compiler found the header file that completely defines the class. + +Also note that when a class that you want to export inherits from another class that is not exportable, this can cause significant issues. According to this [MSVC Warning page](https://docs.microsoft.com/en-us/cpp/error-messages/compiler-warnings/compiler-warning-level-2-c4275?view=vs-2019), it may not strictly be a rule, but we have seen several linker errors when a class that is defined with `GTSAM_EXPORT` extended an Eigen class. In general, it appears that any inheritance of non-exportable class by an exportable class is a bad idea. + +## Conclusion +Hopefully, this little document clarifies when `GTSAM_EXPORT` should and should not be used whenever future GTSAM code is being written. Following the usage rules above, we have been able to get all of the libraries, together with their test and wrapping libraries, to compile/link successfully. \ No newline at end of file diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 235cd30f35..8060ae7f4d 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -299,7 +299,7 @@ GTSAM_EXPORT std::pair qr(const Matrix& A); * @param A is the input matrix, and is the output * @param clear_below_diagonal enables zeroing out below diagonal */ -void inplace_QR(Matrix& A); +GTSAM_EXPORT void inplace_QR(Matrix& A); /** * Imperative algorithm for in-place full elimination with diff --git a/gtsam/base/deprecated/LieMatrix.h b/gtsam/base/deprecated/LieMatrix.h index 953537bf7d..a3d0a43289 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 GTSAM_EXPORT LieMatrix : public Matrix { +struct LieMatrix : public Matrix { /// @name Constructors /// @{ diff --git a/gtsam/base/deprecated/LieScalar.h b/gtsam/base/deprecated/LieScalar.h index 50ea9d6957..4e9bfb7dbb 100644 --- a/gtsam/base/deprecated/LieScalar.h +++ b/gtsam/base/deprecated/LieScalar.h @@ -28,7 +28,7 @@ namespace gtsam { * we can directly add double, Vector, and Matrix into values now, because of * gtsam::traits. */ - struct GTSAM_EXPORT LieScalar { + struct LieScalar { enum { dimension = 1 }; diff --git a/gtsam/base/deprecated/LieVector.h b/gtsam/base/deprecated/LieVector.h index 60c8103e28..745189c3de 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 GTSAM_EXPORT LieVector : public Vector { +struct LieVector : public Vector { enum { dimension = Eigen::Dynamic }; diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 30e902c2b9..718fb2992e 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -37,7 +37,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Point2 : public Vector2 { +class Point2 : public Vector2 { private: public: @@ -66,10 +66,10 @@ class GTSAM_EXPORT Point2 : public Vector2 { /// @{ /// print with optional string - void print(const std::string& s = "") const; + GTSAM_EXPORT void print(const std::string& s = "") const; /// equals with an tolerance, prints out message if unequal - bool equals(const Point2& q, double tol = 1e-9) const; + GTSAM_EXPORT bool equals(const Point2& q, double tol = 1e-9) const; /// @} /// @name Group @@ -86,10 +86,10 @@ class GTSAM_EXPORT Point2 : public Vector2 { Point2 unit() const { return *this/norm(); } /** norm of point, with derivative */ - double norm(OptionalJacobian<1,2> H = boost::none) const; + GTSAM_EXPORT double norm(OptionalJacobian<1,2> H = boost::none) const; /** distance between two points */ - double distance(const Point2& p2, OptionalJacobian<1,2> H1 = boost::none, + GTSAM_EXPORT double distance(const Point2& p2, OptionalJacobian<1,2> H1 = boost::none, OptionalJacobian<1,2> H2 = boost::none) const; /// @} @@ -124,9 +124,9 @@ class GTSAM_EXPORT Point2 : public Vector2 { static Vector2 Logmap(const Point2& p) { return p;} static Point2 Expmap(const Vector2& v) { return Point2(v);} inline double dist(const Point2& p2) const {return distance(p2);} - static boost::optional CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9); - static std::list CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); - static std::list CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9); + GTSAM_EXPORT static boost::optional CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9); + GTSAM_EXPORT static std::list CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); + GTSAM_EXPORT static std::list CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9); /// @} #endif diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 215161b3a4..3b2330403c 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -42,7 +42,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Point3 : public Vector3 { +class Point3 : public Vector3 { public: @@ -63,10 +63,10 @@ class GTSAM_EXPORT Point3 : public Vector3 { /// @{ /** print with optional string */ - void print(const std::string& s = "") const; + GTSAM_EXPORT void print(const std::string& s = "") const; /** equals with an tolerance */ - bool equals(const Point3& p, double tol = 1e-9) const; + GTSAM_EXPORT bool equals(const Point3& p, double tol = 1e-9) const; /// @} /// @name Group @@ -80,21 +80,21 @@ class GTSAM_EXPORT Point3 : public Vector3 { /// @{ /** distance between two points */ - double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none, + GTSAM_EXPORT double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none, OptionalJacobian<1, 3> H2 = boost::none) const; /** Distance of the point from the origin, with Jacobian */ - double norm(OptionalJacobian<1,3> H = boost::none) const; + GTSAM_EXPORT double norm(OptionalJacobian<1,3> H = boost::none) const; /** normalize, with optional Jacobian */ - Point3 normalized(OptionalJacobian<3, 3> H = boost::none) const; + GTSAM_EXPORT Point3 normalized(OptionalJacobian<3, 3> H = boost::none) const; /** cross product @return this x q */ - Point3 cross(const Point3 &q, OptionalJacobian<3, 3> H_p = boost::none, // + GTSAM_EXPORT Point3 cross(const Point3 &q, OptionalJacobian<3, 3> H_p = boost::none, // OptionalJacobian<3, 3> H_q = boost::none) const; /** dot product @return this * q*/ - double dot(const Point3 &q, OptionalJacobian<1, 3> H_p = boost::none, // + GTSAM_EXPORT double dot(const Point3 &q, OptionalJacobian<1, 3> H_p = boost::none, // OptionalJacobian<1, 3> H_q = boost::none) const; /// @} @@ -130,9 +130,9 @@ class GTSAM_EXPORT Point3 : public Vector3 { static Point3 Expmap(const Vector3& v) { return Point3(v);} inline double dist(const Point3& q) const { return (q - *this).norm(); } Point3 normalize(OptionalJacobian<3, 3> H = boost::none) const { return normalized(H);} - Point3 add(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none, + GTSAM_EXPORT Point3 add(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none, OptionalJacobian<3, 3> H2 = boost::none) const; - Point3 sub(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none, + GTSAM_EXPORT Point3 sub(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none, OptionalJacobian<3, 3> H2 = boost::none) const; /// @} #endif diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index efd6a7f88d..388318827d 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -33,7 +33,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Pose2: public LieGroup { +class Pose2: public LieGroup { public: @@ -97,10 +97,10 @@ class GTSAM_EXPORT Pose2: public LieGroup { /// @{ /** 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 Pose2& pose, double tol = 1e-9) const; + GTSAM_EXPORT bool equals(const Pose2& pose, double tol = 1e-9) const; /// @} /// @name Group @@ -110,7 +110,7 @@ class GTSAM_EXPORT Pose2: public LieGroup { inline static Pose2 identity() { return Pose2(); } /// inverse - Pose2 inverse() const; + GTSAM_EXPORT Pose2 inverse() const; /// compose syntactic sugar inline Pose2 operator*(const Pose2& p2) const { @@ -122,16 +122,16 @@ class GTSAM_EXPORT Pose2: public LieGroup { /// @{ ///Exponential map at identity - create a rotation from canonical coordinates \f$ [T_x,T_y,\theta] \f$ - static Pose2 Expmap(const Vector3& xi, ChartJacobian H = boost::none); + GTSAM_EXPORT static Pose2 Expmap(const Vector3& xi, ChartJacobian H = boost::none); ///Log map at identity - return the canonical coordinates \f$ [T_x,T_y,\theta] \f$ of this rotation - static Vector3 Logmap(const Pose2& p, ChartJacobian H = boost::none); + GTSAM_EXPORT static Vector3 Logmap(const Pose2& p, ChartJacobian H = boost::none); /** * Calculate Adjoint map * Ad_pose is 3*3 matrix that when applied to twist xi \f$ [T_x,T_y,\theta] \f$, returns Ad_pose(xi) */ - Matrix3 AdjointMap() const; + GTSAM_EXPORT Matrix3 AdjointMap() const; /// Apply AdjointMap to twist xi inline Vector3 Adjoint(const Vector3& xi) const { @@ -141,7 +141,7 @@ class GTSAM_EXPORT Pose2: public LieGroup { /** * Compute the [ad(w,v)] operator for SE2 as in [Kobilarov09siggraph], pg 19 */ - static Matrix3 adjointMap(const Vector3& v); + GTSAM_EXPORT static Matrix3 adjointMap(const Vector3& v); /** * Action of the adjointMap on a Lie-algebra vector y, with optional derivatives @@ -177,15 +177,15 @@ class GTSAM_EXPORT Pose2: public LieGroup { } /// Derivative of Expmap - static Matrix3 ExpmapDerivative(const Vector3& v); + GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& v); /// Derivative of Logmap - static Matrix3 LogmapDerivative(const Pose2& v); + GTSAM_EXPORT static Matrix3 LogmapDerivative(const Pose2& v); // Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP struct ChartAtOrigin { - static Pose2 Retract(const Vector3& v, ChartJacobian H = boost::none); - static Vector3 Local(const Pose2& r, ChartJacobian H = boost::none); + GTSAM_EXPORT static Pose2 Retract(const Vector3& v, ChartJacobian H = boost::none); + GTSAM_EXPORT static Vector3 Local(const Pose2& r, ChartJacobian H = boost::none); }; using LieGroup::inverse; // version with derivative @@ -195,12 +195,12 @@ class GTSAM_EXPORT Pose2: public LieGroup { /// @{ /** Return point coordinates in pose coordinate frame */ - Point2 transformTo(const Point2& point, + GTSAM_EXPORT Point2 transformTo(const Point2& point, OptionalJacobian<2, 3> Dpose = boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const; /** Return point coordinates in global frame */ - Point2 transformFrom(const Point2& point, + GTSAM_EXPORT Point2 transformFrom(const Point2& point, OptionalJacobian<2, 3> Dpose = boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const; @@ -233,14 +233,14 @@ class GTSAM_EXPORT Pose2: public LieGroup { inline const Rot2& rotation() const { return r_; } //// return transformation matrix - Matrix3 matrix() const; + GTSAM_EXPORT Matrix3 matrix() const; /** * Calculate bearing to a landmark * @param point 2D location of landmark * @return 2D rotation \f$ \in SO(2) \f$ */ - Rot2 bearing(const Point2& point, + GTSAM_EXPORT Rot2 bearing(const Point2& point, OptionalJacobian<1, 3> H1=boost::none, OptionalJacobian<1, 2> H2=boost::none) const; /** @@ -248,7 +248,7 @@ class GTSAM_EXPORT Pose2: public LieGroup { * @param point SO(2) location of other pose * @return 2D rotation \f$ \in SO(2) \f$ */ - Rot2 bearing(const Pose2& pose, + GTSAM_EXPORT Rot2 bearing(const Pose2& pose, OptionalJacobian<1, 3> H1=boost::none, OptionalJacobian<1, 3> H2=boost::none) const; /** @@ -256,7 +256,7 @@ class GTSAM_EXPORT Pose2: public LieGroup { * @param point 2D location of landmark * @return range (double) */ - double range(const Point2& point, + GTSAM_EXPORT double range(const Point2& point, OptionalJacobian<1, 3> H1=boost::none, OptionalJacobian<1, 2> H2=boost::none) const; @@ -265,7 +265,7 @@ class GTSAM_EXPORT Pose2: public LieGroup { * @param point 2D location of other pose * @return range (double) */ - double range(const Pose2& point, + GTSAM_EXPORT double range(const Pose2& point, OptionalJacobian<1, 3> H1=boost::none, OptionalJacobian<1, 3> H2=boost::none) const; diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index 3b27d45c51..a4f6861cc5 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -62,13 +62,13 @@ class SO3: public Matrix3, public LieGroup { } /// Static, named constructor TODO think about relation with above - static SO3 AxisAngle(const Vector3& axis, double theta); + GTSAM_EXPORT static SO3 AxisAngle(const Vector3& axis, double theta); /// @} /// @name Testable /// @{ - void print(const std::string& s) const; + GTSAM_EXPORT void print(const std::string& s) const; bool equals(const SO3 & R, double tol) const { return equal_with_abs_tol(*this, R, tol); @@ -96,19 +96,19 @@ class SO3: public Matrix3, public LieGroup { * Exponential map at identity - create a rotation from canonical coordinates * \f$ [R_x,R_y,R_z] \f$ using Rodrigues' formula */ - static SO3 Expmap(const Vector3& omega, ChartJacobian H = boost::none); + GTSAM_EXPORT static SO3 Expmap(const Vector3& omega, ChartJacobian H = boost::none); /// Derivative of Expmap - static Matrix3 ExpmapDerivative(const Vector3& omega); + GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& omega); /** * Log map at identity - returns the canonical coordinates * \f$ [R_x,R_y,R_z] \f$ of this rotation */ - static Vector3 Logmap(const SO3& R, ChartJacobian H = boost::none); + GTSAM_EXPORT static Vector3 Logmap(const SO3& R, ChartJacobian H = boost::none); /// Derivative of Logmap - static Matrix3 LogmapDerivative(const Vector3& omega); + GTSAM_EXPORT static Matrix3 LogmapDerivative(const Vector3& omega); Matrix3 AdjointMap() const { return *this; diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index f5f824d059..1982b8f505 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -206,7 +206,7 @@ TEST( CalibratedCamera, DBackprojectFromCamera) static Point3 backproject(const Pose3& pose, const Point2& point, const double& depth) { return CalibratedCamera(pose).backproject(point, depth); } -TEST( PinholePose, Dbackproject) +TEST( PinholePose, DbackprojectCalibCamera) { Matrix36 Dpose; Matrix31 Ddepth; diff --git a/gtsam/geometry/tests/testPinholePose.cpp b/gtsam/geometry/tests/testPinholePose.cpp index 05d48f4ccd..1cf2f4a3fd 100644 --- a/gtsam/geometry/tests/testPinholePose.cpp +++ b/gtsam/geometry/tests/testPinholePose.cpp @@ -58,6 +58,7 @@ TEST( PinholePose, constructor) } //****************************************************************************** +/* Already in testPinholeCamera??? TEST(PinholeCamera, Pose) { Matrix actualH; @@ -69,6 +70,7 @@ TEST(PinholeCamera, Pose) { Matrix numericalH = numericalDerivative11(f,camera); EXPECT(assert_equal(numericalH, actualH, 1e-9)); } +*/ /* ************************************************************************* */ TEST( PinholePose, lookat) @@ -207,7 +209,7 @@ static Point3 backproject(const Pose3& pose, const Cal3_S2& cal, return Camera(pose, cal.vector()).backproject(p, depth); } -TEST( PinholePose, Dbackproject) +TEST( PinholePose, DbackprojectRegCamera) { Matrix36 Dpose; Matrix31 Ddepth; diff --git a/gtsam/geometry/tests/testQuaternion.cpp b/gtsam/geometry/tests/testQuaternion.cpp index 843dc6cc18..e862b94adf 100644 --- a/gtsam/geometry/tests/testQuaternion.cpp +++ b/gtsam/geometry/tests/testQuaternion.cpp @@ -81,13 +81,14 @@ TEST(Quaternion , Compose) { } //****************************************************************************** -Vector3 z_axis(0, 0, 1); -Q id(Eigen::AngleAxisd(0, z_axis)); -Q R1(Eigen::AngleAxisd(1, z_axis)); +Vector3 Q_z_axis(0, 0, 1); +Q id(Eigen::AngleAxisd(0, Q_z_axis)); +Q R1(Eigen::AngleAxisd(1, Q_z_axis)); Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0))); //****************************************************************************** TEST(Quaternion , Between) { + Vector3 z_axis(0, 0, 1); Q q1(Eigen::AngleAxisd(0.2, z_axis)); Q q2(Eigen::AngleAxisd(0.1, z_axis)); @@ -98,6 +99,7 @@ TEST(Quaternion , Between) { //****************************************************************************** TEST(Quaternion , Inverse) { + Vector3 z_axis(0, 0, 1); Q q1(Eigen::AngleAxisd(0.1, z_axis)); Q expected(Eigen::AngleAxisd(-0.1, z_axis)); diff --git a/gtsam/inference/tests/testKey.cpp b/gtsam/inference/tests/testKey.cpp index fcdb5709b0..a602585814 100644 --- a/gtsam/inference/tests/testKey.cpp +++ b/gtsam/inference/tests/testKey.cpp @@ -76,7 +76,7 @@ TEST(Key, ChrTest) { /* ************************************************************************* */ // A custom (nonsensical) formatter. -string myFormatter(Key key) { +string keyMyFormatter(Key key) { return "special"; } @@ -91,7 +91,7 @@ TEST(Key, Formatting) { // use key_formatter with a function pointer stringstream ss2; - ss2 << key_formatter(myFormatter) << StreamedKey(key); + ss2 << key_formatter(keyMyFormatter) << StreamedKey(key); EXPECT("special" == ss2.str()); // use key_formatter with a function object. diff --git a/gtsam/inference/tests/testLabeledSymbol.cpp b/gtsam/inference/tests/testLabeledSymbol.cpp index 2a56b39c21..4ac171c73d 100644 --- a/gtsam/inference/tests/testLabeledSymbol.cpp +++ b/gtsam/inference/tests/testLabeledSymbol.cpp @@ -81,7 +81,7 @@ TEST(LabeledSymbol, ChrTest) { /* ************************************************************************* */ // A custom (nonsensical) formatter. -string myFormatter(Key key) { +string labeledSymbolMyFormatter(Key key) { return "special"; } @@ -90,7 +90,7 @@ TEST(LabeledSymbol, Formatting) { // use key_formatter with a function pointer stringstream ss2; - ss2 << key_formatter(myFormatter) << symbol; + ss2 << key_formatter(labeledSymbolMyFormatter) << symbol; EXPECT("special" == ss2.str()); // use key_formatter with a function object. diff --git a/gtsam/inference/tests/testSymbol.cpp b/gtsam/inference/tests/testSymbol.cpp index 43a0e219a1..bedd690441 100644 --- a/gtsam/inference/tests/testSymbol.cpp +++ b/gtsam/inference/tests/testSymbol.cpp @@ -23,7 +23,7 @@ using namespace gtsam; /* ************************************************************************* */ // A custom (nonsensical) formatter. -string myFormatter(Key key) { +string symbolMyFormatter(Key key) { return "special"; } @@ -32,7 +32,7 @@ TEST(Symbol, Formatting) { // use key_formatter with a function pointer stringstream ss2; - ss2 << key_formatter(myFormatter) << symbol; + ss2 << key_formatter(symbolMyFormatter) << symbol; EXPECT("special" == ss2.str()); // use key_formatter with a function object. diff --git a/gtsam_unstable/geometry/Event.h b/gtsam_unstable/geometry/Event.h index d9bacd106c..b221641175 100644 --- a/gtsam_unstable/geometry/Event.h +++ b/gtsam_unstable/geometry/Event.h @@ -60,10 +60,10 @@ class Event { } /** print with optional string */ - void print(const std::string& s = "") const; + GTSAM_EXPORT void print(const std::string& s = "") const; /** equals with an tolerance */ - bool equals(const Event& other, double tol = 1e-9) const; + GTSAM_EXPORT bool equals(const Event& other, double tol = 1e-9) const; /// Updates a with tangent space delta inline Event retract(const Vector4& v) const { @@ -94,6 +94,6 @@ class Event { // Define GTSAM traits template<> -struct GTSAM_EXPORT traits : internal::Manifold {}; +struct traits : internal::Manifold {}; } //\ namespace gtsam diff --git a/gtsam_unstable/geometry/Similarity3.h b/gtsam_unstable/geometry/Similarity3.h index f7ba53d874..a3d80c1d00 100644 --- a/gtsam_unstable/geometry/Similarity3.h +++ b/gtsam_unstable/geometry/Similarity3.h @@ -49,32 +49,32 @@ class Similarity3: public LieGroup { /// @{ /// Default constructor - Similarity3(); + GTSAM_EXPORT Similarity3(); /// Construct pure scaling - Similarity3(double s); + GTSAM_EXPORT Similarity3(double s); /// Construct from GTSAM types - Similarity3(const Rot3& R, const Point3& t, double s); + GTSAM_EXPORT Similarity3(const Rot3& R, const Point3& t, double s); /// Construct from Eigen types - Similarity3(const Matrix3& R, const Vector3& t, double s); + GTSAM_EXPORT Similarity3(const Matrix3& R, const Vector3& t, double s); /// Construct from matrix [R t; 0 s^-1] - Similarity3(const Matrix4& T); + GTSAM_EXPORT Similarity3(const Matrix4& T); /// @} /// @name Testable /// @{ /// Compare with tolerance - bool equals(const Similarity3& sim, double tol) const; + GTSAM_EXPORT bool equals(const Similarity3& sim, double tol) const; /// Exact equality - bool operator==(const Similarity3& other) const; + GTSAM_EXPORT bool operator==(const Similarity3& other) const; /// Print with optional string - void print(const std::string& s) const; + GTSAM_EXPORT void print(const std::string& s) const; GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity3& p); @@ -83,25 +83,25 @@ class Similarity3: public LieGroup { /// @{ /// Return an identity transform - static Similarity3 identity(); + GTSAM_EXPORT static Similarity3 identity(); /// Composition - Similarity3 operator*(const Similarity3& T) const; + GTSAM_EXPORT Similarity3 operator*(const Similarity3& T) const; /// Return the inverse - Similarity3 inverse() const; + GTSAM_EXPORT Similarity3 inverse() const; /// @} /// @name Group action on Point3 /// @{ /// Action on a point p is s*(R*p+t) - Point3 transformFrom(const Point3& p, // + GTSAM_EXPORT Point3 transformFrom(const Point3& p, // OptionalJacobian<3, 7> H1 = boost::none, // OptionalJacobian<3, 3> H2 = boost::none) const; /** syntactic sugar for transformFrom */ - Point3 operator*(const Point3& p) const; + GTSAM_EXPORT Point3 operator*(const Point3& p) const; /// @} /// @name Lie Group @@ -110,12 +110,12 @@ class Similarity3: public LieGroup { /** Log map at the identity * \f$ [R_x,R_y,R_z, t_x, t_y, t_z, \lambda] \f$ */ - static Vector7 Logmap(const Similarity3& s, // + GTSAM_EXPORT static Vector7 Logmap(const Similarity3& s, // OptionalJacobian<7, 7> Hm = boost::none); /** Exponential map at the identity */ - static Similarity3 Expmap(const Vector7& v, // + GTSAM_EXPORT static Similarity3 Expmap(const Vector7& v, // OptionalJacobian<7, 7> Hm = boost::none); /// Chart at the origin @@ -136,17 +136,17 @@ class Similarity3: public LieGroup { * @return 4*4 element of Lie algebra that can be exponentiated * TODO(frank): rename to Hat, make part of traits */ - static Matrix4 wedge(const Vector7& xi); + GTSAM_EXPORT static Matrix4 wedge(const Vector7& xi); /// Project from one tangent space to another - Matrix7 AdjointMap() const; + GTSAM_EXPORT Matrix7 AdjointMap() const; /// @} /// @name Standard interface /// @{ /// Calculate 4*4 matrix group equivalent - const Matrix4 matrix() const; + GTSAM_EXPORT const Matrix4 matrix() const; /// Return a GTSAM rotation const Rot3& rotation() const { @@ -165,7 +165,7 @@ class Similarity3: public LieGroup { /// 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. - operator Pose3() const; + GTSAM_EXPORT operator Pose3() const; /// Dimensionality of tangent space = 7 DOF - used to autodetect sizes inline static size_t Dim() { diff --git a/timing/timeGaussianFactorGraph.cpp b/timing/timeGaussianFactorGraph.cpp index 1efdb95427..3258edb493 100644 --- a/timing/timeGaussianFactorGraph.cpp +++ b/timing/timeGaussianFactorGraph.cpp @@ -153,13 +153,13 @@ TEST(timeGaussianFactorGraph, linearTime) // Switch to 100*100 grid = 10K poses // 1879: 15.6498 15.3851 15.5279 -int size = 100; +int grid_size = 100; /* ************************************************************************* */ TEST(timeGaussianFactorGraph, planar_old) { cout << "Timing planar - original version" << endl; - double time = timePlanarSmoother(size); + double time = timePlanarSmoother(grid_size); cout << "timeGaussianFactorGraph : " << time << endl; //DOUBLES_EQUAL(5.97,time,0.1); } @@ -168,7 +168,7 @@ TEST(timeGaussianFactorGraph, planar_old) TEST(timeGaussianFactorGraph, planar_new) { cout << "Timing planar - new version" << endl; - double time = timePlanarSmoother(size, false); + double time = timePlanarSmoother(grid_size, false); cout << "timeGaussianFactorGraph : " << time << endl; //DOUBLES_EQUAL(5.97,time,0.1); } @@ -177,7 +177,7 @@ TEST(timeGaussianFactorGraph, planar_new) TEST(timeGaussianFactorGraph, planar_eliminate_old) { cout << "Timing planar Eliminate - original version" << endl; - double time = timePlanarSmootherEliminate(size); + double time = timePlanarSmootherEliminate(grid_size); cout << "timeGaussianFactorGraph : " << time << endl; //DOUBLES_EQUAL(5.97,time,0.1); } @@ -186,7 +186,7 @@ TEST(timeGaussianFactorGraph, planar_eliminate_old) TEST(timeGaussianFactorGraph, planar_eliminate_new) { cout << "Timing planar Eliminate - new version" << endl; - double time = timePlanarSmootherEliminate(size, false); + double time = timePlanarSmootherEliminate(grid_size, false); cout << "timeGaussianFactorGraph : " << time << endl; //DOUBLES_EQUAL(5.97,time,0.1); }