diff --git a/.cproject b/.cproject
index b3f26a11d..af582b925 100644
--- a/.cproject
+++ b/.cproject
@@ -5,16 +5,16 @@
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
@@ -298,519 +298,528 @@
-
-
- make
- -j2
- install
- true
- true
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -k
- check
- true
- false
- true
-
-
- make
- -j2
- testSimpleCamera.run
- true
- true
- true
-
-
- make
- -f local.mk
- testCal3_S2.run
- true
- true
- true
-
-
- make
- -j2
- testVSLAMFactor.run
- true
- true
- true
-
-
- make
- -j2
- testCalibratedCamera.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianConditional.run
- true
- true
- true
-
-
- make
- -j2
- testPose2.run
- true
- true
- true
-
-
- make
- -j2
- testRot3.run
- true
- true
- true
-
-
- make
- -j2
- testNonlinearOptimizer.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianFactor.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianFactorGraph.run
- true
- true
- true
-
-
- make
- -j2
- testNonlinearFactorGraph.run
- true
- true
- true
-
-
- make
- -j2
- testPose3.run
- true
- true
- true
-
-
- make
- -j2
- testVectorConfig.run
- true
- true
- true
-
-
- make
- -j2
- testPoint2.run
- true
- true
- true
-
-
- make
- -j2
- testNonlinearFactor.run
- true
- true
- true
-
-
- make
- -j2
- timeGaussianFactor.run
- true
- true
- true
-
-
- make
- -j2
- timeGaussianFactorGraph.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianBayesNet.run
- true
- true
- true
-
-
- make
- testBayesTree.run
- true
- false
- true
-
-
- make
-
- testSymbolicBayesNet.run
- true
- false
- true
-
-
- make
- testSymbolicFactorGraph.run
- true
- false
- true
-
-
- make
- -j2
- testVector.run
- true
- true
- true
-
-
- make
- -j2
- testMatrix.run
- true
- true
- true
-
-
- make
- -j2
- testVSLAMGraph.run
- true
- true
- true
-
-
- make
- -j2
- testNonlinearEquality.run
- true
- true
- true
-
-
- make
- -j2
- testSQP.run
- true
- true
- true
-
-
- make
- -j2
- testNonlinearConstraint.run
- true
- true
- true
-
-
- make
- -j2
- testSQPOptimizer.run
- true
- true
- true
-
-
- make
- -j2
- testVSLAMConfig.run
- true
- true
- true
-
-
- make
- -j2
- testControlConfig.run
- true
- true
- true
-
-
- make
- -j2
- testControlPoint.run
- true
- true
- true
-
-
- make
- -j2
- testControlGraph.run
- true
- true
- true
-
-
- make
- -j2
- testOrdering.run
- true
- true
- true
-
-
- make
- -j2
- testRot2.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianBayesTree.run
- true
- true
- true
-
-
- make
- -j2
- testPose3Config.run
- true
- true
- true
-
-
- make
- -j2
- testUrbanMeasurement.run
- true
- true
- true
-
-
- make
- -j2
- testUrbanOdometry.run
- true
- true
- true
-
-
- make
- -j2
- testIterative.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianISAM2.run
- true
- true
- true
-
-
- make
- -j2
- testSubgraphPreconditioner.run
- true
- true
- true
-
-
- make
- -j2
- testBayesNetPreconditioner.run
- true
- true
- true
-
-
- make
- -j2
- testPose2Factor.run
- true
- true
- true
-
-
- make
- -j2
- timeRot3.run
- true
- true
- true
-
-
- make
- -j2
- testPose2SLAM.run
- true
- true
- true
-
-
- make
- -j2
- testPose2Config.run
- true
- true
- true
-
-
- make
- -j2
- testLieConfig.run
- true
- true
- true
-
-
- make
- -j2
- testPlanarSLAM.run
- true
- true
- true
-
-
- make
- testGraph.run
- true
- false
- true
-
-
- make
- -j2
- testPose3SLAM.run
- true
- true
- true
-
-
- make
- -j2
- testTupleConfig.run
- true
- true
- true
-
-
- make
- -j2
- testPose2Prior.run
- true
- true
- true
-
-
- make
- -j2
- testNoiseModel.run
- true
- true
- true
-
-
- make
- -j2
- testISAM.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianISAM.run
- true
- true
- true
-
-
- make
-
- testSimulated2D.run
- true
- false
- true
-
-
- make
- -j2
- timeMatrix.run
- true
- true
- true
-
-
- make
- -j2
- testKey.run
- true
- true
- true
-
-
- make
- -j2
- install
- true
- true
- true
-
-
- make
- -j2
- clean
- true
- true
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
-
-
+
+
+make
+-j2
+install
+true
+true
+true
+
+
+make
+-j2
+check
+true
+true
+true
+
+
+make
+-k
+check
+true
+false
+true
+
+
+make
+-j2
+testSimpleCamera.run
+true
+true
+true
+
+
+make
+-f local.mk
+testCal3_S2.run
+true
+true
+true
+
+
+make
+-j2
+testVSLAMFactor.run
+true
+true
+true
+
+
+make
+-j2
+testCalibratedCamera.run
+true
+true
+true
+
+
+make
+-j2
+testGaussianConditional.run
+true
+true
+true
+
+
+make
+-j2
+testPose2.run
+true
+true
+true
+
+
+make
+-j2
+testRot3.run
+true
+true
+true
+
+
+make
+-j2
+testNonlinearOptimizer.run
+true
+true
+true
+
+
+make
+-j2
+testGaussianFactor.run
+true
+true
+true
+
+
+make
+-j2
+testGaussianFactorGraph.run
+true
+true
+true
+
+
+make
+-j2
+testNonlinearFactorGraph.run
+true
+true
+true
+
+
+make
+-j2
+testPose3.run
+true
+true
+true
+
+
+make
+-j2
+testVectorConfig.run
+true
+true
+true
+
+
+make
+-j2
+testPoint2.run
+true
+true
+true
+
+
+make
+-j2
+testNonlinearFactor.run
+true
+true
+true
+
+
+make
+-j2
+timeGaussianFactor.run
+true
+true
+true
+
+
+make
+-j2
+timeGaussianFactorGraph.run
+true
+true
+true
+
+
+make
+-j2
+testGaussianBayesNet.run
+true
+true
+true
+
+
+make
+
+testBayesTree.run
+true
+false
+true
+
+
+make
+testSymbolicBayesNet.run
+true
+false
+true
+
+
+make
+
+testSymbolicFactorGraph.run
+true
+false
+true
+
+
+make
+-j2
+testVector.run
+true
+true
+true
+
+
+make
+-j2
+testMatrix.run
+true
+true
+true
+
+
+make
+-j2
+testVSLAMGraph.run
+true
+true
+true
+
+
+make
+-j2
+testNonlinearEquality.run
+true
+true
+true
+
+
+make
+-j2
+testSQP.run
+true
+true
+true
+
+
+make
+-j2
+testNonlinearConstraint.run
+true
+true
+true
+
+
+make
+-j2
+testSQPOptimizer.run
+true
+true
+true
+
+
+make
+-j2
+testVSLAMConfig.run
+true
+true
+true
+
+
+make
+-j2
+testControlConfig.run
+true
+true
+true
+
+
+make
+-j2
+testControlPoint.run
+true
+true
+true
+
+
+make
+-j2
+testControlGraph.run
+true
+true
+true
+
+
+make
+-j2
+testOrdering.run
+true
+true
+true
+
+
+make
+-j2
+testRot2.run
+true
+true
+true
+
+
+make
+-j2
+testGaussianBayesTree.run
+true
+true
+true
+
+
+make
+-j2
+testPose3Config.run
+true
+true
+true
+
+
+make
+-j2
+testUrbanMeasurement.run
+true
+true
+true
+
+
+make
+-j2
+testUrbanOdometry.run
+true
+true
+true
+
+
+make
+-j2
+testIterative.run
+true
+true
+true
+
+
+make
+-j2
+testGaussianISAM2.run
+true
+true
+true
+
+
+make
+-j2
+testSubgraphPreconditioner.run
+true
+true
+true
+
+
+make
+-j2
+testBayesNetPreconditioner.run
+true
+true
+true
+
+
+make
+-j2
+testPose2Factor.run
+true
+true
+true
+
+
+make
+-j2
+timeRot3.run
+true
+true
+true
+
+
+make
+-j2
+testPose2SLAM.run
+true
+true
+true
+
+
+make
+-j2
+testPose2Config.run
+true
+true
+true
+
+
+make
+-j2
+testLieConfig.run
+true
+true
+true
+
+
+make
+-j2
+testPlanarSLAM.run
+true
+true
+true
+
+
+make
+
+testGraph.run
+true
+false
+true
+
+
+make
+-j2
+testPose3SLAM.run
+true
+true
+true
+
+
+make
+-j2
+testTupleConfig.run
+true
+true
+true
+
+
+make
+-j2
+testPose2Prior.run
+true
+true
+true
+
+
+make
+-j2
+testNoiseModel.run
+true
+true
+true
+
+
+make
+-j2
+testISAM.run
+true
+true
+true
+
+
+make
+-j2
+testGaussianISAM.run
+true
+true
+true
+
+
+make
+testSimulated2D.run
+true
+false
+true
+
+
+make
+-j2
+timeMatrix.run
+true
+true
+true
+
+
+make
+-j2
+testKey.run
+true
+true
+true
+
+
+make
+-j2
+timeVectorConfig.run
+true
+true
+true
+
+
+make
+-j2
+install
+true
+true
+true
+
+
+make
+-j2
+clean
+true
+true
+true
+
+
+make
+-j2
+check
+true
+true
+true
+
+
+
+
diff --git a/cpp/Makefile.am b/cpp/Makefile.am
index 1fbd80926..a7ad7803d 100644
--- a/cpp/Makefile.am
+++ b/cpp/Makefile.am
@@ -238,17 +238,19 @@ testVSLAMConfig_LDADD = libgtsam.la
headers += $(sources:.cpp=.h)
# Timing tests
-noinst_PROGRAMS = timeGaussianFactor timeGaussianFactorGraph timeRot3 timeMatrix timeSymbolMaps
+noinst_PROGRAMS = timeGaussianFactor timeGaussianFactorGraph timeRot3 timeMatrix timeSymbolMaps timeVectorConfig
timeRot3_SOURCES = timeRot3.cpp
-timeRot3_LDADD = libgtsam.la
+timeRot3_LDADD = libgtsam.la
timeGaussianFactor_SOURCES = timeGaussianFactor.cpp
-timeGaussianFactor_LDADD = libgtsam.la
+timeGaussianFactor_LDADD = libgtsam.la
timeGaussianFactorGraph_SOURCES = timeGaussianFactorGraph.cpp
-timeGaussianFactorGraph_LDADD = libgtsam.la
-timeMatrix_SOURCES = timeMatrix.cpp
-timeMatrix_LDADD = libgtsam.la
-timeSymbolMaps_SOURCES = timeSymbolMaps.cpp
-timeSymbolMaps_LDADD = libgtsam.la
+timeGaussianFactorGraph_LDADD = libgtsam.la
+timeMatrix_SOURCES = timeMatrix.cpp
+timeMatrix_LDADD = libgtsam.la
+timeSymbolMaps_SOURCES = timeSymbolMaps.cpp
+timeSymbolMaps_LDADD = libgtsam.la
+timeVectorConfig_SOURCES = timeVectorConfig.cpp
+timeVectorConfig_LDADD = libgtsam.la
# create both dynamic and static libraries
AM_CXXFLAGS = -I$(boost) -fPIC
diff --git a/cpp/timeVectorConfig.cpp b/cpp/timeVectorConfig.cpp
new file mode 100644
index 000000000..569127278
--- /dev/null
+++ b/cpp/timeVectorConfig.cpp
@@ -0,0 +1,57 @@
+/*
+ * @file timeVectorConfig.cpp
+ * @brief Performs timing and profiling for VectorConfig operations
+ * @author Frank Dellaert
+ */
+
+#include
+#include
+#include "VectorConfig.h"
+
+using namespace std;
+using namespace gtsam;
+
+/*
+ * Results:
+ * Frank's machine:
+ */
+double timeAssignment(size_t n, size_t m, size_t r) {
+ // assign a large VectorConfig
+ // n = number of times to loop
+ // m = number of vectors
+ // r = rows per vector
+
+ // Create 2 VectorConfigs
+ VectorConfig a, b;
+ for (int i = 0; i < m; ++i) {
+ Vector v = zero(r);
+ Symbol key('x', i);
+ a.add(key, v);
+ b.add(key, v);
+ }
+
+ // start timing
+ double elapsed;
+ {
+ boost::timer t;
+
+ for (int j = 0; j < n; ++j)
+ a = b;
+
+ elapsed = t.elapsed();
+ }
+
+ return elapsed;
+}
+
+int main(int argc, char ** argv) {
+
+ // Time assignment operator
+ cout << "Starting operator=() Timing" << endl;
+ size_t n = 1000, m = 10000, r = 3;
+ double time = timeAssignment(n, m, r);
+ cout << "Average Elapsed time for assigning " << m << "*" << r
+ << " VectorConfigs: " << 10e3 * time / n << "ms." << endl;
+
+ return 0;
+}