Merged in fix/msvc2017 (pull request #332)

Fixed several issues on Windows. Even with this PR merged, I know there are still some problems, especially with doubly linked symbols, but I think this issue is only there for certain targets. I can definitely compile and run some of the examples using this branch, however, whereas before I could not. In addition, it does not affect compilation on Ubuntu or Mac.
release/4.3a0
Frank Dellaert 2018-11-16 17:15:02 +00:00
commit 478c8605c2
13 changed files with 94 additions and 71 deletions

View File

@ -111,17 +111,19 @@ set(CPACK_GENERATOR "TGZ" CACHE STRING "CPack Default Binary Generator")
# BOOST_ROOT: path to install prefix for boost
# Boost_NO_SYSTEM_PATHS: set to true to keep the find script from ignoring BOOST_ROOT
# If using Boost shared libs, disable auto linking
if(MSVC)
# Some libraries, at least Boost Program Options, rely on this to export DLL symbols
# Disable autolinking
# By default, boost only builds static libraries on windows
set(Boost_USE_STATIC_LIBS ON) # only find static libs
# If we ever reset above on windows and, ...
# If we use Boost shared libs, disable auto linking.
# Some libraries, at least Boost Program Options, rely on this to export DLL symbols.
if(NOT Boost_USE_STATIC_LIBS)
add_definitions(-DBOOST_ALL_NO_LIB)
add_definitions(-DBOOST_ALL_DYN_LINK)
endif()
endif()
find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time timer chrono)
find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time timer chrono regex)
# Required components
if(NOT Boost_SERIALIZATION_LIBRARY OR NOT Boost_SYSTEM_LIBRARY OR NOT Boost_FILESYSTEM_LIBRARY OR
@ -133,7 +135,7 @@ option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF)
# Allow for not using the timer libraries on boost < 1.48 (GTSAM timing code falls back to old timer library)
set(GTSAM_BOOST_LIBRARIES
${Boost_SERIALIZATION_LIBRARY} ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY}
${Boost_THREAD_LIBRARY} ${Boost_DATE_TIME_LIBRARY})
${Boost_THREAD_LIBRARY} ${Boost_DATE_TIME_LIBRARY} ${Boost_REGEX_LIBRARY})
if (GTSAM_DISABLE_NEW_TIMERS)
message("WARNING: GTSAM timing instrumentation manually disabled")
add_definitions(-DGTSAM_DISABLE_NEW_TIMERS)
@ -256,6 +258,14 @@ else()
endif()
if (MSVC)
if (NOT GTSAM_BUILD_STATIC_LIBRARY)
# mute eigen static assert to avoid errors in shared lib
add_definitions(-DEIGEN_NO_STATIC_ASSERT)
endif()
add_definitions(/wd4244) # Disable loss of precision which is thrown all over our Eigen
endif()
###############################################################################
# Global compile options
@ -321,6 +331,7 @@ include_directories(BEFORE
if(MSVC)
add_definitions(-D_CRT_SECURE_NO_WARNINGS -D_SCL_SECURE_NO_WARNINGS)
add_definitions(/wd4251 /wd4275 /wd4251 /wd4661 /wd4344 /wd4503) # Disable non-DLL-exported base class and other warnings
add_definitions(/bigobj) # Allow large object files for template-based code
endif()
# GCC 4.8+ complains about local typedefs which we use for shared_ptr etc.

View File

@ -26,21 +26,27 @@
// class __declspec(dllexport) MyClass { ... };
// When included while compiling other code against GTSAM:
// class __declspec(dllimport) MyClass { ... };
#pragma once
// Whether GTSAM is compiled as static or DLL in windows.
// This will be used to decide whether include __declspec(dllimport) or not in headers
#cmakedefine GTSAM_BUILD_STATIC_LIBRARY
#ifdef _WIN32
# ifdef @library_name@_EXPORTS
# define @library_name@_EXPORT __declspec(dllexport)
# define @library_name@_EXTERN_EXPORT __declspec(dllexport) extern
# ifdef @library_name@_BUILD_STATIC_LIBRARY
# define @library_name@_EXPORT
# define @library_name@_EXTERN_EXPORT extern
# else
# ifndef @library_name@_IMPORT_STATIC
# ifdef @library_name@_EXPORTS
# define @library_name@_EXPORT __declspec(dllexport)
# define @library_name@_EXTERN_EXPORT __declspec(dllexport) extern
# else
# define @library_name@_EXPORT __declspec(dllimport)
# define @library_name@_EXTERN_EXPORT __declspec(dllimport)
# else /* @library_name@_IMPORT_STATIC */
# define @library_name@_EXPORT
# define @library_name@_EXTERN_EXPORT extern
# endif /* @library_name@_IMPORT_STATIC */
# endif /* @library_name@_EXPORTS */
#else /* _WIN32 */
# endif
# endif
#else
# define @library_name@_EXPORT
# define @library_name@_EXTERN_EXPORT extern
#endif

View File

@ -167,10 +167,10 @@ public:
// implicit assignment operator for (const GenericValue& rhs) works fine here
/// Assignment operator, protected because only the Value or DERIVED
/// assignment operators should be used.
// DerivedValue<DERIVED>& operator=(const DerivedValue<DERIVED>& rhs) {
// // Nothing to do, do not call base class assignment operator
// return *this;
// }
GenericValue<T>& operator=(const GenericValue<T>& rhs) {
// Nothing to do, do not call base class assignment operator
return *this;
}
private:
@ -187,13 +187,18 @@ public:
ar & boost::serialization::make_nvp("GenericValue",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("value", value_);
}
}
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
};
/// use this macro instead of BOOST_CLASS_EXPORT for GenericValues
#define GTSAM_VALUE_EXPORT(Type) BOOST_CLASS_EXPORT(gtsam::GenericValue<Type>)
};
// traits
template <typename ValueType>
struct traits<GenericValue<ValueType> >

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */
/*
* @file chartTesting.h
* @brief
* @file testLie.h
* @brief Test utilities for Lie groups
* @date November, 2014
* @author Paul Furgale
*/

