Included the inline header at the bottom of SubgraphSolver, NonlinearFactorGraph, NonlinearOptimization, and NonlinearOptimizer. This avoids having to include the '-inl.h' in subsequent projects.

release/4.3a0
Stephen Williams 2011-12-20 23:25:43 +00:00
parent d76176c544
commit 7c87a4f58d
35 changed files with 64 additions and 79 deletions

View File

@ -23,7 +23,7 @@
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
using namespace gtsam; using namespace gtsam;

View File

@ -35,8 +35,8 @@
// implementations for structures - needed if self-contained, and these should be included last // implementations for structures - needed if self-contained, and these should be included last
#include <gtsam/nonlinear/TupleValues.h> #include <gtsam/nonlinear/TupleValues.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/linear/GaussianSequentialSolver.h> #include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/linear/GaussianMultifrontalSolver.h> #include <gtsam/linear/GaussianMultifrontalSolver.h>

View File

@ -22,7 +22,7 @@
// pull in the Pose2 SLAM domain with all typedefs and helper functions defined // pull in the Pose2 SLAM domain with all typedefs and helper functions defined
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>

View File

@ -24,7 +24,7 @@
// pull in the Pose2 SLAM domain with all typedefs and helper functions defined // pull in the Pose2 SLAM domain with all typedefs and helper functions defined
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -19,8 +19,8 @@
#include <boost/shared_ptr.hpp> #include <boost/shared_ptr.hpp>
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/linear/SubgraphSolver-inl.h> #include <gtsam/linear/SubgraphSolver.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -19,7 +19,7 @@
#include <boost/shared_ptr.hpp> #include <boost/shared_ptr.hpp>
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
using namespace std; using namespace std;

View File

