Merge pull request #1650 from borglab/factor-typecast
commit
b5d19fb446
|
@ -36,13 +36,6 @@ set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${CMAKE_CURRENT_SOURCE_DIR}/cmake"
|
||||||
include(GtsamMakeConfigFile)
|
include(GtsamMakeConfigFile)
|
||||||
include(GNUInstallDirs)
|
include(GNUInstallDirs)
|
||||||
|
|
||||||
# Load build type flags and default to Debug mode
|
|
||||||
include(GtsamBuildTypes)
|
|
||||||
|
|
||||||
# Use macros for creating tests/timing scripts
|
|
||||||
include(GtsamTesting)
|
|
||||||
include(GtsamPrinting)
|
|
||||||
|
|
||||||
# guard against in-source builds
|
# guard against in-source builds
|
||||||
if(${GTSAM_SOURCE_DIR} STREQUAL ${GTSAM_BINARY_DIR})
|
if(${GTSAM_SOURCE_DIR} STREQUAL ${GTSAM_BINARY_DIR})
|
||||||
message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ")
|
message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ")
|
||||||
|
@ -50,6 +43,13 @@ endif()
|
||||||
|
|
||||||
include(cmake/HandleGeneralOptions.cmake) # CMake build options
|
include(cmake/HandleGeneralOptions.cmake) # CMake build options
|
||||||
|
|
||||||
|
# Load build type flags and default to Debug mode
|
||||||
|
include(GtsamBuildTypes)
|
||||||
|
|
||||||
|
# Use macros for creating tests/timing scripts
|
||||||
|
include(GtsamTesting)
|
||||||
|
include(GtsamPrinting)
|
||||||
|
|
||||||
############### Decide on BOOST ######################################
|
############### Decide on BOOST ######################################
|
||||||
# Enable or disable serialization with GTSAM_ENABLE_BOOST_SERIALIZATION
|
# Enable or disable serialization with GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||||
option(GTSAM_ENABLE_BOOST_SERIALIZATION "Enable Boost serialization" ON)
|
option(GTSAM_ENABLE_BOOST_SERIALIZATION "Enable Boost serialization" ON)
|
||||||
|
|
|
@ -55,9 +55,6 @@ if(NOT CMAKE_BUILD_TYPE AND NOT MSVC AND NOT XCODE_VERSION)
|
||||||
"Choose the type of build, options are: None Debug Release Timing Profiling RelWithDebInfo." FORCE)
|
"Choose the type of build, options are: None Debug Release Timing Profiling RelWithDebInfo." FORCE)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
# Add option for using build type postfixes to allow installing multiple build modes
|
|
||||||
option(GTSAM_BUILD_TYPE_POSTFIXES "Enable/Disable appending the build type to the name of compiled libraries" ON)
|
|
||||||
|
|
||||||
# Define all cache variables, to be populated below depending on the OS/compiler:
|
# Define all cache variables, to be populated below depending on the OS/compiler:
|
||||||
set(GTSAM_COMPILE_OPTIONS_PRIVATE "" CACHE INTERNAL "(Do not edit) Private compiler flags for all build configurations." FORCE)
|
set(GTSAM_COMPILE_OPTIONS_PRIVATE "" CACHE INTERNAL "(Do not edit) Private compiler flags for all build configurations." FORCE)
|
||||||
set(GTSAM_COMPILE_OPTIONS_PUBLIC "" CACHE INTERNAL "(Do not edit) Public compiler flags (exported to user projects) for all build configurations." FORCE)
|
set(GTSAM_COMPILE_OPTIONS_PUBLIC "" CACHE INTERNAL "(Do not edit) Public compiler flags (exported to user projects) for all build configurations." FORCE)
|
||||||
|
@ -82,6 +79,13 @@ set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_RELWITHDEBINFO "NDEBUG" CACHE STRING "(Us
|
||||||
set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_RELEASE "NDEBUG" CACHE STRING "(User editable) Private preprocessor macros for Release configuration.")
|
set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_RELEASE "NDEBUG" CACHE STRING "(User editable) Private preprocessor macros for Release configuration.")
|
||||||
set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_PROFILING "NDEBUG" CACHE STRING "(User editable) Private preprocessor macros for Profiling configuration.")
|
set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_PROFILING "NDEBUG" CACHE STRING "(User editable) Private preprocessor macros for Profiling configuration.")
|
||||||
set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_TIMING "NDEBUG;ENABLE_TIMING" CACHE STRING "(User editable) Private preprocessor macros for Timing configuration.")
|
set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_TIMING "NDEBUG;ENABLE_TIMING" CACHE STRING "(User editable) Private preprocessor macros for Timing configuration.")
|
||||||
|
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_DEFINITIONS_PRIVATE_DEBUG)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_DEFINITIONS_PRIVATE_RELWITHDEBINFO)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_DEFINITIONS_PRIVATE_RELEASE)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_DEFINITIONS_PRIVATE_PROFILING)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_DEFINITIONS_PRIVATE_TIMING)
|
||||||
|
|
||||||
if(MSVC)
|
if(MSVC)
|
||||||
# Common to all configurations:
|
# Common to all configurations:
|
||||||
list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE
|
list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE
|
||||||
|
@ -143,6 +147,13 @@ else()
|
||||||
set(GTSAM_COMPILE_OPTIONS_PRIVATE_TIMING -g -O3 CACHE STRING "(User editable) Private compiler flags for Timing configuration.")
|
set(GTSAM_COMPILE_OPTIONS_PRIVATE_TIMING -g -O3 CACHE STRING "(User editable) Private compiler flags for Timing configuration.")
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_OPTIONS_PRIVATE_DEBUG)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_OPTIONS_PRIVATE_RELWITHDEBINFO)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_OPTIONS_PRIVATE_RELEASE)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_OPTIONS_PRIVATE_PROFILING)
|
||||||
|
mark_as_advanced(GTSAM_COMPILE_OPTIONS_PRIVATE_TIMING)
|
||||||
|
|
||||||
# Enable C++17:
|
# Enable C++17:
|
||||||
if (NOT CMAKE_VERSION VERSION_LESS 3.8)
|
if (NOT CMAKE_VERSION VERSION_LESS 3.8)
|
||||||
set(GTSAM_COMPILE_FEATURES_PUBLIC "cxx_std_17" CACHE STRING "CMake compile features property for all gtsam targets.")
|
set(GTSAM_COMPILE_FEATURES_PUBLIC "cxx_std_17" CACHE STRING "CMake compile features property for all gtsam targets.")
|
||||||
|
@ -198,7 +209,6 @@ if(${CMAKE_CXX_COMPILER_ID} STREQUAL "Clang")
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if (NOT MSVC)
|
if (NOT MSVC)
|
||||||
option(GTSAM_BUILD_WITH_MARCH_NATIVE "Enable/Disable building with all instructions supported by native architecture (binary may not be portable!)" OFF)
|
|
||||||
if(GTSAM_BUILD_WITH_MARCH_NATIVE)
|
if(GTSAM_BUILD_WITH_MARCH_NATIVE)
|
||||||
# Check if Apple OS and compiler is [Apple]Clang
|
# Check if Apple OS and compiler is [Apple]Clang
|
||||||
if(APPLE AND (${CMAKE_CXX_COMPILER_ID} MATCHES "^(Apple)?Clang$"))
|
if(APPLE AND (${CMAKE_CXX_COMPILER_ID} MATCHES "^(Apple)?Clang$"))
|
||||||
|
|
|
@ -42,7 +42,7 @@ endmacro()
|
||||||
# GTSAM_BUILD_EXAMPLES_ALWAYS is enabled. They may also be built with 'make examples'.
|
# GTSAM_BUILD_EXAMPLES_ALWAYS is enabled. They may also be built with 'make examples'.
|
||||||
#
|
#
|
||||||
# Usage example:
|
# Usage example:
|
||||||
# gtsamAddExamplesGlob("*.cpp" "BrokenExample.cpp" "gtsam;GeographicLib")
|
# gtsamAddExamplesGlob("*.cpp" "BrokenExample.cpp" "gtsam;GeographicLib" ON)
|
||||||
#
|
#
|
||||||
# Arguments:
|
# Arguments:
|
||||||
# globPatterns: The list of files or glob patterns from which to create examples, with
|
# globPatterns: The list of files or glob patterns from which to create examples, with
|
||||||
|
@ -51,8 +51,9 @@ endmacro()
|
||||||
# excludedFiles: A list of files or globs to exclude, e.g. "C*.cpp;BrokenExample.cpp". Pass
|
# excludedFiles: A list of files or globs to exclude, e.g. "C*.cpp;BrokenExample.cpp". Pass
|
||||||
# an empty string "" if nothing needs to be excluded.
|
# an empty string "" if nothing needs to be excluded.
|
||||||
# linkLibraries: The list of libraries to link to.
|
# linkLibraries: The list of libraries to link to.
|
||||||
macro(gtsamAddExamplesGlob globPatterns excludedFiles linkLibraries)
|
# buildWithAll: Build examples with `make` and/or `make all`
|
||||||
gtsamAddExesGlob_impl("${globPatterns}" "${excludedFiles}" "${linkLibraries}" "examples" ${GTSAM_BUILD_EXAMPLES_ALWAYS})
|
macro(gtsamAddExamplesGlob globPatterns excludedFiles linkLibraries buildWithAll)
|
||||||
|
gtsamAddExesGlob_impl("${globPatterns}" "${excludedFiles}" "${linkLibraries}" "examples" ${buildWithAll})
|
||||||
endmacro()
|
endmacro()
|
||||||
|
|
||||||
|
|
||||||
|
@ -76,8 +77,9 @@ endmacro()
|
||||||
# excludedFiles: A list of files or globs to exclude, e.g. "C*.cpp;BrokenExample.cpp". Pass
|
# excludedFiles: A list of files or globs to exclude, e.g. "C*.cpp;BrokenExample.cpp". Pass
|
||||||
# an empty string "" if nothing needs to be excluded.
|
# an empty string "" if nothing needs to be excluded.
|
||||||
# linkLibraries: The list of libraries to link to.
|
# linkLibraries: The list of libraries to link to.
|
||||||
macro(gtsamAddTimingGlob globPatterns excludedFiles linkLibraries)
|
# buildWithAll: Build examples with `make` and/or `make all`
|
||||||
gtsamAddExesGlob_impl("${globPatterns}" "${excludedFiles}" "${linkLibraries}" "timing" ${GTSAM_BUILD_TIMING_ALWAYS})
|
macro(gtsamAddTimingGlob globPatterns excludedFiles linkLibraries buildWithAll)
|
||||||
|
gtsamAddExesGlob_impl("${globPatterns}" "${excludedFiles}" "${linkLibraries}" "timing" ${buildWithAll})
|
||||||
endmacro()
|
endmacro()
|
||||||
|
|
||||||
|
|
||||||
|
@ -86,9 +88,8 @@ endmacro()
|
||||||
# Build macros for using tests
|
# Build macros for using tests
|
||||||
enable_testing()
|
enable_testing()
|
||||||
|
|
||||||
option(GTSAM_BUILD_TESTS "Enable/Disable building of tests" ON)
|
#TODO(Varun) Move to HandlePrintConfiguration.cmake. This will require additional changes.
|
||||||
option(GTSAM_BUILD_EXAMPLES_ALWAYS "Build examples with 'make all' (build with 'make examples' if not)" ON)
|
option(GTSAM_BUILD_TESTS "Enable/Disable building of tests" ON)
|
||||||
option(GTSAM_BUILD_TIMING_ALWAYS "Build timing scripts with 'make all' (build with 'make timing' if not" OFF)
|
|
||||||
|
|
||||||
# Add option for combining unit tests
|
# Add option for combining unit tests
|
||||||
if(MSVC OR XCODE_VERSION)
|
if(MSVC OR XCODE_VERSION)
|
||||||
|
@ -123,6 +124,7 @@ add_custom_target(timing)
|
||||||
# Implementations of this file's macros:
|
# Implementations of this file's macros:
|
||||||
|
|
||||||
macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries)
|
macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries)
|
||||||
|
#TODO(Varun) Building of tests should not depend on global gtsam flag
|
||||||
if(GTSAM_BUILD_TESTS)
|
if(GTSAM_BUILD_TESTS)
|
||||||
# Add group target if it doesn't already exist
|
# Add group target if it doesn't already exist
|
||||||
if(NOT TARGET check.${groupName})
|
if(NOT TARGET check.${groupName})
|
||||||
|
|
|
@ -8,6 +8,18 @@ else()
|
||||||
set(GTSAM_UNSTABLE_AVAILABLE 0)
|
set(GTSAM_UNSTABLE_AVAILABLE 0)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
### GtsamTesting related options
|
||||||
|
option(GTSAM_BUILD_EXAMPLES_ALWAYS "Build examples with 'make all' (build with 'make examples' if not)" ON)
|
||||||
|
option(GTSAM_BUILD_TIMING_ALWAYS "Build timing scripts with 'make all' (build with 'make timing' if not" OFF)
|
||||||
|
###
|
||||||
|
|
||||||
|
# Add option for using build type postfixes to allow installing multiple build modes
|
||||||
|
option(GTSAM_BUILD_TYPE_POSTFIXES "Enable/Disable appending the build type to the name of compiled libraries" ON)
|
||||||
|
|
||||||
|
if (NOT MSVC)
|
||||||
|
option(GTSAM_BUILD_WITH_MARCH_NATIVE "Enable/Disable building with all instructions supported by native architecture (binary may not be portable!)" OFF)
|
||||||
|
endif()
|
||||||
|
|
||||||
# Configurable Options
|
# Configurable Options
|
||||||
if(GTSAM_UNSTABLE_AVAILABLE)
|
if(GTSAM_UNSTABLE_AVAILABLE)
|
||||||
option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON)
|
option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON)
|
||||||
|
|
|
@ -47,9 +47,9 @@ linkLibraries: The list of libraries to link to in addition to CppUnitLite.
|
||||||
</code></pre>
|
</code></pre>
|
||||||
</li>
|
</li>
|
||||||
<li>
|
<li>
|
||||||
<p><code>gtsamAddExamplesGlob(globPatterns excludedFiles linkLibraries)</code> Add scripts that will serve as examples of how to use the library. A list of files or glob patterns is specified, and one executable will be created for each matching .cpp file. These executables will not be installed. They are build with 'make all' if GTSAM_BUILD_EXAMPLES_ALWAYS is enabled. They may also be built with 'make examples'.</p>
|
<p><code>gtsamAddExamplesGlob(globPatterns excludedFiles linkLibraries buildWithAll)</code> Add scripts that will serve as examples of how to use the library. A list of files or glob patterns is specified, and one executable will be created for each matching .cpp file. These executables will not be installed. They are build with 'make all' if GTSAM_BUILD_EXAMPLES_ALWAYS is enabled. They may also be built with 'make examples'.</p>
|
||||||
<p>Usage example:</p>
|
<p>Usage example:</p>
|
||||||
<pre><code>gtsamAddExamplesGlob("*.cpp" "BrokenExample.cpp" "gtsam;GeographicLib")
|
<pre><code>gtsamAddExamplesGlob("*.cpp" "BrokenExample.cpp" "gtsam;GeographicLib" ON)
|
||||||
</code></pre>
|
</code></pre>
|
||||||
<p>Arguments:</p>
|
<p>Arguments:</p>
|
||||||
<pre><code>globPatterns: The list of files or glob patterns from which to create unit tests, with
|
<pre><code>globPatterns: The list of files or glob patterns from which to create unit tests, with
|
||||||
|
@ -58,6 +58,7 @@ linkLibraries: The list of libraries to link to in addition to CppUnitLite.
|
||||||
excludedFiles: A list of files or globs to exclude, e.g. "C*.cpp;BrokenExample.cpp". Pass
|
excludedFiles: A list of files or globs to exclude, e.g. "C*.cpp;BrokenExample.cpp". Pass
|
||||||
an empty string "" if nothing needs to be excluded.
|
an empty string "" if nothing needs to be excluded.
|
||||||
linkLibraries: The list of libraries to link to.
|
linkLibraries: The list of libraries to link to.
|
||||||
|
buildWithAll: Build examples with `make` and/or `make all`
|
||||||
</code></pre>
|
</code></pre>
|
||||||
</li>
|
</li>
|
||||||
</ul>
|
</ul>
|
||||||
|
|
|
@ -52,11 +52,11 @@ Defines two useful functions for creating CTest unit tests. Also immediately cr
|
||||||
Pass an empty string "" if nothing needs to be excluded.
|
Pass an empty string "" if nothing needs to be excluded.
|
||||||
linkLibraries: The list of libraries to link to in addition to CppUnitLite.
|
linkLibraries: The list of libraries to link to in addition to CppUnitLite.
|
||||||
|
|
||||||
* `gtsamAddExamplesGlob(globPatterns excludedFiles linkLibraries)` Add scripts that will serve as examples of how to use the library. A list of files or glob patterns is specified, and one executable will be created for each matching .cpp file. These executables will not be installed. They are build with 'make all' if GTSAM_BUILD_EXAMPLES_ALWAYS is enabled. They may also be built with 'make examples'.
|
* `gtsamAddExamplesGlob(globPatterns excludedFiles linkLibraries buildWithAll)` Add scripts that will serve as examples of how to use the library. A list of files or glob patterns is specified, and one executable will be created for each matching .cpp file. These executables will not be installed. They are build with 'make all' if GTSAM_BUILD_EXAMPLES_ALWAYS is enabled. They may also be built with 'make examples'.
|
||||||
|
|
||||||
Usage example:
|
Usage example:
|
||||||
|
|
||||||
gtsamAddExamplesGlob("*.cpp" "BrokenExample.cpp" "gtsam;GeographicLib")
|
gtsamAddExamplesGlob("*.cpp" "BrokenExample.cpp" "gtsam;GeographicLib" ON)
|
||||||
|
|
||||||
Arguments:
|
Arguments:
|
||||||
|
|
||||||
|
@ -66,6 +66,7 @@ Defines two useful functions for creating CTest unit tests. Also immediately cr
|
||||||
excludedFiles: A list of files or globs to exclude, e.g. "C*.cpp;BrokenExample.cpp". Pass
|
excludedFiles: A list of files or globs to exclude, e.g. "C*.cpp;BrokenExample.cpp". Pass
|
||||||
an empty string "" if nothing needs to be excluded.
|
an empty string "" if nothing needs to be excluded.
|
||||||
linkLibraries: The list of libraries to link to.
|
linkLibraries: The list of libraries to link to.
|
||||||
|
buildWithAll: Build examples with `make` and/or `make all`
|
||||||
|
|
||||||
## GtsamMakeConfigFile
|
## GtsamMakeConfigFile
|
||||||
|
|
||||||
|
|
|
@ -20,4 +20,4 @@ if (NOT GTSAM_USE_BOOST_FEATURES)
|
||||||
)
|
)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
gtsamAddExamplesGlob("*.cpp" "${excluded_examples}" "gtsam;${Boost_PROGRAM_OPTIONS_LIBRARY}")
|
gtsamAddExamplesGlob("*.cpp" "${excluded_examples}" "gtsam;${Boost_PROGRAM_OPTIONS_LIBRARY}" ${GTSAM_BUILD_EXAMPLES_ALWAYS})
|
||||||
|
|
|
@ -42,8 +42,8 @@
|
||||||
#include <functional>
|
#include <functional>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <iterator>
|
#include <iterator>
|
||||||
#include <vector>
|
|
||||||
#include <numeric>
|
#include <numeric>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
#include "Switching.h"
|
#include "Switching.h"
|
||||||
#include "TinyHybridExample.h"
|
#include "TinyHybridExample.h"
|
||||||
|
@ -613,11 +613,11 @@ TEST(HybridGaussianFactorGraph, assembleGraphTree) {
|
||||||
// Create expected decision tree with two factor graphs:
|
// Create expected decision tree with two factor graphs:
|
||||||
|
|
||||||
// Get mixture factor:
|
// Get mixture factor:
|
||||||
auto mixture = std::dynamic_pointer_cast<GaussianMixtureFactor>(fg.at(0));
|
auto mixture = fg.at<GaussianMixtureFactor>(0);
|
||||||
CHECK(mixture);
|
CHECK(mixture);
|
||||||
|
|
||||||
// Get prior factor:
|
// Get prior factor:
|
||||||
const auto gf = std::dynamic_pointer_cast<HybridConditional>(fg.at(1));
|
const auto gf = fg.at<HybridConditional>(1);
|
||||||
CHECK(gf);
|
CHECK(gf);
|
||||||
using GF = GaussianFactor::shared_ptr;
|
using GF = GaussianFactor::shared_ptr;
|
||||||
const GF prior = gf->asGaussian();
|
const GF prior = gf->asGaussian();
|
||||||
|
|
|
@ -310,6 +310,21 @@ class FactorGraph {
|
||||||
*/
|
*/
|
||||||
sharedFactor& at(size_t i) { return factors_.at(i); }
|
sharedFactor& at(size_t i) { return factors_.at(i); }
|
||||||
|
|
||||||
|
/** Get a specific factor by index and typecast to factor type F
|
||||||
|
* (this checks array bounds and may throw
|
||||||
|
* an exception, as opposed to operator[] which does not).
|
||||||
|
*/
|
||||||
|
template <typename F>
|
||||||
|
std::shared_ptr<F> at(size_t i) {
|
||||||
|
return std::dynamic_pointer_cast<F>(factors_.at(i));
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Const version of templated `at` method.
|
||||||
|
template <typename F>
|
||||||
|
const std::shared_ptr<F> at(size_t i) const {
|
||||||
|
return std::dynamic_pointer_cast<F>(factors_.at(i));
|
||||||
|
}
|
||||||
|
|
||||||
/** Get a specific factor by index (this does not check array bounds, as
|
/** Get a specific factor by index (this does not check array bounds, as
|
||||||
* opposed to at() which does).
|
* opposed to at() which does).
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
* -------------------------------------------------------------------------- */
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @file Key.h
|
* @file Key.cpp
|
||||||
* @brief
|
* @brief
|
||||||
* @author Richard Roberts
|
* @author Richard Roberts
|
||||||
* @author Alex Cunningham
|
* @author Alex Cunningham
|
||||||
|
@ -26,6 +26,9 @@ using namespace std;
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
/// Assign default key formatter
|
||||||
|
KeyFormatter DefaultKeyFormatter = &_defaultKeyFormatter;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string _defaultKeyFormatter(Key key) {
|
string _defaultKeyFormatter(Key key) {
|
||||||
const Symbol asSymbol(key);
|
const Symbol asSymbol(key);
|
||||||
|
|
|
@ -37,10 +37,16 @@ using KeyFormatter = std::function<std::string(Key)>;
|
||||||
// Helper function for DefaultKeyFormatter
|
// Helper function for DefaultKeyFormatter
|
||||||
GTSAM_EXPORT std::string _defaultKeyFormatter(Key key);
|
GTSAM_EXPORT std::string _defaultKeyFormatter(Key key);
|
||||||
|
|
||||||
/// The default KeyFormatter, which is used if no KeyFormatter is passed to
|
/**
|
||||||
/// a nonlinear 'print' function. Automatically detects plain integer keys
|
* The default KeyFormatter, which is used if no KeyFormatter is passed
|
||||||
/// and Symbol keys.
|
* to a 'print' function.
|
||||||
static const KeyFormatter DefaultKeyFormatter = &_defaultKeyFormatter;
|
*
|
||||||
|
* Automatically detects plain integer keys and Symbol keys.
|
||||||
|
*
|
||||||
|
* Marked as `extern` so that it can be updated by external libraries.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
extern GTSAM_EXPORT KeyFormatter DefaultKeyFormatter;
|
||||||
|
|
||||||
// Helper function for Multi-robot Key Formatter
|
// Helper function for Multi-robot Key Formatter
|
||||||
GTSAM_EXPORT std::string _multirobotKeyFormatter(gtsam::Key key);
|
GTSAM_EXPORT std::string _multirobotKeyFormatter(gtsam::Key key);
|
||||||
|
@ -124,7 +130,3 @@ struct traits<Key> {
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -312,6 +312,12 @@ namespace gtsam {
|
||||||
/** Get a view of the A matrix */
|
/** Get a view of the A matrix */
|
||||||
ABlock getA() { return Ab_.range(0, size()); }
|
ABlock getA() { return Ab_.range(0, size()); }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get a view of the A matrix for the variable
|
||||||
|
* pointed to by the given key.
|
||||||
|
*/
|
||||||
|
ABlock getA(const Key& key) { return Ab_(find(key) - begin()); }
|
||||||
|
|
||||||
/** Update an information matrix by adding the information corresponding to this factor
|
/** Update an information matrix by adding the information corresponding to this factor
|
||||||
* (used internally during elimination).
|
* (used internally during elimination).
|
||||||
* @param scatter A mapping from variable index to slot index in this HessianFactor
|
* @param scatter A mapping from variable index to slot index in this HessianFactor
|
||||||
|
|
|
@ -391,8 +391,7 @@ TEST(GaussianFactorGraph, clone) {
|
||||||
EXPECT(assert_equal(init_graph, actCloned)); // Same as the original version
|
EXPECT(assert_equal(init_graph, actCloned)); // Same as the original version
|
||||||
|
|
||||||
// Apply an in-place change to init_graph and compare
|
// Apply an in-place change to init_graph and compare
|
||||||
JacobianFactor::shared_ptr jacFactor0 =
|
JacobianFactor::shared_ptr jacFactor0 = init_graph.at<JacobianFactor>(0);
|
||||||
std::dynamic_pointer_cast<JacobianFactor>(init_graph.at(0));
|
|
||||||
CHECK(jacFactor0);
|
CHECK(jacFactor0);
|
||||||
jacFactor0->getA(jacFactor0->begin()) *= 7.;
|
jacFactor0->getA(jacFactor0->begin()) *= 7.;
|
||||||
EXPECT(assert_inequal(init_graph, exp_graph));
|
EXPECT(assert_inequal(init_graph, exp_graph));
|
||||||
|
|
|
@ -65,7 +65,10 @@ TEST(JacobianFactor, constructors_and_accessors)
|
||||||
JacobianFactor actual(terms[0].first, terms[0].second, b, noise);
|
JacobianFactor actual(terms[0].first, terms[0].second, b, noise);
|
||||||
EXPECT(assert_equal(expected, actual));
|
EXPECT(assert_equal(expected, actual));
|
||||||
LONGS_EQUAL((long)terms[0].first, (long)actual.keys().back());
|
LONGS_EQUAL((long)terms[0].first, (long)actual.keys().back());
|
||||||
|
// Key iterator
|
||||||
EXPECT(assert_equal(terms[0].second, actual.getA(actual.end() - 1)));
|
EXPECT(assert_equal(terms[0].second, actual.getA(actual.end() - 1)));
|
||||||
|
// Key
|
||||||
|
EXPECT(assert_equal(terms[0].second, actual.getA(terms[0].first)));
|
||||||
EXPECT(assert_equal(b, expected.getb()));
|
EXPECT(assert_equal(b, expected.getb()));
|
||||||
EXPECT(assert_equal(b, actual.getb()));
|
EXPECT(assert_equal(b, actual.getb()));
|
||||||
EXPECT(noise == expected.get_model());
|
EXPECT(noise == expected.get_model());
|
||||||
|
@ -78,7 +81,10 @@ TEST(JacobianFactor, constructors_and_accessors)
|
||||||
terms[1].first, terms[1].second, b, noise);
|
terms[1].first, terms[1].second, b, noise);
|
||||||
EXPECT(assert_equal(expected, actual));
|
EXPECT(assert_equal(expected, actual));
|
||||||
LONGS_EQUAL((long)terms[1].first, (long)actual.keys().back());
|
LONGS_EQUAL((long)terms[1].first, (long)actual.keys().back());
|
||||||
|
// Key iterator
|
||||||
EXPECT(assert_equal(terms[1].second, actual.getA(actual.end() - 1)));
|
EXPECT(assert_equal(terms[1].second, actual.getA(actual.end() - 1)));
|
||||||
|
// Key
|
||||||
|
EXPECT(assert_equal(terms[1].second, actual.getA(terms[1].first)));
|
||||||
EXPECT(assert_equal(b, expected.getb()));
|
EXPECT(assert_equal(b, expected.getb()));
|
||||||
EXPECT(assert_equal(b, actual.getb()));
|
EXPECT(assert_equal(b, actual.getb()));
|
||||||
EXPECT(noise == expected.get_model());
|
EXPECT(noise == expected.get_model());
|
||||||
|
@ -91,7 +97,10 @@ TEST(JacobianFactor, constructors_and_accessors)
|
||||||
terms[1].first, terms[1].second, terms[2].first, terms[2].second, b, noise);
|
terms[1].first, terms[1].second, terms[2].first, terms[2].second, b, noise);
|
||||||
EXPECT(assert_equal(expected, actual));
|
EXPECT(assert_equal(expected, actual));
|
||||||
LONGS_EQUAL((long)terms[2].first, (long)actual.keys().back());
|
LONGS_EQUAL((long)terms[2].first, (long)actual.keys().back());
|
||||||
|
// Key iterator
|
||||||
EXPECT(assert_equal(terms[2].second, actual.getA(actual.end() - 1)));
|
EXPECT(assert_equal(terms[2].second, actual.getA(actual.end() - 1)));
|
||||||
|
// Key
|
||||||
|
EXPECT(assert_equal(terms[2].second, actual.getA(terms[2].first)));
|
||||||
EXPECT(assert_equal(b, expected.getb()));
|
EXPECT(assert_equal(b, expected.getb()));
|
||||||
EXPECT(assert_equal(b, actual.getb()));
|
EXPECT(assert_equal(b, actual.getb()));
|
||||||
EXPECT(noise == expected.get_model());
|
EXPECT(noise == expected.get_model());
|
||||||
|
|
|
@ -65,10 +65,9 @@ class GncOptimizer {
|
||||||
nfg_.resize(graph.size());
|
nfg_.resize(graph.size());
|
||||||
for (size_t i = 0; i < graph.size(); i++) {
|
for (size_t i = 0; i < graph.size(); i++) {
|
||||||
if (graph[i]) {
|
if (graph[i]) {
|
||||||
NoiseModelFactor::shared_ptr factor = std::dynamic_pointer_cast<
|
NoiseModelFactor::shared_ptr factor = graph.at<NoiseModelFactor>(i);
|
||||||
NoiseModelFactor>(graph[i]);
|
auto robust =
|
||||||
auto robust = std::dynamic_pointer_cast<
|
std::dynamic_pointer_cast<noiseModel::Robust>(factor->noiseModel());
|
||||||
noiseModel::Robust>(factor->noiseModel());
|
|
||||||
// if the factor has a robust loss, we remove the robust loss
|
// if the factor has a robust loss, we remove the robust loss
|
||||||
nfg_[i] = robust ? factor-> cloneWithNewNoiseModel(robust->noise()) : factor;
|
nfg_[i] = robust ? factor-> cloneWithNewNoiseModel(robust->noise()) : factor;
|
||||||
}
|
}
|
||||||
|
@ -401,11 +400,9 @@ class GncOptimizer {
|
||||||
newGraph.resize(nfg_.size());
|
newGraph.resize(nfg_.size());
|
||||||
for (size_t i = 0; i < nfg_.size(); i++) {
|
for (size_t i = 0; i < nfg_.size(); i++) {
|
||||||
if (nfg_[i]) {
|
if (nfg_[i]) {
|
||||||
auto factor = std::dynamic_pointer_cast<
|
auto factor = nfg_.at<NoiseModelFactor>(i);
|
||||||
NoiseModelFactor>(nfg_[i]);
|
auto noiseModel = std::dynamic_pointer_cast<noiseModel::Gaussian>(
|
||||||
auto noiseModel =
|
factor->noiseModel());
|
||||||
std::dynamic_pointer_cast<noiseModel::Gaussian>(
|
|
||||||
factor->noiseModel());
|
|
||||||
if (noiseModel) {
|
if (noiseModel) {
|
||||||
Matrix newInfo = weights[i] * noiseModel->information();
|
Matrix newInfo = weights[i] * noiseModel->information();
|
||||||
auto newNoiseModel = noiseModel::Gaussian::Information(newInfo);
|
auto newNoiseModel = noiseModel::Gaussian::Information(newInfo);
|
||||||
|
|
|
@ -59,10 +59,12 @@ class Values {
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
|
|
||||||
// New in 4.0, we have to specialize every insert/update/at to generate
|
// New in 4.0, we have to specialize every insert/update/at
|
||||||
// wrappers Instead of the old: void insert(size_t j, const gtsam::Value&
|
// to generate wrappers.
|
||||||
// value); void update(size_t j, const gtsam::Value& val); gtsam::Value
|
// Instead of the old:
|
||||||
// at(size_t j) const;
|
// void insert(size_t j, const gtsam::Value& value);
|
||||||
|
// void update(size_t j, const gtsam::Value& val);
|
||||||
|
// gtsam::Value at(size_t j) const;
|
||||||
|
|
||||||
// The order is important: Vector has to precede Point2/Point3 so `atVector`
|
// The order is important: Vector has to precede Point2/Point3 so `atVector`
|
||||||
// can work for those fixed-size vectors.
|
// can work for those fixed-size vectors.
|
||||||
|
@ -99,6 +101,10 @@ class Values {
|
||||||
template <T = {gtsam::Point2, gtsam::Point3}>
|
template <T = {gtsam::Point2, gtsam::Point3}>
|
||||||
void insert(size_t j, const T& val);
|
void insert(size_t j, const T& val);
|
||||||
|
|
||||||
|
// The order is important: Vector has to precede Point2/Point3 so `atVector`
|
||||||
|
// can work for those fixed-size vectors.
|
||||||
|
void update(size_t j, Vector vector);
|
||||||
|
void update(size_t j, Matrix matrix);
|
||||||
void update(size_t j, const gtsam::Point2& point2);
|
void update(size_t j, const gtsam::Point2& point2);
|
||||||
void update(size_t j, const gtsam::Point3& point3);
|
void update(size_t j, const gtsam::Point3& point3);
|
||||||
void update(size_t j, const gtsam::Rot2& rot2);
|
void update(size_t j, const gtsam::Rot2& rot2);
|
||||||
|
@ -125,10 +131,12 @@ class Values {
|
||||||
void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
|
void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
|
||||||
void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
|
void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
|
||||||
void update(size_t j, const gtsam::NavState& nav_state);
|
void update(size_t j, const gtsam::NavState& nav_state);
|
||||||
void update(size_t j, Vector vector);
|
|
||||||
void update(size_t j, Matrix matrix);
|
|
||||||
void update(size_t j, double c);
|
void update(size_t j, double c);
|
||||||
|
|
||||||
|
// The order is important: Vector has to precede Point2/Point3 so `atVector`
|
||||||
|
// can work for those fixed-size vectors.
|
||||||
|
void insert_or_assign(size_t j, Vector vector);
|
||||||
|
void insert_or_assign(size_t j, Matrix matrix);
|
||||||
void insert_or_assign(size_t j, const gtsam::Point2& point2);
|
void insert_or_assign(size_t j, const gtsam::Point2& point2);
|
||||||
void insert_or_assign(size_t j, const gtsam::Point3& point3);
|
void insert_or_assign(size_t j, const gtsam::Point3& point3);
|
||||||
void insert_or_assign(size_t j, const gtsam::Rot2& rot2);
|
void insert_or_assign(size_t j, const gtsam::Rot2& rot2);
|
||||||
|
@ -165,8 +173,6 @@ class Values {
|
||||||
void insert_or_assign(size_t j,
|
void insert_or_assign(size_t j,
|
||||||
const gtsam::imuBias::ConstantBias& constant_bias);
|
const gtsam::imuBias::ConstantBias& constant_bias);
|
||||||
void insert_or_assign(size_t j, const gtsam::NavState& nav_state);
|
void insert_or_assign(size_t j, const gtsam::NavState& nav_state);
|
||||||
void insert_or_assign(size_t j, Vector vector);
|
|
||||||
void insert_or_assign(size_t j, Matrix matrix);
|
|
||||||
void insert_or_assign(size_t j, double c);
|
void insert_or_assign(size_t j, double c);
|
||||||
|
|
||||||
template <T = {gtsam::Point2,
|
template <T = {gtsam::Point2,
|
||||||
|
|
|
@ -372,9 +372,11 @@ TEST(ShonanAveraging2, noisyToyGraphWithHuber) {
|
||||||
|
|
||||||
// test that each factor is actually robust
|
// test that each factor is actually robust
|
||||||
for (size_t i=0; i<=4; i++) { // note: last is the Gauge factor and is not robust
|
for (size_t i=0; i<=4; i++) { // note: last is the Gauge factor and is not robust
|
||||||
const auto &robust = std::dynamic_pointer_cast<noiseModel::Robust>(
|
const auto &robust = std::dynamic_pointer_cast<noiseModel::Robust>(
|
||||||
std::dynamic_pointer_cast<NoiseModelFactor>(graph[i])->noiseModel());
|
graph.at<NoiseModelFactor>(i)->noiseModel());
|
||||||
EXPECT(robust); // we expect the factors to be use a robust noise model (in particular, Huber)
|
// we expect the factors to be use a robust noise model
|
||||||
|
// (in particular, Huber)
|
||||||
|
EXPECT(robust);
|
||||||
}
|
}
|
||||||
|
|
||||||
// test result
|
// test result
|
||||||
|
|
|
@ -156,6 +156,9 @@ virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
|
|
||||||
|
gtsam::TriangulationResult point() const;
|
||||||
|
gtsam::TriangulationResult point(const gtsam::Values& values) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef gtsam::SmartProjectionPoseFactor<gtsam::Cal3_S2>
|
typedef gtsam::SmartProjectionPoseFactor<gtsam::Cal3_S2>
|
||||||
|
|
|
@ -97,8 +97,7 @@ TEST(dataSet, load2D) {
|
||||||
auto model = noiseModel::Unit::Create(3);
|
auto model = noiseModel::Unit::Create(3);
|
||||||
BetweenFactor<Pose2> expected(1, 0, Pose2(-0.99879, 0.0417574, -0.00818381),
|
BetweenFactor<Pose2> expected(1, 0, Pose2(-0.99879, 0.0417574, -0.00818381),
|
||||||
model);
|
model);
|
||||||
BetweenFactor<Pose2>::shared_ptr actual =
|
BetweenFactor<Pose2>::shared_ptr actual = graph->at<BetweenFactor<Pose2>>(0);
|
||||||
std::dynamic_pointer_cast<BetweenFactor<Pose2>>(graph->at(0));
|
|
||||||
EXPECT(assert_equal(expected, *actual));
|
EXPECT(assert_equal(expected, *actual));
|
||||||
|
|
||||||
// Check binary measurements, Pose2
|
// Check binary measurements, Pose2
|
||||||
|
@ -113,9 +112,8 @@ TEST(dataSet, load2D) {
|
||||||
// // Check factor parsing
|
// // Check factor parsing
|
||||||
const auto actualFactors = parseFactors<Pose2>(filename);
|
const auto actualFactors = parseFactors<Pose2>(filename);
|
||||||
for (size_t i : {0, 1, 2, 3, 4, 5}) {
|
for (size_t i : {0, 1, 2, 3, 4, 5}) {
|
||||||
EXPECT(assert_equal(
|
EXPECT(assert_equal(*graph->at<BetweenFactor<Pose2>>(i), *actualFactors[i],
|
||||||
*std::dynamic_pointer_cast<BetweenFactor<Pose2>>(graph->at(i)),
|
1e-5));
|
||||||
*actualFactors[i], 1e-5));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check pose parsing
|
// Check pose parsing
|
||||||
|
@ -194,9 +192,8 @@ TEST(dataSet, readG2o3D) {
|
||||||
// Check factor parsing
|
// Check factor parsing
|
||||||
const auto actualFactors = parseFactors<Pose3>(g2oFile);
|
const auto actualFactors = parseFactors<Pose3>(g2oFile);
|
||||||
for (size_t i : {0, 1, 2, 3, 4, 5}) {
|
for (size_t i : {0, 1, 2, 3, 4, 5}) {
|
||||||
EXPECT(assert_equal(
|
EXPECT(assert_equal(*expectedGraph.at<BetweenFactor<Pose3>>(i),
|
||||||
*std::dynamic_pointer_cast<BetweenFactor<Pose3>>(expectedGraph[i]),
|
*actualFactors[i], 1e-5));
|
||||||
*actualFactors[i], 1e-5));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check pose parsing
|
// Check pose parsing
|
||||||
|
|
|
@ -12,4 +12,4 @@ endif()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
gtsamAddExamplesGlob("*.cpp" "${excluded_examples}" "gtsam_unstable")
|
gtsamAddExamplesGlob("*.cpp" "${excluded_examples}" "gtsam_unstable" ${GTSAM_BUILD_EXAMPLES_ALWAYS})
|
||||||
|
|
|
@ -183,13 +183,10 @@ class LoopyBelief {
|
||||||
// accumulate unary factors
|
// accumulate unary factors
|
||||||
if (graph.at(factorIndex)->size() == 1) {
|
if (graph.at(factorIndex)->size() == 1) {
|
||||||
if (!prodOfUnaries)
|
if (!prodOfUnaries)
|
||||||
prodOfUnaries = std::dynamic_pointer_cast<DecisionTreeFactor>(
|
prodOfUnaries = graph.at<DecisionTreeFactor>(factorIndex);
|
||||||
graph.at(factorIndex));
|
|
||||||
else
|
else
|
||||||
prodOfUnaries = std::make_shared<DecisionTreeFactor>(
|
prodOfUnaries = std::make_shared<DecisionTreeFactor>(
|
||||||
*prodOfUnaries *
|
*prodOfUnaries * (*graph.at<DecisionTreeFactor>(factorIndex)));
|
||||||
(*std::dynamic_pointer_cast<DecisionTreeFactor>(
|
|
||||||
graph.at(factorIndex))));
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -9,4 +9,4 @@ if (NOT GTSAM_USE_BOOST_FEATURES)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
|
||||||
gtsamAddExamplesGlob("*.cpp" "${excluded_examples}" "gtsam_unstable")
|
gtsamAddExamplesGlob("*.cpp" "${excluded_examples}" "gtsam_unstable" ${GTSAM_BUILD_EXAMPLES_ALWAYS})
|
||||||
|
|
|
@ -87,7 +87,7 @@ TEST(NonlinearClusterTree, Clusters) {
|
||||||
Ordering ordering;
|
Ordering ordering;
|
||||||
ordering.push_back(x1);
|
ordering.push_back(x1);
|
||||||
const auto [bn, fg] = gfg->eliminatePartialSequential(ordering);
|
const auto [bn, fg] = gfg->eliminatePartialSequential(ordering);
|
||||||
auto expectedFactor = std::dynamic_pointer_cast<HessianFactor>(fg->at(0));
|
auto expectedFactor = fg->at<HessianFactor>(0);
|
||||||
if (!expectedFactor)
|
if (!expectedFactor)
|
||||||
throw std::runtime_error("Expected HessianFactor");
|
throw std::runtime_error("Expected HessianFactor");
|
||||||
|
|
||||||
|
|
|
@ -1 +1 @@
|
||||||
gtsamAddTimingGlob("*.cpp" "" "gtsam_unstable")
|
gtsamAddTimingGlob("*.cpp" "" "gtsam_unstable" ${GTSAM_BUILD_TIMING_ALWAYS})
|
||||||
|
|
|
@ -323,7 +323,7 @@ TEST( NonlinearFactor, cloneWithNewNoiseModel )
|
||||||
// create actual
|
// create actual
|
||||||
NonlinearFactorGraph actual;
|
NonlinearFactorGraph actual;
|
||||||
SharedNoiseModel noise2 = noiseModel::Isotropic::Sigma(2,sigma2);
|
SharedNoiseModel noise2 = noiseModel::Isotropic::Sigma(2,sigma2);
|
||||||
actual.push_back( std::dynamic_pointer_cast<NoiseModelFactor>(nfg[0])->cloneWithNewNoiseModel(noise2) );
|
actual.push_back(nfg.at<NoiseModelFactor>(0)->cloneWithNewNoiseModel(noise2));
|
||||||
|
|
||||||
// check it's all good
|
// check it's all good
|
||||||
CHECK(assert_equal(expected, actual));
|
CHECK(assert_equal(expected, actual));
|
||||||
|
|
|
@ -14,6 +14,6 @@ if (NOT GTSAM_USE_BOOST_FEATURES)
|
||||||
)
|
)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
gtsamAddTimingGlob("*.cpp" "${excluded_scripts}" "gtsam")
|
gtsamAddTimingGlob("*.cpp" "${excluded_scripts}" "gtsam" ${GTSAM_BUILD_TIMING_ALWAYS})
|
||||||
|
|
||||||
target_link_libraries(timeGaussianFactorGraph CppUnitLite)
|
target_link_libraries(timeGaussianFactorGraph CppUnitLite)
|
||||||
|
|
Loading…
Reference in New Issue