View File

@ -87,17 +87,19 @@ bool DiscreteConditional::equals(const DiscreteFactor& other,
Potentials::ADT DiscreteConditional::choose(const Values& parentsValues) const {
ADT pFS(*this);
Key j; size_t value;
for(Key key: parents())
try {
j = (key);
value = parentsValues.at(j);
pFS = pFS.choose(j, value);
} catch (exception&) {
cout << "Key: " << j << " Value: " << value << endl;
parentsValues.print("parentsValues: ");
// pFS.print("pFS: ");
throw runtime_error("DiscreteConditional::choose: parent value missing");
};
for(Key key: parents()) {
try {
j = (key);
value = parentsValues.at(j);
pFS = pFS.choose(j, value);
} catch (exception&) {
cout << "Key: " << j << " Value: " << value << endl;
parentsValues.print("parentsValues: ");
// pFS.print("pFS: ");
throw runtime_error("DiscreteConditional::choose: parent value missing");
};
}
return pFS;
}

View File

@ -211,11 +211,11 @@ public:
bool diagonalDamping = false) {
if (E.cols() == 2) {
Matrix2 P2;
ComputePointCovariance(P2, E, lambda, diagonalDamping);
ComputePointCovariance<2>(P2, E, lambda, diagonalDamping);
return P2;
} else {
Matrix3 P3;
ComputePointCovariance(P3, E, lambda, diagonalDamping);
ComputePointCovariance<3>(P3, E, lambda, diagonalDamping);
return P3;
}
}
@ -229,12 +229,12 @@ public:
bool diagonalDamping = false) {
if (E.cols() == 2) {
Matrix2 P;
ComputePointCovariance(P, E, lambda, diagonalDamping);
return SchurComplement(Fblocks, E, P, b);
ComputePointCovariance<2>(P, E, lambda, diagonalDamping);
return SchurComplement<2>(Fblocks, E, P, b);
} else {
Matrix3 P;
ComputePointCovariance(P, E, lambda, diagonalDamping);
return SchurComplement(Fblocks, E, P, b);
ComputePointCovariance<3>(P, E, lambda, diagonalDamping);
return SchurComplement<3>(Fblocks, E, P, b);
}
}

View File

