Symbol.h is now included just in time, no longer by default everywhere.

release/4.3a0
Frank Dellaert 2012-06-02 19:05:38 +00:00
parent 5160c2eb50
commit a2512475c9
42 changed files with 192 additions and 154 deletions

View File

@ -663,6 +663,14 @@
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testGeneralSFMFactor_Cal3Bundler.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testGeneralSFMFactor_Cal3Bundler.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testValues.run" path="build/gtsam/nonlinear" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>

View File

@ -18,6 +18,9 @@
// pull in the planar SLAM domain with all typedefs and helper functions defined
#include <gtsam/slam/planarSLAM.h>
// we will use Symbol keys
#include <gtsam/nonlinear/Symbol.h>
using namespace std;
using namespace gtsam;

View File

@ -22,6 +22,7 @@
*/
#include <gtsam/nonlinear/ExtendedKalmanFilter-inl.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/geometry/Point2.h>

View File

@ -18,15 +18,16 @@
#include "vSLAMutils.h"
#include "Feature2D.h"
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/slam/visualSLAM.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/nonlinear/NonlinearISAM.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <boost/shared_ptr.hpp>
#include <boost/foreach.hpp>
using namespace boost;
using boost::shared_ptr;
using namespace std;
using namespace gtsam;

View File

@ -18,13 +18,14 @@
#include "vSLAMutils.h"
#include "Feature2D.h"
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/slam/visualSLAM.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <boost/shared_ptr.hpp>
using namespace boost;
using boost::shared_ptr;
using namespace std;
using namespace gtsam;

View File

