Merge branch 'develop' into hybrid-timing
commit
0518b60c4d
|
@ -21,12 +21,13 @@ if (NOT MSVC)
|
|||
endif()
|
||||
|
||||
# Configurable Options
|
||||
option(BUILD_SHARED_LIBS "Build shared libraries" ON)
|
||||
if(GTSAM_UNSTABLE_AVAILABLE)
|
||||
option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON)
|
||||
option(GTSAM_UNSTABLE_BUILD_PYTHON "Enable/Disable Python wrapper for libgtsam_unstable" ON)
|
||||
option(GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX "Enable/Disable MATLAB wrapper for libgtsam_unstable" OFF)
|
||||
endif()
|
||||
option(GTSAM_FORCE_SHARED_LIB "Force gtsam to be a shared library, overriding BUILD_SHARED_LIBS" ON)
|
||||
option(GTSAM_FORCE_SHARED_LIB "Force gtsam to be a shared library, overriding BUILD_SHARED_LIBS" OFF)
|
||||
option(GTSAM_FORCE_STATIC_LIB "Force gtsam to be a static library, overriding BUILD_SHARED_LIBS" OFF)
|
||||
option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices. If enable, Rot3::EXPMAP is enforced by default." OFF)
|
||||
option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." ON)
|
||||
|
@ -48,7 +49,9 @@ option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration
|
|||
option(GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR "Use the slower but correct version of BetweenFactor" OFF)
|
||||
option(GTSAM_SLOW_BUT_CORRECT_EXPMAP "Use slower but correct expmap for Pose2" OFF)
|
||||
|
||||
if (GTSAM_FORCE_SHARED_LIB)
|
||||
if (GTSAM_FORCE_SHARED_LIB AND GTSAM_FORCE_STATIC_LIB)
|
||||
message(FATAL_ERROR "GTSAM_FORCE_SHARED_LIB and GTSAM_FORCE_STATIC_LIB are both true. Please, to unambiguously select the desired library type to use to build GTSAM, set one of GTSAM_FORCE_SHARED_LIB=ON, GTSAM_FORCE_STATIC_LIB=ON, or BUILD_SHARED_LIBS={ON/OFF}")
|
||||
elseif (GTSAM_FORCE_SHARED_LIB)
|
||||
message(STATUS "GTSAM is a shared library due to GTSAM_FORCE_SHARED_LIB")
|
||||
set(GTSAM_LIBRARY_TYPE SHARED CACHE STRING "" FORCE)
|
||||
set(GTSAM_SHARED_LIB 1 CACHE BOOL "" FORCE)
|
||||
|
@ -57,10 +60,9 @@ elseif (GTSAM_FORCE_STATIC_LIB)
|
|||
set(GTSAM_LIBRARY_TYPE STATIC CACHE STRING "" FORCE)
|
||||
set(GTSAM_SHARED_LIB 0 CACHE BOOL "" FORCE)
|
||||
elseif (BUILD_SHARED_LIBS)
|
||||
message(STATUS "GTSAM is a shared library due to BUILD_SHARED_LIBS is ON")
|
||||
set(GTSAM_LIBRARY_TYPE SHARED CACHE STRING "" FORCE)
|
||||
set(GTSAM_SHARED_LIB 1 CACHE BOOL "" FORCE)
|
||||
elseif((DEFINED BUILD_SHARED_LIBS) AND (NOT BUILD_SHARED_LIBS))
|
||||
elseif(NOT BUILD_SHARED_LIBS)
|
||||
message(STATUS "GTSAM is a static library due to BUILD_SHARED_LIBS is OFF")
|
||||
set(GTSAM_LIBRARY_TYPE STATIC CACHE STRING "" FORCE)
|
||||
set(GTSAM_SHARED_LIB 0 CACHE BOOL "" FORCE)
|
||||
|
|
|
@ -13,7 +13,8 @@ if(WIN32)
|
|||
set_target_properties(metis-gtsam PROPERTIES
|
||||
PREFIX ""
|
||||
COMPILE_FLAGS /w
|
||||
RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/../../../bin")
|
||||
RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/../../../bin"
|
||||
WINDOWS_EXPORT_ALL_SYMBOLS ON)
|
||||
endif()
|
||||
|
||||
if (APPLE)
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/concept_check.hpp>
|
||||
#include <boost/concept/assert.hpp>
|
||||
#include <boost/concept/requires.hpp>
|
||||
|
|
|
@ -1151,7 +1151,7 @@ TEST(Matrix, Matrix24IsVectorSpace) {
|
|||
}
|
||||
|
||||
TEST(Matrix, RowMajorIsVectorSpace) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
typedef Eigen::Matrix<double, 2, 3, Eigen::RowMajor> RowMajor;
|
||||
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowMajor>);
|
||||
#endif
|
||||
|
@ -1166,7 +1166,7 @@ TEST(Matrix, VectorIsVectorSpace) {
|
|||
}
|
||||
|
||||
TEST(Matrix, RowVectorIsVectorSpace) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
typedef Eigen::Matrix<double, 1, -1> RowVector;
|
||||
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowVector>);
|
||||
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Vector5>);
|
||||
|
|
|
@ -272,7 +272,7 @@ TEST(Vector, VectorIsVectorSpace) {
|
|||
}
|
||||
|
||||
TEST(Vector, RowVectorIsVectorSpace) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
typedef Eigen::Matrix<double,1,-1> RowVector;
|
||||
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowVector>);
|
||||
#endif
|
||||
|
|
|
@ -59,7 +59,7 @@ void TimingOutline::add(size_t usecs, size_t usecsWall) {
|
|||
TimingOutline::TimingOutline(const std::string& label, size_t id) :
|
||||
id_(id), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), myOrder_(
|
||||
0), lastChildOrder_(0), label_(label) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
timer_.stop();
|
||||
#endif
|
||||
|
@ -68,7 +68,7 @@ TimingOutline::TimingOutline(const std::string& label, size_t id) :
|
|||
|
||||
/* ************************************************************************* */
|
||||
size_t TimingOutline::time() const {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
size_t time = 0;
|
||||
bool hasChildren = false;
|
||||
for(const ChildMap::value_type& child: children_) {
|
||||
|
@ -86,7 +86,7 @@ size_t TimingOutline::time() const {
|
|||
|
||||
/* ************************************************************************* */
|
||||
void TimingOutline::print(const std::string& outline) const {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
std::string formattedLabel = label_;
|
||||
std::replace(formattedLabel.begin(), formattedLabel.end(), '_', ' ');
|
||||
std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU ("
|
||||
|
@ -157,7 +157,7 @@ void TimingOutline::printCsv(bool addLineBreak) const {
|
|||
|
||||
void TimingOutline::print2(const std::string& outline,
|
||||
const double parentTotal) const {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
const int w1 = 24, w2 = 2, w3 = 6, w4 = 8, precision = 2;
|
||||
const double selfTotal = self(), selfMean = selfTotal / double(n_);
|
||||
const double childTotal = secs();
|
||||
|
@ -202,7 +202,7 @@ void TimingOutline::print2(const std::string& outline,
|
|||
/* ************************************************************************* */
|
||||
const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
|
||||
const std::string& label, const std::weak_ptr<TimingOutline>& thisPtr) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
assert(thisPtr.lock().get() == this);
|
||||
std::shared_ptr<TimingOutline>& result = children_[child];
|
||||
if (!result) {
|
||||
|
@ -221,7 +221,7 @@ const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
|
|||
/* ************************************************************************* */
|
||||
void TimingOutline::tic() {
|
||||
// Disable this entire function if we are not using boost
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
assert(timer_.is_stopped());
|
||||
timer_.start();
|
||||
|
@ -240,7 +240,7 @@ void TimingOutline::tic() {
|
|||
/* ************************************************************************* */
|
||||
void TimingOutline::toc() {
|
||||
// Disable this entire function if we are not using boost
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
|
||||
|
@ -274,7 +274,7 @@ void TimingOutline::toc() {
|
|||
|
||||
/* ************************************************************************* */
|
||||
void TimingOutline::finishedIteration() {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
if (tIt_ > tMax_)
|
||||
tMax_ = tIt_;
|
||||
if (tMin_ == 0 || tIt_ < tMin_)
|
||||
|
@ -289,7 +289,7 @@ void TimingOutline::finishedIteration() {
|
|||
/* ************************************************************************* */
|
||||
size_t getTicTocID(const char *descriptionC) {
|
||||
// disable anything which refers to TimingOutline as well, for good measure
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
const std::string description(descriptionC);
|
||||
// Global (static) map from strings to ID numbers and current next ID number
|
||||
static size_t nextId = 0;
|
||||
|
@ -312,7 +312,7 @@ size_t getTicTocID(const char *descriptionC) {
|
|||
/* ************************************************************************* */
|
||||
void tic(size_t id, const char *labelC) {
|
||||
// disable anything which refers to TimingOutline as well, for good measure
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
const std::string label(labelC);
|
||||
std::shared_ptr<TimingOutline> node = //
|
||||
gCurrentTimer.lock()->child(id, label, gCurrentTimer);
|
||||
|
@ -324,7 +324,7 @@ void tic(size_t id, const char *labelC) {
|
|||
/* ************************************************************************* */
|
||||
void toc(size_t id, const char *labelC) {
|
||||
// disable anything which refers to TimingOutline as well, for good measure
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
const std::string label(labelC);
|
||||
std::shared_ptr<TimingOutline> current(gCurrentTimer.lock());
|
||||
if (id != current->id_) {
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/dllexport.h>
|
||||
#include <gtsam/config.h> // for GTSAM_USE_TBB
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/version.hpp>
|
||||
#endif
|
||||
|
||||
|
@ -107,7 +107,7 @@
|
|||
// have matching gttic/gttoc statments. You may want to consider reorganizing your timing
|
||||
// outline to match the scope of your code.
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
// Automatically use the new Boost timers if version is recent enough.
|
||||
#if BOOST_VERSION >= 104800
|
||||
# ifndef GTSAM_DISABLE_NEW_TIMERS
|
||||
|
@ -165,7 +165,7 @@ namespace gtsam {
|
|||
ChildMap children_; ///< subtrees
|
||||
|
||||
// disable all timers if not using boost
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
boost::timer::cpu_timer timer_;
|
||||
#else
|
||||
|
@ -183,7 +183,7 @@ namespace gtsam {
|
|||
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
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
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
|
||||
|
|
|
@ -112,13 +112,12 @@ namespace gtsam {
|
|||
// }
|
||||
|
||||
/**
|
||||
* @brief Multiply all the `factors` and normalize the
|
||||
* product to prevent underflow.
|
||||
* @brief Multiply all the `factors`.
|
||||
*
|
||||
* @param factors The factors to multiply as a DiscreteFactorGraph.
|
||||
* @return DecisionTreeFactor
|
||||
*/
|
||||
static DecisionTreeFactor ProductAndNormalize(
|
||||
static DecisionTreeFactor DiscreteProduct(
|
||||
const DiscreteFactorGraph& factors) {
|
||||
// PRODUCT: multiply all factors
|
||||
#if GTSAM_HYBRID_TIMING
|
||||
|
@ -129,14 +128,14 @@ namespace gtsam {
|
|||
gttoc_(DiscreteProduct);
|
||||
#endif
|
||||
|
||||
// Max over all the potentials by pretending all keys are frontal:
|
||||
auto normalizer = product.max(product.size());
|
||||
|
||||
#if GTSAM_HYBRID_TIMING
|
||||
gttic_(DiscreteNormalize);
|
||||
#endif
|
||||
// Max over all the potentials by pretending all keys are frontal:
|
||||
auto denominator = product.max(product.size());
|
||||
|
||||
// Normalize the product factor to prevent underflow.
|
||||
product = product / (*normalizer);
|
||||
product = product / (*denominator);
|
||||
#if GTSAM_HYBRID_TIMING
|
||||
gttoc_(DiscreteNormalize);
|
||||
#endif
|
||||
|
@ -149,7 +148,7 @@ namespace gtsam {
|
|||
std::pair<DiscreteConditional::shared_ptr, DiscreteFactor::shared_ptr> //
|
||||
EliminateForMPE(const DiscreteFactorGraph& factors,
|
||||
const Ordering& frontalKeys) {
|
||||
DecisionTreeFactor product = ProductAndNormalize(factors);
|
||||
DecisionTreeFactor product = DiscreteProduct(factors);
|
||||
|
||||
// max out frontals, this is the factor on the separator
|
||||
gttic(max);
|
||||
|
@ -227,7 +226,7 @@ namespace gtsam {
|
|||
std::pair<DiscreteConditional::shared_ptr, DiscreteFactor::shared_ptr> //
|
||||
EliminateDiscrete(const DiscreteFactorGraph& factors,
|
||||
const Ordering& frontalKeys) {
|
||||
DecisionTreeFactor product = ProductAndNormalize(factors);
|
||||
DecisionTreeFactor product = DiscreteProduct(factors);
|
||||
|
||||
// sum out frontals, this is the factor on the separator
|
||||
#if GTSAM_HYBRID_TIMING
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include <gtsam/linear/linearExceptions.h>
|
||||
#include <gtsam/inference/Ordering.h>
|
||||
#include <gtsam/base/Vector.h>
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#include <gtsam/base/timing.h>
|
||||
#endif
|
||||
|
||||
|
@ -123,7 +123,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear,
|
|||
auto currentState = static_cast<const State*>(state_.get());
|
||||
bool verbose = (params_.verbosityLM >= LevenbergMarquardtParams::TRYLAMBDA);
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
boost::timer::cpu_timer lamda_iteration_timer;
|
||||
lamda_iteration_timer.start();
|
||||
|
@ -222,7 +222,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear,
|
|||
} // if (systemSolvedSuccessfully)
|
||||
|
||||
if (params_.verbosityLM == LevenbergMarquardtParams::SUMMARY) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
// do timing
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
double iterationTime = 1e-9 * lamda_iteration_timer.elapsed().wall;
|
||||
|
|
Loading…
Reference in New Issue