Skip to content

Commit

Permalink
Merge pull request #85 from borglab/msvc-fixes
Browse files Browse the repository at this point in the history
Changes to get gtsam to compile in Windows and fix matlab builds
  • Loading branch information
jlblancoc authored Jul 19, 2019
2 parents 0c3e05f + 438b4ff commit ec04369
Show file tree
Hide file tree
Showing 52 changed files with 277 additions and 260 deletions.
36 changes: 16 additions & 20 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -179,20 +179,18 @@ option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF)
# so we downgraded this to classic filenames-based variables, and manually adding
# the target_include_directories(xxx ${Boost_INCLUDE_DIR})
set(GTSAM_BOOST_LIBRARIES
optimized
${Boost_SERIALIZATION_LIBRARY_RELEASE}
${Boost_SYSTEM_LIBRARY_RELEASE}
${Boost_FILESYSTEM_LIBRARY_RELEASE}
${Boost_THREAD_LIBRARY_RELEASE}
${Boost_DATE_TIME_LIBRARY_RELEASE}
${Boost_REGEX_LIBRARY_RELEASE}
debug
${Boost_SERIALIZATION_LIBRARY_DEBUG}
${Boost_SYSTEM_LIBRARY_DEBUG}
${Boost_FILESYSTEM_LIBRARY_DEBUG}
${Boost_THREAD_LIBRARY_DEBUG}
${Boost_DATE_TIME_LIBRARY_DEBUG}
${Boost_REGEX_LIBRARY_DEBUG}
optimized ${Boost_SERIALIZATION_LIBRARY_RELEASE}
optimized ${Boost_SYSTEM_LIBRARY_RELEASE}
optimized ${Boost_FILESYSTEM_LIBRARY_RELEASE}
optimized ${Boost_THREAD_LIBRARY_RELEASE}
optimized ${Boost_DATE_TIME_LIBRARY_RELEASE}
optimized ${Boost_REGEX_LIBRARY_RELEASE}
debug ${Boost_SERIALIZATION_LIBRARY_DEBUG}
debug ${Boost_SYSTEM_LIBRARY_DEBUG}
debug ${Boost_FILESYSTEM_LIBRARY_DEBUG}
debug ${Boost_THREAD_LIBRARY_DEBUG}
debug ${Boost_DATE_TIME_LIBRARY_DEBUG}
debug ${Boost_REGEX_LIBRARY_DEBUG}
)
message(STATUS "GTSAM_BOOST_LIBRARIES: ${GTSAM_BOOST_LIBRARIES}")
if (GTSAM_DISABLE_NEW_TIMERS)
Expand All @@ -201,12 +199,10 @@ if (GTSAM_DISABLE_NEW_TIMERS)
else()
if(Boost_TIMER_LIBRARY)
list(APPEND GTSAM_BOOST_LIBRARIES
optimized
${Boost_TIMER_LIBRARY_RELEASE}
${Boost_CHRONO_LIBRARY_RELEASE}
debug
${Boost_TIMER_LIBRARY_DEBUG}
${Boost_CHRONO_LIBRARY_DEBUG}
optimized ${Boost_TIMER_LIBRARY_RELEASE}
optimized ${Boost_CHRONO_LIBRARY_RELEASE}
debug ${Boost_TIMER_LIBRARY_DEBUG}
debug ${Boost_CHRONO_LIBRARY_DEBUG}
)
else()
list(APPEND GTSAM_BOOST_LIBRARIES rt) # When using the header-only boost timer library, need -lrt
Expand Down
37 changes: 37 additions & 0 deletions Using-GTSAM-EXPORT.md
Original file line number Diff line number Diff line change
@@ -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<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
```

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<class gtsam::SO3>::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.
5 changes: 4 additions & 1 deletion cmake/GtsamBuildTypes.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,10 @@ set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_PROFILING "NDEBUG" CACHE STRING "(Us
set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_TIMING "NDEBUG;ENABLE_TIMING" CACHE STRING "(User editable) Private preprocessor macros for Timing configuration.")
if(MSVC)
# Common to all configurations:
list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE WINDOWS_LEAN_AND_MEAN)
list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE
WINDOWS_LEAN_AND_MEAN
NOMINMAX
)
endif()

# Other (non-preprocessor macros) compiler flags:
Expand Down
22 changes: 14 additions & 8 deletions cmake/GtsamMatlabWrap.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,11 @@ mark_as_advanced(FORCE MEX_COMMAND)
# Now that we have mex, trace back to find the Matlab installation root
get_filename_component(MEX_COMMAND "${MEX_COMMAND}" REALPATH)
get_filename_component(mex_path "${MEX_COMMAND}" PATH)
get_filename_component(MATLAB_ROOT "${mex_path}/.." ABSOLUTE)
if(mex_path MATCHES ".*/win64$")
get_filename_component(MATLAB_ROOT "${mex_path}/../.." ABSOLUTE)
else()
get_filename_component(MATLAB_ROOT "${mex_path}/.." ABSOLUTE)
endif()
set(MATLAB_ROOT "${MATLAB_ROOT}" CACHE PATH "Path to MATLAB installation root (e.g. /usr/local/MATLAB/R2012a)")


Expand Down Expand Up @@ -78,28 +82,29 @@ function(wrap_library_internal interfaceHeader linkLibraries extraIncludeDirs ex
set(mexModuleExt mexw32)
endif()
endif()

# Wrap codegen interface
#usage: wrap interfacePath moduleName toolboxPath headerPath
# interfacePath : *absolute* path to directory of module interface file
# moduleName : the name of the module, interface file must be called moduleName.h
# toolboxPath : the directory in which to generate the wrappers
# headerPath : path to matlab.h
# headerPath : path to matlab.h

# Extract module name from interface header file name
get_filename_component(interfaceHeader "${interfaceHeader}" ABSOLUTE)
get_filename_component(modulePath "${interfaceHeader}" PATH)
get_filename_component(moduleName "${interfaceHeader}" NAME_WE)

# Paths for generated files
set(generated_files_path "${PROJECT_BINARY_DIR}/wrap/${moduleName}")
set(generated_cpp_file "${generated_files_path}/${moduleName}_wrapper.cpp")
set(compiled_mex_modules_root "${PROJECT_BINARY_DIR}/wrap/${moduleName}_mex")

message(STATUS "Building wrap module ${moduleName}")

# Find matlab.h in GTSAM
if("${PROJECT_NAME}" STREQUAL "GTSAM")
if(("${PROJECT_NAME}" STREQUAL "gtsam") OR
("${PROJECT_NAME}" STREQUAL "gtsam_unstable"))
set(matlab_h_path "${PROJECT_SOURCE_DIR}")
else()
if(NOT GTSAM_INCLUDE_DIR)
Expand Down Expand Up @@ -221,6 +226,7 @@ function(wrap_library_internal interfaceHeader linkLibraries extraIncludeDirs ex
string(REPLACE ";" " " mexFlagsSpaced "${GTSAM_BUILD_MEX_BINARY_FLAGS}")
add_library(${moduleName}_matlab_wrapper MODULE ${generated_cpp_file} ${interfaceHeader} ${otherSourcesAndObjects})
target_link_libraries(${moduleName}_matlab_wrapper ${correctedOtherLibraries})
target_link_libraries(${moduleName}_matlab_wrapper ${moduleName})
set_target_properties(${moduleName}_matlab_wrapper PROPERTIES
OUTPUT_NAME "${moduleName}_wrapper"
PREFIX ""
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/Matrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,7 @@ GTSAM_EXPORT std::pair<Matrix,Matrix> 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
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/deprecated/LieMatrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
/// @{
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/deprecated/LieScalar.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 };

Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/deprecated/LieVector.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 };

Expand Down
18 changes: 9 additions & 9 deletions gtsam/base/timing.h
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
Expand Down Expand Up @@ -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<TimingOutline>&
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<TimingOutline>&
child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& 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
Expand Down
3 changes: 1 addition & 2 deletions gtsam/geometry/CalibratedCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,7 @@

namespace gtsam {

class GTSAM_EXPORT CheiralityException: public ThreadsafeException<
CheiralityException> {
class GTSAM_EXPORT CheiralityException: public ThreadsafeException<CheiralityException> {
public:
CheiralityException()
: CheiralityException(std::numeric_limits<Key>::max()) {}
Expand Down
14 changes: 7 additions & 7 deletions gtsam/geometry/EssentialMatrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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 {
Expand Down Expand Up @@ -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;

Expand All @@ -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;

/**
Expand All @@ -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;

/// @}
Expand Down
16 changes: 8 additions & 8 deletions gtsam/geometry/Point2.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Point2 : public Vector2 {
class Point2 : public Vector2 {
private:

public:
Expand Down Expand Up @@ -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
Expand All @@ -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;

/// @}
Expand Down Expand Up @@ -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<Point2> CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9);
static std::list<Point2> CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional<Point2> fh);
static std::list<Point2> CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9);
GTSAM_EXPORT static boost::optional<Point2> CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9);
GTSAM_EXPORT static std::list<Point2> CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional<Point2> fh);
GTSAM_EXPORT static std::list<Point2> CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9);
/// @}
#endif

Expand Down
Loading

0 comments on commit ec04369

Please sign in to comment.