diff --git a/.cproject b/.cproject
index a43d32f58..d759a7a65 100644
--- a/.cproject
+++ b/.cproject
@@ -2857,6 +2857,14 @@
true
true
+
+ make
+ -j5
+ timeLago.run
+ true
+ true
+ true
+
make
-j4
diff --git a/gtsam/nonlinear/lago.cpp b/gtsam/nonlinear/lago.cpp
index c2a7d9454..c0f328d9f 100644
--- a/gtsam/nonlinear/lago.cpp
+++ b/gtsam/nonlinear/lago.cpp
@@ -21,6 +21,7 @@
#include
#include
#include
+#include
#include
@@ -198,6 +199,7 @@ GaussianFactorGraph buildLinearOrientationGraph(
/* ************************************************************************* */
// Select the subgraph of betweenFactors and transforms priors into between wrt a fictitious node
static NonlinearFactorGraph buildPose2graph(const NonlinearFactorGraph& graph) {
+ gttic_(buildPose2graph);
NonlinearFactorGraph pose2Graph;
BOOST_FOREACH(const boost::shared_ptr& factor, graph) {
@@ -250,6 +252,7 @@ static PredecessorMap findOdometricPath(
// Return the orientations of a graph including only BetweenFactors
static VectorValues computeOrientations(const NonlinearFactorGraph& pose2Graph,
bool useOdometricPath) {
+ gttic_(computeOrientations);
// Find a minimum spanning tree
PredecessorMap tree;
@@ -293,6 +296,7 @@ VectorValues initializeOrientations(const NonlinearFactorGraph& graph,
/* ************************************************************************* */
Values computePoses(const NonlinearFactorGraph& pose2graph,
VectorValues& orientationsLago) {
+ gttic_(computePoses);
// Linearized graph on full poses
GaussianFactorGraph linearPose2graph;
diff --git a/gtsam/nonlinear/tests/CMakeLists.txt b/gtsam/nonlinear/tests/CMakeLists.txt
index 69a3700f2..378d93de4 100644
--- a/gtsam/nonlinear/tests/CMakeLists.txt
+++ b/gtsam/nonlinear/tests/CMakeLists.txt
@@ -1 +1 @@
-gtsamAddTestsGlob(nonlinear "test*.cpp" "" "gtsam")
+gtsamAddTestsGlob(nonlinear "*.cpp" "" "gtsam")
diff --git a/gtsam/nonlinear/tests/timeLago.cpp b/gtsam/nonlinear/tests/timeLago.cpp
new file mode 100644
index 000000000..d09756fa0
--- /dev/null
+++ b/gtsam/nonlinear/tests/timeLago.cpp
@@ -0,0 +1,72 @@
+/* ----------------------------------------------------------------------------
+
+ * GTSAM Copyright 2010, Georgia Tech Research Corporation,
+ * Atlanta, Georgia 30332-0415
+ * All Rights Reserved
+ * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
+
+ * See LICENSE for the license information
+
+ * -------------------------------------------------------------------------- */
+
+/**
+ * @file timeVirtual.cpp
+ * @brief Time the overhead of using virtual destructors and methods
+ * @author Richard Roberts
+ * @date Dec 3, 2010
+ */
+
+#include
+#include
+#include
+#include
+#include
+
+#include
+
+using namespace std;
+using namespace gtsam;
+
+int main(int argc, char *argv[]) {
+
+ size_t trials = 1000;
+
+ // read graph
+ NonlinearFactorGraph g;
+ Values initial;
+ string inputFile = findExampleDataFile("noisyToyGraph");
+ readG2o(inputFile, g, initial);
+
+ // Add prior on the pose having index (key) = 0
+ noiseModel::Diagonal::shared_ptr priorModel = //
+ noiseModel::Diagonal::Sigmas(Vector3(0, 0, 0));
+ g.add(PriorFactor(0, Pose2(), priorModel));
+
+ // LAGO
+ for (size_t i = 0; i < trials; i++) {
+ {
+ gttic_(lago);
+
+ gttic_(init);
+ Values lagoInitial = lago::initialize(g);
+ gttoc_(init);
+
+ gttic_(refine);
+ GaussNewtonOptimizer optimizer(g, lagoInitial);
+ Values result = optimizer.optimize();
+ gttoc_(refine);
+ }
+
+ {
+ gttic_(optimize);
+ GaussNewtonOptimizer optimizer(g, initial);
+ Values result = optimizer.optimize();
+ }
+
+ tictoc_finishedIteration_();
+ }
+
+ tictoc_print_();
+
+ return 0;
+}