Merge pull request #1108 from borglab/fix/headers

Header discipline in base
release/4.3a0
Frank Dellaert 2022-02-17 01:25:01 -05:00 committed by GitHub
commit 55ad1841bd
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
25 changed files with 237 additions and 179 deletions

View File

@ -96,7 +96,11 @@ function build ()
configure
if [ "$(uname)" == "Linux" ]; then
make -j$(nproc)
if (($(nproc) > 2)); then
make -j$(nproc)
else
make -j2
fi
elif [ "$(uname)" == "Darwin" ]; then
make -j$(sysctl -n hw.physicalcpu)
fi
@ -114,7 +118,11 @@ function test ()
# Actual testing
if [ "$(uname)" == "Linux" ]; then
make -j$(nproc) check
if (($(nproc) > 2)); then
make -j$(nproc) check
else
make -j2 check
fi
elif [ "$(uname)" == "Darwin" ]; then
make -j$(sysctl -n hw.physicalcpu) check
fi

View File

@ -26,10 +26,12 @@
#include <gtsam/nonlinear/ExpressionFactorGraph.h>
// Header order is close to far
#include <gtsam/inference/Symbol.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/sfm/SfmData.h> // for loading BAL datasets !
#include <gtsam/slam/dataset.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/inference/Symbol.h>
#include <boost/format.hpp>
#include <vector>
using namespace std;

View File

@ -16,12 +16,14 @@
*/
// For an explanation of headers, see SFMExample.cpp
#include <gtsam/inference/Symbol.h>
#include <gtsam/sfm/SfmData.h> // for loading BAL datasets !
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/slam/dataset.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/sfm/SfmData.h> // for loading BAL datasets !
#include <gtsam/slam/dataset.h>
#include <gtsam/inference/Symbol.h>
#include <boost/format.hpp>
#include <vector>
using namespace std;

View File

@ -17,16 +17,16 @@
*/
// For an explanation of headers, see SFMExample.cpp
#include <gtsam/inference/Symbol.h>
#include <gtsam/inference/Ordering.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/sfm/SfmData.h> // for loading BAL datasets !
#include <gtsam/slam/dataset.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/inference/Ordering.h>
#include <gtsam/base/timing.h>
#include <boost/format.hpp>
#include <vector>
using namespace std;

View File

@ -25,6 +25,7 @@
#include <boost/tuple/tuple.hpp>
#include <boost/tokenizer.hpp>
#include <boost/format.hpp>
#include <cstdarg>
#include <cstring>

View File

@ -26,12 +26,9 @@
#include <gtsam/base/OptionalJacobian.h>
#include <gtsam/base/Vector.h>
#include <gtsam/config.h>
#include <boost/format.hpp>
#include <functional>
#include <boost/tuple/tuple.hpp>
#include <boost/math/special_functions/fpclassify.hpp>
#include <vector>
/**
* Matrix is a typedef in the gtsam namespace
@ -523,82 +520,4 @@ GTSAM_EXPORT Matrix LLt(const Matrix& A);
GTSAM_EXPORT Matrix RtR(const Matrix& A);
GTSAM_EXPORT Vector columnNormSquare(const Matrix &A);
} // namespace gtsam
#include <boost/serialization/nvp.hpp>
#include <boost/serialization/array.hpp>
#include <boost/serialization/split_free.hpp>
namespace boost {
namespace serialization {
/**
* Ref. https://stackoverflow.com/questions/18382457/eigen-and-boostserialize/22903063#22903063
*
* Eigen supports calling resize() on both static and dynamic matrices.
* This allows for a uniform API, with resize having no effect if the static matrix
* is already the correct size.
* https://eigen.tuxfamily.org/dox/group__TutorialMatrixClass.html#TutorialMatrixSizesResizing
*
* We use all the Matrix template parameters to ensure wide compatibility.
*
* eigen_typekit in ROS uses the same code
* http://docs.ros.org/lunar/api/eigen_typekit/html/eigen__mqueue_8cpp_source.html
*/
// split version - sends sizes ahead
template<class Archive,
typename Scalar_,
int Rows_,
int Cols_,
int Ops_,
int MaxRows_,
int MaxCols_>
void save(Archive & ar,
const Eigen::Matrix<Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_> & m,
const unsigned int /*version*/) {
const size_t rows = m.rows(), cols = m.cols();
ar << BOOST_SERIALIZATION_NVP(rows);
ar << BOOST_SERIALIZATION_NVP(cols);
ar << make_nvp("data", make_array(m.data(), m.size()));
}
template<class Archive,
typename Scalar_,
int Rows_,
int Cols_,
int Ops_,
int MaxRows_,
int MaxCols_>
void load(Archive & ar,
Eigen::Matrix<Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_> & m,
const unsigned int /*version*/) {
size_t rows, cols;
ar >> BOOST_SERIALIZATION_NVP(rows);
ar >> BOOST_SERIALIZATION_NVP(cols);
m.resize(rows, cols);
ar >> make_nvp("data", make_array(m.data(), m.size()));
}
// templated version of BOOST_SERIALIZATION_SPLIT_FREE(Eigen::Matrix);
template<class Archive,
typename Scalar_,
int Rows_,
int Cols_,
int Ops_,
int MaxRows_,
int MaxCols_>
void serialize(Archive & ar,
Eigen::Matrix<Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_> & m,
const unsigned int version) {
split_free(ar, m, version);
}
// specialized to Matrix for MATLAB wrapper
template <class Archive>
void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) {
split_free(ar, m, version);
}
} // namespace serialization
} // namespace boost
} // namespace gtsam