@ -12,13 +12,15 @@
/**
* @file ISAM2-impl.cpp
* @brief Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
* @author Michael Kaess, Richard Roberts
* @author Michael Kaess
* @author Richard Roberts
*/
#include <gtsam/nonlinear/ISAM2-impl.h>
#include <gtsam/nonlinear/Symbol.h> // for selective linearization thresholds
#include <gtsam/base/debug.h>
#include <boost/range/adaptors.hpp>
#include <boost/range/algorithm.hpp>
#include <gtsam/nonlinear/ISAM2-impl.h>
#include <gtsam/base/debug.h>
namespace gtsam {

View File

@ -33,7 +33,6 @@
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Symbol.h>
/**
* Macro to add a standard clone function to a derived factor

View File

@ -17,14 +17,14 @@
#pragma once
#include <set>
#include <gtsam/base/FastMap.h>
#include <gtsam/nonlinear/Key.h>
#include <gtsam/inference/inference.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/base/FastMap.h>
#include <boost/foreach.hpp>
#include <boost/assign/list_inserter.hpp>
#include <boost/pool/pool_alloc.hpp>
#include <set>
namespace gtsam {

View File

@ -14,9 +14,10 @@
* @author Alex Cunningham
*/
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/TestableAssertions.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/base/TestableAssertions.h>
#include <CppUnitLite/TestHarness.h>
using namespace std;
using namespace gtsam;

View File

@ -16,11 +16,12 @@
* @date Feb 7, 2012
*/
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/Cal3DS2.h>
#include <gtsam/geometry/Cal3Bundler.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/base/serializationTestHelpers.h>
#include <CppUnitLite/TestHarness.h>

View File

@ -10,28 +10,29 @@
* -------------------------------------------------------------------------- */
/**
* @file testDynamicValues.cpp
* @file testValues.cpp
* @author Richard Roberts
*/
#include <CppUnitLite/TestHarness.h>
#include <stdexcept>
#include <limits>
#include <boost/assign/std/list.hpp> // for operator +=
using namespace boost::assign;
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/TestableAssertions.h>
#include <gtsam/base/LieVector.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/nonlinear/Values.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/std/list.hpp> // for operator +=
using namespace boost::assign;
#include <stdexcept>
#include <limits>
using namespace gtsam;
using namespace std;
static double inf = std::numeric_limits<double>::infinity();
const Key key1(Symbol('v',1)), key2(Symbol('v',2)), key3(Symbol('v',3)), key4(Symbol('v',4));
const Symbol key1('v',1), key2('v',2), key3('v',3), key4('v',4);
/* ************************************************************************* */
TEST( Values, equals1 )

View File

@ -20,9 +20,10 @@
#pragma once
#include <gtsam/geometry/Point2.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/geometry/CalibratedCamera.h>
#include <gtsam/geometry/Point2.h>
#include <gtsam/geometry/Point3.h>
namespace gtsam {

View File

@ -19,7 +19,6 @@
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>

View File

@ -20,7 +20,6 @@
#include <gtsam/geometry/Pose3.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>

View File

@ -18,6 +18,7 @@
*/
#include <gtsam/slam/smallExample.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearFactor.h>

View File

@ -16,23 +16,24 @@
* @brief unit tests for GeneralSFMFactor
*/
#include <iostream>
#include <vector>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/slam/RangeFactor.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/linear/VectorValues.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/base/Testable.h>
#include <boost/shared_ptr.hpp>
#include <CppUnitLite/TestHarness.h>
using namespace boost;
#include <gtsam/base/Testable.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/slam/RangeFactor.h>
#include <gtsam/slam/PriorFactor.h>
#include <iostream>
#include <vector>
using namespace std;
using namespace gtsam;

View File

@ -10,28 +10,30 @@
* -------------------------------------------------------------------------- */
/**
* @file testGeneralSFMFactor.cpp
* @file testGeneralSFMFactor_Cal3Bundler.cpp
* @date Dec 27, 2010
* @author nikai
* @brief unit tests for GeneralSFMFactor
*/
#include <iostream>
#include <vector>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/slam/RangeFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/linear/VectorValues.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Cal3Bundler.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/base/Testable.h>
#include <boost/shared_ptr.hpp>
#include <CppUnitLite/TestHarness.h>
using namespace boost;
#include <gtsam/base/Testable.h>
#include <gtsam/geometry/Cal3Bundler.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/slam/RangeFactor.h>
#include <iostream>
#include <vector>
using namespace std;
using namespace gtsam;
@ -146,8 +148,8 @@ vector<GeneralCamera> genCameraVariableCalibration() {
return X ;
}
shared_ptr<Ordering> getOrdering(const vector<GeneralCamera>& X, const vector<Point3>& L) {
shared_ptr<Ordering> ordering(new Ordering);
boost::shared_ptr<Ordering> getOrdering(const std::vector<GeneralCamera>& X, const std::vector<Point3>& L) {
boost::shared_ptr<Ordering> ordering(new Ordering);
for ( size_t i = 0 ; i < L.size() ; ++i ) ordering->push_back(Symbol('l', i)) ;
for ( size_t i = 0 ; i < X.size() ; ++i ) ordering->push_back(Symbol('x', i)) ;
return ordering ;

View File

@ -14,16 +14,16 @@
* @author Frank Dellaert
**/
#include <gtsam/slam/planarSLAM.h>
#include <gtsam/slam/BearingRangeFactor.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/base/TestableAssertions.h>
#include <iostream>
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/TestableAssertions.h>
#include <gtsam/slam/planarSLAM.h>
#include <gtsam/slam/BearingRangeFactor.h>
using namespace std;
using namespace gtsam;
using namespace planarSLAM;
// some shared test values
static Pose2 x1, x2(1, 1, 0), x3(1, 1, M_PI_4);

View File

@ -17,6 +17,7 @@
*/
#include <gtsam/slam/visualSLAM.h>
#include <gtsam/nonlinear/Symbol.h>
#include <CppUnitLite/TestHarness.h>
using namespace std;

View File

@ -16,12 +16,12 @@
* @date Feb 7, 2012
*/
#include <gtsam/linear/GaussianISAM.h>
#include <gtsam/linear/GaussianMultifrontalSolver.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/slam/planarSLAM.h>
#include <gtsam/slam/visualSLAM.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/linear/GaussianISAM.h>
#include <gtsam/linear/GaussianMultifrontalSolver.h>
#include <gtsam/base/serializationTestHelpers.h>
#include <CppUnitLite/TestHarness.h>

View File

@ -16,17 +16,17 @@
* @brief unit tests for simulated2DOriented
*/
#include <iostream>
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h>
#include <gtsam/slam/simulated2D.h>
#include <gtsam/slam/simulated2DOriented.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h>
using namespace std;
using namespace gtsam;
using namespace simulated2DOriented;
#include <iostream>
#include <CppUnitLite/TestHarness.h>
// Convenience for named keys
Key kx(size_t i) { return Symbol('x',i); }

View File

@ -19,6 +19,7 @@
#include <gtsam/slam/StereoFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/geometry/StereoCamera.h>
#include <gtsam/geometry/Pose3.h>

View File

@ -20,6 +20,7 @@
#include <gtsam/slam/visualSLAM.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/nonlinear/Symbol.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/shared_ptr.hpp>

View File

@ -23,7 +23,6 @@
#include <gtsam/slam/ProjectionFactor.h>
#include <gtsam/slam/StereoFactor.h>
#include <gtsam/slam/RangeFactor.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>

View File

@ -23,7 +23,6 @@
#include <gtsam/geometry/Point3.h>
#include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/Symbol.h>
// \namespace

View File

@ -18,10 +18,11 @@
#include <iostream>
#include <CppUnitLite/TestHarness.h>
#include <gtsam_unstable/slam/simulated3D.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam_unstable/slam/simulated3D.h>
using namespace gtsam;
using namespace simulated3D;

View File

@ -15,12 +15,13 @@
* @author Alex Cunningham
*/
#include <CppUnitLite/TestHarness.h>
#include <gtsam/slam/simulated2DConstraints.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <CppUnitLite/TestHarness.h>
namespace iq2D = simulated2D::inequality_constraints;
using namespace std;
using namespace gtsam;

View File

@ -15,15 +15,17 @@
* @author Richard Roberts
*/
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/numericalDerivative.h>
#include <gtsam/inference/BayesTree-inl.h>
#include <gtsam/slam/pose2SLAM.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/nonlinear/DoglegOptimizerImpl.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/linear/JacobianFactor.h>
#include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/linear/GaussianBayesTree.h>
#include <gtsam/nonlinear/DoglegOptimizerImpl.h>
#include <gtsam/slam/pose2SLAM.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/inference/BayesTree-inl.h>
#include <gtsam/base/numericalDerivative.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/bind.hpp>
#include <boost/assign/list_of.hpp> // for 'list_of()'

View File

@ -14,14 +14,15 @@
* @author Stephen Williams
*/
#include <CppUnitLite/TestHarness.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/ExtendedKalmanFilter-inl.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/geometry/Point2.h>
#include <CppUnitLite/TestHarness.h>
using namespace gtsam;
/* ************************************************************************* */

View File

@ -16,7 +16,14 @@
* @author Frank Dellaert
**/
#include <iostream>
#include <gtsam/slam/smallExample.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/linear/GaussianConditional.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Testable.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/tuple/tuple.hpp>
#include <boost/assign/std/list.hpp> // for operator +=
@ -24,18 +31,10 @@
#include <boost/assign/std/map.hpp> // for insert
using namespace boost::assign;
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Testable.h>
#include <gtsam/linear/GaussianConditional.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/nonlinear/Ordering.h>
#include <iostream>
using namespace std;
using namespace gtsam;
using namespace example;
using namespace boost;
static SharedDiagonal
sigma0_1 = sharedSigma(2,0.1), sigma_02 = sharedSigma(2,0.2),
@ -53,7 +52,7 @@ TEST( GaussianFactor, linearFactor )
JacobianFactor expected(ordering[kx1], -10*I,ordering[kx2], 10*I, b, noiseModel::Unit::Create(2));
// create a small linear factor graph
FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering);
FactorGraph<JacobianFactor> fg = example::createGaussianFactorGraph(ordering);
// get the factor kf2 from the factor graph
JacobianFactor::shared_ptr lf = fg[1];
@ -94,7 +93,7 @@ TEST( GaussianFactor, getDim )
{
// get a factor
Ordering ordering; ordering += kx1,kx2,kl1;
GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering);
GaussianFactor::shared_ptr factor = fg[0];
// get the size of a variable
@ -166,13 +165,13 @@ TEST( GaussianFactor, error )
{
// create a small linear factor graph
Ordering ordering; ordering += kx1,kx2,kl1;
GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering);
// get the first factor from the factor graph
GaussianFactor::shared_ptr lf = fg[0];
// check the error of the first factor with noisy config
VectorValues cfg = createZeroDelta(ordering);
VectorValues cfg = example::createZeroDelta(ordering);
// calculate the error from the factor kf1
// note the error is the same as in testNonlinearFactor
@ -226,7 +225,7 @@ TEST( GaussianFactor, matrix )
{
// create a small linear factor graph
Ordering ordering; ordering += kx1,kx2,kl1;
FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering);
FactorGraph<JacobianFactor> fg = example::createGaussianFactorGraph(ordering);
// get the factor kf2 from the factor graph
//GaussianFactor::shared_ptr lf = fg[1]; // NOTE: using the older version
@ -263,7 +262,7 @@ TEST( GaussianFactor, matrix )
EQUALITY(b_act2,b2);
// Ensure that whitening is consistent
shared_ptr<noiseModel::Gaussian> model = lf->get_model();
boost::shared_ptr<noiseModel::Gaussian> model = lf->get_model();
model->WhitenSystem(A_act2, b_act2);
EQUALITY(A_act1, A_act2);
EQUALITY(b_act1, b_act2);
@ -274,7 +273,7 @@ TEST( GaussianFactor, matrix_aug )
{
// create a small linear factor graph
Ordering ordering; ordering += kx1,kx2,kl1;
FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering);
FactorGraph<JacobianFactor> fg = example::createGaussianFactorGraph(ordering);
// get the factor kf2 from the factor graph
//GaussianFactor::shared_ptr lf = fg[1];
@ -307,7 +306,7 @@ TEST( GaussianFactor, matrix_aug )
EQUALITY(Ab_act2,Ab2);
// Ensure that whitening is consistent
shared_ptr<noiseModel::Gaussian> model = lf->get_model();
boost::shared_ptr<noiseModel::Gaussian> model = lf->get_model();
model->WhitenInPlace(Ab_act1);
EQUALITY(Ab_act1, Ab_act2);
}
@ -385,7 +384,7 @@ TEST( GaussianFactor, size )
{
// create a linear factor graph
Ordering ordering; ordering += kx1,kx2,kl1;
GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
GaussianFactorGraph fg = example::createGaussianFactorGraph(ordering);
// get some factors from the graph
boost::shared_ptr<GaussianFactor> factor1 = fg[0];

View File

@ -15,9 +15,16 @@
* @author Christian Potthast
**/
#include <string.h>
#include <iostream>
using namespace std;
#include <gtsam/slam/smallExample.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/linear/GaussianBayesNet.h>
#include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/inference/SymbolicFactorGraph.h>
#include <gtsam/base/numericalDerivative.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Testable.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/foreach.hpp>
#include <boost/tuple/tuple.hpp>
@ -26,16 +33,10 @@ using namespace std;
#include <boost/assign/std/vector.hpp> // for operator +=
using namespace boost::assign;
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h>
#include <gtsam/inference/SymbolicFactorGraph.h>
#include <gtsam/linear/GaussianBayesNet.h>
#include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/slam/smallExample.h>
#include <string.h>
#include <iostream>
using namespace std;
using namespace gtsam;
using namespace example;

View File

@ -15,20 +15,21 @@
* @author Michael Kaess
*/
#include <boost/foreach.hpp>
#include <boost/assign/std/list.hpp> // for operator +=
using namespace boost::assign;
#include <CppUnitLite/TestHarness.h>
#include <gtsam/geometry/Rot2.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/linear/GaussianBayesNet.h>
#include <gtsam/inference/ISAM.h>
#include <gtsam/linear/GaussianISAM.h>
#include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/linear/GaussianMultifrontalSolver.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/inference/ISAM.h>
#include <gtsam/geometry/Rot2.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/foreach.hpp>
#include <boost/assign/std/list.hpp> // for operator +=
using namespace boost::assign;
using namespace std;
using namespace gtsam;

View File

@ -15,9 +15,20 @@
* @author nikai
*/
#include <iostream>
#include <CppUnitLite/TestHarness.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/slam/planarSLAM.h>
#include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/linear/GaussianJunctionTree.h>
#include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/linear/GaussianMultifrontalSolver.h>
#include <gtsam/inference/BayesTree-inl.h>
#include <gtsam/base/TestableAssertions.h>
#include <gtsam/base/debug.h>
#include <gtsam/base/cholesky.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/list_of.hpp>
#include <boost/assign/std/list.hpp> // for operator +=
@ -25,16 +36,7 @@
#include <boost/assign/std/vector.hpp>
using namespace boost::assign;
#include <gtsam/base/debug.h>
#include <gtsam/base/cholesky.h>
#include <gtsam/inference/BayesTree-inl.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/linear/GaussianJunctionTree.h>
#include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/linear/GaussianMultifrontalSolver.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/slam/planarSLAM.h>
#include <gtsam/slam/pose2SLAM.h>
#include <iostream>
using namespace std;
using namespace gtsam;

View File

@ -17,6 +17,7 @@
#include <CppUnitLite/TestHarness.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/linear/GaussianSequentialSolver.h>
#include <gtsam/linear/GaussianMultifrontalSolver.h>
#include <gtsam/slam/smallExample.h>

View File

@ -14,15 +14,16 @@
* @author Alex Cunningham
*/
#include <CppUnitLite/TestHarness.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/simulated2DConstraints.h>
#include <gtsam/slam/visualSLAM.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/geometry/Pose2.h>
#include <CppUnitLite/TestHarness.h>
using namespace std;
using namespace gtsam;

View File

@ -32,6 +32,7 @@
#include <gtsam/slam/simulated2D.h>
#include <gtsam/linear/GaussianFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Symbol.h>
using namespace std;
using namespace gtsam;

View File

@ -32,6 +32,7 @@ using namespace boost::assign;
#include <gtsam/slam/smallExample.h>
#include <gtsam/inference/FactorGraph.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Symbol.h>
using namespace gtsam;
using namespace example;

View File

@ -7,6 +7,7 @@
#include <gtsam/linear/Sampler.h>
#include <gtsam/nonlinear/NonlinearISAM.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/slam/planarSLAM.h>
using namespace gtsam;

View File

@ -17,6 +17,7 @@
#include <gtsam/slam/smallExample.h>
#include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
#include <gtsam/nonlinear/DoglegOptimizer.h>

View File

@ -24,6 +24,7 @@
#include <gtsam/geometry/Rot3.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/slam/PriorFactor.h>

View File

@ -26,6 +26,7 @@ using namespace boost::assign;
#include <gtsam/inference/SymbolicFactorGraph.h>
#include <gtsam/inference/SymbolicSequentialSolver.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Symbol.h>
using namespace std;
using namespace gtsam;

View File

@ -15,20 +15,20 @@
* @author Frank Dellaert
*/
#include <boost/assign/std/list.hpp> // for operator +=
using namespace boost::assign;
#include <CppUnitLite/TestHarness.h>
#include <gtsam/slam/smallExample.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/inference/SymbolicFactorGraph.h>
#include <gtsam/inference/BayesNet-inl.h>
#include <gtsam/inference/SymbolicSequentialSolver.h>
#include <gtsam/nonlinear/Ordering.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/std/list.hpp> // for operator +=
using namespace boost::assign;
using namespace std;
using namespace gtsam;
using namespace example;
Key kx(size_t i) { return Symbol('x',i); }
Key kl(size_t i) { return Symbol('l',i); }
@ -45,7 +45,7 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
expected.push_factor(o[kx(2)],o[kl(1)]);
// construct it from the factor graph
GaussianFactorGraph factorGraph = createGaussianFactorGraph(o);
GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(o);
SymbolicFactorGraph actual(factorGraph);
CHECK(assert_equal(expected, actual));
@ -55,7 +55,7 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
//TEST( SymbolicFactorGraph, findAndRemoveFactors )
//{
// // construct it from the factor graph graph
// GaussianFactorGraph factorGraph = createGaussianFactorGraph();
// GaussianFactorGraph factorGraph = example::createGaussianFactorGraph();
// SymbolicFactorGraph actual(factorGraph);
// SymbolicFactor::shared_ptr f1 = actual[0];
// SymbolicFactor::shared_ptr f3 = actual[2];
@ -75,7 +75,7 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
//TEST( SymbolicFactorGraph, factors)
//{
// // create a test graph
// GaussianFactorGraph factorGraph = createGaussianFactorGraph();
// GaussianFactorGraph factorGraph = example::createGaussianFactorGraph();
// SymbolicFactorGraph fg(factorGraph);
//
// // ask for all factor indices connected to x1
@ -95,7 +95,7 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
//TEST( SymbolicFactorGraph, removeAndCombineFactors )
//{
// // create a test graph
// GaussianFactorGraph factorGraph = createGaussianFactorGraph();
// GaussianFactorGraph factorGraph = example::createGaussianFactorGraph();
// SymbolicFactorGraph fg(factorGraph);
//
// // combine all factors connected to x1
@ -111,7 +111,7 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
//{
// Ordering o; o += kx(1),kl(1),kx(2);
// // create a test graph
// GaussianFactorGraph factorGraph = createGaussianFactorGraph(o);
// GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(o);
// SymbolicFactorGraph fg(factorGraph);
//
// // eliminate
@ -139,7 +139,7 @@ TEST( SymbolicFactorGraph, eliminate )
expected.push_back(x1);
// create a test graph
GaussianFactorGraph factorGraph = createGaussianFactorGraph(o);
GaussianFactorGraph factorGraph = example::createGaussianFactorGraph(o);
SymbolicFactorGraph fg(factorGraph);
// eliminate it