Added document explaining GTSAM_EXPORT usage rules
parent
ffb3043284
commit
e28fb84fef
|
@ -0,0 +1,41 @@
|
|||
# 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 defined 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 defined 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<char,struct std::char_traits<char>,class std::allocator<char> > 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<class gtsam::SO3>::Print(class gtsam::SO3 const &,class std::basic_string<char,struct std::char_traits<char>,class std::allocator<char> > 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
|
||||
```
|
||||
|
||||
Sorry for the long error message there, but I want to quickly decode it to help understand what is going on. 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::Testabl<class gtsam::SO3>::Print (...)`. Note that this error did _not_ occur when compiling the library that actually has SO3 inside of it.
|
||||
|
||||
## But Why?
|
||||
To me, the behavior of GTSAM_EXPORT was very baffling. However, I believe it can be explained by understanding the rules that MSVC operates under.
|
||||
|
||||
First, we need to understand exactly what `GTSAM_EXPORT` does. When you use `GTSAM_EXPORT` on a function (or class) definition, it actually does two things. First, when you are building the library, it turns into a "dllexport" command, telling the compiler that this function should go into the DLL and be visible externally. When you pull in that same header for a different library, it switches to a "dllimport" command, telling the compiler 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 defined 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.
|
||||
|
||||
This leads to another compiler rule that finishes explaining the usage rules proposed above.
|
||||
|
||||
***Compiler Rule #3*** If a class is defined with `GTSAM_EXPORT`, then any classes it inherits from must be definable with a dllexport command as well.
|
||||
|
||||
One of the most immediate results of this compiler rule is that any class that inherits from an Eigen class _cannot_ be defined with `GTSAM_EXPORT`. Because Eigen is a header-only class, compiler rule #2 prohibits any Eigen class from being defined with a "dllexport" command. Therefore, no Eigen inherited classes can use `GTSAM_EXPORT` either. (Note that individual functions with an inherited class can be "exported." Just not the entire class.)
|
||||
|
||||
## 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, I have been able to get all of the libraries, together with their test and wrapping libraries, to compile/link successfully.
|
|
@ -62,13 +62,13 @@ public:
|
|||
}
|
||||
|
||||
/// 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 @@ public:
|
|||
* 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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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<Pose3,Camera>(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;
|
||||
|
|
|
@ -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));
|
||||
|
||||
|
|
|
@ -60,10 +60,10 @@ public:
|
|||
}
|
||||
|
||||
/** 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 @@ public:
|
|||
|
||||
// Define GTSAM traits
|
||||
template<>
|
||||
struct GTSAM_EXPORT traits<Event> : internal::Manifold<Event> {};
|
||||
struct traits<Event> : internal::Manifold<Event> {};
|
||||
|
||||
} //\ namespace gtsam
|
||||
|
|
|
@ -49,32 +49,32 @@ public:
|
|||
/// @{
|
||||
|
||||
/// 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 @@ public:
|
|||
/// @{
|
||||
|
||||
/// 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 @@ public:
|
|||
/** 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 @@ public:
|
|||
* @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 @@ 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.
|
||||
operator Pose3() const;
|
||||
GTSAM_EXPORT operator Pose3() const;
|
||||
|
||||
/// Dimensionality of tangent space = 7 DOF - used to autodetect sizes
|
||||
inline static size_t Dim() {
|
||||
|
|
Loading…
Reference in New Issue