Add headers in the place they are needed

release/4.3a0
Frank Dellaert 2022-02-16 15:08:28 -05:00
parent a97eae628c
commit c78af4d3ea
18 changed files with 67 additions and 50 deletions

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

@ -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

@ -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

@ -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;