Merge pull request #1438 from borglab/feaure/remove_misc_boost

release/4.3a0
Frank Dellaert 2023-02-05 14:19:59 -08:00 committed by GitHub
commit a086e2562c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
70 changed files with 474 additions and 512 deletions

View File

@ -20,19 +20,15 @@ jobs:
# Github Actions requires a single row to be added to the build matrix. # Github Actions requires a single row to be added to the build matrix.
# See https://help.github.com/en/articles/workflow-syntax-for-github-actions. # See https://help.github.com/en/articles/workflow-syntax-for-github-actions.
name: [ name: [
ubuntu-20.04-gcc-7,
ubuntu-20.04-gcc-9, ubuntu-20.04-gcc-9,
ubuntu-20.04-clang-9, ubuntu-20.04-clang-9,
ubuntu-22.04-gcc-11,
ubuntu-22.04-clang-14,
] ]
build_type: [Debug, Release] build_type: [Debug, Release]
build_unstable: [ON] build_unstable: [ON]
include: include:
- name: ubuntu-20.04-gcc-7
os: ubuntu-20.04
compiler: gcc
version: "7"
- name: ubuntu-20.04-gcc-9 - name: ubuntu-20.04-gcc-9
os: ubuntu-20.04 os: ubuntu-20.04
compiler: gcc compiler: gcc
@ -43,14 +39,24 @@ jobs:
compiler: clang compiler: clang
version: "9" version: "9"
- name: ubuntu-22.04-gcc-11
os: ubuntu-22.04
compiler: gcc
version: "11"
- name: ubuntu-22.04-clang-14
os: ubuntu-22.04
compiler: clang
version: "14"
steps: steps:
- name: Checkout - name: Checkout
uses: actions/checkout@v2 uses: actions/checkout@v3
- name: Install Dependencies - name: Install Dependencies
run: | run: |
# LLVM (clang) 9 is not in Bionic's repositories so we add the official LLVM repository. # LLVM (clang) 9/14 is not in Bionic's repositories so we add the official LLVM repository.
if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then if [ "${{ matrix.compiler }}" = "clang" ]; then
# (ipv4|ha).pool.sks-keyservers.net is the SKS GPG global keyserver pool # (ipv4|ha).pool.sks-keyservers.net is the SKS GPG global keyserver pool
# ipv4 avoids potential timeouts because of crappy IPv6 infrastructure # ipv4 avoids potential timeouts because of crappy IPv6 infrastructure
# 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository

View File

@ -14,7 +14,7 @@ jobs:
GTSAM_BUILD_UNSTABLE: ${{ matrix.build_unstable }} GTSAM_BUILD_UNSTABLE: ${{ matrix.build_unstable }}
strategy: strategy:
fail-fast: false fail-fast: true
matrix: matrix:
# Github Actions requires a single row to be added to the build matrix. # Github Actions requires a single row to be added to the build matrix.
# See https://help.github.com/en/articles/workflow-syntax-for-github-actions. # See https://help.github.com/en/articles/workflow-syntax-for-github-actions.
@ -32,20 +32,14 @@ jobs:
steps: steps:
- name: Checkout - name: Checkout
uses: actions/checkout@v2 uses: actions/checkout@v3
- name: Install Dependencies - name: Install Dependencies
run: | run: |
brew install cmake ninja brew install cmake ninja
brew install boost brew install boost
if [ "${{ matrix.compiler }}" = "gcc" ]; then
brew install gcc@${{ matrix.version }}
echo "CC=gcc-${{ matrix.version }}" >> $GITHUB_ENV
echo "CXX=g++-${{ matrix.version }}" >> $GITHUB_ENV
else
sudo xcode-select -switch /Applications/Xcode.app sudo xcode-select -switch /Applications/Xcode.app
echo "CC=clang" >> $GITHUB_ENV echo "CC=clang" >> $GITHUB_ENV
echo "CXX=clang++" >> $GITHUB_ENV echo "CXX=clang++" >> $GITHUB_ENV
fi
- name: Build and Test - name: Build and Test
run: bash .github/scripts/unix.sh -t run: bash .github/scripts/unix.sh -t

View File

@ -14,58 +14,45 @@ jobs:
PYTHON_VERSION: ${{ matrix.python_version }} PYTHON_VERSION: ${{ matrix.python_version }}
strategy: strategy:
fail-fast: false fail-fast: true
matrix: matrix:
# Github Actions requires a single row to be added to the build matrix. # Github Actions requires a single row to be added to the build matrix.
# See https://help.github.com/en/articles/workflow-syntax-for-github-actions. # See https://help.github.com/en/articles/workflow-syntax-for-github-actions.
name: [ name:
ubuntu-20.04-gcc-7, [
ubuntu-20.04-gcc-9, ubuntu-20.04-gcc-9,
ubuntu-20.04-gcc-9-tbb,
ubuntu-20.04-clang-9, ubuntu-20.04-clang-9,
macOS-11-xcode-13.4.1, macOS-11-xcode-13.4.1,
ubuntu-20.04-gcc-7-tbb,
] ]
build_type: [Debug, Release] build_type: [Release]
python_version: [3] python_version: [3]
include: include:
- name: ubuntu-20.04-gcc-7
os: ubuntu-20.04
compiler: gcc
version: "7"
- name: ubuntu-20.04-gcc-9 - name: ubuntu-20.04-gcc-9
os: ubuntu-20.04 os: ubuntu-20.04
compiler: gcc compiler: gcc
version: "9" version: "9"
- name: ubuntu-20.04-clang-9 - name: ubuntu-20.04-gcc-9-tbb
os: ubuntu-20.04 os: ubuntu-20.04
compiler: clang compiler: gcc
version: "9" version: "9"
flag: tbb
# NOTE temporarily added this as it is a required check.
- name: ubuntu-20.04-clang-9 - name: ubuntu-20.04-clang-9
os: ubuntu-20.04 os: ubuntu-20.04
compiler: clang compiler: clang
version: "9" version: "9"
build_type: Debug
python_version: "3"
- name: macOS-11-xcode-13.4.1 - name: macOS-11-xcode-13.4.1
os: macOS-11 os: macOS-11
compiler: xcode compiler: xcode
version: "13.4.1" version: "13.4.1"
- name: ubuntu-20.04-gcc-7-tbb
os: ubuntu-20.04
compiler: gcc
version: "7"
flag: tbb
steps: steps:
- name: Checkout - name: Checkout
uses: actions/checkout@v2 uses: actions/checkout@v3
- name: Install (Linux) - name: Install (Linux)
if: runner.os == 'Linux' if: runner.os == 'Linux'
run: | run: |
@ -98,15 +85,9 @@ jobs:
brew tap ProfFan/robotics brew tap ProfFan/robotics
brew install cmake ninja brew install cmake ninja
brew install boost brew install boost
if [ "${{ matrix.compiler }}" = "gcc" ]; then
brew install gcc@${{ matrix.version }}
echo "CC=gcc-${{ matrix.version }}" >> $GITHUB_ENV
echo "CXX=g++-${{ matrix.version }}" >> $GITHUB_ENV
else
sudo xcode-select -switch /Applications/Xcode.app sudo xcode-select -switch /Applications/Xcode.app
echo "CC=clang" >> $GITHUB_ENV echo "CC=clang" >> $GITHUB_ENV
echo "CXX=clang++" >> $GITHUB_ENV echo "CXX=clang++" >> $GITHUB_ENV
fi
- name: Set GTSAM_WITH_TBB Flag - name: Set GTSAM_WITH_TBB Flag
if: matrix.flag == 'tbb' if: matrix.flag == 'tbb'
run: | run: |

View File

@ -15,78 +15,80 @@ jobs:
BOOST_VERSION: 1.67.0 BOOST_VERSION: 1.67.0
strategy: strategy:
fail-fast: false fail-fast: true
matrix: matrix:
# Github Actions requires a single row to be added to the build matrix. # Github Actions requires a single row to be added to the build matrix.
# See https://help.github.com/en/articles/workflow-syntax-for-github-actions. # See https://help.github.com/en/articles/workflow-syntax-for-github-actions.
name: name:
[ [
ubuntu-gcc-deprecated, ubuntu-clang-deprecated,
ubuntu-gcc-quaternions, ubuntu-clang-quaternions,
ubuntu-gcc-tbb, ubuntu-clang-tbb,
ubuntu-cayleymap, ubuntu-clang-cayleymap,
ubuntu-clang-system-libs,
] ]
build_type: [Debug, Release] build_type: [Debug, Release]
include: include:
- name: ubuntu-gcc-deprecated - name: ubuntu-clang-deprecated
os: ubuntu-20.04 os: ubuntu-22.04
compiler: gcc compiler: clang
version: "9" version: "14"
flag: deprecated flag: deprecated
- name: ubuntu-gcc-quaternions - name: ubuntu-clang-quaternions
os: ubuntu-20.04 os: ubuntu-22.04
compiler: gcc compiler: clang
version: "9" version: "14"
flag: quaternions flag: quaternions
- name: ubuntu-gcc-tbb - name: ubuntu-clang-tbb
os: ubuntu-20.04 os: ubuntu-22.04
compiler: gcc compiler: clang
version: "9" version: "14"
flag: tbb flag: tbb
- name: ubuntu-cayleymap - name: ubuntu-clang-cayleymap
os: ubuntu-20.04 os: ubuntu-22.04
compiler: gcc compiler: clang
version: "9" version: "14"
flag: cayley flag: cayley
- name: ubuntu-system-libs - name: ubuntu-clang-system-libs
os: ubuntu-20.04 os: ubuntu-22.04
compiler: gcc compiler: clang
version: "9" version: "14"
flag: system-libs flag: system
steps: steps:
- name: Checkout - name: Checkout
uses: actions/checkout@v2 uses: actions/checkout@v3
- name: Install (Linux) - name: Install (Linux)
if: runner.os == 'Linux' if: runner.os == 'Linux'
run: | run: |
# LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. sudo apt-get -y update
if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then sudo apt-get -y install software-properties-common
# LLVM (clang) 9/14 is not in 22.04 (jammy)'s repositories so we add the official LLVM repository.
if [ "${{ matrix.compiler }}" = "clang" ]; then
# (ipv4|ha).pool.sks-keyservers.net is the SKS GPG global keyserver pool
# ipv4 avoids potential timeouts because of crappy IPv6 infrastructure
# 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository
# This key is not in the keystore by default for Ubuntu so we need to add it.
LLVM_KEY=15CF4D18AF4F7421
gpg --keyserver keyserver.ubuntu.com --recv-key $LLVM_KEY || gpg --keyserver hkp://keyserver.ubuntu.com:80 --recv-key $LLVM_KEY gpg --keyserver keyserver.ubuntu.com --recv-key $LLVM_KEY || gpg --keyserver hkp://keyserver.ubuntu.com:80 --recv-key $LLVM_KEY
gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - gpg -a --export $LLVM_KEY | sudo apt-key add -
sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" sudo add-apt-repository "deb http://apt.llvm.org/jammy/ llvm-toolchain-jammy main"
fi fi
sudo apt-get -y update
sudo apt-get -y install cmake build-essential pkg-config libpython3-dev python3-numpy libicu-dev sudo apt-get -y install cmake build-essential pkg-config libpython3-dev python3-numpy libicu-dev
if [ "${{ matrix.compiler }}" = "gcc" ]; then
sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib
echo "CC=gcc-${{ matrix.version }}" >> $GITHUB_ENV
echo "CXX=g++-${{ matrix.version }}" >> $GITHUB_ENV
else
sudo apt-get install -y clang-${{ matrix.version }} g++-multilib sudo apt-get install -y clang-${{ matrix.version }} g++-multilib
echo "CC=clang-${{ matrix.version }}" >> $GITHUB_ENV echo "CC=clang-${{ matrix.version }}" >> $GITHUB_ENV
echo "CXX=clang++-${{ matrix.version }}" >> $GITHUB_ENV echo "CXX=clang++-${{ matrix.version }}" >> $GITHUB_ENV
fi
- name: Install Boost - name: Install Boost
if: runner.os == 'Linux' if: runner.os == 'Linux'
@ -97,15 +99,9 @@ jobs:
if: runner.os == 'macOS' if: runner.os == 'macOS'
run: | run: |
brew install cmake ninja boost brew install cmake ninja boost
if [ "${{ matrix.compiler }}" = "gcc" ]; then
brew install gcc@${{ matrix.version }}
echo "CC=gcc-${{ matrix.version }}" >> $GITHUB_ENV
echo "CXX=g++-${{ matrix.version }}" >> $GITHUB_ENV
else
sudo xcode-select -switch /Applications/Xcode_${{ matrix.version }}.app sudo xcode-select -switch /Applications/Xcode_${{ matrix.version }}.app
echo "CC=clang" >> $GITHUB_ENV echo "CC=clang" >> $GITHUB_ENV
echo "CXX=clang++" >> $GITHUB_ENV echo "CXX=clang++" >> $GITHUB_ENV
fi
- name: Set Allow Deprecated Flag - name: Set Allow Deprecated Flag
if: matrix.flag == 'deprecated' if: matrix.flag == 'deprecated'
@ -135,8 +131,11 @@ jobs:
- name: Use system versions of 3rd party libraries - name: Use system versions of 3rd party libraries
if: matrix.flag == 'system' if: matrix.flag == 'system'
run: | run: |
sudo apt-get install libeigen3-dev
echo "GTSAM_USE_SYSTEM_EIGEN=ON" >> $GITHUB_ENV echo "GTSAM_USE_SYSTEM_EIGEN=ON" >> $GITHUB_ENV
echo "GTSAM_USE_SYSTEM_METIS=ON" >> $GITHUB_ENV # TODO(dellaert): This does not work yet?
# sudo apt-get install metis
# echo "GTSAM_USE_SYSTEM_METIS=ON" >> $GITHUB_ENV
- name: Build & Test - name: Build & Test
run: | run: |

View File

@ -16,7 +16,7 @@ jobs:
BOOST_EXE: boost_1_72_0-msvc-14.2 BOOST_EXE: boost_1_72_0-msvc-14.2
strategy: strategy:
fail-fast: false fail-fast: true
matrix: matrix:
# Github Actions requires a single row to be added to the build matrix. # Github Actions requires a single row to be added to the build matrix.
# See https://help.github.com/en/articles/workflow-syntax-for-github-actions. # See https://help.github.com/en/articles/workflow-syntax-for-github-actions.
@ -94,7 +94,7 @@ jobs:
echo "BOOST_ROOT=$BOOST_PATH" >> $env:GITHUB_ENV echo "BOOST_ROOT=$BOOST_PATH" >> $env:GITHUB_ENV
- name: Checkout - name: Checkout
uses: actions/checkout@v2 uses: actions/checkout@v3
- name: Configuration - name: Configuration
run: | run: |

View File

@ -88,6 +88,9 @@ if(MSVC)
WINDOWS_LEAN_AND_MEAN WINDOWS_LEAN_AND_MEAN
NOMINMAX NOMINMAX
) )
list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC
_ENABLE_EXTENDED_ALIGNED_STORAGE
)
# Avoid literally hundreds to thousands of warnings: # Avoid literally hundreds to thousands of warnings:
list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC
/wd4267 # warning C4267: 'initializing': conversion from 'size_t' to 'int', possible loss of data /wd4267 # warning C4267: 'initializing': conversion from 'size_t' to 'int', possible loss of data

View File

