From a2512475c925cd3772f0e65a0338beac174de5a1 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 2 Jun 2012 19:05:38 +0000 Subject: [PATCH] Symbol.h is now included just in time, no longer by default everywhere. --- .cproject | 8 ++++ examples/PlanarSLAMExample_easy.cpp | 3 ++ examples/easyPoint2KalmanFilter.cpp | 1 + examples/vSLAMexample/vISAMexample.cpp | 7 ++-- examples/vSLAMexample/vSFMexample.cpp | 7 ++-- gtsam/nonlinear/ISAM2-impl.cpp | 8 ++-- gtsam/nonlinear/NonlinearFactor.h | 1 - gtsam/nonlinear/Ordering.h | 6 +-- gtsam/nonlinear/tests/testOrdering.cpp | 5 ++- .../tests/testSerializationNonlinear.cpp | 3 +- gtsam/nonlinear/tests/testValues.cpp | 23 ++++++------ gtsam/slam/GeneralSFMFactor.h | 5 ++- gtsam/slam/pose2SLAM.h | 1 - gtsam/slam/pose3SLAM.h | 1 - gtsam/slam/smallExample.cpp | 1 + gtsam/slam/tests/testGeneralSFMFactor.cpp | 25 +++++++------ .../testGeneralSFMFactor_Cal3Bundler.cpp | 32 ++++++++-------- gtsam/slam/tests/testPlanarSLAM.cpp | 10 ++--- gtsam/slam/tests/testProjectionFactor.cpp | 1 + gtsam/slam/tests/testSerializationSLAM.cpp | 6 +-- gtsam/slam/tests/testSimulated2DOriented.cpp | 12 +++--- gtsam/slam/tests/testStereoFactor.cpp | 1 + gtsam/slam/tests/testVisualSLAM.cpp | 1 + gtsam/slam/visualSLAM.h | 1 - gtsam_unstable/slam/simulated3D.h | 1 - gtsam_unstable/slam/tests/testSimulated3D.cpp | 5 ++- tests/testBoundingConstraint.cpp | 5 ++- tests/testDoglegOptimizer.cpp | 14 ++++--- tests/testExtendedKalmanFilter.cpp | 5 ++- tests/testGaussianFactor.cpp | 37 +++++++++---------- tests/testGaussianFactorGraphB.cpp | 25 +++++++------ tests/testGaussianISAM.cpp | 19 +++++----- tests/testGaussianJunctionTreeB.cpp | 26 +++++++------ tests/testInferenceB.cpp | 1 + tests/testNonlinearEquality.cpp | 7 ++-- tests/testNonlinearFactor.cpp | 1 + tests/testNonlinearFactorGraph.cpp | 1 + tests/testNonlinearISAM.cpp | 1 + tests/testNonlinearOptimizer.cpp | 1 + tests/testRot3Optimization.cpp | 1 + tests/testSymbolicBayesNetB.cpp | 1 + tests/testSymbolicFactorGraphB.cpp | 26 ++++++------- 42 files changed, 192 insertions(+), 154 deletions(-) diff --git a/.cproject b/.cproject index c19b1a91a..ec6a2bf6f 100644 --- a/.cproject +++ b/.cproject @@ -663,6 +663,14 @@ true true + + make + -j5 + testGeneralSFMFactor_Cal3Bundler.run + true + true + true + make -j5 diff --git a/examples/PlanarSLAMExample_easy.cpp b/examples/PlanarSLAMExample_easy.cpp index cd4a7aefd..fc371033e 100644 --- a/examples/PlanarSLAMExample_easy.cpp +++ b/examples/PlanarSLAMExample_easy.cpp @@ -18,6 +18,9 @@ // pull in the planar SLAM domain with all typedefs and helper functions defined #include +// we will use Symbol keys +#include + using namespace std; using namespace gtsam; diff --git a/examples/easyPoint2KalmanFilter.cpp b/examples/easyPoint2KalmanFilter.cpp index b13058a07..2b4d2476a 100644 --- a/examples/easyPoint2KalmanFilter.cpp +++ b/examples/easyPoint2KalmanFilter.cpp @@ -22,6 +22,7 @@ */ #include +#include #include #include #include diff --git a/examples/vSLAMexample/vISAMexample.cpp b/examples/vSLAMexample/vISAMexample.cpp index 6b47c9633..d23ea9b10 100644 --- a/examples/vSLAMexample/vISAMexample.cpp +++ b/examples/vSLAMexample/vISAMexample.cpp @@ -18,15 +18,16 @@ #include "vSLAMutils.h" #include "Feature2D.h" -#include -#include #include #include #include +#include +#include +#include #include #include -using namespace boost; +using boost::shared_ptr; using namespace std; using namespace gtsam; diff --git a/examples/vSLAMexample/vSFMexample.cpp b/examples/vSLAMexample/vSFMexample.cpp index 6eb3955f2..be41ad831 100644 --- a/examples/vSLAMexample/vSFMexample.cpp +++ b/examples/vSLAMexample/vSFMexample.cpp @@ -18,13 +18,14 @@ #include "vSLAMutils.h" #include "Feature2D.h" -#include -#include #include #include +#include +#include +#include #include -using namespace boost; +using boost::shared_ptr; using namespace std; using namespace gtsam; diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index 8fe117e34..46fbe94f9 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -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 +#include // for selective linearization thresholds +#include #include #include -#include -#include namespace gtsam { diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index bf6527599..12001551c 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -33,7 +33,6 @@ #include #include -#include /** * Macro to add a standard clone function to a derived factor diff --git a/gtsam/nonlinear/Ordering.h b/gtsam/nonlinear/Ordering.h index 879b50677..f775f168b 100644 --- a/gtsam/nonlinear/Ordering.h +++ b/gtsam/nonlinear/Ordering.h @@ -17,14 +17,14 @@ #pragma once -#include -#include +#include #include -#include +#include #include #include #include +#include namespace gtsam { diff --git a/gtsam/nonlinear/tests/testOrdering.cpp b/gtsam/nonlinear/tests/testOrdering.cpp index f57e3281a..beb16f741 100644 --- a/gtsam/nonlinear/tests/testOrdering.cpp +++ b/gtsam/nonlinear/tests/testOrdering.cpp @@ -14,9 +14,10 @@ * @author Alex Cunningham */ -#include -#include #include +#include +#include +#include using namespace std; using namespace gtsam; diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index 120a9fa94..bc023f115 100644 --- a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp +++ b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp @@ -16,11 +16,12 @@ * @date Feb 7, 2012 */ +#include +#include #include #include #include #include -#include #include #include diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 6ccd3b083..f5caa846b 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -10,28 +10,29 @@ * -------------------------------------------------------------------------- */ /** - * @file testDynamicValues.cpp + * @file testValues.cpp * @author Richard Roberts */ -#include -#include -#include -#include // for operator += -using namespace boost::assign; - +#include +#include +#include +#include #include #include #include -#include -#include -#include + +#include +#include // for operator += +using namespace boost::assign; +#include +#include using namespace gtsam; using namespace std; static double inf = std::numeric_limits::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 ) diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index d046d0e1b..d64585b7d 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -20,9 +20,10 @@ #pragma once -#include #include - +#include +#include +#include namespace gtsam { diff --git a/gtsam/slam/pose2SLAM.h b/gtsam/slam/pose2SLAM.h index 337ab9f7a..84fbc528f 100644 --- a/gtsam/slam/pose2SLAM.h +++ b/gtsam/slam/pose2SLAM.h @@ -19,7 +19,6 @@ #include #include -#include #include #include #include diff --git a/gtsam/slam/pose3SLAM.h b/gtsam/slam/pose3SLAM.h index e42238892..f81070818 100644 --- a/gtsam/slam/pose3SLAM.h +++ b/gtsam/slam/pose3SLAM.h @@ -20,7 +20,6 @@ #include #include #include -#include #include #include #include diff --git a/gtsam/slam/smallExample.cpp b/gtsam/slam/smallExample.cpp index 2e9194466..b0e709a80 100644 --- a/gtsam/slam/smallExample.cpp +++ b/gtsam/slam/smallExample.cpp @@ -18,6 +18,7 @@ */ #include +#include #include #include #include diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index 5b8a217bc..f9911ce7d 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor.cpp @@ -16,23 +16,24 @@ * @brief unit tests for GeneralSFMFactor */ -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include using namespace boost; -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include using namespace std; using namespace gtsam; diff --git a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp index 76cf7d180..7698acae4 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp @@ -10,28 +10,30 @@ * -------------------------------------------------------------------------- */ /** - * @file testGeneralSFMFactor.cpp + * @file testGeneralSFMFactor_Cal3Bundler.cpp * @date Dec 27, 2010 * @author nikai * @brief unit tests for GeneralSFMFactor */ -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include -using namespace boost; -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include using namespace std; using namespace gtsam; @@ -146,8 +148,8 @@ vector genCameraVariableCalibration() { return X ; } -shared_ptr getOrdering(const vector& X, const vector& L) { - shared_ptr ordering(new Ordering); +boost::shared_ptr getOrdering(const std::vector& X, const std::vector& L) { + boost::shared_ptr 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 ; diff --git a/gtsam/slam/tests/testPlanarSLAM.cpp b/gtsam/slam/tests/testPlanarSLAM.cpp index 8859f7a08..11efc7b5e 100644 --- a/gtsam/slam/tests/testPlanarSLAM.cpp +++ b/gtsam/slam/tests/testPlanarSLAM.cpp @@ -14,16 +14,16 @@ * @author Frank Dellaert **/ +#include +#include +#include +#include + #include #include -#include -#include -#include - 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); diff --git a/gtsam/slam/tests/testProjectionFactor.cpp b/gtsam/slam/tests/testProjectionFactor.cpp index 80b35f269..2ec97f301 100644 --- a/gtsam/slam/tests/testProjectionFactor.cpp +++ b/gtsam/slam/tests/testProjectionFactor.cpp @@ -17,6 +17,7 @@ */ #include +#include #include using namespace std; diff --git a/gtsam/slam/tests/testSerializationSLAM.cpp b/gtsam/slam/tests/testSerializationSLAM.cpp index 4442d73fc..23093a28e 100644 --- a/gtsam/slam/tests/testSerializationSLAM.cpp +++ b/gtsam/slam/tests/testSerializationSLAM.cpp @@ -16,12 +16,12 @@ * @date Feb 7, 2012 */ -#include -#include #include #include #include - +#include +#include +#include #include #include diff --git a/gtsam/slam/tests/testSimulated2DOriented.cpp b/gtsam/slam/tests/testSimulated2DOriented.cpp index b3d6e8d9e..afca72402 100644 --- a/gtsam/slam/tests/testSimulated2DOriented.cpp +++ b/gtsam/slam/tests/testSimulated2DOriented.cpp @@ -16,17 +16,17 @@ * @brief unit tests for simulated2DOriented */ -#include -#include - -#include -#include #include #include +#include +#include +#include using namespace std; using namespace gtsam; -using namespace simulated2DOriented; + +#include +#include // Convenience for named keys Key kx(size_t i) { return Symbol('x',i); } diff --git a/gtsam/slam/tests/testStereoFactor.cpp b/gtsam/slam/tests/testStereoFactor.cpp index ffa512d96..9a8a27054 100644 --- a/gtsam/slam/tests/testStereoFactor.cpp +++ b/gtsam/slam/tests/testStereoFactor.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include diff --git a/gtsam/slam/tests/testVisualSLAM.cpp b/gtsam/slam/tests/testVisualSLAM.cpp index 27b930022..dc9b64f4d 100644 --- a/gtsam/slam/tests/testVisualSLAM.cpp +++ b/gtsam/slam/tests/testVisualSLAM.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include diff --git a/gtsam/slam/visualSLAM.h b/gtsam/slam/visualSLAM.h index 9933c4d9f..32824b60e 100644 --- a/gtsam/slam/visualSLAM.h +++ b/gtsam/slam/visualSLAM.h @@ -23,7 +23,6 @@ #include #include #include -#include #include #include #include diff --git a/gtsam_unstable/slam/simulated3D.h b/gtsam_unstable/slam/simulated3D.h index 66552b926..ef79991b8 100644 --- a/gtsam_unstable/slam/simulated3D.h +++ b/gtsam_unstable/slam/simulated3D.h @@ -23,7 +23,6 @@ #include #include #include -#include // \namespace diff --git a/gtsam_unstable/slam/tests/testSimulated3D.cpp b/gtsam_unstable/slam/tests/testSimulated3D.cpp index 5aca0ce3a..d7633f473 100644 --- a/gtsam_unstable/slam/tests/testSimulated3D.cpp +++ b/gtsam_unstable/slam/tests/testSimulated3D.cpp @@ -18,10 +18,11 @@ #include #include +#include +#include +#include #include #include -#include -#include using namespace gtsam; using namespace simulated3D; diff --git a/tests/testBoundingConstraint.cpp b/tests/testBoundingConstraint.cpp index 35b1833ee..d728742f7 100644 --- a/tests/testBoundingConstraint.cpp +++ b/tests/testBoundingConstraint.cpp @@ -15,12 +15,13 @@ * @author Alex Cunningham */ -#include - #include +#include #include #include +#include + namespace iq2D = simulated2D::inequality_constraints; using namespace std; using namespace gtsam; diff --git a/tests/testDoglegOptimizer.cpp b/tests/testDoglegOptimizer.cpp index ae8c6e00e..f175ca9f3 100644 --- a/tests/testDoglegOptimizer.cpp +++ b/tests/testDoglegOptimizer.cpp @@ -15,15 +15,17 @@ * @author Richard Roberts */ -#include -#include -#include +#include +#include +#include +#include #include #include #include -#include -#include -#include +#include +#include + +#include #include #include // for 'list_of()' diff --git a/tests/testExtendedKalmanFilter.cpp b/tests/testExtendedKalmanFilter.cpp index c0e5af4f7..9071d9c63 100644 --- a/tests/testExtendedKalmanFilter.cpp +++ b/tests/testExtendedKalmanFilter.cpp @@ -14,14 +14,15 @@ * @author Stephen Williams */ -#include - #include #include #include #include +#include #include +#include + using namespace gtsam; /* ************************************************************************* */ diff --git a/tests/testGaussianFactor.cpp b/tests/testGaussianFactor.cpp index 2cfb7a076..f380ad4e2 100644 --- a/tests/testGaussianFactor.cpp +++ b/tests/testGaussianFactor.cpp @@ -16,7 +16,14 @@ * @author Frank Dellaert **/ -#include +#include +#include +#include +#include +#include +#include + +#include #include #include // for operator += @@ -24,18 +31,10 @@ #include // for insert using namespace boost::assign; -#include - -#include -#include -#include -#include -#include +#include 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 fg = createGaussianFactorGraph(ordering); + FactorGraph 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 fg = createGaussianFactorGraph(ordering); + FactorGraph 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 model = lf->get_model(); + boost::shared_ptr 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 fg = createGaussianFactorGraph(ordering); + FactorGraph 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 model = lf->get_model(); + boost::shared_ptr 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 factor1 = fg[0]; diff --git a/tests/testGaussianFactorGraphB.cpp b/tests/testGaussianFactorGraphB.cpp index 2e68200f5..6eb673018 100644 --- a/tests/testGaussianFactorGraphB.cpp +++ b/tests/testGaussianFactorGraphB.cpp @@ -15,9 +15,16 @@ * @author Christian Potthast **/ -#include -#include -using namespace std; +#include +#include +#include +#include +#include +#include +#include +#include + +#include #include #include @@ -26,16 +33,10 @@ using namespace std; #include // for operator += using namespace boost::assign; -#include - -#include -#include -#include -#include -#include -#include -#include +#include +#include +using namespace std; using namespace gtsam; using namespace example; diff --git a/tests/testGaussianISAM.cpp b/tests/testGaussianISAM.cpp index 4c798aa8d..d4946a625 100644 --- a/tests/testGaussianISAM.cpp +++ b/tests/testGaussianISAM.cpp @@ -15,20 +15,21 @@ * @author Michael Kaess */ -#include -#include // for operator += -using namespace boost::assign; - -#include - -#include +#include #include +#include #include -#include #include #include #include -#include +#include +#include + +#include + +#include +#include // for operator += +using namespace boost::assign; using namespace std; using namespace gtsam; diff --git a/tests/testGaussianJunctionTreeB.cpp b/tests/testGaussianJunctionTreeB.cpp index 6ec160a5d..7d73ef83b 100644 --- a/tests/testGaussianJunctionTreeB.cpp +++ b/tests/testGaussianJunctionTreeB.cpp @@ -15,9 +15,20 @@ * @author nikai */ -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include +#include +#include + +#include #include #include // for operator += @@ -25,16 +36,7 @@ #include using namespace boost::assign; -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include using namespace std; using namespace gtsam; diff --git a/tests/testInferenceB.cpp b/tests/testInferenceB.cpp index 05573c686..e023fe7e3 100644 --- a/tests/testInferenceB.cpp +++ b/tests/testInferenceB.cpp @@ -17,6 +17,7 @@ #include +#include #include #include #include diff --git a/tests/testNonlinearEquality.cpp b/tests/testNonlinearEquality.cpp index 639e67591..2b35e9f60 100644 --- a/tests/testNonlinearEquality.cpp +++ b/tests/testNonlinearEquality.cpp @@ -14,15 +14,16 @@ * @author Alex Cunningham */ -#include - -#include #include #include #include +#include #include #include #include +#include + +#include using namespace std; using namespace gtsam; diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index d1a891356..eac14d480 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -32,6 +32,7 @@ #include #include #include +#include using namespace std; using namespace gtsam; diff --git a/tests/testNonlinearFactorGraph.cpp b/tests/testNonlinearFactorGraph.cpp index 4f3e7560f..59ee0977e 100644 --- a/tests/testNonlinearFactorGraph.cpp +++ b/tests/testNonlinearFactorGraph.cpp @@ -32,6 +32,7 @@ using namespace boost::assign; #include #include #include +#include using namespace gtsam; using namespace example; diff --git a/tests/testNonlinearISAM.cpp b/tests/testNonlinearISAM.cpp index cf8782e09..28926ff5d 100644 --- a/tests/testNonlinearISAM.cpp +++ b/tests/testNonlinearISAM.cpp @@ -7,6 +7,7 @@ #include #include +#include #include using namespace gtsam; diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index 1a134b8a3..a59584c96 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include diff --git a/tests/testRot3Optimization.cpp b/tests/testRot3Optimization.cpp index df2471933..3e78414e9 100644 --- a/tests/testRot3Optimization.cpp +++ b/tests/testRot3Optimization.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include diff --git a/tests/testSymbolicBayesNetB.cpp b/tests/testSymbolicBayesNetB.cpp index e25cf33ca..356f4bb34 100644 --- a/tests/testSymbolicBayesNetB.cpp +++ b/tests/testSymbolicBayesNetB.cpp @@ -26,6 +26,7 @@ using namespace boost::assign; #include #include #include +#include using namespace std; using namespace gtsam; diff --git a/tests/testSymbolicFactorGraphB.cpp b/tests/testSymbolicFactorGraphB.cpp index 9b195e0c1..cb64ddb4a 100644 --- a/tests/testSymbolicFactorGraphB.cpp +++ b/tests/testSymbolicFactorGraphB.cpp @@ -15,20 +15,20 @@ * @author Frank Dellaert */ -#include // for operator += -using namespace boost::assign; - -#include - #include +#include +#include #include #include #include -#include + +#include + +#include // 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