@ -89,17 +89,17 @@ TEST(CameraSet, Pinhole) {
Vector4 b = actualV;
Vector v = Ft * (b - E * P * Et * b);
schur << Ft * F - Ft * E * P * Et * F, v, v.transpose(), 30;
SymmetricBlockMatrix actualReduced = Set::SchurComplement(Fs, E, P, b);
SymmetricBlockMatrix actualReduced = Set::SchurComplement<3>(Fs, E, P, b);
EXPECT(assert_equal(schur, actualReduced.selfadjointView()));
// Check Schur complement update, same order, should just double
KeyVector allKeys {1, 2}, keys {1, 2};
Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys, actualReduced);
Set::UpdateSchurComplement<3>(Fs, E, P, b, allKeys, keys, actualReduced);
EXPECT(assert_equal((Matrix )(2.0 * schur), actualReduced.selfadjointView()));
// Check Schur complement update, keys reversed
KeyVector keys2 {2, 1};
Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys2, actualReduced);
Set::UpdateSchurComplement<3>(Fs, E, P, b, allKeys, keys2, actualReduced);
Vector4 reverse_b;
reverse_b << b.tail<2>(), b.head<2>();
Vector reverse_v = Ft * (reverse_b - E * P * Et * reverse_b);

View File

@ -120,8 +120,6 @@ TEST(OrientedPlane3, localCoordinates_retract) {
maxXiLimit << M_PI, M_PI, 10.0;
for (size_t i = 0; i < numIterations; i++) {
sleep(0);
// Create a Plane
OrientedPlane3 p1(randomVector(minPlaneLimit, maxPlaneLimit));
Vector v12 = randomVector(minXiLimit, maxXiLimit);

View File

@ -11,8 +11,10 @@
/**
* @file Ordering.h
* @brief Variable ordering for the elimination algorithm
* @author Richard Roberts
* @author Andrew Melim
* @author Frank Dellaert
* @date Sep 2, 2010
*/
@ -21,7 +23,6 @@
#include <gtsam/inference/Key.h>
#include <gtsam/inference/VariableIndex.h>
#include <gtsam/inference/MetisIndex.h>
#include <gtsam/inference/FactorGraph.h>
#include <gtsam/base/FastSet.h>
#include <boost/assign/list_inserter.hpp>
@ -77,8 +78,8 @@ public:
/// Compute a fill-reducing ordering using COLAMD from a factor graph (see details for note on
/// performance). This internally builds a VariableIndex so if you already have a VariableIndex,
/// it is faster to use COLAMD(const VariableIndex&)
template<class FACTOR>
static Ordering Colamd(const FactorGraph<FACTOR>& graph) {
template<class FACTOR_GRAPH>
static Ordering Colamd(const FACTOR_GRAPH& graph) {
if (graph.empty())
return Ordering();
else
@ -96,8 +97,8 @@ public:
/// constrainLast will be ordered in the same order specified in the KeyVector \c
/// constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be
/// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well.
template<class FACTOR>
static Ordering ColamdConstrainedLast(const FactorGraph<FACTOR>& graph,
template<class FACTOR_GRAPH>
static Ordering ColamdConstrainedLast(const FACTOR_GRAPH& graph,
const KeyVector& constrainLast, bool forceOrder = false) {
if (graph.empty())
return Ordering();
@ -123,8 +124,8 @@ public:
/// constrainFirst will be ordered in the same order specified in the KeyVector \c
/// constrainFirst. If \c forceOrder is false, the variables in \c constrainFirst will be
/// ordered before all the others, but will be rearranged by CCOLAMD to reduce fill-in as well.
template<class FACTOR>
static Ordering ColamdConstrainedFirst(const FactorGraph<FACTOR>& graph,
template<class FACTOR_GRAPH>
static Ordering ColamdConstrainedFirst(const FACTOR_GRAPH& graph,
const KeyVector& constrainFirst, bool forceOrder = false) {
if (graph.empty())
return Ordering();
@ -152,8 +153,8 @@ public:
/// arbitrary order. Any variables not present in \c groups will be assigned to group 0. This
/// function simply fills the \c cmember argument to CCOLAMD with the supplied indices, see the
/// CCOLAMD documentation for more information.
template<class FACTOR>
static Ordering ColamdConstrained(const FactorGraph<FACTOR>& graph,
template<class FACTOR_GRAPH>
static Ordering ColamdConstrained(const FACTOR_GRAPH& graph,
const FastMap<Key, int>& groups) {
if (graph.empty())
return Ordering();
@ -172,8 +173,8 @@ public:
const VariableIndex& variableIndex, const FastMap<Key, int>& groups);
/// Return a natural Ordering. Typically used by iterative solvers
template<class FACTOR>
static Ordering Natural(const FactorGraph<FACTOR> &fg) {
template<class FACTOR_GRAPH>
static Ordering Natural(const FACTOR_GRAPH &fg) {
KeySet src = fg.keys();
KeyVector keys(src.begin(), src.end());
std::stable_sort(keys.begin(), keys.end());
@ -181,15 +182,15 @@ public:
}
/// METIS Formatting function
template<class FACTOR>
template<class FACTOR_GRAPH>
static GTSAM_EXPORT void CSRFormat(std::vector<int>& xadj,
std::vector<int>& adj, const FactorGraph<FACTOR>& graph);
std::vector<int>& adj, const FACTOR_GRAPH& graph);
/// Compute an ordering determined by METIS from a VariableIndex
static GTSAM_EXPORT Ordering Metis(const MetisIndex& met);
template<class FACTOR>
static Ordering Metis(const FactorGraph<FACTOR>& graph) {
template<class FACTOR_GRAPH>
static Ordering Metis(const FACTOR_GRAPH& graph) {
return Metis(MetisIndex(graph));
}
@ -197,9 +198,9 @@ public:
/// @name Named Constructors @{
template<class FACTOR>
template<class FACTOR_GRAPH>
static Ordering Create(OrderingType orderingType,
const FactorGraph<FACTOR>& graph) {
const FACTOR_GRAPH& graph) {
if (graph.empty())
return Ordering();

View File

@ -486,7 +486,7 @@ boost::shared_ptr<GaussianConditional> HessianFactor::eliminateCholesky(const Or
// Erase the eliminated keys in this factor
keys_.erase(begin(), begin() + nFrontals);
} catch (const CholeskyFailed& e) {
} catch (const CholeskyFailed&) {
throw IndeterminantLinearSystemException(keys.front());
}

View File

@ -148,7 +148,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear,
// ============ Solve is where most computation happens !! =================
delta = solve(dampedSystem, params_);
systemSolvedSuccessfully = true;
} catch (const IndeterminantLinearSystemException& e) {
} catch (const IndeterminantLinearSystemException&) {
systemSolvedSuccessfully = false;
}

View File

@ -147,7 +147,7 @@ struct LevenbergMarquardtState : public NonlinearOptimizerState {
CachedModel* item = getCachedModel(dim);
item->A.diagonal() = sqrtHessianDiagonal.at(key); // use diag(hessian)
damped += boost::make_shared<JacobianFactor>(key, item->A, item->b, item->model);
} catch (const std::out_of_range& e) {
} catch (const std::out_of_range&) {
continue; // Don't attempt any damping if no key found in diagonal
}
}

View File

@ -18,7 +18,10 @@
#pragma once
// All headers in base:
// All headers in base, except:
// treeTraversal-inst.h: very specific to only a few compilation units
// numericalDerivative.h : includes things in linear, nonlinear :-(
// testLie.h: includes numericalDerivative
#include <gtsam/base/Lie.h>
#include <gtsam/base/chartTesting.h>
#include <gtsam/base/cholesky.h>
@ -38,7 +41,6 @@
#include <gtsam/base/lieProxies.h>
#include <gtsam/base/Manifold.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/numericalDerivative.h>
#include <gtsam/base/OptionalJacobian.h>
#include <gtsam/base/ProductLieGroup.h>
#include <gtsam/base/serialization.h>
@ -46,10 +48,8 @@
#include <gtsam/base/SymmetricBlockMatrix.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/TestableAssertions.h>
#include <gtsam/base/testLie.h>
#include <gtsam/base/ThreadsafeException.h>
#include <gtsam/base/timing.h>
#include <gtsam/base/treeTraversal-inst.h>
#include <gtsam/base/types.h>
#include <gtsam/base/Value.h>
#include <gtsam/base/Vector.h>