@ -31,7 +31,6 @@
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/inference/Symbol.h> #include <gtsam/inference/Symbol.h>
#include <boost/format.hpp>
#include <vector> #include <vector>
using namespace std; using namespace std;
@ -50,8 +49,7 @@ int main(int argc, char* argv[]) {
// Load the SfM data from file // Load the SfM data from file
SfmData mydata = SfmData::FromBalFile(filename); SfmData mydata = SfmData::FromBalFile(filename);
cout << boost::format("read %1% tracks on %2% cameras\n") % cout << "read " << mydata.numberTracks() << " tracks on " << mydata.numberCameras() << " cameras" << endl;
mydata.numberTracks() % mydata.numberCameras();
// Create a factor graph // Create a factor graph
ExpressionFactorGraph graph; ExpressionFactorGraph graph;

View File

@ -23,7 +23,6 @@
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/inference/Symbol.h> #include <gtsam/inference/Symbol.h>
#include <boost/format.hpp>
#include <vector> #include <vector>
using namespace std; using namespace std;
@ -45,7 +44,7 @@ int main (int argc, char* argv[]) {
// Load the SfM data from file // Load the SfM data from file
SfmData mydata = SfmData::FromBalFile(filename); SfmData mydata = SfmData::FromBalFile(filename);
cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.numberTracks() % mydata.numberCameras(); cout << "read " << mydata.numberTracks() << " tracks on " << mydata.numberCameras() << " cameras" << endl;
// Create a factor graph // Create a factor graph
NonlinearFactorGraph graph; NonlinearFactorGraph graph;

View File

@ -26,7 +26,6 @@
#include <gtsam/inference/Ordering.h> #include <gtsam/inference/Ordering.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <vector> #include <vector>
using namespace std; using namespace std;
@ -47,8 +46,7 @@ int main(int argc, char* argv[]) {
// Load the SfM data from file // Load the SfM data from file
SfmData mydata = SfmData::FromBalFile(filename); SfmData mydata = SfmData::FromBalFile(filename);
cout << boost::format("read %1% tracks on %2% cameras\n") % cout << "read " << mydata.numberTracks() << " tracks on " << mydata.numberCameras() << " cameras" << endl;
mydata.numberTracks() % mydata.numberCameras();
// Create a factor graph // Create a factor graph
NonlinearFactorGraph graph; NonlinearFactorGraph graph;
@ -128,9 +126,9 @@ int main(int argc, char* argv[]) {
cout << endl << endl; cout << endl << endl;
cout << "Time comparison by solving " << filename << " results:" << endl; cout << "Time comparison by solving " << filename << " results:" << endl;
cout << boost::format("%1% point tracks and %2% cameras\n") %
mydata.numberTracks() % mydata.numberCameras() cout << mydata.numberTracks() << " point tracks and " << mydata.numberCameras()
<< endl; << " cameras" << endl;
tictoc_print_(); tictoc_print_();
} }

View File

@ -51,7 +51,7 @@ public:
BOOST_CONCEPT_USAGE(IsGroup) { BOOST_CONCEPT_USAGE(IsGroup) {
BOOST_STATIC_ASSERT_MSG( BOOST_STATIC_ASSERT_MSG(
(boost::is_base_of<group_tag, structure_category_tag>::value), (std::is_base_of<group_tag, structure_category_tag>::value),
"This type's structure_category trait does not assert it as a group (or derived)"); "This type's structure_category trait does not assert it as a group (or derived)");
e = traits<G>::Identity(); e = traits<G>::Identity();
e = traits<G>::Compose(g, h); e = traits<G>::Compose(g, h);

View File

@ -266,7 +266,7 @@ public:
BOOST_CONCEPT_USAGE(IsLieGroup) { BOOST_CONCEPT_USAGE(IsLieGroup) {
BOOST_STATIC_ASSERT_MSG( BOOST_STATIC_ASSERT_MSG(
(boost::is_base_of<lie_group_tag, structure_category_tag>::value), (std::is_base_of<lie_group_tag, structure_category_tag>::value),
"This type's trait does not assert it is a Lie group (or derived)"); "This type's trait does not assert it is a Lie group (or derived)");
// group opertations with Jacobians // group opertations with Jacobians

View File

@ -144,7 +144,7 @@ public:
BOOST_CONCEPT_USAGE(IsManifold) { BOOST_CONCEPT_USAGE(IsManifold) {
BOOST_STATIC_ASSERT_MSG( BOOST_STATIC_ASSERT_MSG(
(boost::is_base_of<manifold_tag, structure_category_tag>::value), (std::is_base_of<manifold_tag, structure_category_tag>::value),
"This type's structure_category trait does not assert it as a manifold (or derived)"); "This type's structure_category trait does not assert it as a manifold (or derived)");
BOOST_STATIC_ASSERT(TangentVector::SizeAtCompileTime == dim); BOOST_STATIC_ASSERT(TangentVector::SizeAtCompileTime == dim);

View File

@ -23,9 +23,6 @@
#include <Eigen/SVD> #include <Eigen/SVD>
#include <Eigen/LU> #include <Eigen/LU>
#include <boost/tokenizer.hpp>
#include <boost/format.hpp>
#include <cstdarg> #include <cstdarg>
#include <cstring> #include <cstring>
#include <iomanip> #include <iomanip>
@ -128,8 +125,10 @@ bool linear_dependent(const Matrix& A, const Matrix& B, double tol) {
/* ************************************************************************* */ /* ************************************************************************* */
Vector operator^(const Matrix& A, const Vector & v) { Vector operator^(const Matrix& A, const Vector & v) {
if (A.rows()!=v.size()) throw std::invalid_argument( if (A.rows()!=v.size()) {
boost::str(boost::format("Matrix operator^ : A.m(%d)!=v.size(%d)") % A.rows() % v.size())); throw std::invalid_argument("Matrix operator^ : A.m(" + std::to_string(A.rows()) + ")!=v.size(" +
std::to_string(v.size()) + ")");
}
// Vector vt = v.transpose(); // Vector vt = v.transpose();
// Vector vtA = vt * A; // Vector vtA = vt * A;
// return vtA.transpose(); // return vtA.transpose();
@ -611,11 +610,12 @@ std::string formatMatrixIndented(const std::string& label, const Matrix& matrix,
else else
matrixPrinted << matrix; matrixPrinted << matrix;
const std::string matrixStr = matrixPrinted.str(); const std::string matrixStr = matrixPrinted.str();
boost::tokenizer<boost::char_separator<char> > tok(matrixStr, boost::char_separator<char>("\n"));
// Split the matrix string into lines and indent them
std::string line;
std::istringstream iss(matrixStr);
DenseIndex row = 0; DenseIndex row = 0;
for(const std::string& line: tok) while (std::getline(iss, line)) {
{
assert(row < effectiveRows); assert(row < effectiveRows);
if(row > 0) if(row > 0)
ss << padding; ss << padding;
@ -624,6 +624,7 @@ std::string formatMatrixIndented(const std::string& label, const Matrix& matrix,
ss << "\n"; ss << "\n";
++ row; ++ row;
} }
} else { } else {
ss << "Empty (" << matrix.rows() << "x" << matrix.cols() << ")"; ss << "Empty (" << matrix.rows() << "x" << matrix.cols() << ")";
} }

View File

@ -46,9 +46,11 @@ private:
protected: protected:
typedef std::basic_string<char, std::char_traits<char>, typedef std::basic_string<char, std::char_traits<char>,
tbb::tbb_allocator<char> > String; tbb::tbb_allocator<char> > String;
typedef tbb::tbb_allocator<char> Allocator;
#else #else
protected: protected:
typedef std::string String; typedef std::string String;
typedef std::allocator<char> Allocator;
#endif #endif
protected: protected:

View File

@ -474,7 +474,7 @@ public:
BOOST_CONCEPT_USAGE(IsVectorSpace) { BOOST_CONCEPT_USAGE(IsVectorSpace) {
BOOST_STATIC_ASSERT_MSG( BOOST_STATIC_ASSERT_MSG(
(boost::is_base_of<vector_space_tag, structure_category_tag>::value), (std::is_base_of<vector_space_tag, structure_category_tag>::value),
"This type's trait does not assert it as a vector space (or derived)"); "This type's trait does not assert it as a vector space (or derived)");
r = p + q; r = p + q;
r = -p; r = -p;

View File

@ -20,7 +20,6 @@
#include <gtsam/base/cholesky.h> #include <gtsam/base/cholesky.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <cmath> #include <cmath>
using namespace std; using namespace std;

View File

@ -71,10 +71,10 @@ typename Eigen::Matrix<double, N, 1> numericalGradient(
std::function<double(const X&)> h, const X& x, double delta = 1e-5) { std::function<double(const X&)> h, const X& x, double delta = 1e-5) {
double factor = 1.0 / (2.0 * delta); double factor = 1.0 / (2.0 * delta);
BOOST_STATIC_ASSERT_MSG( static_assert(
(boost::is_base_of<manifold_tag, typename traits<X>::structure_category>::value), (std::is_base_of<manifold_tag, typename traits<X>::structure_category>::value),
"Template argument X must be a manifold type."); "Template argument X must be a manifold type.");
BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type or N must be specified."); static_assert(N>0, "Template argument X must be fixed-size type or N must be specified.");
// Prepare a tangent vector to perturb x with, only works for fixed size // Prepare a tangent vector to perturb x with, only works for fixed size
typename traits<X>::TangentVector d; typename traits<X>::TangentVector d;
@ -111,13 +111,13 @@ typename internal::FixedSizeMatrix<Y, X>::type numericalDerivative11(
std::function<Y(const X&)> h, const X& x, double delta = 1e-5) { std::function<Y(const X&)> h, const X& x, double delta = 1e-5) {
typedef typename internal::FixedSizeMatrix<Y,X>::type Matrix; typedef typename internal::FixedSizeMatrix<Y,X>::type Matrix;
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
typedef traits<Y> TraitsY; typedef traits<Y> TraitsY;
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X>::structure_category>::value),
"Template argument X must be a manifold type."); "Template argument X must be a manifold type.");
BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type or N must be specified."); static_assert(N>0, "Template argument X must be fixed-size type or N must be specified.");
typedef traits<X> TraitsX; typedef traits<X> TraitsX;
// get value at x, and corresponding chart // get value at x, and corresponding chart
@ -165,9 +165,9 @@ typename internal::FixedSizeMatrix<Y,X>::type numericalDerivative11(Y (*h)(const
template<class Y, class X1, class X2, int N = traits<X1>::dimension> template<class Y, class X1, class X2, int N = traits<X1>::dimension>
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative21(const std::function<Y(const X1&, const X2&)>& h, typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative21(const std::function<Y(const X1&, const X2&)>& h,
const X1& x1, const X2& x2, double delta = 1e-5) { const X1& x1, const X2& x2, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X1, N>( return numericalDerivative11<Y, X1, N>(
std::bind(h, std::placeholders::_1, std::cref(x2)), x1, delta); std::bind(h, std::placeholders::_1, std::cref(x2)), x1, delta);
@ -194,9 +194,9 @@ typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative21(Y (*h)(cons
template<class Y, class X1, class X2, int N = traits<X2>::dimension> template<class Y, class X1, class X2, int N = traits<X2>::dimension>
typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative22(std::function<Y(const X1&, const X2&)> h, typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative22(std::function<Y(const X1&, const X2&)> h,
const X1& x1, const X2& x2, double delta = 1e-5) { const X1& x1, const X2& x2, double delta = 1e-5) {
// BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), // static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
// "Template argument X1 must be a manifold type."); // "Template argument X1 must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value),
"Template argument X2 must be a manifold type."); "Template argument X2 must be a manifold type.");
return numericalDerivative11<Y, X2, N>( return numericalDerivative11<Y, X2, N>(
std::bind(h, std::cref(x1), std::placeholders::_1), x2, delta); std::bind(h, std::cref(x1), std::placeholders::_1), x2, delta);
@ -226,9 +226,9 @@ template<class Y, class X1, class X2, class X3, int N = traits<X1>::dimension>
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative31( typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative31(
std::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1,
const X2& x2, const X3& x3, double delta = 1e-5) { const X2& x2, const X3& x3, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X1, N>( return numericalDerivative11<Y, X1, N>(
std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3)), std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3)),
@ -259,9 +259,9 @@ template<class Y, class X1, class X2, class X3, int N = traits<X2>::dimension>
typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative32( typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative32(
std::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1,
const X2& x2, const X3& x3, double delta = 1e-5) { const X2& x2, const X3& x3, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value),
"Template argument X2 must be a manifold type."); "Template argument X2 must be a manifold type.");
return numericalDerivative11<Y, X2, N>( return numericalDerivative11<Y, X2, N>(
std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3)), std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3)),
@ -292,9 +292,9 @@ template<class Y, class X1, class X2, class X3, int N = traits<X3>::dimension>
typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative33( typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative33(
std::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1,
const X2& x2, const X3& x3, double delta = 1e-5) { const X2& x2, const X3& x3, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X3>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X3>::structure_category>::value),
"Template argument X3 must be a manifold type."); "Template argument X3 must be a manifold type.");
return numericalDerivative11<Y, X3, N>( return numericalDerivative11<Y, X3, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1), std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1),
@ -325,9 +325,9 @@ template<class Y, class X1, class X2, class X3, class X4, int N = traits<X1>::di
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative41( typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative41(
std::function<Y(const X1&, const X2&, const X3&, const X4&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X1, N>( return numericalDerivative11<Y, X1, N>(
std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3), std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3),
@ -359,9 +359,9 @@ template<class Y, class X1, class X2, class X3, class X4, int N = traits<X2>::di
typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative42( typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative42(
std::function<Y(const X1&, const X2&, const X3&, const X4&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value),
"Template argument X2 must be a manifold type."); "Template argument X2 must be a manifold type.");
return numericalDerivative11<Y, X2, N>( return numericalDerivative11<Y, X2, N>(
std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3), std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3),
@ -393,9 +393,9 @@ template<class Y, class X1, class X2, class X3, class X4, int N = traits<X3>::di
typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative43( typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative43(
std::function<Y(const X1&, const X2&, const X3&, const X4&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X3>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X3>::structure_category>::value),
"Template argument X3 must be a manifold type."); "Template argument X3 must be a manifold type.");
return numericalDerivative11<Y, X3, N>( return numericalDerivative11<Y, X3, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1, std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1,
@ -427,9 +427,9 @@ template<class Y, class X1, class X2, class X3, class X4, int N = traits<X4>::di
typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative44( typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative44(
std::function<Y(const X1&, const X2&, const X3&, const X4&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X4>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X4>::structure_category>::value),
"Template argument X4 must be a manifold type."); "Template argument X4 must be a manifold type.");
return numericalDerivative11<Y, X4, N>( return numericalDerivative11<Y, X4, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3),
@ -462,9 +462,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, int N = trai
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative51( typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative51(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X1, N>( return numericalDerivative11<Y, X1, N>(
std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3), std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3),
@ -498,9 +498,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, int N = trai
typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative52( typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative52(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X2, N>( return numericalDerivative11<Y, X2, N>(
std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3), std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3),
@ -534,9 +534,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, int N = trai
typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative53( typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative53(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X3, N>( return numericalDerivative11<Y, X3, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1, std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1,
@ -570,9 +570,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, int N = trai
typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative54( typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative54(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X4, N>( return numericalDerivative11<Y, X4, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3),
@ -606,9 +606,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, int N = trai
typename internal::FixedSizeMatrix<Y,X5>::type numericalDerivative55( typename internal::FixedSizeMatrix<Y,X5>::type numericalDerivative55(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X5, N>( return numericalDerivative11<Y, X5, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3),
@ -643,9 +643,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, class X6, in
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative61( typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative61(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X1, N>( return numericalDerivative11<Y, X1, N>(
std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3), std::bind(h, std::placeholders::_1, std::cref(x2), std::cref(x3),
@ -680,9 +680,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, class X6, in
typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative62( typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative62(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X2, N>( return numericalDerivative11<Y, X2, N>(
std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3), std::bind(h, std::cref(x1), std::placeholders::_1, std::cref(x3),
@ -717,9 +717,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, class X6, in
typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative63( typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative63(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X3, N>( return numericalDerivative11<Y, X3, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1, std::bind(h, std::cref(x1), std::cref(x2), std::placeholders::_1,
@ -754,9 +754,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, class X6, in
typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative64( typename internal::FixedSizeMatrix<Y,X4>::type numericalDerivative64(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X4, N>( return numericalDerivative11<Y, X4, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3),
@ -791,9 +791,9 @@ template<class Y, class X1, class X2, class X3, class X4, class X5, class X6, in
typename internal::FixedSizeMatrix<Y,X5>::type numericalDerivative65( typename internal::FixedSizeMatrix<Y,X5>::type numericalDerivative65(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, const X1& x1,
const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) { const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X5, N>( return numericalDerivative11<Y, X5, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3),
@ -829,9 +829,9 @@ typename internal::FixedSizeMatrix<Y, X6>::type numericalDerivative66(
std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h, std::function<Y(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&)> h,
const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6,
double delta = 1e-5) { double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type."); "Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type."); "Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X6, N>( return numericalDerivative11<Y, X6, N>(
std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3), std::bind(h, std::cref(x1), std::cref(x2), std::cref(x3),
@ -860,7 +860,7 @@ inline typename internal::FixedSizeMatrix<Y,X6>::type numericalDerivative66(Y (*
template<class X> template<class X>
inline typename internal::FixedSizeMatrix<X,X>::type numericalHessian(std::function<double(const X&)> f, const X& x, inline typename internal::FixedSizeMatrix<X,X>::type numericalHessian(std::function<double(const X&)> f, const X& x,
double delta = 1e-5) { double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X>::structure_category>::value), static_assert( (std::is_base_of<gtsam::manifold_tag, typename traits<X>::structure_category>::value),
"Template argument X must be a manifold type."); "Template argument X must be a manifold type.");
typedef Eigen::Matrix<double, traits<X>::dimension, 1> VectorD; typedef Eigen::Matrix<double, traits<X>::dimension, 1> VectorD;
typedef std::function<double(const X&)> F; typedef std::function<double(const X&)> F;

View File

@ -19,9 +19,6 @@
#include <gtsam/base/debug.h> #include <gtsam/base/debug.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/algorithm/string/replace.hpp>
#include <boost/format.hpp>
#include <cmath> #include <cmath>
#include <cstddef> #include <cstddef>
#include <cassert> #include <cassert>
@ -78,7 +75,7 @@ size_t TimingOutline::time() const {
/* ************************************************************************* */ /* ************************************************************************* */
void TimingOutline::print(const std::string& outline) const { void TimingOutline::print(const std::string& outline) const {
std::string formattedLabel = label_; std::string formattedLabel = label_;
boost::replace_all(formattedLabel, "_", " "); std::replace(formattedLabel.begin(), formattedLabel.end(), '_', ' ');
std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU (" std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU ("
<< n_ << " times, " << wall() << " wall, " << secs() << " children, min: " << n_ << " times, " << wall() << " wall, " << secs() << " children, min: "
<< min() << " max: " << max() << ")\n"; << min() << " max: " << max() << ")\n";
@ -247,16 +244,14 @@ void toc(size_t id, const char *label) {
if (id != current->id_) { if (id != current->id_) {
gTimingRoot->print(); gTimingRoot->print();
throw std::invalid_argument( throw std::invalid_argument(
(boost::format( "gtsam timing: Mismatched tic/toc: gttoc(\"" + std::string(label) +
"gtsam timing: Mismatched tic/toc: gttoc(\"%s\") called when last tic was \"%s\".") "\") called when last tic was \"" + current->label_ + "\".");
% label % current->label_).str());
} }
if (!current->parent_.lock()) { if (!current->parent_.lock()) {
gTimingRoot->print(); gTimingRoot->print();
throw std::invalid_argument( throw std::invalid_argument(
(boost::format( "gtsam timing: Mismatched tic/toc: extra gttoc(\"" + std::string(label) +
"gtsam timing: Mismatched tic/toc: extra gttoc(\"%s\"), already at the root") "\"), already at the root");
% label).str());
} }
current->toc(); current->toc();
gCurrentTimer = current->parent_; gCurrentTimer = current->parent_;

View File

@ -234,27 +234,27 @@ namespace gtsam {
#if (_MSC_VER < 1800) #if (_MSC_VER < 1800)
#include <boost/math/special_functions/fpclassify.hpp> #include <cmath>
namespace std { namespace std {
template<typename T> inline int isfinite(T a) { template<typename T> inline int isfinite(T a) {
return (int)boost::math::isfinite(a); } return (int)std::isfinite(a); }
template<typename T> inline int isnan(T a) { template<typename T> inline int isnan(T a) {
return (int)boost::math::isnan(a); } return (int)std::isnan(a); }
template<typename T> inline int isinf(T a) { template<typename T> inline int isinf(T a) {
return (int)boost::math::isinf(a); } return (int)std::isinf(a); }
} }
#endif #endif
#include <boost/math/constants/constants.hpp> #include <cmath>
#ifndef M_PI #ifndef M_PI
#define M_PI (boost::math::constants::pi<double>()) #define M_PI (3.14159265358979323846)
#endif #endif
#ifndef M_PI_2 #ifndef M_PI_2
#define M_PI_2 (boost::math::constants::pi<double>() / 2.0) #define M_PI_2 (M_PI / 2.0)
#endif #endif
#ifndef M_PI_4 #ifndef M_PI_4
#define M_PI_4 (boost::math::constants::pi<double>() / 4.0) #define M_PI_4 (M_PI / 4.0)
#endif #endif
#endif #endif

View File

@ -25,10 +25,10 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <functional>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
using namespace boost::placeholders;
namespace { namespace {
noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1); noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1);
@ -119,8 +119,8 @@ TEST(Chebyshev2, InterpolateVector) {
EXPECT(assert_equal(expected, fx(X, actualH), 1e-9)); EXPECT(assert_equal(expected, fx(X, actualH), 1e-9));
// Check derivative // Check derivative
std::function<Vector2(ParameterMatrix<2>)> f = boost::bind( std::function<Vector2(ParameterMatrix<2>)> f = std::bind(
&Chebyshev2::VectorEvaluationFunctor<2>::operator(), fx, _1, nullptr); &Chebyshev2::VectorEvaluationFunctor<2>::operator(), fx, std::placeholders::_1, nullptr);
Matrix numericalH = Matrix numericalH =
numericalDerivative11<Vector2, ParameterMatrix<2>, 2 * N>(f, X); numericalDerivative11<Vector2, ParameterMatrix<2>, 2 * N>(f, X);
EXPECT(assert_equal(numericalH, actualH, 1e-9)); EXPECT(assert_equal(numericalH, actualH, 1e-9));
@ -378,7 +378,7 @@ TEST(Chebyshev2, VectorDerivativeFunctor) {
// Test Jacobian // Test Jacobian
Matrix expectedH = numericalDerivative11<Vector2, ParameterMatrix<M>, M * N>( Matrix expectedH = numericalDerivative11<Vector2, ParameterMatrix<M>, M * N>(
boost::bind(&VecD::operator(), fx, _1, nullptr), X); std::bind(&VecD::operator(), fx, std::placeholders::_1, nullptr), X);
EXPECT(assert_equal(expectedH, actualH, 1e-7)); EXPECT(assert_equal(expectedH, actualH, 1e-7));
} }
@ -410,7 +410,7 @@ TEST(Chebyshev2, VectorDerivativeFunctor2) {
VecD vecd(N, points(0), 0, T); VecD vecd(N, points(0), 0, T);
vecd(X, actualH); vecd(X, actualH);
Matrix expectedH = numericalDerivative11<Vector1, ParameterMatrix<M>, M * N>( Matrix expectedH = numericalDerivative11<Vector1, ParameterMatrix<M>, M * N>(
boost::bind(&VecD::operator(), vecd, _1, nullptr), X); std::bind(&VecD::operator(), vecd, std::placeholders::_1, nullptr), X);
EXPECT(assert_equal(expectedH, actualH, 1e-6)); EXPECT(assert_equal(expectedH, actualH, 1e-6));
} }
@ -427,7 +427,7 @@ TEST(Chebyshev2, ComponentDerivativeFunctor) {
EXPECT_DOUBLES_EQUAL(0, fx(X, actualH), 1e-8); EXPECT_DOUBLES_EQUAL(0, fx(X, actualH), 1e-8);
Matrix expectedH = numericalDerivative11<double, ParameterMatrix<M>, M * N>( Matrix expectedH = numericalDerivative11<double, ParameterMatrix<M>, M * N>(
boost::bind(&CompFunc::operator(), fx, _1, nullptr), X); std::bind(&CompFunc::operator(), fx, std::placeholders::_1, nullptr), X);
EXPECT(assert_equal(expectedH, actualH, 1e-7)); EXPECT(assert_equal(expectedH, actualH, 1e-7));
} }

View File

@ -24,6 +24,7 @@
#include <algorithm> #include <algorithm>
#include <map> #include <map>
#include <string> #include <string>
#include <iomanip>
#include <vector> #include <vector>
namespace gtsam { namespace gtsam {
@ -162,7 +163,9 @@ namespace gtsam {
const typename Base::LabelFormatter& labelFormatter = const typename Base::LabelFormatter& labelFormatter =
&DefaultFormatter) const { &DefaultFormatter) const {
auto valueFormatter = [](const double& v) { auto valueFormatter = [](const double& v) {
return (boost::format("%4.8g") % v).str(); std::stringstream ss;
ss << std::setw(4) << std::setprecision(8) << v;
return ss.str();
}; };
Base::print(s, labelFormatter, valueFormatter); Base::print(s, labelFormatter, valueFormatter);
} }

View File

@ -22,7 +22,6 @@
#include <gtsam/discrete/DecisionTree.h> #include <gtsam/discrete/DecisionTree.h>
#include <algorithm> #include <algorithm>
#include <boost/format.hpp>
#include <cmath> #include <cmath>
#include <fstream> #include <fstream>
@ -33,6 +32,7 @@
#include <string> #include <string>
#include <vector> #include <vector>
#include <optional> #include <optional>
#include <cassert>
namespace gtsam { namespace gtsam {
@ -192,8 +192,8 @@ namespace gtsam {
~Choice() override { ~Choice() override {
#ifdef DT_DEBUG_MEMORY #ifdef DT_DEBUG_MEMORY
std::std::cout << Node::nrNodes << " destructing (Choice) " << this->id() std::cout << Node::nrNodes << " destructing (Choice) " << this->id()
<< std::std::endl; << std::endl;
#endif #endif
} }
@ -282,9 +282,9 @@ namespace gtsam {
const ValueFormatter& valueFormatter) const override { const ValueFormatter& valueFormatter) const override {
std::cout << s << " Choice("; std::cout << s << " Choice(";
std::cout << labelFormatter(label_) << ") " << std::endl; std::cout << labelFormatter(label_) << ") " << std::endl;
for (size_t i = 0; i < branches_.size(); i++) for (size_t i = 0; i < branches_.size(); i++) {
branches_[i]->print((boost::format("%s %d") % s % i).str(), branches_[i]->print(s + " " + std::to_string(i), labelFormatter, valueFormatter);
labelFormatter, valueFormatter); }
} }
/** output to graphviz (as a a graph) */ /** output to graphviz (as a a graph) */
@ -643,11 +643,8 @@ namespace gtsam {
// Create a simple choice node with values as leaves. // Create a simple choice node with values as leaves.
if (size != nrChoices) { if (size != nrChoices) {
std::cout << "Trying to create DD on " << begin->first << std::endl; std::cout << "Trying to create DD on " << begin->first << std::endl;
std::cout << boost::format( std::cout << "DecisionTree::create: expected " << nrChoices
"DecisionTree::create: expected %d values but got %d " << " values but got " << size << " instead" << std::endl;
"instead") %
nrChoices % size
<< std::endl;
throw std::invalid_argument("DecisionTree::create invalid argument"); throw std::invalid_argument("DecisionTree::create invalid argument");
} }
auto choice = std::make_shared<Choice>(begin->first, endY - beginY); auto choice = std::make_shared<Choice>(begin->first, endY - beginY);

View File

@ -22,7 +22,6 @@
#include <gtsam/discrete/DecisionTreeFactor.h> #include <gtsam/discrete/DecisionTreeFactor.h>
#include <gtsam/discrete/DiscreteConditional.h> #include <gtsam/discrete/DiscreteConditional.h>
#include <boost/format.hpp>
#include <utility> #include <utility>
using namespace std; using namespace std;
@ -79,8 +78,9 @@ namespace gtsam {
const KeyFormatter& formatter) const { const KeyFormatter& formatter) const {
cout << s; cout << s;
cout << " f["; cout << " f[";
for (auto&& key : keys()) for (auto&& key : keys()) {
cout << boost::format(" (%1%,%2%),") % formatter(key) % cardinality(key); cout << " (" << formatter(key) << "," << cardinality(key) << "),";
}
cout << " ]" << endl; cout << " ]" << endl;
ADT::print("", formatter); ADT::print("", formatter);
} }
@ -104,13 +104,12 @@ namespace gtsam {
/* ************************************************************************ */ /* ************************************************************************ */
DecisionTreeFactor::shared_ptr DecisionTreeFactor::combine( DecisionTreeFactor::shared_ptr DecisionTreeFactor::combine(
size_t nrFrontals, ADT::Binary op) const { size_t nrFrontals, ADT::Binary op) const {
if (nrFrontals > size()) if (nrFrontals > size()) {
throw invalid_argument( throw invalid_argument(
(boost::format(
"DecisionTreeFactor::combine: invalid number of frontal " "DecisionTreeFactor::combine: invalid number of frontal "
"keys %d, nr.keys=%d") % "keys " +
nrFrontals % size()) std::to_string(nrFrontals) + ", nr.keys=" + std::to_string(size()));
.str()); }
// sum over nrFrontals keys // sum over nrFrontals keys
size_t i; size_t i;
@ -132,13 +131,13 @@ namespace gtsam {
/* ************************************************************************ */ /* ************************************************************************ */
DecisionTreeFactor::shared_ptr DecisionTreeFactor::combine( DecisionTreeFactor::shared_ptr DecisionTreeFactor::combine(
const Ordering& frontalKeys, ADT::Binary op) const { const Ordering& frontalKeys, ADT::Binary op) const {
if (frontalKeys.size() > size()) if (frontalKeys.size() > size()) {
throw invalid_argument( throw invalid_argument(
(boost::format(
"DecisionTreeFactor::combine: invalid number of frontal " "DecisionTreeFactor::combine: invalid number of frontal "
"keys %d, nr.keys=%d") % "keys " +
frontalKeys.size() % size()) std::to_string(frontalKeys.size()) + ", nr.keys=" +
.str()); std::to_string(size()));
}
// sum over nrFrontals keys // sum over nrFrontals keys
size_t i; size_t i;
@ -193,7 +192,9 @@ namespace gtsam {
/* ************************************************************************ */ /* ************************************************************************ */
static std::string valueFormatter(const double& v) { static std::string valueFormatter(const double& v) {
return (boost::format("%4.2g") % v).str(); std::stringstream ss;
ss << std::setw(4) << std::setprecision(2) << std::fixed << v;
return ss.str();
} }
/** output to graphviz format, stream version */ /** output to graphviz format, stream version */

View File

@ -17,7 +17,6 @@
*/ */
#include <iostream> #include <iostream>
#include <boost/format.hpp> // for key names
#include "DiscreteKey.h" #include "DiscreteKey.h"
namespace gtsam { namespace gtsam {
@ -26,7 +25,7 @@ namespace gtsam {
DiscreteKeys::DiscreteKeys(const vector<int>& cs) { DiscreteKeys::DiscreteKeys(const vector<int>& cs) {
for (size_t i = 0; i < cs.size(); i++) { for (size_t i = 0; i < cs.size(); i++) {
string name = boost::str(boost::format("v%1%") % i); string name = "v" + std::to_string(i);
push_back(DiscreteKey(i, cs[i])); push_back(DiscreteKey(i, cs[i]));
} }
} }

View File

@ -25,8 +25,6 @@
#include <gtsam/discrete/DecisionTree-inl.h> // for convert only #include <gtsam/discrete/DecisionTree-inl.h> // for convert only
#define DISABLE_TIMING #define DISABLE_TIMING
#include <boost/tokenizer.hpp>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <gtsam/discrete/Signature.h> #include <gtsam/discrete/Signature.h>
@ -81,8 +79,8 @@ void resetCounts() {
} }
void printCounts(const string& s) { void printCounts(const string& s) {
#ifndef DISABLE_TIMING #ifndef DISABLE_TIMING
cout << boost::format("%s: %3d muls, %3d adds, %g ms.") % s % muls % adds % cout << s << ": " << std::setw(3) << muls << " muls, " <<
(1000 * elapsed) std::setw(3) << adds << " adds, " << 1000 * elapsed << " ms."
<< endl; << endl;
#endif #endif
resetCounts(); resetCounts();
@ -133,7 +131,9 @@ ADT create(const Signature& signature) {
ADT p(signature.discreteKeys(), signature.cpt()); ADT p(signature.discreteKeys(), signature.cpt());
static size_t count = 0; static size_t count = 0;
const DiscreteKey& key = signature.key(); const DiscreteKey& key = signature.key();
string DOTfile = (boost::format("CPT-%03d-%d") % ++count % key.first).str(); std::stringstream ss;
ss << "CPT-" << std::setw(3) << std::setfill('0') << ++count << "-" << key.first;
string DOTfile = ss.str();
dot(p, DOTfile); dot(p, DOTfile);
return p; return p;
} }

View File

@ -26,6 +26,8 @@
#include <gtsam/discrete/DecisionTree-inl.h> #include <gtsam/discrete/DecisionTree-inl.h>
#include <gtsam/discrete/Signature.h> #include <gtsam/discrete/Signature.h>
#include <iomanip>
using std::vector; using std::vector;
using std::string; using std::string;
using std::map; using std::map;
@ -50,7 +52,9 @@ struct CrazyDecisionTree : public DecisionTree<string, Crazy> {
void print(const std::string& s = "") const { void print(const std::string& s = "") const {
auto keyFormatter = [](const std::string& s) { return s; }; auto keyFormatter = [](const std::string& s) { return s; };
auto valueFormatter = [](const Crazy& v) { auto valueFormatter = [](const Crazy& v) {
return (boost::format("{%d,%4.2g}") % v.a % v.b).str(); std::stringstream ss;
ss << "{" << v.a << "," << std::setw(4) << std::setprecision(2) << v.b << "}";
return ss.str();
}; };
DecisionTree<string, Crazy>::print("", keyFormatter, valueFormatter); DecisionTree<string, Crazy>::print("", keyFormatter, valueFormatter);
} }
@ -86,7 +90,7 @@ struct DT : public DecisionTree<string, int> {
void print(const std::string& s = "") const { void print(const std::string& s = "") const {
auto keyFormatter = [](const std::string& s) { return s; }; auto keyFormatter = [](const std::string& s) { return s; };
auto valueFormatter = [](const int& v) { auto valueFormatter = [](const int& v) {
return (boost::format("%d") % v).str(); return std::to_string(v);
}; };
std::cout << s; std::cout << s;
Base::print("", keyFormatter, valueFormatter); Base::print("", keyFormatter, valueFormatter);

View File

@ -24,8 +24,6 @@
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <gtsam/base/lieProxies.h> #include <gtsam/base/lieProxies.h>
#include <boost/math/constants/constants.hpp>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
using namespace std; using namespace std;
@ -195,7 +193,7 @@ TEST( Rot3, retract)
/* ************************************************************************* */ /* ************************************************************************* */
TEST( Rot3, log) { TEST( Rot3, log) {
static const double PI = boost::math::constants::pi<double>(); static const double PI = std::acos(-1.0);
Vector w; Vector w;
Rot3 R; Rot3 R;

View File

@ -20,8 +20,6 @@
#include <gtsam/discrete/DecisionTreeFactor.h> #include <gtsam/discrete/DecisionTreeFactor.h>
#include <gtsam/hybrid/HybridFactorGraph.h> #include <gtsam/hybrid/HybridFactorGraph.h>
#include <boost/format.hpp>
namespace gtsam { namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -22,7 +22,6 @@
#include <gtsam/hybrid/HybridFactor.h> #include <gtsam/hybrid/HybridFactor.h>
#include <gtsam/inference/FactorGraph.h> #include <gtsam/inference/FactorGraph.h>
#include <boost/format.hpp>
#include <unordered_map> #include <unordered_map>
namespace gtsam { namespace gtsam {

View File

@ -27,7 +27,6 @@
#include <gtsam/nonlinear/Symbol.h> #include <gtsam/nonlinear/Symbol.h>
#include <algorithm> #include <algorithm>
#include <boost/format.hpp>
#include <cmath> #include <cmath>
#include <limits> #include <limits>
#include <vector> #include <vector>
@ -194,7 +193,7 @@ class MixtureFactor : public HybridFactor {
std::cout << "\nMixtureFactor\n"; std::cout << "\nMixtureFactor\n";
auto valueFormatter = [](const sharedFactor& v) { auto valueFormatter = [](const sharedFactor& v) {
if (v) { if (v) {
return (boost::format("Nonlinear factor on %d keys") % v->size()).str(); return "Nonlinear factor on " + std::to_string(v->size()) + " keys";
} else { } else {
return std::string("nullptr"); return std::string("nullptr");
} }

View File

@ -209,9 +209,13 @@ struct EliminationData {
// Fill nodes index - we do this here instead of calling insertRoot at the end to avoid // Fill nodes index - we do this here instead of calling insertRoot at the end to avoid
// putting orphan subtrees in the index - they'll already be in the index of the ISAM2 // putting orphan subtrees in the index - they'll already be in the index of the ISAM2
// object they're added to. // object they're added to.
for (const Key& j: myData.bayesTreeNode->conditional()->frontals()) for (const Key& j : myData.bayesTreeNode->conditional()->frontals()) {
#ifdef GTSAM_USE_TBB
nodesIndex_.insert({j, myData.bayesTreeNode});
#else
nodesIndex_.emplace(j, myData.bayesTreeNode); nodesIndex_.emplace(j, myData.bayesTreeNode);
#endif
}
// Store remaining factor in parent's gathered factors // Store remaining factor in parent's gathered factors
if (!eliminationResult.second->empty()) { if (!eliminationResult.second->empty()) {
#ifdef GTSAM_USE_TBB #ifdef GTSAM_USE_TBB

View File

@ -20,7 +20,6 @@
#include <gtsam/inference/Key.h> #include <gtsam/inference/Key.h>
#include <gtsam/inference/LabeledSymbol.h> #include <gtsam/inference/LabeledSymbol.h>
#include <boost/lexical_cast.hpp>
#include <iostream> #include <iostream>
using namespace std; using namespace std;
@ -30,10 +29,12 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
string _defaultKeyFormatter(Key key) { string _defaultKeyFormatter(Key key) {
const Symbol asSymbol(key); const Symbol asSymbol(key);
if (asSymbol.chr() > 0) if (asSymbol.chr() > 0) {
return (string) asSymbol; return (string) asSymbol;
else }
return boost::lexical_cast<string>(key); else {
return std::to_string(key);
}
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -48,10 +49,12 @@ string _multirobotKeyFormatter(Key key) {
return (string) asLabeledSymbol; return (string) asLabeledSymbol;
const Symbol asSymbol(key); const Symbol asSymbol(key);
if (asLabeledSymbol.chr() > 0) if (asLabeledSymbol.chr() > 0) {
return (string) asSymbol; return (string) asSymbol;
else }
return boost::lexical_cast<string>(key); else {
return std::to_string(key);
}
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -17,8 +17,6 @@
#include <gtsam/inference/LabeledSymbol.h> #include <gtsam/inference/LabeledSymbol.h>
#include <boost/format.hpp>
#include <boost/lexical_cast.hpp>
#include <iostream> #include <iostream>
namespace gtsam { namespace gtsam {
@ -73,7 +71,9 @@ void LabeledSymbol::print(const std::string& s) const {
/* ************************************************************************* */ /* ************************************************************************* */
LabeledSymbol::operator std::string() const { LabeledSymbol::operator std::string() const {
return str(boost::format("%c%c%d") % c_ % label_ % j_); char buffer[100];
snprintf(buffer, 100, "%c%c%lu", c_, label_, j_);
return std::string(buffer);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -19,8 +19,6 @@
#include <vector> #include <vector>
#include <limits> #include <limits>
#include <boost/format.hpp>
#include <gtsam/inference/Ordering.h> #include <gtsam/inference/Ordering.h>
#include <gtsam/3rdparty/CCOLAMD/Include/ccolamd.h> #include <gtsam/3rdparty/CCOLAMD/Include/ccolamd.h>
@ -107,9 +105,9 @@ Ordering Ordering::ColamdConstrained(const VariableIndex& variableIndex,
gttic(ccolamd); gttic(ccolamd);
int rv = ccolamd((int) nFactors, (int) nVars, (int) Alen, &A[0], &p[0], int rv = ccolamd((int) nFactors, (int) nVars, (int) Alen, &A[0], &p[0],
knobs, stats, &cmember[0]); knobs, stats, &cmember[0]);
if (rv != 1) if (rv != 1) {
throw runtime_error( throw runtime_error("ccolamd failed with return value " + to_string(rv));
(boost::format("ccolamd failed with return value %1%") % rv).str()); }
} }
// ccolamd_report(stats); // ccolamd_report(stats);

View File

@ -18,12 +18,11 @@
#include <gtsam/inference/Symbol.h> #include <gtsam/inference/Symbol.h>
#include <boost/bind/bind.hpp>
#include <boost/format.hpp>
#include <limits.h> #include <limits.h>
#include <list> #include <list>
#include <iostream> #include <iostream>
#include <sstream>
#include <cstdio>
namespace gtsam { namespace gtsam {
@ -40,8 +39,8 @@ Symbol::Symbol(Key key) :
Key Symbol::key() const { Key Symbol::key() const {
if (j_ > indexMask) { if (j_ > indexMask) {
boost::format msg("Symbol index is too large, j=%d, indexMask=%d"); std::stringstream msg;
msg % j_ % indexMask; msg << "Symbol index is too large, j=" << j_ << ", indexMask=" << indexMask;
throw std::invalid_argument(msg.str()); throw std::invalid_argument(msg.str());
} }
Key key = (Key(c_) << indexBits) | j_; Key key = (Key(c_) << indexBits) | j_;
@ -57,7 +56,9 @@ bool Symbol::equals(const Symbol& expected, double tol) const {
} }
Symbol::operator std::string() const { Symbol::operator std::string() const {
return str(boost::format("%c%d") % c_ % j_); char buffer[10];
snprintf(buffer, 10, "%c%lu", c_, j_);
return std::string(buffer);
} }
static Symbol make(gtsam::Key key) { return Symbol(key);} static Symbol make(gtsam::Key key) { return Symbol(key);}

View File

@ -18,7 +18,6 @@
*/ */
#include <gtsam/linear/ConjugateGradientSolver.h> #include <gtsam/linear/ConjugateGradientSolver.h>
#include <boost/algorithm/string.hpp>
#include <iostream> #include <iostream>
using namespace std; using namespace std;
@ -49,7 +48,9 @@ std::string ConjugateGradientParameters::blasTranslator(const BLASKernel value)
/*****************************************************************************/ /*****************************************************************************/
ConjugateGradientParameters::BLASKernel ConjugateGradientParameters::blasTranslator( ConjugateGradientParameters::BLASKernel ConjugateGradientParameters::blasTranslator(
const std::string &src) { const std::string &src) {
std::string s = src; boost::algorithm::to_upper(s); std::string s = src;
// Convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "GTSAM") return ConjugateGradientParameters::GTSAM; if (s == "GTSAM") return ConjugateGradientParameters::GTSAM;
/* default is SBM */ /* default is SBM */

View File

@ -21,13 +21,10 @@
#include <gtsam/linear/linearExceptions.h> #include <gtsam/linear/linearExceptions.h>
#include <gtsam/hybrid/HybridValues.h> #include <gtsam/hybrid/HybridValues.h>
#include <boost/format.hpp>
#ifdef __GNUC__ #ifdef __GNUC__
#pragma GCC diagnostic push #pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-variable" #pragma GCC diagnostic ignored "-Wunused-variable"
#endif #endif
#include <boost/lambda/lambda.hpp>
#include <boost/lambda/bind.hpp>
#ifdef __GNUC__ #ifdef __GNUC__
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
#endif #endif
@ -104,22 +101,20 @@ namespace gtsam {
void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const { void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const {
cout << s << " p("; cout << s << " p(";
for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) { for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) {
cout << (boost::format("%1%") % (formatter(*it))).str() cout << formatter(*it) << (nrFrontals() > 1 ? " " : "");
<< (nrFrontals() > 1 ? " " : "");
} }
if (nrParents()) { if (nrParents()) {
cout << " |"; cout << " |";
for (const_iterator it = beginParents(); it != endParents(); ++it) { for (const_iterator it = beginParents(); it != endParents(); ++it) {
cout << " " << (boost::format("%1%") % (formatter(*it))).str(); cout << " " << formatter(*it);
} }
} }
cout << ")" << endl; cout << ")" << endl;
cout << formatMatrixIndented(" R = ", R()) << endl; cout << formatMatrixIndented(" R = ", R()) << endl;
for (const_iterator it = beginParents() ; it != endParents() ; ++it) { for (const_iterator it = beginParents() ; it != endParents() ; ++it) {
cout << formatMatrixIndented((boost::format(" S[%1%] = ")%(formatter(*it))).str(), getA(it)) cout << formatMatrixIndented(" S[" + formatter(*it) + "] = ", getA(it)) << endl;
<< endl;
} }
cout << formatMatrixIndented(" d = ", getb(), true) << "\n"; cout << formatMatrixIndented(" d = ", getb(), true) << "\n";
if (nrParents() == 0) { if (nrParents() == 0) {

View File

@ -17,7 +17,6 @@
*/ */
#include <gtsam/linear/GaussianDensity.h> #include <gtsam/linear/GaussianDensity.h>
#include <boost/format.hpp>
#include <string> #include <string>
using std::cout; using std::cout;
@ -37,8 +36,9 @@ GaussianDensity GaussianDensity::FromMeanAndStddev(Key key, const Vector& mean,
void GaussianDensity::print(const string& s, void GaussianDensity::print(const string& s,
const KeyFormatter& formatter) const { const KeyFormatter& formatter) const {
cout << s << ": density on "; cout << s << ": density on ";
for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) {
cout << (boost::format("[%1%]") % (formatter(*it))).str() << " "; cout << "[" << formatter(*it) << "] ";
}
cout << endl; cout << endl;
gtsam::print(mean(), "mean: "); gtsam::print(mean(), "mean: ");
gtsam::print(covariance(), "covariance: "); gtsam::print(covariance(), "covariance: ");

View File

@ -29,8 +29,6 @@
#include <gtsam/base/ThreadsafeException.h> #include <gtsam/base/ThreadsafeException.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <sstream> #include <sstream>
#include <limits> #include <limits>
#include "gtsam/base/Vector.h" #include "gtsam/base/Vector.h"
@ -134,18 +132,14 @@ HessianFactor::HessianFactor(Key j1, Key j2, Key j3, const Matrix& G11,
/* ************************************************************************* */ /* ************************************************************************* */
namespace { namespace {
DenseIndex _getSizeHF(const Vector& m) { static std::vector<DenseIndex> _getSizeHFVec(const std::vector<Vector>& m) {
return m.size();
}
std::vector<DenseIndex> _getSizeHFVec(const std::vector<Vector>& m) {
std::vector<DenseIndex> dims; std::vector<DenseIndex> dims;
for (const Vector& v : m) { for (const Vector& v : m) {
dims.push_back(v.size()); dims.push_back(v.size());
} }
return dims; return dims;
} }
} } // namespace
/* ************************************************************************* */ /* ************************************************************************* */
HessianFactor::HessianFactor(const KeyVector& js, HessianFactor::HessianFactor(const KeyVector& js,

View File

@ -19,7 +19,6 @@
#include <gtsam/linear/IterativeSolver.h> #include <gtsam/linear/IterativeSolver.h>
#include <gtsam/linear/GaussianFactorGraph.h> #include <gtsam/linear/GaussianFactorGraph.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <boost/algorithm/string.hpp>
#include <iostream> #include <iostream>
using namespace std; using namespace std;
@ -57,7 +56,8 @@ ostream& operator<<(ostream &os, const IterativeOptimizationParameters &p) {
IterativeOptimizationParameters::Verbosity IterativeOptimizationParameters::verbosityTranslator( IterativeOptimizationParameters::Verbosity IterativeOptimizationParameters::verbosityTranslator(
const string &src) { const string &src) {
string s = src; string s = src;
boost::algorithm::to_upper(s); // Convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "SILENT") if (s == "SILENT")
return IterativeOptimizationParameters::SILENT; return IterativeOptimizationParameters::SILENT;
else if (s == "COMPLEXITY") else if (s == "COMPLEXITY")

View File

@ -31,8 +31,6 @@
#include <gtsam/base/FastMap.h> #include <gtsam/base/FastMap.h>
#include <gtsam/base/cholesky.h> #include <gtsam/base/cholesky.h>
#include <boost/format.hpp>
#include <cmath> #include <cmath>
#include <sstream> #include <sstream>
#include <stdexcept> #include <stdexcept>
@ -407,7 +405,7 @@ void JacobianFactor::print(const string& s,
if (!s.empty()) if (!s.empty())
cout << s << "\n"; cout << s << "\n";
for (const_iterator key = begin(); key != end(); ++key) { for (const_iterator key = begin(); key != end(); ++key) {
cout << boost::format(" A[%1%] = ") % formatter(*key); cout << " A[" << formatter(*key) << "] = ";
cout << getA(key).format(matlabFormat()) << endl; cout << getA(key).format(matlabFormat()) << endl;
} }
cout << formatMatrixIndented(" b = ", getb(), true) << "\n"; cout << formatMatrixIndented(" b = ", getb(), true) << "\n";

View File

@ -19,8 +19,6 @@
#include <gtsam/linear/NoiseModel.h> #include <gtsam/linear/NoiseModel.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <cmath> #include <cmath>
#include <iostream> #include <iostream>
#include <limits> #include <limits>
@ -606,7 +604,7 @@ Isotropic::shared_ptr Isotropic::Variance(size_t dim, double variance, bool smar
/* ************************************************************************* */ /* ************************************************************************* */
void Isotropic::print(const string& name) const { void Isotropic::print(const string& name) const {
cout << boost::format("isotropic dim=%1% sigma=%2%") % dim() % sigma_ << endl; cout << "isotropic dim=" << dim() << " sigma=" << sigma_ << endl;
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -13,7 +13,6 @@
#include <gtsam/linear/SubgraphPreconditioner.h> #include <gtsam/linear/SubgraphPreconditioner.h>
#include <gtsam/linear/NoiseModel.h> #include <gtsam/linear/NoiseModel.h>
#include <memory> #include <memory>
#include <boost/algorithm/string.hpp>
#include <iostream> #include <iostream>
#include <vector> #include <vector>
@ -41,7 +40,9 @@ void PreconditionerParameters::print(ostream &os) const {
/***************************************************************************************/ /***************************************************************************************/
PreconditionerParameters::Kernel PreconditionerParameters::kernelTranslator(const std::string &src) { PreconditionerParameters::Kernel PreconditionerParameters::kernelTranslator(const std::string &src) {
std::string s = src; boost::algorithm::to_upper(s); std::string s = src;
// convert string s to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "GTSAM") return PreconditionerParameters::GTSAM; if (s == "GTSAM") return PreconditionerParameters::GTSAM;
else if (s == "CHOLMOD") return PreconditionerParameters::CHOLMOD; else if (s == "CHOLMOD") return PreconditionerParameters::CHOLMOD;
/* default is cholmod */ /* default is cholmod */
@ -50,7 +51,9 @@ PreconditionerParameters::Kernel PreconditionerParameters::kernelTranslator(cons
/***************************************************************************************/ /***************************************************************************************/
PreconditionerParameters::Verbosity PreconditionerParameters::verbosityTranslator(const std::string &src) { PreconditionerParameters::Verbosity PreconditionerParameters::verbosityTranslator(const std::string &src) {
std::string s = src; boost::algorithm::to_upper(s); std::string s = src;
// convert string to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "SILENT") return PreconditionerParameters::SILENT; if (s == "SILENT") return PreconditionerParameters::SILENT;
else if (s == "COMPLEXITY") return PreconditionerParameters::COMPLEXITY; else if (s == "COMPLEXITY") return PreconditionerParameters::COMPLEXITY;
else if (s == "ERROR") return PreconditionerParameters::ERROR; else if (s == "ERROR") return PreconditionerParameters::ERROR;

View File

@ -25,7 +25,6 @@
#include <gtsam/linear/SubgraphBuilder.h> #include <gtsam/linear/SubgraphBuilder.h>
#include <gtsam/base/kruskal.h> #include <gtsam/base/kruskal.h>
#include <boost/algorithm/string.hpp>
#include <boost/archive/text_iarchive.hpp> #include <boost/archive/text_iarchive.hpp>
#include <boost/archive/text_oarchive.hpp> #include <boost/archive/text_oarchive.hpp>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
@ -133,7 +132,8 @@ ostream &operator<<(ostream &os, const SubgraphBuilderParameters &p) {
SubgraphBuilderParameters::Skeleton SubgraphBuilderParameters::Skeleton
SubgraphBuilderParameters::skeletonTranslator(const std::string &src) { SubgraphBuilderParameters::skeletonTranslator(const std::string &src) {
std::string s = src; std::string s = src;
boost::algorithm::to_upper(s); // convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "NATURALCHAIN") if (s == "NATURALCHAIN")
return NATURALCHAIN; return NATURALCHAIN;
else if (s == "BFS") else if (s == "BFS")
@ -161,7 +161,8 @@ std::string SubgraphBuilderParameters::skeletonTranslator(Skeleton s) {
SubgraphBuilderParameters::SkeletonWeight SubgraphBuilderParameters::SkeletonWeight
SubgraphBuilderParameters::skeletonWeightTranslator(const std::string &src) { SubgraphBuilderParameters::skeletonWeightTranslator(const std::string &src) {
std::string s = src; std::string s = src;
boost::algorithm::to_upper(s); // convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "EQUAL") if (s == "EQUAL")
return EQUAL; return EQUAL;
else if (s == "RHS") else if (s == "RHS")
@ -196,7 +197,8 @@ SubgraphBuilderParameters::AugmentationWeight
SubgraphBuilderParameters::augmentationWeightTranslator( SubgraphBuilderParameters::augmentationWeightTranslator(
const std::string &src) { const std::string &src) {
std::string s = src; std::string s = src;
boost::algorithm::to_upper(s); // convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "SKELETON") return SKELETON; if (s == "SKELETON") return SKELETON;
// else if (s == "STRETCH") return STRETCH; // else if (s == "STRETCH") return STRETCH;
// else if (s == "GENERALIZED_STRETCH") return GENERALIZED_STRETCH; // else if (s == "GENERALIZED_STRETCH") return GENERALIZED_STRETCH;

View File

@ -18,7 +18,6 @@
#include <gtsam/linear/linearExceptions.h> #include <gtsam/linear/linearExceptions.h>
#include <gtsam/inference/Symbol.h> #include <gtsam/inference/Symbol.h>
#include <boost/format.hpp>
#include <boost/lexical_cast.hpp> #include <boost/lexical_cast.hpp>
namespace gtsam { namespace gtsam {
@ -29,9 +28,8 @@ namespace gtsam {
if(!description_) { if(!description_) {
description_ = String( description_ = String(
"\nIndeterminant linear system detected while working near variable\n" "\nIndeterminant linear system detected while working near variable\n"
+ boost::lexical_cast<String>(j_) + + std::to_string(j_) +
+ " (Symbol: " + boost::lexical_cast<String>( + " (Symbol: " + gtsam::DefaultKeyFormatter(gtsam::Symbol(j_)) + ").\n"
gtsam::DefaultKeyFormatter(gtsam::Symbol(j_))) + ").\n"
"\n\ "\n\
Thrown when a linear system is ill-posed. The most common cause for this\n\ Thrown when a linear system is ill-posed. The most common cause for this\n\
error is having underconstrained variables. Mathematically, the system is\n\ error is having underconstrained variables. Mathematically, the system is\n\
@ -45,22 +43,21 @@ more information.");
/* ************************************************************************* */ /* ************************************************************************* */
const char* InvalidNoiseModel::what() const noexcept { const char* InvalidNoiseModel::what() const noexcept {
if(description_.empty()) if(description_.empty())
description_ = (boost::format( description_ = "A JacobianFactor was attempted to be constructed or modified to use a\n"
"A JacobianFactor was attempted to be constructed or modified to use a\n"
"noise model of incompatible dimension. The JacobianFactor has\n" "noise model of incompatible dimension. The JacobianFactor has\n"
"dimensionality (i.e. length of error vector) %d but the provided noise\n" "dimensionality (i.e. length of error vector) " + std::to_string(factorDims) +
"model has dimensionality %d.") % factorDims % noiseModelDims).str(); " but the provided noise model has dimensionality " + std::to_string(noiseModelDims) + ".";
return description_.c_str(); return description_.c_str();
} }
/* ************************************************************************* */ /* ************************************************************************* */
const char* InvalidMatrixBlock::what() const noexcept { const char* InvalidMatrixBlock::what() const noexcept {
if(description_.empty()) if(description_.empty()) {
description_ = (boost::format( description_ = "A JacobianFactor was attempted to be constructed with a matrix block of\n"
"A JacobianFactor was attempted to be constructed with a matrix block of\n" "inconsistent dimension. The JacobianFactor has " + std::to_string(factorRows) +
"inconsistent dimension. The JacobianFactor has %d rows (i.e. length of\n" " rows (i.e. length of error vector) but the provided matrix block has " +
"error vector) but the provided matrix block has %d rows.") std::to_string(blockRows) + " rows.";
% factorRows % blockRows).str(); }
return description_.c_str(); return description_.c_str();
} }

View File

@ -23,7 +23,6 @@
#include <gtsam/base/types.h> #include <gtsam/base/types.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <boost/algorithm/string.hpp>
#include <string> #include <string>
#include <iostream> #include <iostream>
@ -71,7 +70,8 @@ TEST( GeographicLib, UTM) {
// Obtained by // Obtained by
// http://geographiclib.sourceforge.net/cgi-bin/GeoConvert?input=33.87071+-84.30482000000001&zone=-3&prec=2&option=Submit // http://geographiclib.sourceforge.net/cgi-bin/GeoConvert?input=33.87071+-84.30482000000001&zone=-3&prec=2&option=Submit
auto actual = UTMUPS::EncodeZone(zone, northp); auto actual = UTMUPS::EncodeZone(zone, northp);
boost::to_upper(actual); // transform to upper case
std::transform(actual.begin(), actual.end(), actual.begin(), ::toupper);
EXPECT(actual=="16N"); EXPECT(actual=="16N");
EXPECT_DOUBLES_EQUAL(749305.58, x, 1e-2); EXPECT_DOUBLES_EQUAL(749305.58, x, 1e-2);
EXPECT_DOUBLES_EQUAL(3751090.08, y, 1e-2); EXPECT_DOUBLES_EQUAL(3751090.08, y, 1e-2);

View File

@ -24,13 +24,13 @@
#include <gtsam/linear/GaussianFactorGraph.h> #include <gtsam/linear/GaussianFactorGraph.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <boost/algorithm/string.hpp>
namespace gtsam { namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
DoglegParams::VerbosityDL DoglegParams::verbosityDLTranslator(const std::string &verbosityDL) const { DoglegParams::VerbosityDL DoglegParams::verbosityDLTranslator(const std::string &verbosityDL) const {
std::string s = verbosityDL; boost::algorithm::to_upper(s); std::string s = verbosityDL;
// convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "SILENT") return DoglegParams::SILENT; if (s == "SILENT") return DoglegParams::SILENT;
if (s == "VERBOSE") return DoglegParams::VERBOSE; if (s == "VERBOSE") return DoglegParams::VERBOSE;

View File

@ -16,7 +16,6 @@
*/ */
#include <gtsam/nonlinear/ISAM2Params.h> #include <gtsam/nonlinear/ISAM2Params.h>
#include <boost/algorithm/string.hpp>
using namespace std; using namespace std;
@ -46,7 +45,8 @@ DoglegOptimizerImpl::TrustRegionAdaptationMode
ISAM2DoglegParams::adaptationModeTranslator( ISAM2DoglegParams::adaptationModeTranslator(
const string& adaptationMode) const { const string& adaptationMode) const {
string s = adaptationMode; string s = adaptationMode;
boost::algorithm::to_upper(s); // convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "SEARCH_EACH_ITERATION") if (s == "SEARCH_EACH_ITERATION")
return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; return DoglegOptimizerImpl::SEARCH_EACH_ITERATION;
if (s == "ONE_STEP_PER_ITERATION") if (s == "ONE_STEP_PER_ITERATION")
@ -60,7 +60,8 @@ ISAM2DoglegParams::adaptationModeTranslator(
ISAM2Params::Factorization ISAM2Params::factorizationTranslator( ISAM2Params::Factorization ISAM2Params::factorizationTranslator(
const string& str) { const string& str) {
string s = str; string s = str;
boost::algorithm::to_upper(s); // convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "QR") return ISAM2Params::QR; if (s == "QR") return ISAM2Params::QR;
if (s == "CHOLESKY") return ISAM2Params::CHOLESKY; if (s == "CHOLESKY") return ISAM2Params::CHOLESKY;

View File

@ -21,7 +21,7 @@
#include <gtsam/linear/GaussianFactorGraph.h> #include <gtsam/linear/GaussianFactorGraph.h>
#include <gtsam/nonlinear/DoglegOptimizerImpl.h> #include <gtsam/nonlinear/DoglegOptimizerImpl.h>
#include <boost/variant.hpp>
#include <string> #include <string>
namespace gtsam { namespace gtsam {

View File

@ -27,8 +27,6 @@
#include <gtsam/nonlinear/ISAM2Params.h> #include <gtsam/nonlinear/ISAM2Params.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <boost/variant.hpp>
namespace gtsam { namespace gtsam {
/** /**

View File

@ -28,11 +28,10 @@
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <cmath> #include <cmath>
#include <fstream> #include <fstream>
#include <iostream> #include <iostream>
#include <iomanip>
#include <limits> #include <limits>
#include <string> #include <string>
@ -62,7 +61,8 @@ LevenbergMarquardtOptimizer::LevenbergMarquardtOptimizer(const NonlinearFactorGr
/* ************************************************************************* */ /* ************************************************************************* */
void LevenbergMarquardtOptimizer::initTime() { void LevenbergMarquardtOptimizer::initTime() {
startTime_ = boost::posix_time::microsec_clock::universal_time(); // use chrono to measure time in microseconds
startTime_ = std::chrono::high_resolution_clock::now();
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -104,9 +104,12 @@ inline void LevenbergMarquardtOptimizer::writeLogFile(double currentError){
if (!params_.logFile.empty()) { if (!params_.logFile.empty()) {
ofstream os(params_.logFile.c_str(), ios::app); ofstream os(params_.logFile.c_str(), ios::app);
boost::posix_time::ptime currentTime = boost::posix_time::microsec_clock::universal_time(); // use chrono to measure time in microseconds
auto currentTime = std::chrono::high_resolution_clock::now();
// Get the time spent in seconds and print it
double timeSpent = std::chrono::duration_cast<std::chrono::microseconds>(currentTime - startTime_).count() / 1e6;
os << /*inner iterations*/ currentState->totalNumberInnerIterations << "," os << /*inner iterations*/ currentState->totalNumberInnerIterations << ","
<< 1e-6 * (currentTime - startTime_).total_microseconds() << "," << timeSpent << ","
<< /*current error*/ currentError << "," << currentState->lambda << "," << /*current error*/ currentError << "," << currentState->lambda << ","
<< /*outer iterations*/ currentState->iterations << endl; << /*outer iterations*/ currentState->iterations << endl;
} }
@ -218,12 +221,12 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear,
#else #else
double iterationTime = lamda_iteration_timer.elapsed(); double iterationTime = lamda_iteration_timer.elapsed();
#endif #endif
if (currentState->iterations == 0) if (currentState->iterations == 0) {
cout << "iter cost cost_change lambda success iter_time" << endl; cout << "iter cost cost_change lambda success iter_time" << endl;
}
cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d % 3.2e") % currentState->iterations % cout << setw(4) << currentState->iterations << " " << setw(8) << newError << " " << setw(3) << setprecision(2)
newError % costChange % currentState->lambda % systemSolvedSuccessfully % << costChange << " " << setw(3) << setprecision(2) << currentState->lambda << " " << setw(4)
iterationTime << endl; << systemSolvedSuccessfully << " " << setw(3) << setprecision(2) << iterationTime << endl;
} }
if (step_is_successful) { if (step_is_successful) {

View File

@ -23,7 +23,7 @@
#include <gtsam/nonlinear/NonlinearOptimizer.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/nonlinear/LevenbergMarquardtParams.h> #include <gtsam/nonlinear/LevenbergMarquardtParams.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <boost/date_time/posix_time/posix_time.hpp> #include <chrono>
class NonlinearOptimizerMoreOptimizationTest; class NonlinearOptimizerMoreOptimizationTest;
@ -36,7 +36,9 @@ class GTSAM_EXPORT LevenbergMarquardtOptimizer: public NonlinearOptimizer {
protected: protected:
const LevenbergMarquardtParams params_; ///< LM parameters const LevenbergMarquardtParams params_; ///< LM parameters
boost::posix_time::ptime startTime_;
// startTime_ is a chrono time point
std::chrono::time_point<std::chrono::high_resolution_clock> startTime_; ///< time when optimization started
void initTime(); void initTime();

View File

@ -19,7 +19,6 @@
*/ */
#include <gtsam/nonlinear/LevenbergMarquardtParams.h> #include <gtsam/nonlinear/LevenbergMarquardtParams.h>
#include <boost/algorithm/string/case_conv.hpp>
#include <iostream> #include <iostream>
#include <string> #include <string>
@ -31,7 +30,8 @@ namespace gtsam {
LevenbergMarquardtParams::VerbosityLM LevenbergMarquardtParams::verbosityLMTranslator( LevenbergMarquardtParams::VerbosityLM LevenbergMarquardtParams::verbosityLMTranslator(
const std::string &src) { const std::string &src) {
std::string s = src; std::string s = src;
boost::algorithm::to_upper(s); // convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "SILENT") if (s == "SILENT")
return LevenbergMarquardtParams::SILENT; return LevenbergMarquardtParams::SILENT;
if (s == "SUMMARY") if (s == "SUMMARY")

View File

@ -18,7 +18,6 @@
#include <gtsam/hybrid/HybridValues.h> #include <gtsam/hybrid/HybridValues.h>
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <boost/format.hpp>
namespace gtsam { namespace gtsam {
@ -96,12 +95,12 @@ NoiseModelFactor::shared_ptr NoiseModelFactor::cloneWithNewNoiseModel(
/* ************************************************************************* */ /* ************************************************************************* */
static void check(const SharedNoiseModel& noiseModel, size_t m) { static void check(const SharedNoiseModel& noiseModel, size_t m) {
if (noiseModel && m != noiseModel->dim()) if (noiseModel && m != noiseModel->dim()) {
throw std::invalid_argument( throw std::invalid_argument(
boost::str( "NoiseModelFactor: NoiseModel has dimension " +
boost::format( std::to_string(noiseModel->dim()) +
"NoiseModelFactor: NoiseModel has dimension %1% instead of %2%.") " instead of " + std::to_string(m) + ".");
% noiseModel->dim() % m)); }
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -9,7 +9,6 @@
*/ */
#include <gtsam/nonlinear/NonlinearOptimizerParams.h> #include <gtsam/nonlinear/NonlinearOptimizerParams.h>
#include <boost/algorithm/string.hpp>
namespace gtsam { namespace gtsam {
@ -17,7 +16,8 @@ namespace gtsam {
NonlinearOptimizerParams::Verbosity NonlinearOptimizerParams::verbosityTranslator( NonlinearOptimizerParams::Verbosity NonlinearOptimizerParams::verbosityTranslator(
const std::string &src) { const std::string &src) {
std::string s = src; std::string s = src;
boost::algorithm::to_upper(s); // Convert to upper case
std::transform(s.begin(), s.end(), s.begin(), ::toupper);
if (s == "SILENT") if (s == "SILENT")
return NonlinearOptimizerParams::SILENT; return NonlinearOptimizerParams::SILENT;
if (s == "ERROR") if (s == "ERROR")

View File

@ -338,7 +338,8 @@ namespace gtsam {
// supplied \c filter function. // supplied \c filter function.
template<class ValueType> template<class ValueType>
static bool filterHelper(const std::function<bool(Key)> filter, const ConstKeyValuePair& key_value) { static bool filterHelper(const std::function<bool(Key)> filter, const ConstKeyValuePair& key_value) {
BOOST_STATIC_ASSERT((!boost::is_same<ValueType, Value>::value)); // static_assert if ValueType is type: Value
static_assert(!std::is_same<Value, ValueType>::value, "ValueType must not be type: Value to use this filter");
// Filter and check the type // Filter and check the type
return filter(key_value.key) && (dynamic_cast<const GenericValue<ValueType>*>(&key_value.value)); return filter(key_value.key) && (dynamic_cast<const GenericValue<ValueType>*>(&key_value.value));
} }

View File

@ -17,16 +17,17 @@
*/ */
#pragma once #pragma once
#include <gtsam/config.h> // Configuration from CMake #include <gtsam/config.h> // Configuration from CMake
#include <gtsam/nonlinear/internal/JacobianMap.h> #include <gtsam/nonlinear/internal/JacobianMap.h>
#include <gtsam/inference/Key.h> #include <gtsam/inference/Key.h>
#include <gtsam/base/Manifold.h> #include <gtsam/base/Manifold.h>
#include <boost/type_traits/aligned_storage.hpp>
#include <Eigen/Core> #include <Eigen/Core>
#include <iostream> #include <iostream>
#include <optional> #include <optional>
#include <type_traits>
namespace gtsam { namespace gtsam {
namespace internal { namespace internal {
@ -36,8 +37,8 @@ template<int T> struct CallRecord;
/// Storage type for the execution trace. /// Storage type for the execution trace.
/// It enforces the proper alignment in a portable way. /// It enforces the proper alignment in a portable way.
/// Provide a traceSize() sized array of this type to traceExecution as traceStorage. /// Provide a traceSize() sized array of this type to traceExecution as traceStorage.
static const unsigned TraceAlignment = 32; static const unsigned TraceAlignment = 16; // 16 bytes is the default alignment used by Eigen.
typedef boost::aligned_storage<1, TraceAlignment>::type ExecutionTraceStorage; typedef std::aligned_storage<1, TraceAlignment>::type ExecutionTraceStorage;
template<bool UseBlock, typename Derived> template<bool UseBlock, typename Derived>
struct UseBlockIf { struct UseBlockIf {

View File

@ -41,34 +41,42 @@
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
#include <gtsam/base/types.h> #include <gtsam/base/types.h>
#include <boost/filesystem/operations.hpp>
#include <boost/filesystem/path.hpp>
#include <optional> #include <optional>
#include <cmath> #include <cmath>
#include <fstream> #include <fstream>
#include <iostream> #include <iostream>
#include <stdexcept> #include <stdexcept>
#include <string>
#if defined(__GNUC__) && (__GNUC__ == 7)
#include <experimental/filesystem>
namespace fs = std::experimental::filesystem;
#else
#include <filesystem>
namespace fs = std::filesystem;
#endif
using namespace std;
namespace fs = boost::filesystem;
using gtsam::symbol_shorthand::L; using gtsam::symbol_shorthand::L;
using std::cout;
using std::endl;
#define LINESIZE 81920 #define LINESIZE 81920
namespace gtsam { namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
string findExampleDataFile(const string &name) { std::string findExampleDataFile(const std::string &name) {
// Search source tree and installed location // Search source tree and installed location
vector<string> rootsToSearch; std::vector<std::string> rootsToSearch;
// Constants below are defined by CMake, see gtsam/gtsam/CMakeLists.txt // Constants below are defined by CMake, see gtsam/gtsam/CMakeLists.txt
rootsToSearch.push_back(GTSAM_SOURCE_TREE_DATASET_DIR); rootsToSearch.push_back(GTSAM_SOURCE_TREE_DATASET_DIR);
rootsToSearch.push_back(GTSAM_INSTALLED_DATASET_DIR); rootsToSearch.push_back(GTSAM_INSTALLED_DATASET_DIR);
// Search for filename as given, and with .graph and .txt extensions // Search for filename as given, and with .graph and .txt extensions
vector<string> namesToSearch; std::vector<std::string> namesToSearch;
namesToSearch.push_back(name); namesToSearch.push_back(name);
namesToSearch.push_back(name + ".graph"); namesToSearch.push_back(name + ".graph");
namesToSearch.push_back(name + ".txt"); namesToSearch.push_back(name + ".txt");
@ -85,7 +93,7 @@ string findExampleDataFile(const string &name) {
} }
// If we did not return already, then we did not find the file // If we did not return already, then we did not find the file
throw invalid_argument( throw std::invalid_argument(
"gtsam::findExampleDataFile could not find a matching " "gtsam::findExampleDataFile could not find a matching "
"file in\n" GTSAM_SOURCE_TREE_DATASET_DIR "file in\n" GTSAM_SOURCE_TREE_DATASET_DIR
" or\n" GTSAM_INSTALLED_DATASET_DIR " named\n" + " or\n" GTSAM_INSTALLED_DATASET_DIR " named\n" +
@ -94,10 +102,10 @@ string findExampleDataFile(const string &name) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
string createRewrittenFileName(const string &name) { std::string createRewrittenFileName(const std::string &name) {
// Search source tree and installed location // Search source tree and installed location
if (!exists(fs::path(name))) { if (!exists(fs::path(name))) {
throw invalid_argument( throw std::invalid_argument(
"gtsam::createRewrittenFileName could not find a matching file in\n" + "gtsam::createRewrittenFileName could not find a matching file in\n" +
name); name);
} }
@ -113,17 +121,17 @@ string createRewrittenFileName(const string &name) {
// Type for parser functions used in parseLines below. // Type for parser functions used in parseLines below.
template <typename T> template <typename T>
using Parser = using Parser =
std::function<std::optional<T>(istream &is, const string &tag)>; std::function<std::optional<T>(std::istream &is, const std::string &tag)>;
// Parse a file by calling the parse(is, tag) function for every line. // Parse a file by calling the parse(is, tag) function for every line.
// The result of calling the function is ignored, so typically parse function // The result of calling the function is ignored, so typically parse function
// works via a side effect, like adding a factor into a graph etc. // works via a side effect, like adding a factor into a graph etc.
template <typename T> template <typename T>
static void parseLines(const string &filename, Parser<T> parse) { static void parseLines(const std::string &filename, Parser<T> parse) {
ifstream is(filename.c_str()); std::ifstream is(filename.c_str());
if (!is) if (!is)
throw invalid_argument("parse: can not find file " + filename); throw std::invalid_argument("parse: can not find file " + filename);
string tag; std::string tag;
while (is >> tag) { while (is >> tag) {
parse(is, tag); // ignore return value parse(is, tag); // ignore return value
is.ignore(LINESIZE, '\n'); is.ignore(LINESIZE, '\n');
@ -133,10 +141,10 @@ static void parseLines(const string &filename, Parser<T> parse) {
/* ************************************************************************* */ /* ************************************************************************* */
// Parse types T into a size_t-indexed map // Parse types T into a size_t-indexed map
template <typename T> template <typename T>
map<size_t, T> parseToMap(const string &filename, Parser<pair<size_t, T>> parse, std::map<size_t, T> parseToMap(const std::string &filename, Parser<std::pair<size_t, T>> parse,
size_t maxIndex) { size_t maxIndex) {
map<size_t, T> result; std::map<size_t, T> result;
Parser<pair<size_t, T>> emplace = [&](istream &is, const string &tag) { Parser<std::pair<size_t, T>> emplace = [&](std::istream &is, const std::string &tag) {
if (auto t = parse(is, tag)) { if (auto t = parse(is, tag)) {
if (!maxIndex || t->first <= maxIndex) if (!maxIndex || t->first <= maxIndex)
result.emplace(*t); result.emplace(*t);
@ -150,9 +158,9 @@ map<size_t, T> parseToMap(const string &filename, Parser<pair<size_t, T>> parse,
/* ************************************************************************* */ /* ************************************************************************* */
// Parse a file and push results on a vector // Parse a file and push results on a vector
template <typename T> template <typename T>
static vector<T> parseToVector(const string &filename, Parser<T> parse) { static std::vector<T> parseToVector(const std::string &filename, Parser<T> parse) {
vector<T> result; std::vector<T> result;
Parser<T> add = [&result, parse](istream &is, const string &tag) { Parser<T> add = [&result, parse](std::istream &is, const std::string &tag) {
if (auto t = parse(is, tag)) if (auto t = parse(is, tag))
result.push_back(*t); result.push_back(*t);
return std::nullopt; return std::nullopt;
@ -162,7 +170,7 @@ static vector<T> parseToVector(const string &filename, Parser<T> parse) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
std::optional<IndexedPose> parseVertexPose(istream &is, const string &tag) { std::optional<IndexedPose> parseVertexPose(std::istream &is, const std::string &tag) {
if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) {
size_t id; size_t id;
double x, y, yaw; double x, y, yaw;
@ -182,8 +190,8 @@ GTSAM_EXPORT std::map<size_t, Pose2> parseVariables<Pose2>(
} }
/* ************************************************************************* */ /* ************************************************************************* */
std::optional<IndexedLandmark> parseVertexLandmark(istream &is, std::optional<IndexedLandmark> parseVertexLandmark(std::istream &is,
const string &tag) { const std::string &tag) {
if (tag == "VERTEX_XY") { if (tag == "VERTEX_XY") {
size_t id; size_t id;
double x, y; double x, y;
@ -232,7 +240,7 @@ static SharedNoiseModel createNoiseModel(
// v(1)' v(3) v(4); // v(1)' v(3) v(4);
// v(2)' v(4)' v(5) ] // v(2)' v(4)' v(5) ]
if (v(0) == 0.0 || v(3) == 0.0 || v(5) == 0.0) if (v(0) == 0.0 || v(3) == 0.0 || v(5) == 0.0)
throw runtime_error( throw std::runtime_error(
"load2D::readNoiseModel looks like this is not G2O matrix order"); "load2D::readNoiseModel looks like this is not G2O matrix order");
M << v(0), v(1), v(2), v(1), v(3), v(4), v(2), v(4), v(5); M << v(0), v(1), v(2), v(1), v(3), v(4), v(2), v(4), v(5);
break; break;
@ -244,12 +252,12 @@ static SharedNoiseModel createNoiseModel(
// v(1)' v(2) v(5); // v(1)' v(2) v(5);
// v(4)' v(5)' v(3) ] // v(4)' v(5)' v(3) ]
if (v(0) == 0.0 || v(2) == 0.0 || v(3) == 0.0) if (v(0) == 0.0 || v(2) == 0.0 || v(3) == 0.0)
throw invalid_argument( throw std::invalid_argument(
"load2D::readNoiseModel looks like this is not TORO matrix order"); "load2D::readNoiseModel looks like this is not TORO matrix order");
M << v(0), v(1), v(4), v(1), v(2), v(5), v(4), v(5), v(3); M << v(0), v(1), v(4), v(1), v(2), v(5), v(4), v(5), v(3);
break; break;
default: default:
throw runtime_error("load2D: invalid noise format"); throw std::runtime_error("load2D: invalid noise format");
} }
// Now, create a Gaussian noise model // Now, create a Gaussian noise model
@ -267,7 +275,7 @@ static SharedNoiseModel createNoiseModel(
model = noiseModel::Gaussian::Covariance(M, smart); model = noiseModel::Gaussian::Covariance(M, smart);
break; break;
default: default:
throw invalid_argument("load2D: invalid noise format"); throw std::invalid_argument("load2D: invalid noise format");
} }
switch (kernelFunctionType) { switch (kernelFunctionType) {
@ -283,12 +291,12 @@ static SharedNoiseModel createNoiseModel(
noiseModel::mEstimator::Tukey::Create(4.6851), model); noiseModel::mEstimator::Tukey::Create(4.6851), model);
break; break;
default: default:
throw invalid_argument("load2D: invalid kernel function type"); throw std::invalid_argument("load2D: invalid kernel function type");
} }
} }
/* ************************************************************************* */ /* ************************************************************************* */
std::optional<IndexedEdge> parseEdge(istream &is, const string &tag) { std::optional<IndexedEdge> parseEdge(std::istream &is, const std::string &tag) {
if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") || if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") ||
(tag == "ODOMETRY")) { (tag == "ODOMETRY")) {
@ -316,7 +324,7 @@ template <typename T> struct ParseFactor : ParseMeasurement<T> {
// We parse a measurement then convert // We parse a measurement then convert
typename std::optional<typename BetweenFactor<T>::shared_ptr> typename std::optional<typename BetweenFactor<T>::shared_ptr>
operator()(istream &is, const string &tag) { operator()(std::istream &is, const std::string &tag) {
if (auto m = ParseMeasurement<T>::operator()(is, tag)) if (auto m = ParseMeasurement<T>::operator()(is, tag))
return std::make_shared<BetweenFactor<T>>( return std::make_shared<BetweenFactor<T>>(
m->key1(), m->key2(), m->measured(), m->noiseModel()); m->key1(), m->key2(), m->measured(), m->noiseModel());
@ -341,8 +349,8 @@ template <> struct ParseMeasurement<Pose2> {
SharedNoiseModel model; SharedNoiseModel model;
// The actual parser // The actual parser
std::optional<BinaryMeasurement<Pose2>> operator()(istream &is, std::optional<BinaryMeasurement<Pose2>> operator()(std::istream &is,
const string &tag) { const std::string &tag) {
auto edge = parseEdge(is, tag); auto edge = parseEdge(is, tag);
if (!edge) if (!edge)
return std::nullopt; return std::nullopt;
@ -353,7 +361,7 @@ template <> struct ParseMeasurement<Pose2> {
// optional filter // optional filter
size_t id1, id2; size_t id1, id2;
tie(id1, id2) = edge->first; std::tie(id1, id2) = edge->first;
if (maxIndex && (id1 > maxIndex || id2 > maxIndex)) if (maxIndex && (id1 > maxIndex || id2 > maxIndex))
return std::nullopt; return std::nullopt;
@ -375,7 +383,7 @@ template <> struct ParseMeasurement<Pose2> {
std::shared_ptr<Sampler> createSampler(const SharedNoiseModel &model) { std::shared_ptr<Sampler> createSampler(const SharedNoiseModel &model) {
auto noise = std::dynamic_pointer_cast<noiseModel::Diagonal>(model); auto noise = std::dynamic_pointer_cast<noiseModel::Diagonal>(model);
if (!noise) if (!noise)
throw invalid_argument("gtsam::load: invalid noise model for adding noise" throw std::invalid_argument("gtsam::load: invalid noise model for adding noise"
"(current version assumes diagonal noise model)!"); "(current version assumes diagonal noise model)!");
return std::shared_ptr<Sampler>(new Sampler(noise)); return std::shared_ptr<Sampler>(new Sampler(noise));
} }
@ -447,7 +455,7 @@ template <> struct ParseMeasurement<BearingRange2D> {
// The actual parser // The actual parser
std::optional<BinaryMeasurement<BearingRange2D>> std::optional<BinaryMeasurement<BearingRange2D>>
operator()(istream &is, const string &tag) { operator()(std::istream &is, const std::string &tag) {
if (tag != "BR" && tag != "LANDMARK") if (tag != "BR" && tag != "LANDMARK")
return std::nullopt; return std::nullopt;
@ -497,14 +505,14 @@ template <> struct ParseMeasurement<BearingRange2D> {
}; };
/* ************************************************************************* */ /* ************************************************************************* */
GraphAndValues load2D(const string &filename, SharedNoiseModel model, GraphAndValues load2D(const std::string &filename, SharedNoiseModel model,
size_t maxIndex, bool addNoise, bool smart, size_t maxIndex, bool addNoise, bool smart,
NoiseFormat noiseFormat, NoiseFormat noiseFormat,
KernelFunctionType kernelFunctionType) { KernelFunctionType kernelFunctionType) {
// Single pass for poses and landmarks. // Single pass for poses and landmarks.
auto initial = std::make_shared<Values>(); auto initial = std::make_shared<Values>();
Parser<int> insert = [maxIndex, &initial](istream &is, const string &tag) { Parser<int> insert = [maxIndex, &initial](std::istream &is, const std::string &tag) {
if (auto indexedPose = parseVertexPose(is, tag)) { if (auto indexedPose = parseVertexPose(is, tag)) {
if (!maxIndex || indexedPose->first <= maxIndex) if (!maxIndex || indexedPose->first <= maxIndex)
initial->insert(indexedPose->first, indexedPose->second); initial->insert(indexedPose->first, indexedPose->second);
@ -529,7 +537,7 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model,
// Combine in a single parser that adds factors to `graph`, but also inserts // Combine in a single parser that adds factors to `graph`, but also inserts
// new variables into `initial` when needed. // new variables into `initial` when needed.
Parser<int> parse = [&](istream &is, const string &tag) { Parser<int> parse = [&](std::istream &is, const std::string &tag) {
if (auto f = parseBetweenFactor(is, tag)) { if (auto f = parseBetweenFactor(is, tag)) {
graph->push_back(*f); graph->push_back(*f);
@ -560,19 +568,20 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model,
parseLines(filename, parse); parseLines(filename, parse);
return make_pair(graph, initial); return {graph, initial};
} }
/* ************************************************************************* */ /* ************************************************************************* */
GraphAndValues load2D(pair<string, SharedNoiseModel> dataset, size_t maxIndex, GraphAndValues load2D(std::pair<std::string, SharedNoiseModel> dataset,
bool addNoise, bool smart, NoiseFormat noiseFormat, size_t maxIndex, bool addNoise, bool smart,
NoiseFormat noiseFormat,
KernelFunctionType kernelFunctionType) { KernelFunctionType kernelFunctionType) {
return load2D(dataset.first, dataset.second, maxIndex, addNoise, smart, return load2D(dataset.first, dataset.second, maxIndex, addNoise, smart,
noiseFormat, kernelFunctionType); noiseFormat, kernelFunctionType);
} }
/* ************************************************************************* */ /* ************************************************************************* */
GraphAndValues load2D_robust(const string &filename, GraphAndValues load2D_robust(const std::string &filename,
const noiseModel::Base::shared_ptr &model, const noiseModel::Base::shared_ptr &model,
size_t maxIndex) { size_t maxIndex) {
return load2D(filename, model, maxIndex); return load2D(filename, model, maxIndex);
@ -581,9 +590,9 @@ GraphAndValues load2D_robust(const string &filename,
/* ************************************************************************* */ /* ************************************************************************* */
void save2D(const NonlinearFactorGraph &graph, const Values &config, void save2D(const NonlinearFactorGraph &graph, const Values &config,
const noiseModel::Diagonal::shared_ptr model, const noiseModel::Diagonal::shared_ptr model,
const string &filename) { const std::string &filename) {
fstream stream(filename.c_str(), fstream::out); std::fstream stream(filename.c_str(), std::fstream::out);
// save poses // save poses
for (const auto &key_pose : config.extract<Pose2>()) { for (const auto &key_pose : config.extract<Pose2>()) {
@ -612,7 +621,7 @@ void save2D(const NonlinearFactorGraph &graph, const Values &config,
} }
/* ************************************************************************* */ /* ************************************************************************* */
GraphAndValues readG2o(const string &g2oFile, const bool is3D, GraphAndValues readG2o(const std::string &g2oFile, const bool is3D,
KernelFunctionType kernelFunctionType) { KernelFunctionType kernelFunctionType) {
if (is3D) { if (is3D) {
return load3D(g2oFile); return load3D(g2oFile);
@ -628,8 +637,8 @@ GraphAndValues readG2o(const string &g2oFile, const bool is3D,
/* ************************************************************************* */ /* ************************************************************************* */
void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate,
const string &filename) { const std::string &filename) {
fstream stream(filename.c_str(), fstream::out); std::fstream stream(filename.c_str(), std::fstream::out);
// Use a lambda here to more easily modify behavior in future. // Use a lambda here to more easily modify behavior in future.
auto index = [](gtsam::Key key) { return Symbol(key).index(); }; auto index = [](gtsam::Key key) { return Symbol(key).index(); };
@ -674,7 +683,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate,
std::dynamic_pointer_cast<noiseModel::Gaussian>(model); std::dynamic_pointer_cast<noiseModel::Gaussian>(model);
if (!gaussianModel) { if (!gaussianModel) {
model->print("model\n"); model->print("model\n");
throw invalid_argument("writeG2o: invalid noise model!"); throw std::invalid_argument("writeG2o: invalid noise model!");
} }
Matrix3 Info = gaussianModel->R().transpose() * gaussianModel->R(); Matrix3 Info = gaussianModel->R().transpose() * gaussianModel->R();
Pose2 pose = factor->measured(); //.inverse(); Pose2 pose = factor->measured(); //.inverse();
@ -698,7 +707,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate,
std::dynamic_pointer_cast<noiseModel::Gaussian>(model); std::dynamic_pointer_cast<noiseModel::Gaussian>(model);
if (!gaussianModel) { if (!gaussianModel) {
model->print("model\n"); model->print("model\n");
throw invalid_argument("writeG2o: invalid noise model!"); throw std::invalid_argument("writeG2o: invalid noise model!");
} }
Matrix6 Info = gaussianModel->R().transpose() * gaussianModel->R(); Matrix6 Info = gaussianModel->R().transpose() * gaussianModel->R();
const Pose3 pose3D = factor3D->measured(); const Pose3 pose3D = factor3D->measured();
@ -729,7 +738,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate,
/* ************************************************************************* */ /* ************************************************************************* */
// parse quaternion in x,y,z,w order, and normalize to unit length // parse quaternion in x,y,z,w order, and normalize to unit length
istream &operator>>(istream &is, Quaternion &q) { std::istream &operator>>(std::istream &is, Quaternion &q) {
double x, y, z, w; double x, y, z, w;
is >> x >> y >> z >> w; is >> x >> y >> z >> w;
const double norm = sqrt(w * w + x * x + y * y + z * z), f = 1.0 / norm; const double norm = sqrt(w * w + x * x + y * y + z * z), f = 1.0 / norm;
@ -739,7 +748,7 @@ istream &operator>>(istream &is, Quaternion &q) {
/* ************************************************************************* */ /* ************************************************************************* */
// parse Rot3 from roll, pitch, yaw // parse Rot3 from roll, pitch, yaw
istream &operator>>(istream &is, Rot3 &R) { std::istream &operator>>(std::istream &is, Rot3 &R) {
double yaw, pitch, roll; double yaw, pitch, roll;
is >> roll >> pitch >> yaw; // notice order ! is >> roll >> pitch >> yaw; // notice order !
R = Rot3::Ypr(yaw, pitch, roll); R = Rot3::Ypr(yaw, pitch, roll);
@ -747,20 +756,20 @@ istream &operator>>(istream &is, Rot3 &R) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
std::optional<pair<size_t, Pose3>> parseVertexPose3(istream &is, std::optional<std::pair<size_t, Pose3>> parseVertexPose3(std::istream &is,
const string &tag) { const std::string &tag) {
if (tag == "VERTEX3") { if (tag == "VERTEX3") {
size_t id; size_t id;
double x, y, z; double x, y, z;
Rot3 R; Rot3 R;
is >> id >> x >> y >> z >> R; is >> id >> x >> y >> z >> R;
return make_pair(id, Pose3(R, {x, y, z})); return std::make_pair(id, Pose3(R, {x, y, z}));
} else if (tag == "VERTEX_SE3:QUAT") { } else if (tag == "VERTEX_SE3:QUAT") {
size_t id; size_t id;
double x, y, z; double x, y, z;
Quaternion q; Quaternion q;
is >> id >> x >> y >> z >> q; is >> id >> x >> y >> z >> q;
return make_pair(id, Pose3(q, {x, y, z})); return std::make_pair(id, Pose3(q, {x, y, z}));
} else } else
return std::nullopt; return std::nullopt;
} }
@ -772,13 +781,13 @@ GTSAM_EXPORT std::map<size_t, Pose3> parseVariables<Pose3>(
} }
/* ************************************************************************* */ /* ************************************************************************* */
std::optional<pair<size_t, Point3>> parseVertexPoint3(istream &is, std::optional<std::pair<size_t, Point3>> parseVertexPoint3(std::istream &is,
const string &tag) { const std::string &tag) {
if (tag == "VERTEX_TRACKXYZ") { if (tag == "VERTEX_TRACKXYZ") {
size_t id; size_t id;
double x, y, z; double x, y, z;
is >> id >> x >> y >> z; is >> id >> x >> y >> z;
return make_pair(id, Point3(x, y, z)); return std::make_pair(id, Point3(x, y, z));
} else } else
return std::nullopt; return std::nullopt;
} }
@ -791,7 +800,7 @@ GTSAM_EXPORT std::map<size_t, Point3> parseVariables<Point3>(
/* ************************************************************************* */ /* ************************************************************************* */
// Parse a symmetric covariance matrix (onlyupper-triangular part is stored) // Parse a symmetric covariance matrix (onlyupper-triangular part is stored)
istream &operator>>(istream &is, Matrix6 &m) { std::istream &operator>>(std::istream &is, Matrix6 &m) {
for (size_t i = 0; i < 6; i++) for (size_t i = 0; i < 6; i++)
for (size_t j = i; j < 6; j++) { for (size_t j = i; j < 6; j++) {
is >> m(i, j); is >> m(i, j);
@ -808,8 +817,8 @@ template <> struct ParseMeasurement<Pose3> {
size_t maxIndex; size_t maxIndex;
// The actual parser // The actual parser
std::optional<BinaryMeasurement<Pose3>> operator()(istream &is, std::optional<BinaryMeasurement<Pose3>> operator()(std::istream &is,
const string &tag) { const std::string &tag) {
if (tag != "EDGE3" && tag != "EDGE_SE3:QUAT") if (tag != "EDGE3" && tag != "EDGE_SE3:QUAT")
return std::nullopt; return std::nullopt;
@ -913,7 +922,7 @@ parseFactors<Pose3>(const std::string &filename,
} }
/* ************************************************************************* */ /* ************************************************************************* */
GraphAndValues load3D(const string &filename) { GraphAndValues load3D(const std::string &filename) {
auto graph = std::make_shared<NonlinearFactorGraph>(); auto graph = std::make_shared<NonlinearFactorGraph>();
auto initial = std::make_shared<Values>(); auto initial = std::make_shared<Values>();
@ -922,7 +931,7 @@ GraphAndValues load3D(const string &filename) {
// Single pass for variables and factors. Unlike 2D version, does *not* insert // Single pass for variables and factors. Unlike 2D version, does *not* insert
// variables into `initial` if referenced but not present. // variables into `initial` if referenced but not present.
Parser<int> parse = [&](istream &is, const string &tag) { Parser<int> parse = [&](std::istream &is, const std::string &tag) {
if (auto indexedPose = parseVertexPose3(is, tag)) { if (auto indexedPose = parseVertexPose3(is, tag)) {
initial->insert(indexedPose->first, indexedPose->second); initial->insert(indexedPose->first, indexedPose->second);
} else if (auto indexedLandmark = parseVertexPoint3(is, tag)) { } else if (auto indexedLandmark = parseVertexPoint3(is, tag)) {
@ -934,7 +943,7 @@ GraphAndValues load3D(const string &filename) {
}; };
parseLines(filename, parse); parseLines(filename, parse);
return make_pair(graph, initial); return {graph, initial};
} }
// Wrapper-friendly versions of parseFactors<Pose2> and parseFactors<Pose2> // Wrapper-friendly versions of parseFactors<Pose2> and parseFactors<Pose2>

View File

@ -22,8 +22,6 @@
#include <gtsam/inference/Symbol.h> #include <gtsam/inference/Symbol.h>
#include <gtsam/base/TestableAssertions.h> #include <gtsam/base/TestableAssertions.h>
#include <boost/algorithm/string.hpp>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <iostream> #include <iostream>
@ -38,7 +36,8 @@ TEST(dataSet, findExampleDataFile) {
const string expected_end = "examples/Data/example.graph"; const string expected_end = "examples/Data/example.graph";
const string actual = findExampleDataFile("example"); const string actual = findExampleDataFile("example");
string actual_end = actual.substr(actual.size() - expected_end.size(), expected_end.size()); string actual_end = actual.substr(actual.size() - expected_end.size(), expected_end.size());
boost::replace_all(actual_end, "\\", "/"); // Convert directory separators to forward-slash // replace all ocurrences of \\ with / use stl
std::replace(actual_end.begin(), actual_end.end(), '\\', '/');
EXPECT(assert_equal(expected_end, actual_end)); EXPECT(assert_equal(expected_end, actual_end));
} }

View File

@ -21,7 +21,6 @@
#include <gtsam/discrete/DiscreteValues.h> #include <gtsam/discrete/DiscreteValues.h>
#include <gtsam_unstable/dllexport.h> #include <gtsam_unstable/dllexport.h>
#include <boost/format.hpp>
#include <map> #include <map>
namespace gtsam { namespace gtsam {
@ -86,13 +85,13 @@ class GTSAM_UNSTABLE_EXPORT Constraint : public DiscreteFactor {
/// Render as markdown table. /// Render as markdown table.
std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter, std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
const Names& names = {}) const override { const Names& names = {}) const override {
return (boost::format("`Constraint` on %1% variables\n") % (size())).str(); return "`Constraint` on " + std::to_string(size()) + " variables\n";
} }
/// Render as html table. /// Render as html table.
std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter, std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
const Names& names = {}) const override { const Names& names = {}) const override {
return (boost::format("<p>Constraint on %1% variables</p>") % (size())).str(); return "<p>Constraint on " + std::to_string(size()) + " variables</p>";
} }
/// @} /// @}

View File

@ -12,8 +12,6 @@
#include <gtsam/base/debug.h> #include <gtsam/base/debug.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <algorithm> #include <algorithm>
using namespace std; using namespace std;
@ -171,8 +169,8 @@ void solveStaged(size_t addMutex = 2) {
// remove this slot from consideration // remove this slot from consideration
slotsAvailable[bestSlot] = 0.0; slotsAvailable[bestSlot] = 0.0;
cout << boost::format("%s = %d (%d), count = %d") % scheduler.studentName(6-s) cout << scheduler.studentName(6 - s) << " = " << scheduler.slotName(bestSlot) << " (" << bestSlot
% scheduler.slotName(bestSlot) % bestSlot % count << endl; << "), count = " << count << endl;
} }
tictoc_print_(); tictoc_print_();
@ -229,9 +227,8 @@ void sampleSolutions() {
size_t min = *min_element(stats.begin(), stats.end()); size_t min = *min_element(stats.begin(), stats.end());
size_t nz = count_if(stats.begin(), stats.end(), NonZero); size_t nz = count_if(stats.begin(), stats.end(), NonZero);
if (nz >= 15 && max <= 2) { if (nz >= 15 && max <= 2) {
cout << boost::format( cout << "Sampled schedule " << (n + 1) << ", min = " << min << ", nz = " << nz
"Sampled schedule %d, min = %d, nz = %d, max = %d\n") % (n + 1) % min << ", max = " << max << endl;
% nz % max;
for (size_t i = 0; i < 7; i++) { for (size_t i = 0; i < 7; i++) {
cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName( cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName(
slots[i]) << endl; slots[i]) << endl;
@ -320,9 +317,8 @@ void accomodateStudent() {
DiscreteValues values; DiscreteValues values;
values[dkey.first] = bestSlot; values[dkey.first] = bestSlot;
size_t count = (*root)(values); size_t count = (*root)(values);
cout << boost::format("%s = %d (%d), count = %d") % scheduler.studentName(0) cout << scheduler.studentName(0) << " = " << scheduler.slotName(bestSlot) << " (" << bestSlot
% scheduler.slotName(bestSlot) % bestSlot % count << endl; << "), count = " << count << endl;
// sample schedules // sample schedules
for (size_t n = 0; n < 10; n++) { for (size_t n = 0; n < 10; n++) {
auto sample0 = chordal->sample(); auto sample0 = chordal->sample();

View File

@ -12,8 +12,6 @@
#include <gtsam/base/debug.h> #include <gtsam/base/debug.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <algorithm> #include <algorithm>
using namespace std; using namespace std;
@ -193,8 +191,9 @@ void solveStaged(size_t addMutex = 2) {
// remove this slot from consideration // remove this slot from consideration
slotsAvailable[bestSlot] = 0.0; slotsAvailable[bestSlot] = 0.0;
cout << boost::format("%s = %d (%d), count = %d") % scheduler.studentName(NRSTUDENTS-1-s) cout << scheduler.studentName(NRSTUDENTS - 1 - s) << " = " <<
% scheduler.slotName(bestSlot) % bestSlot % count << endl; scheduler.slotName(bestSlot) << " (" << bestSlot
<< "), count = " << count << endl;
} }
tictoc_print_(); tictoc_print_();
} }
@ -234,9 +233,8 @@ void sampleSolutions() {
size_t min = *min_element(stats.begin(), stats.end()); size_t min = *min_element(stats.begin(), stats.end());
size_t nz = count_if(stats.begin(), stats.end(), NonZero); size_t nz = count_if(stats.begin(), stats.end(), NonZero);
if (nz >= 15 && max <= 2) { if (nz >= 15 && max <= 2) {
cout << boost::format( cout << "Sampled schedule " << (n + 1) << ", min = " << min
"Sampled schedule %d, min = %d, nz = %d, max = %d\n") % (n + 1) % min << ", nz = " << nz << ", max = " << max << endl;
% nz % max;
for (size_t i = 0; i < NRSTUDENTS; i++) { for (size_t i = 0; i < NRSTUDENTS; i++) {
cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName( cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName(
slots[i]) << endl; slots[i]) << endl;

View File

@ -12,8 +12,6 @@
#include <gtsam/base/debug.h> #include <gtsam/base/debug.h>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <algorithm> #include <algorithm>
using namespace std; using namespace std;
@ -218,8 +216,8 @@ void solveStaged(size_t addMutex = 2) {
// remove this slot from consideration // remove this slot from consideration
slotsAvailable[bestSlot] = 0.0; slotsAvailable[bestSlot] = 0.0;
cout << boost::format("%s = %d (%d), count = %d") % scheduler.studentName(NRSTUDENTS-1-s) cout << scheduler.studentName(NRSTUDENTS - 1 - s) << " = " << scheduler.slotName(bestSlot) << " (" << bestSlot
% scheduler.slotName(bestSlot) % bestSlot % count << endl; << "), count = " << count << endl;
} }
tictoc_print_(); tictoc_print_();
} }
@ -263,9 +261,7 @@ void sampleSolutions() {
size_t min = *min_element(stats.begin(), stats.end()); size_t min = *min_element(stats.begin(), stats.end());
size_t nz = count_if(stats.begin(), stats.end(), NonZero); size_t nz = count_if(stats.begin(), stats.end(), NonZero);
if (nz >= 16 && max <= 3) { if (nz >= 16 && max <= 3) {
cout << boost::format( cout << "Sampled schedule " << n + 1 << ", min = " << min << ", nz = " << nz << ", max = " << max << endl;
"Sampled schedule %d, min = %d, nz = %d, max = %d\n") % (n + 1) % min
% nz % max;
for (size_t i = 0; i < NRSTUDENTS; i++) { for (size_t i = 0; i < NRSTUDENTS; i++) {
cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName( cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName(
slots[i]) << endl; slots[i]) << endl;

View File

@ -71,7 +71,7 @@ class LoopyBelief {
void print(const std::string& s = "") const { void print(const std::string& s = "") const {
cout << s << ":" << endl; cout << s << ":" << endl;
for (const auto& [key, _] : starGraphs_) { for (const auto& [key, _] : starGraphs_) {
starGraphs_.at(key).print((boost::format("Node %d:") % key).str()); starGraphs_.at(key).print("Node " + std::to_string(key) + ":");
} }
} }
@ -124,9 +124,11 @@ class LoopyBelief {
val[key] = v; val[key] = v;
sum += (*beliefAtKey)(val); sum += (*beliefAtKey)(val);
} }
// TODO(kartikarcot): Check if this makes sense
string sumFactorTable; string sumFactorTable;
for (size_t v = 0; v < allDiscreteKeys.at(key).second; ++v) for (size_t v = 0; v < allDiscreteKeys.at(key).second; ++v) {
sumFactorTable = (boost::format("%s %f") % sumFactorTable % sum).str(); sumFactorTable = sumFactorTable + " " + std::to_string(sum);
}
DecisionTreeFactor sumFactor(allDiscreteKeys.at(key), sumFactorTable); DecisionTreeFactor sumFactor(allDiscreteKeys.at(key), sumFactorTable);
if (debug) sumFactor.print("denomFactor: "); if (debug) sumFactor.print("denomFactor: ");
beliefAtKey = beliefAtKey =

View File

@ -24,8 +24,6 @@
#include <gtsam_unstable/geometry/Event.h> #include <gtsam_unstable/geometry/Event.h>
#include <gtsam_unstable/slam/TOAFactor.h> #include <gtsam_unstable/slam/TOAFactor.h>
#include <boost/format.hpp>
#include <vector> #include <vector>
using namespace std; using namespace std;

View File

@ -16,7 +16,6 @@
*/ */
#include <gtsam_unstable/nonlinear/LinearizedFactor.h> #include <gtsam_unstable/nonlinear/LinearizedFactor.h>
#include <boost/format.hpp>
#include <iostream> #include <iostream>
namespace gtsam { namespace gtsam {
@ -69,8 +68,9 @@ void LinearizedJacobianFactor::print(const std::string& s, const KeyFormatter& k
std::cout << keyFormatter(key) << " "; std::cout << keyFormatter(key) << " ";
std::cout << std::endl; std::cout << std::endl;
for(const_iterator key=begin(); key!=end(); ++key) for(const_iterator key=begin(); key!=end(); ++key) {
std::cout << boost::format("A[%1%]=\n")%keyFormatter(*key) << A(*key) << std::endl; std::cout << "A[" << keyFormatter(*key) << "]=\n" << A(*key) << std::endl;
}
std::cout << "b=\n" << b() << std::endl; std::cout << "b=\n" << b() << std::endl;
lin_points_.print("Linearization Point: "); lin_points_.print("Linearization Point: ");

View File

@ -19,6 +19,8 @@
#include <gtsam_unstable/nonlinear/expressionTesting.h> #include <gtsam_unstable/nonlinear/expressionTesting.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <type_traits>
using namespace gtsam; using namespace gtsam;
@ -46,8 +48,8 @@ struct ProjectionChart {
namespace gtsam { namespace gtsam {
namespace traits { namespace traits {
template<> struct is_chart<ProjectionChart> : public boost::true_type {}; template<> struct is_chart<ProjectionChart> : public std::true_type {};
template<> struct dimension<ProjectionChart> : public boost::integral_constant<int, 2> {}; template<> struct dimension<ProjectionChart> : public std::integral_constant<int, 2> {};
} // namespace traits } // namespace traits
} // namespace gtsam } // namespace gtsam

View File

@ -25,7 +25,6 @@
#include <gtsam_unstable/slam/TOAFactor.h> #include <gtsam_unstable/slam/TOAFactor.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <boost/format.hpp>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -21,8 +21,6 @@
#include <gtsam_unstable/base/DSF.h> #include <gtsam_unstable/base/DSF.h>
#include <gtsam/base/DSFMap.h> #include <gtsam/base/DSFMap.h>
#include <boost/format.hpp>
#include <fstream> #include <fstream>
#include <iostream> #include <iostream>
#include <random> #include <random>
@ -31,7 +29,6 @@
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
using boost::format;
int main(int argc, char* argv[]) { int main(int argc, char* argv[]) {
@ -52,8 +49,7 @@ int main(int argc, char* argv[]) {
volatile double fpm = 0.5; // fraction of points matched volatile double fpm = 0.5; // fraction of points matched
volatile size_t nm = fpm * n * np; // number of matches volatile size_t nm = fpm * n * np; // number of matches
cout << format("\nTesting with %1% images, %2% points, %3% matches\n") cout << "\nTesting with " << (int)m << " images, " << (int)N << " points, " << (int)nm << " matches\n";
% (int)m % (int)N % (int)nm;
cout << "Generating " << nm << " matches" << endl; cout << "Generating " << nm << " matches" << endl;
std::mt19937 rng; std::mt19937 rng;
std::uniform_int_distribution<> rn(0, N - 1); std::uniform_int_distribution<> rn(0, N - 1);
@ -64,7 +60,7 @@ int main(int argc, char* argv[]) {
for (size_t k = 0; k < nm; k++) for (size_t k = 0; k < nm; k++)
matches.push_back(Match(rn(rng), rn(rng))); matches.push_back(Match(rn(rng), rn(rng)));
os << format("%1%,%2%,%3%,") % (int)m % (int)N % (int)nm; os << (int)m << "," << (int)N << "," << (int)nm << ",";
{ {
// DSFBase version // DSFBase version
@ -77,7 +73,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(dsftimeNode, dsftime); tictoc_getNode(dsftimeNode, dsftime);
dsftime = dsftimeNode->secs(); dsftime = dsftimeNode->secs();
os << dsftime << ","; os << dsftime << ",";
cout << format("DSFBase: %1% s") % dsftime << endl; cout << "DSFBase: " << dsftime << " s" << endl;
tictoc_reset_(); tictoc_reset_();
} }
@ -92,7 +88,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(dsftimeNode, dsftime); tictoc_getNode(dsftimeNode, dsftime);
dsftime = dsftimeNode->secs(); dsftime = dsftimeNode->secs();
os << dsftime << endl; os << dsftime << endl;
cout << format("DSFMap: %1% s") % dsftime << endl; cout << "DSFMap: " << dsftime << " s" << endl;
tictoc_reset_(); tictoc_reset_();
} }
@ -109,7 +105,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(dsftimeNode, dsftime); tictoc_getNode(dsftimeNode, dsftime);
dsftime = dsftimeNode->secs(); dsftime = dsftimeNode->secs();
os << dsftime << endl; os << dsftime << endl;
cout << format("DSF functional: %1% s") % dsftime << endl; cout << "DSF functional: " << dsftime << " s" << endl;
tictoc_reset_(); tictoc_reset_();
} }
@ -126,7 +122,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(dsftimeNode, dsftime); tictoc_getNode(dsftimeNode, dsftime);
dsftime = dsftimeNode->secs(); dsftime = dsftimeNode->secs();
os << dsftime << ","; os << dsftime << ",";
cout << format("DSF in-place: %1% s") % dsftime << endl; cout << "DSF in-place: " << dsftime << " s" << endl;
tictoc_reset_(); tictoc_reset_();
} }

View File

@ -16,9 +16,6 @@
* @date Sep 18, 2010 * @date Sep 18, 2010
*/ */
#include <boost/format.hpp>
#include <boost/lambda/lambda.hpp>
#include <gtsam/base/timing.h> #include <gtsam/base/timing.h>
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>
@ -30,8 +27,6 @@
using namespace std; using namespace std;
//namespace ublas = boost::numeric::ublas; //namespace ublas = boost::numeric::ublas;
//using namespace Eigen; //using namespace Eigen;
using boost::format;
using namespace boost::lambda;
static std::mt19937 rng; static std::mt19937 rng;
static std::uniform_real_distribution<> uniform(-1.0, 0.0); static std::uniform_real_distribution<> uniform(-1.0, 0.0);
@ -61,10 +56,10 @@ int main(int argc, char* argv[]) {
gtsam::SubMatrix top = mat.block(0, 0, n, n); gtsam::SubMatrix top = mat.block(0, 0, n, n);
gtsam::SubMatrix block = mat.block(m/4, n/4, m-m/2, n-n/2); gtsam::SubMatrix block = mat.block(m/4, n/4, m-m/2, n-n/2);
cout << format(" Basic: %1%x%2%\n") % (int)m % (int)n; cout << " Basic: " << (int)m << "x" << (int)n << endl;
cout << format(" Full: mat(%1%:%2%, %3%:%4%)\n") % 0 % (int)m % 0 % (int)n; cout << " Full: mat(" << 0 << ":" << (int)m << ", " << 0 << ":" << (int)n << ")" << endl;
cout << format(" Top: mat(%1%:%2%, %3%:%4%)\n") % 0 % (int)n % 0 % (int)n; cout << " Top: mat(" << 0 << ":" << (int)n << ", " << 0 << ":" << (int)n << ")" << endl;
cout << format(" Block: mat(%1%:%2%, %3%:%4%)\n") % size_t(m/4) % size_t(m-m/4) % size_t(n/4) % size_t(n-n/4); cout << " Block: mat(" << size_t(m/4) << ":" << size_t(m-m/4) << ", " << size_t(n/4) << ":" << size_t(n-n/4) << ")" << endl;
cout << endl; cout << endl;
{ {
@ -87,7 +82,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(basicTimeNode, basicTime); tictoc_getNode(basicTimeNode, basicTime);
basicTime = basicTimeNode->secs(); basicTime = basicTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(mat.rows()*mat.cols()*nReps)) << endl; cout << " Basic: " << double(1000000 * basicTime / double(mat.rows()*mat.cols()*nReps)) << " μs/element" << endl;
gttic_(fullTime); gttic_(fullTime);
for(size_t rep=0; rep<nReps; ++rep) for(size_t rep=0; rep<nReps; ++rep)
@ -98,7 +93,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(fullTimeNode, fullTime); tictoc_getNode(fullTimeNode, fullTime);
fullTime = fullTimeNode->secs(); fullTime = fullTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(full.rows()*full.cols()*nReps)) << endl; cout << " Full: " << double(1000000 * fullTime / double(full.rows()*full.cols()*nReps)) << " μs/element" << endl;
gttic_(topTime); gttic_(topTime);
for(size_t rep=0; rep<nReps; ++rep) for(size_t rep=0; rep<nReps; ++rep)
@ -109,7 +104,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(topTimeNode, topTime); tictoc_getNode(topTimeNode, topTime);
topTime = topTimeNode->secs(); topTime = topTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(top.rows()*top.cols()*nReps)) << endl; cout << " Top: " << double(1000000 * topTime / double(top.rows()*top.cols()*nReps)) << " μs/element" << endl;
gttic_(blockTime); gttic_(blockTime);
for(size_t rep=0; rep<nReps; ++rep) for(size_t rep=0; rep<nReps; ++rep)
@ -120,7 +115,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(blockTimeNode, blockTime); tictoc_getNode(blockTimeNode, blockTime);
blockTime = blockTimeNode->secs(); blockTime = blockTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Block: %1% mus/element") % double(1000000 * blockTime / double(block.rows()*block.cols()*nReps)) << endl; cout << " Block: " << double(1000000 * blockTime / double(block.rows()*block.cols()*nReps)) << " μs/element" << endl;
cout << endl; cout << endl;
} }
@ -145,7 +140,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(basicTimeNode, basicTime); tictoc_getNode(basicTimeNode, basicTime);
basicTime = basicTimeNode->secs(); basicTime = basicTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(mat.rows()*mat.cols()*nReps)) << endl; cout << " Basic: " << double(1000000 * basicTime / double(mat.rows()*mat.cols()*nReps)) << " μs/element" << endl;
gttic_(fullTime); gttic_(fullTime);
for(size_t rep=0; rep<nReps; ++rep) for(size_t rep=0; rep<nReps; ++rep)
@ -156,7 +151,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(fullTimeNode, fullTime); tictoc_getNode(fullTimeNode, fullTime);
fullTime = fullTimeNode->secs(); fullTime = fullTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(full.rows()*full.cols()*nReps)) << endl; cout << " Full: " << double(1000000 * fullTime / double(full.rows()*full.cols()*nReps)) << " μs/element" << endl;
gttic_(topTime); gttic_(topTime);
for(size_t rep=0; rep<nReps; ++rep) for(size_t rep=0; rep<nReps; ++rep)
@ -167,7 +162,7 @@ int main(int argc, char* argv[]) {
tictoc_getNode(topTimeNode, topTime); tictoc_getNode(topTimeNode, topTime);
topTime = topTimeNode->secs(); topTime = topTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(top.rows()*top.cols()*nReps)) << endl; cout << " Top: " << double(1000000 * topTime / double(top.rows()*top.cols()*nReps)) << " μs/element" << endl;
gttic_(blockTime); gttic_(blockTime);
for(size_t rep=0; rep<nReps; ++rep) for(size_t rep=0; rep<nReps; ++rep)
@ -178,62 +173,63 @@ int main(int argc, char* argv[]) {
tictoc_getNode(blockTimeNode, blockTime); tictoc_getNode(blockTimeNode, blockTime);
blockTime = blockTimeNode->secs(); blockTime = blockTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Block: %1% mus/element") % double(1000000 * blockTime / double(block.rows()*block.cols()*nReps)) << endl; cout << " Block: " << double(1000000 * blockTime / double(block.rows()*block.cols()*nReps)) << " μs/element" << endl;
cout << endl; cout << endl;
} }
{ {
double basicTime, fullTime, topTime, blockTime; double basicTime, fullTime, topTime, blockTime;
typedef pair<size_t,size_t> ij_t; typedef std::pair<size_t,size_t> ij_t;
vector<ij_t> ijs(100000); std::vector<ij_t> ijs(100000);
cout << "Row-major matrix, random assignment:" << endl; cout << "Row-major matrix, random assignment:" << endl;
// Do a few initial assignments to let any cache effects stabilize // Do a few initial assignments to let any cache effects stabilize
for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng),uniform_j(rng))); for (auto& ij : ijs) ij = {uniform_i(rng), uniform_j(rng)};
for(size_t rep=0; rep<1000; ++rep) for(size_t rep=0; rep<1000; ++rep)
for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = uniform(rng); } for(const auto& [i, j]: ijs) { mat(i, j) = uniform(rng); }
gttic_(basicTime); gttic_(basicTime);
for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng),uniform_j(rng))); for (auto& ij : ijs) ij = {uniform_i(rng), uniform_j(rng)};
for(size_t rep=0; rep<1000; ++rep) for(size_t rep=0; rep<1000; ++rep)
for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = uniform(rng); } for(const auto& [i, j]: ijs) { mat(i, j) = uniform(rng); }
gttoc_(basicTime); gttoc_(basicTime);
tictoc_getNode(basicTimeNode, basicTime); tictoc_getNode(basicTimeNode, basicTime);
basicTime = basicTimeNode->secs(); basicTime = basicTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(ijs.size()*nReps)) << endl; cout << " Basic: " << double(1000000 * basicTime / double(ijs.size()*nReps)) << " μs/element" << endl;
gttic_(fullTime); gttic_(fullTime);
for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng),uniform_j(rng))); for (auto& ij : ijs) ij = {uniform_i(rng), uniform_j(rng)};
for(size_t rep=0; rep<1000; ++rep) for(size_t rep=0; rep<1000; ++rep)
for(const ij_t& ij: ijs) { full(ij.first, ij.second) = uniform(rng); } for(const auto& [i, j]: ijs) { full(i, j) = uniform(rng); }
gttoc_(fullTime); gttoc_(fullTime);
tictoc_getNode(fullTimeNode, fullTime); tictoc_getNode(fullTimeNode, fullTime);
fullTime = fullTimeNode->secs(); fullTime = fullTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(ijs.size()*nReps)) << endl; cout << " Full: " << double(1000000 * fullTime / double(ijs.size()*nReps)) << " μs/element" << endl;
gttic_(topTime); gttic_(topTime);
for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng)%top.rows(),uniform_j(rng))); for (auto& ij : ijs) ij = {uniform_i(rng) % top.rows(), uniform_j(rng)};
for(size_t rep=0; rep<1000; ++rep) for(size_t rep=0; rep<1000; ++rep)
for(const ij_t& ij: ijs) { top(ij.first, ij.second) = uniform(rng); } for(const auto& [i, j]: ijs) { top(i, j) = uniform(rng); }
gttoc_(topTime); gttoc_(topTime);
tictoc_getNode(topTimeNode, topTime); tictoc_getNode(topTimeNode, topTime);
topTime = topTimeNode->secs(); topTime = topTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(ijs.size()*nReps)) << endl; cout << " Top: " << double(1000000 * topTime / double(ijs.size()*nReps)) << " μs/element" << endl;
gttic_(blockTime); gttic_(blockTime);
for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng)%block.rows(),uniform_j(rng)%block.cols())); for (auto& ij : ijs)
ij = {uniform_i(rng) % block.rows(), uniform_j(rng) % block.cols()};
for(size_t rep=0; rep<1000; ++rep) for(size_t rep=0; rep<1000; ++rep)
for(const ij_t& ij: ijs) { block(ij.first, ij.second) = uniform(rng); } for(const auto& [i, j]: ijs) { block(i, j) = uniform(rng); }
gttoc_(blockTime); gttoc_(blockTime);
tictoc_getNode(blockTimeNode, blockTime); tictoc_getNode(blockTimeNode, blockTime);
blockTime = blockTimeNode->secs(); blockTime = blockTimeNode->secs();
gtsam::tictoc_reset_(); gtsam::tictoc_reset_();
cout << format(" Block: %1% mus/element") % double(1000000 * blockTime / double(ijs.size()*nReps)) << endl; cout << " Block: " << double(1000000 * blockTime / double(ijs.size()*nReps)) << " μs/element" << endl;
cout << endl; cout << endl;
} }