View File

@ -0,0 +1,89 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file MatrixSerialization.h
* @brief Serialization for matrices
* @author Frank Dellaert
* @date February 2022
*/
// \callgraph
#pragma once
#include <gtsam/base/Matrix.h>
#include <boost/serialization/array.hpp>
#include <boost/serialization/nvp.hpp>
#include <boost/serialization/split_free.hpp>
namespace boost {
namespace serialization {
/**
* Ref.
* https://stackoverflow.com/questions/18382457/eigen-and-boostserialize/22903063#22903063
*
* Eigen supports calling resize() on both static and dynamic matrices.
* This allows for a uniform API, with resize having no effect if the static
* matrix is already the correct size.
* https://eigen.tuxfamily.org/dox/group__TutorialMatrixClass.html#TutorialMatrixSizesResizing
*
* We use all the Matrix template parameters to ensure wide compatibility.
*
* eigen_typekit in ROS uses the same code
* http://docs.ros.org/lunar/api/eigen_typekit/html/eigen__mqueue_8cpp_source.html
*/
// split version - sends sizes ahead
template <class Archive, typename Scalar_, int Rows_, int Cols_, int Ops_,
int MaxRows_, int MaxCols_>
void save(
Archive& ar,
const Eigen::Matrix<Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_>& m,
const unsigned int /*version*/) {
const size_t rows = m.rows(), cols = m.cols();
ar << BOOST_SERIALIZATION_NVP(rows);
ar << BOOST_SERIALIZATION_NVP(cols);
ar << make_nvp("data", make_array(m.data(), m.size()));
}
template <class Archive, typename Scalar_, int Rows_, int Cols_, int Ops_,
int MaxRows_, int MaxCols_>
void load(Archive& ar,
Eigen::Matrix<Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_>& m,
const unsigned int /*version*/) {
size_t rows, cols;
ar >> BOOST_SERIALIZATION_NVP(rows);
ar >> BOOST_SERIALIZATION_NVP(cols);
m.resize(rows, cols);
ar >> make_nvp("data", make_array(m.data(), m.size()));
}
// templated version of BOOST_SERIALIZATION_SPLIT_FREE(Eigen::Matrix);
template <class Archive, typename Scalar_, int Rows_, int Cols_, int Ops_,
int MaxRows_, int MaxCols_>
void serialize(
Archive& ar,
Eigen::Matrix<Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_>& m,
const unsigned int version) {
split_free(ar, m, version);
}
// specialized to Matrix for MATLAB wrapper
template <class Archive>
void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) {
split_free(ar, m, version);
}
} // namespace serialization
} // namespace boost

View File

@ -21,6 +21,7 @@
#include <gtsam/config.h> // Configuration from CMake
#include <gtsam/base/Vector.h>
#include <boost/serialization/nvp.hpp>
#include <boost/serialization/assume_abstract.hpp>
#include <memory>

View File

