From f24002816d79c2cde091cb34f1e6e7e7791805d0 Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Fri, 6 Jul 2012 14:19:19 +0000 Subject: [PATCH] --- gtsam/slam/tests/testSparseBA.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/gtsam/slam/tests/testSparseBA.cpp b/gtsam/slam/tests/testSparseBA.cpp index 8d441aa34..cc6e11400 100644 --- a/gtsam/slam/tests/testSparseBA.cpp +++ b/gtsam/slam/tests/testSparseBA.cpp @@ -10,13 +10,13 @@ * -------------------------------------------------------------------------- */ /** - * @file testSba.cpp + * @file testsparseBA.cpp * @brief * @date Jul 5, 2012 * @author Yong-Dian Jian */ -#include +#include #include #include #include @@ -66,7 +66,7 @@ static Camera camera1(pose1, calib1); static Camera camera2(pose2, calib2); /* ************************************************************************* */ -sba::Graph testGraph1() { +sparseBA::Graph testGraph1() { Point2 z11(-100, 100); Point2 z12(-100,-100); Point2 z13( 100,-100); @@ -77,7 +77,7 @@ sba::Graph testGraph1() { Point2 z24( 125, 125); - sba::Graph g; + sparseBA::Graph g; g.addMeasurement(z11, sigma, C(1), L(1)); g.addMeasurement(z12, sigma, C(1), L(2)); g.addMeasurement(z13, sigma, C(1), L(3)); @@ -89,7 +89,7 @@ sba::Graph testGraph1() { return g; } -sba::Graph testGraph2() { +sparseBA::Graph testGraph2() { Point2 z11(-100, 100); Point2 z12(-100,-100); Point2 z13( 100,-100); @@ -99,7 +99,7 @@ sba::Graph testGraph2() { Point2 z23( 125,-125); Point2 z24( 125, 125); - sba::Graph g; + sparseBA::Graph g; g.addMeasurement(z11, sigma, X(1), L(1), K(1)); g.addMeasurement(z12, sigma, X(1), L(2), K(1)); g.addMeasurement(z13, sigma, X(1), L(3), K(1)); @@ -112,10 +112,10 @@ sba::Graph testGraph2() { } /* ************************************************************************* */ -TEST( optimizeLM1, sba ) +TEST( optimizeLM1, sparseBA ) { // build a graph - sba::Graph graph(testGraph1()); + sparseBA::Graph graph(testGraph1()); // add 3 landmark constraints graph.addPointConstraint(L(1), landmark1); @@ -150,10 +150,10 @@ TEST( optimizeLM1, sba ) } /* ************************************************************************* */ -TEST( optimizeLM2, sba ) +TEST( optimizeLM2, sparseBA ) { // build a graph - sba::Graph graph(testGraph2()); + sparseBA::Graph graph(testGraph2()); // add 3 landmark constraints graph.addPointConstraint(L(1), landmark1);