@ -24,8 +24,8 @@
#include <gtsam/linear/NoiseModel.h> #include <gtsam/linear/NoiseModel.h>
#include <gtsam/nonlinear/Key.h> #include <gtsam/nonlinear/Key.h>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
/* /*
* TODO: make factors independent of RotValues * TODO: make factors independent of RotValues

View File

@ -23,8 +23,8 @@ using namespace boost;
// Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h // Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph-inl.h>
#include <gtsam/slam/visualSLAM.h> #include <gtsam/slam/visualSLAM.h>
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>

View File

@ -22,8 +22,8 @@ using namespace boost;
// Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h // Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph-inl.h>
#include <gtsam/slam/visualSLAM.h> #include <gtsam/slam/visualSLAM.h>
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>

View File

@ -13,9 +13,8 @@
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <gtsam/linear/SubgraphSolver.h>
#include <gtsam/linear/iterative-inl.h> #include <gtsam/linear/iterative-inl.h>
#include <gtsam/inference/EliminationTree-inl.h> #include <gtsam/inference/EliminationTree.h>
using namespace std; using namespace std;

View File

@ -95,4 +95,6 @@ private:
SubgraphSolver():IterativeSolver(){} SubgraphSolver():IterativeSolver(){}
}; };
} // nsamespace gtsam } // namespace gtsam
#include <gtsam/linear/SubgraphSolver-inl.h>

View File

@ -7,7 +7,7 @@
#include <gtsam/linear/GaussianBayesNet.h> #include <gtsam/linear/GaussianBayesNet.h>
#include <gtsam/linear/GaussianISAM.h> // To get optimize(BayesTree<GaussianConditional>) #include <gtsam/linear/GaussianISAM.h> // To get optimize(BayesTree<GaussianConditional>)
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Ordering.h> #include <gtsam/nonlinear/Ordering.h>
namespace gtsam { namespace gtsam {

View File

@ -19,7 +19,7 @@
// \callgraph // \callgraph
#pragma once #pragma once
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
namespace gtsam { namespace gtsam {

View File

@ -19,16 +19,11 @@
#pragma once #pragma once
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/inference/FactorGraph.h>
#include <gtsam/inference/FactorGraph-inl.h>
#include <gtsam/inference/inference.h> #include <gtsam/inference/inference.h>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <cmath> #include <cmath>
#define INSTANTIATE_NONLINEAR_FACTOR_GRAPH(C) \
INSTANTIATE_FACTOR_GRAPH(NonlinearFactor<C>); \
template class NonlinearFactorGraph<C>;
using namespace std; using namespace std;
namespace gtsam { namespace gtsam {

View File

@ -100,3 +100,5 @@ namespace gtsam {
}; };
} // namespace } // namespace
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>

View File

@ -20,10 +20,9 @@
#include <gtsam/linear/GaussianSequentialSolver.h> #include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/linear/GaussianMultifrontalSolver.h> #include <gtsam/linear/GaussianMultifrontalSolver.h>
#include <gtsam/nonlinear/NonlinearOptimization.h>
#include <gtsam/linear/SubgraphSolver-inl.h> #include <gtsam/linear/SubgraphSolver.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
using namespace std; using namespace std;

View File

@ -50,3 +50,4 @@ namespace gtsam {
} }
#include <gtsam/nonlinear/NonlinearOptimization-inl.h>

View File

@ -23,12 +23,8 @@
#include <iostream> #include <iostream>
#include <boost/tuple/tuple.hpp> #include <boost/tuple/tuple.hpp>
#include <gtsam/base/cholesky.h> #include <gtsam/base/cholesky.h>
#include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/nonlinear/DoglegOptimizerImpl.h> #include <gtsam/nonlinear/DoglegOptimizerImpl.h>
#define INSTANTIATE_NONLINEAR_OPTIMIZER(G,C) \
template class NonlinearOptimizer<G,C>;
using namespace std; using namespace std;
namespace gtsam { namespace gtsam {

View File

@ -419,3 +419,5 @@ bool check_convergence (
double currentError, double newError); double currentError, double newError);
} // gtsam } // gtsam
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h>

View File

@ -16,16 +16,13 @@
**/ **/
#include <gtsam/slam/planarSLAM.h> #include <gtsam/slam/planarSLAM.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
// Use planarSLAM namespace for specific SLAM instance // Use planarSLAM namespace for specific SLAM instance
namespace gtsam { namespace gtsam {
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(planarSLAM::Values)
INSTANTIATE_NONLINEAR_OPTIMIZER(planarSLAM::Graph, planarSLAM::Values)
namespace planarSLAM { namespace planarSLAM {
Graph::Graph(const NonlinearFactorGraph<Values>& graph) : Graph::Graph(const NonlinearFactorGraph<Values>& graph) :

View File

@ -16,14 +16,12 @@
**/ **/
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
// Use pose2SLAM namespace for specific SLAM instance // Use pose2SLAM namespace for specific SLAM instance
namespace gtsam { namespace gtsam {
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(pose2SLAM::Values)
INSTANTIATE_NONLINEAR_OPTIMIZER(pose2SLAM::Graph, pose2SLAM::Values)
template class NonlinearOptimizer<pose2SLAM::Graph, pose2SLAM::Values, GaussianFactorGraph, GaussianSequentialSolver>; template class NonlinearOptimizer<pose2SLAM::Graph, pose2SLAM::Values, GaussianFactorGraph, GaussianSequentialSolver>;
namespace pose2SLAM { namespace pose2SLAM {

View File

@ -16,15 +16,12 @@
**/ **/
#include <gtsam/slam/pose3SLAM.h> #include <gtsam/slam/pose3SLAM.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
// Use pose3SLAM namespace for specific SLAM instance // Use pose3SLAM namespace for specific SLAM instance
namespace gtsam { namespace gtsam {
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(pose3SLAM::Values)
INSTANTIATE_NONLINEAR_OPTIMIZER(pose3SLAM::Graph, pose3SLAM::Values)
namespace pose3SLAM { namespace pose3SLAM {
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -32,9 +32,9 @@ using namespace std;
#include <gtsam/slam/smallExample.h> #include <gtsam/slam/smallExample.h>
// template definitions // template definitions
#include <gtsam/inference/FactorGraph-inl.h> #include <gtsam/inference/FactorGraph.h>
#include <gtsam/nonlinear/Ordering.h> #include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
namespace gtsam { namespace gtsam {
namespace example { namespace example {

View File

@ -16,9 +16,9 @@ using namespace boost;
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/TupleValues.h> #include <gtsam/nonlinear/TupleValues.h>
#include <gtsam/nonlinear/NonlinearEquality.h> #include <gtsam/nonlinear/NonlinearEquality.h>

View File

@ -16,9 +16,9 @@ using namespace boost;
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/TupleValues.h> #include <gtsam/nonlinear/TupleValues.h>
#include <gtsam/nonlinear/NonlinearEquality.h> #include <gtsam/nonlinear/NonlinearEquality.h>

View File

@ -18,8 +18,8 @@
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/inference/FactorGraph-inl.h> #include <gtsam/inference/FactorGraph.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
using namespace gtsam; using namespace gtsam;

View File

@ -20,11 +20,11 @@
#include <gtsam/geometry/StereoCamera.h> #include <gtsam/geometry/StereoCamera.h>
#include <gtsam/geometry/Pose3.h> #include <gtsam/geometry/Pose3.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/slam/StereoFactor.h> #include <gtsam/slam/StereoFactor.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph.h>
#include <gtsam/slam/visualSLAM.h> #include <gtsam/slam/visualSLAM.h>
using namespace std; using namespace std;

View File

@ -25,9 +25,9 @@ using namespace boost;
// Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h // Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph.h>
#include <gtsam/slam/visualSLAM.h> #include <gtsam/slam/visualSLAM.h>
using namespace std; using namespace std;

View File

@ -16,12 +16,9 @@
*/ */
#include <gtsam/slam/visualSLAM.h> #include <gtsam/slam/visualSLAM.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
namespace gtsam { namespace gtsam {
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(visualSLAM::Values)
INSTANTIATE_NONLINEAR_OPTIMIZER(visualSLAM::Graph, visualSLAM::Values)
} }

View File

@ -18,8 +18,8 @@
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <gtsam/slam/simulated2DConstraints.h> #include <gtsam/slam/simulated2DConstraints.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
namespace iq2D = gtsam::simulated2D::inequality_constraints; namespace iq2D = gtsam::simulated2D::inequality_constraints;
using namespace std; using namespace std;

View File

@ -34,7 +34,7 @@
#include <gtsam/slam/smallExample.h> #include <gtsam/slam/smallExample.h>
#include <gtsam/slam/simulated2D.h> #include <gtsam/slam/simulated2D.h>
#include <gtsam/linear/GaussianFactor.h> #include <gtsam/linear/GaussianFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -33,8 +33,8 @@ using namespace boost::assign;
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>
#include <gtsam/slam/smallExample.h> #include <gtsam/slam/smallExample.h>
#include <gtsam/inference/FactorGraph-inl.h> #include <gtsam/inference/FactorGraph.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
using namespace gtsam; using namespace gtsam;
using namespace example; using namespace example;

View File

@ -36,9 +36,9 @@ using namespace boost;
#include <gtsam/linear/NoiseModel.h> #include <gtsam/linear/NoiseModel.h>
// template definitions // template definitions
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
using namespace gtsam; using namespace gtsam;

View File

@ -6,7 +6,7 @@
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -22,9 +22,9 @@
#include <gtsam/base/lieProxies.h> #include <gtsam/base/lieProxies.h>
#include <gtsam/geometry/Point3.h> #include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Rot3Q.h> #include <gtsam/geometry/Rot3Q.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization.h>
#include <gtsam/slam/BetweenFactor.h> #include <gtsam/slam/BetweenFactor.h>
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>