From 18e23c20dfc1c037e3119a7aa93968da928fae6c Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 22 May 2012 12:27:34 +0000 Subject: [PATCH] Added missing header --- gtsam/slam/tests/testPose2SLAM.cpp | 10 +++++++--- tests/testNonlinearOptimizer.cpp | 27 +++++++++++++-------------- 2 files changed, 20 insertions(+), 17 deletions(-) diff --git a/gtsam/slam/tests/testPose2SLAM.cpp b/gtsam/slam/tests/testPose2SLAM.cpp index 22c02ab52..5aa633bbf 100644 --- a/gtsam/slam/tests/testPose2SLAM.cpp +++ b/gtsam/slam/tests/testPose2SLAM.cpp @@ -16,6 +16,7 @@ #include #include +#include #include #include using namespace gtsam; @@ -145,7 +146,7 @@ TEST( Pose2SLAM, linearization ) } /* ************************************************************************* */ -TEST(Pose2Graph, optimize) { +TEST(Pose2SLAM, optimize) { // create a Pose graph with one equality constraint and one measurement pose2SLAM::Graph fg; @@ -171,11 +172,14 @@ TEST(Pose2Graph, optimize) { expected.insert(pose2SLAM::PoseKey(0), Pose2(0,0,0)); expected.insert(pose2SLAM::PoseKey(1), Pose2(1,2,M_PI_2)); CHECK(assert_equal(expected, actual)); + + // Check marginals + Marginals marginals = fg.marginals(actual); } /* ************************************************************************* */ // test optimization with 3 poses -TEST(Pose2Graph, optimizeThreePoses) { +TEST(Pose2SLAM, optimizeThreePoses) { // Create a hexagon of poses pose2SLAM::Values hexagon = pose2SLAM::circle(3,1.0); @@ -289,7 +293,7 @@ TEST_UNSAFE(Pose2SLAM, optimizeCircle) { } /* ************************************************************************* */ -TEST(Pose2Graph, optimize2) { +TEST(Pose2SLAM, optimize2) { // Pose2SLAMOptimizer myOptimizer("100"); // Matrix A1 = myOptimizer.a1(); // Matrix A2 = myOptimizer.a2(); diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index d1eb01f27..a926b9e1b 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -15,26 +15,25 @@ * @author Frank Dellaert */ -#include -using namespace std; - -#include // for operator += -using namespace boost::assign; +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include -using namespace boost; +#include // for operator += +using namespace boost::assign; -#include -#include -#include -#include -#include -#include -#include -#include +#include +using namespace std; using namespace gtsam; const double tol = 1e-5;