@ -264,46 +264,4 @@ GTSAM_EXPORT Vector concatVectors(const std::list<Vector>& vs);
* concatenate Vectors
*/
GTSAM_EXPORT Vector concatVectors(size_t nrVectors, ...);
} // namespace gtsam
#include <boost/serialization/nvp.hpp>
#include <boost/serialization/array.hpp>
#include <boost/serialization/split_free.hpp>
namespace boost {
namespace serialization {
// split version - copies into an STL vector for serialization
template<class Archive>
void save(Archive & ar, const gtsam::Vector & v, unsigned int /*version*/) {
const size_t size = v.size();
ar << BOOST_SERIALIZATION_NVP(size);
ar << make_nvp("data", make_array(v.data(), v.size()));
}
template<class Archive>
void load(Archive & ar, gtsam::Vector & v, unsigned int /*version*/) {
size_t size;
ar >> BOOST_SERIALIZATION_NVP(size);
v.resize(size);
ar >> make_nvp("data", make_array(v.data(), v.size()));
}
// split version - copies into an STL vector for serialization
template<class Archive, int D>
void save(Archive & ar, const Eigen::Matrix<double,D,1> & v, unsigned int /*version*/) {
ar << make_nvp("data", make_array(v.data(), v.RowsAtCompileTime));
}
template<class Archive, int D>
void load(Archive & ar, Eigen::Matrix<double,D,1> & v, unsigned int /*version*/) {
ar >> make_nvp("data", make_array(v.data(), v.RowsAtCompileTime));
}
} // namespace serialization
} // namespace boost
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector)
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector2)
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector3)
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector6)
} // namespace gtsam

View File

@ -0,0 +1,65 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file VectorSerialization.h
* @brief serialization for Vectors
* @author Frank Dellaert
* @date February 2022
*/
#pragma once
#include <gtsam/base/Vector.h>
#include <boost/serialization/array.hpp>
#include <boost/serialization/nvp.hpp>
#include <boost/serialization/split_free.hpp>
namespace boost {
namespace serialization {
// split version - copies into an STL vector for serialization
template <class Archive>
void save(Archive& ar, const gtsam::Vector& v, unsigned int /*version*/) {
const size_t size = v.size();
ar << BOOST_SERIALIZATION_NVP(size);
ar << make_nvp("data", make_array(v.data(), v.size()));
}
template <class Archive>
void load(Archive& ar, gtsam::Vector& v, unsigned int /*version*/) {
size_t size;
ar >> BOOST_SERIALIZATION_NVP(size);
v.resize(size);
ar >> make_nvp("data", make_array(v.data(), v.size()));
}
// split version - copies into an STL vector for serialization
template <class Archive, int D>
void save(Archive& ar, const Eigen::Matrix<double, D, 1>& v,
unsigned int /*version*/) {
ar << make_nvp("data", make_array(v.data(), v.RowsAtCompileTime));
}
template <class Archive, int D>
void load(Archive& ar, Eigen::Matrix<double, D, 1>& v,
unsigned int /*version*/) {
ar >> make_nvp("data", make_array(v.data(), v.RowsAtCompileTime));
}
} // namespace serialization
} // namespace boost
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector)
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector2)
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector3)
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector6)

View File

@ -18,6 +18,7 @@
#pragma once
#include <gtsam/base/Matrix.h>
#include <gtsam/base/MatrixSerialization.h>
#include <gtsam/base/FastVector.h>
namespace gtsam {

View File

@ -82,6 +82,7 @@ class IndexPairSetMap {
};
#include <gtsam/base/Matrix.h>
#include <gtsam/base/MatrixSerialization.h>
bool linear_independent(Matrix A, Matrix B, double tol);
#include <gtsam/base/Value.h>

View File

@ -18,7 +18,6 @@
#pragma once
#include <gtsam/base/Matrix.h>
#include <boost/shared_ptr.hpp>
namespace gtsam {

View File

@ -19,6 +19,7 @@
#include <gtsam/inference/Key.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/MatrixSerialization.h>
#include <gtsam/base/Vector.h>
#include <gtsam/base/FastList.h>
#include <gtsam/base/FastMap.h>

View File

@ -22,6 +22,7 @@
#include <gtsam/base/Testable.h>
#include <gtsam/base/OptionalJacobian.h>
#include <boost/concept/assert.hpp>
#include <boost/serialization/nvp.hpp>
#include <iostream>
namespace gtsam {

View File

@ -21,6 +21,7 @@
#pragma once
#include <gtsam/geometry/Cal3DS2_Base.h>
#include <boost/shared_ptr.hpp>
namespace gtsam {

View File

@ -21,6 +21,7 @@
#include <gtsam/geometry/Cal3.h>
#include <gtsam/geometry/Point2.h>
#include <boost/shared_ptr.hpp>
namespace gtsam {

View File

@ -22,6 +22,8 @@
#include <gtsam/geometry/Cal3.h>
#include <gtsam/geometry/Point2.h>
#include <boost/shared_ptr.hpp>
#include <string>
namespace gtsam {

View File

@ -17,6 +17,7 @@
#include <gtsam/geometry/Point3.h>
#include <cmath>
#include <iostream>
#include <vector>
using namespace std;

View File

@ -24,6 +24,8 @@
#include <gtsam/dllexport.h>
#include <Eigen/Core>
#include <boost/serialization/nvp.hpp>
#include <iostream> // TODO(frank): how to avoid?
#include <string>
#include <type_traits>

View File

@ -23,11 +23,12 @@
#include <gtsam/geometry/Point2.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/base/Manifold.h>
#include <gtsam/base/Vector.h>
#include <gtsam/base/VectorSerialization.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/dllexport.h>
#include <boost/optional.hpp>
#include <boost/serialization/nvp.hpp>
#include <random>
#include <string>

View File

@ -17,42 +17,41 @@
*/
#include <gtsam/linear/GaussianDensity.h>
#include <boost/format.hpp>
#include <string>
using namespace std;
using std::cout;
using std::endl;
using std::string;
namespace gtsam {
/* ************************************************************************* */
GaussianDensity GaussianDensity::FromMeanAndStddev(Key key,
const Vector& mean,
double sigma) {
return GaussianDensity(key, mean,
Matrix::Identity(mean.size(), mean.size()),
noiseModel::Isotropic::Sigma(mean.size(), sigma));
}
/* ************************************************************************* */
GaussianDensity GaussianDensity::FromMeanAndStddev(Key key, const Vector& mean,
double sigma) {
return GaussianDensity(key, mean, Matrix::Identity(mean.size(), mean.size()),
noiseModel::Isotropic::Sigma(mean.size(), sigma));
}
/* ************************************************************************* */
void GaussianDensity::print(const string &s, const KeyFormatter& formatter) const
{
cout << s << ": density on ";
for(const_iterator it = beginFrontals(); it != endFrontals(); ++it)
cout << (boost::format("[%1%]")%(formatter(*it))).str() << " ";
cout << endl;
gtsam::print(mean(), "mean: ");
gtsam::print(covariance(), "covariance: ");
if(model_)
model_->print("Noise model: ");
}
/* ************************************************************************* */
void GaussianDensity::print(const string& s,
const KeyFormatter& formatter) const {
cout << s << ": density on ";
for (const_iterator it = beginFrontals(); it != endFrontals(); ++it)
cout << (boost::format("[%1%]") % (formatter(*it))).str() << " ";
cout << endl;
gtsam::print(mean(), "mean: ");
gtsam::print(covariance(), "covariance: ");
if (model_) model_->print("Noise model: ");
}
/* ************************************************************************* */
Vector GaussianDensity::mean() const {
VectorValues soln = this->solve(VectorValues());
return soln[firstFrontalKey()];
}
/* ************************************************************************* */
Vector GaussianDensity::mean() const {
VectorValues soln = this->solve(VectorValues());
return soln[firstFrontalKey()];
}
/* ************************************************************************* */
Matrix GaussianDensity::covariance() const {
return information().inverse();
}
/* ************************************************************************* */
Matrix GaussianDensity::covariance() const { return information().inverse(); }
} // gtsam
} // namespace gtsam

View File

@ -19,6 +19,7 @@
#include <gtsam/linear/LossFunctions.h>
#include <iostream>
#include <vector>
using namespace std;

View File

@ -16,6 +16,7 @@
*/
#include <gtsam_unstable/nonlinear/LinearizedFactor.h>
#include <boost/format.hpp>
#include <iostream>
namespace gtsam {

View File

@ -7,9 +7,6 @@
* @author Alex Cunningham
*/
#include <CppUnitLite/TestHarness.h>
#include <iostream>
#include <gtsam_unstable/slam/serialization.h>
#include <gtsam/geometry/Pose2.h>
@ -18,12 +15,16 @@
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/sam/BearingRangeFactor.h>
#include <stdlib.h>
#include <fstream>
#include <sstream>
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/std/vector.hpp>
#include <boost/filesystem.hpp>
#include <iostream>
#include <cstdlib>
#include <fstream>
#include <sstream>
using namespace std;
using namespace gtsam;
using namespace boost::assign;