diff --git a/.cproject b/.cproject
index 90e48745b..46b623bb9 100644
--- a/.cproject
+++ b/.cproject
@@ -582,7 +582,6 @@
 			
 			
 				make
-				
 				tests/testBayesTree.run
 				true
 				false
@@ -590,7 +589,6 @@
 			
 			
 				make
-				
 				testBinaryBayesNet.run
 				true
 				false
@@ -638,7 +636,6 @@
 			
 			
 				make
-				
 				testSymbolicBayesNet.run
 				true
 				false
@@ -646,7 +643,6 @@
 			
 			
 				make
-				
 				tests/testSymbolicFactor.run
 				true
 				false
@@ -654,7 +650,6 @@
 			
 			
 				make
-				
 				testSymbolicFactorGraph.run
 				true
 				false
@@ -670,7 +665,6 @@
 			
 			
 				make
-				
 				tests/testBayesTree
 				true
 				false
@@ -1006,7 +1000,6 @@
 			
 			
 				make
-				
 				testErrors.run
 				true
 				false
@@ -1236,46 +1229,6 @@
 				true
 				true
 			
-			
-				make
-				-j5
-				testBTree.run
-				true
-				true
-				true
-			
-			
-				make
-				-j5
-				testDSF.run
-				true
-				true
-				true
-			
-			
-				make
-				-j5
-				testDSFMap.run
-				true
-				true
-				true
-			
-			
-				make
-				-j5
-				testDSFVector.run
-				true
-				true
-				true
-			
-			
-				make
-				-j5
-				testFixedVector.run
-				true
-				true
-				true
-			
 			
 				make
 				-j2
@@ -1358,6 +1311,7 @@
 			
 			
 				make
+				
 				testSimulated2DOriented.run
 				true
 				false
@@ -1397,6 +1351,7 @@
 			
 			
 				make
+				
 				testSimulated2D.run
 				true
 				false
@@ -1404,6 +1359,7 @@
 			
 			
 				make
+				
 				testSimulated3D.run
 				true
 				false
@@ -1417,6 +1373,46 @@
 				true
 				true
 			
+			
+				make
+				-j5
+				testBTree.run
+				true
+				true
+				true
+			
+			
+				make
+				-j5
+				testDSF.run
+				true
+				true
+				true
+			
+			
+				make
+				-j5
+				testDSFMap.run
+				true
+				true
+				true
+			
+			
+				make
+				-j5
+				testDSFVector.run
+				true
+				true
+				true
+			
+			
+				make
+				-j5
+				testFixedVector.run
+				true
+				true
+				true
+			
 			
 				make
 				-j5
@@ -1674,7 +1670,6 @@
 			
 			
 				cpack
-				
 				-G DEB
 				true
 				false
@@ -1682,7 +1677,6 @@
 			
 			
 				cpack
-				
 				-G RPM
 				true
 				false
@@ -1690,7 +1684,6 @@
 			
 			
 				cpack
-				
 				-G TGZ
 				true
 				false
@@ -1698,7 +1691,6 @@
 			
 			
 				cpack
-				
 				--config CPackSourceConfig.cmake
 				true
 				false
@@ -2425,7 +2417,6 @@
 			
 			
 				make
-				
 				testGraph.run
 				true
 				false
@@ -2433,7 +2424,6 @@
 			
 			
 				make
-				
 				testJunctionTree.run
 				true
 				false
@@ -2441,7 +2431,6 @@
 			
 			
 				make
-				
 				testSymbolicBayesNetB.run
 				true
 				false
@@ -2647,14 +2636,6 @@
 				true
 				true
 			
-			
-				make
-				-j5
-				testInitializePose3.run
-				true
-				true
-				true
-			
 			
 				make
 				-j2
@@ -2929,6 +2910,7 @@
 			
 			
 				make
+				
 				tests/testGaussianISAM2
 				true
 				false
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 004ded5e4..6fcce54b6 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -123,6 +123,11 @@ else()
 endif()
 
 
+if(${Boost_VERSION} EQUAL 105600)
+	message("Ignoring Boost restriction on optional lvalue assignment from rvalues")
+	add_definitions(-DBOOST_OPTIONAL_ALLOW_BINDING_TO_RVALUES)
+endif()
+
 ###############################################################################
 # Find TBB
 find_package(TBB)
@@ -169,9 +174,9 @@ endif()
 
 ###############################################################################
 # Find OpenMP (if we're also using MKL)
-if(GTSAM_WITH_EIGEN_MKL AND GTSAM_USE_EIGEN_MKL_OPENMP AND GTSAM_USE_EIGEN_MKL)
-    find_package(OpenMP)
+find_package(OpenMP)  # do this here to generate correct message if disabled
 
+if(GTSAM_WITH_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP AND GTSAM_USE_EIGEN_MKL)
     if(OPENMP_FOUND AND GTSAM_USE_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP)
         set(GTSAM_USE_EIGEN_MKL_OPENMP 1) # This will go into config.h
         set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
diff --git a/cmake/FindMKL.cmake b/cmake/FindMKL.cmake
index c387ce9d3..44681f7b8 100644
--- a/cmake/FindMKL.cmake
+++ b/cmake/FindMKL.cmake
@@ -58,6 +58,7 @@ FIND_PATH(MKL_ROOT_DIR
     /opt/intel/mkl/*/
     /opt/intel/cmkl/
     /opt/intel/cmkl/*/
+    /opt/intel/*/mkl/
     /Library/Frameworks/Intel_MKL.framework/Versions/Current/lib/universal
         "C:/Program Files (x86)/Intel/ComposerXE-2011/mkl"
         "C:/Program Files (x86)/Intel/Composer XE 2013/mkl"
diff --git a/examples/Data/pose3example-offdiagonal.txt b/examples/Data/pose3example-offdiagonal.txt
index c3eb883a4..08ca2e1d1 100644
--- a/examples/Data/pose3example-offdiagonal.txt
+++ b/examples/Data/pose3example-offdiagonal.txt
@@ -1,3 +1,3 @@
 VERTEX_SE3:QUAT 0 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.000000
 VERTEX_SE3:QUAT 1 1.001367 0.015390 0.004948 0.190253 0.283162 -0.392318 0.854230
-EDGE_SE3:QUAT 0 1   1.001367 0.015390 0.004948   0.190253 0.283162 -0.392318 0.854230   10000.000000 1.000000 1.000000 1.000000 1.000000 1.000000   10000.000000 2.000000 2.000000 2.000000 2.000000   10000.000000 3.000000 3.000000 3.000000   10000.000000 4.000000 4.000000   10000.000000 5.000000   10000.000000
\ No newline at end of file
+EDGE_SE3:QUAT 0 1   1.001367 0.015390 0.004948   0.190253 0.283162 -0.392318 0.854230   10000.000000 1.000000 1.000000 1.000000 1.000000 1.000000   10000.000000 2.000000 2.000000 2.000000 2.000000   10000.000000 3.000000 3.000000 3.000000   10000.000000 4.000000 4.000000   10000.000000 5.000000   10000.0000
\ No newline at end of file
diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp
index a34a96c9b..5454f4c11 100644
--- a/examples/LocalizationExample.cpp
+++ b/examples/LocalizationExample.cpp
@@ -120,15 +120,15 @@ int main(int argc, char** argv) {
   // For simplicity, we will use the same noise model for each odometry factor
   noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.2, 0.2, 0.1));
   // Create odometry (Between) factors between consecutive poses
-  graph.push_back(BetweenFactor(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise));
-  graph.push_back(BetweenFactor(2, 3, Pose2(2.0, 0.0, 0.0), odometryNoise));
+  graph.add(BetweenFactor(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise));
+  graph.add(BetweenFactor(2, 3, Pose2(2.0, 0.0, 0.0), odometryNoise));
 
   // 2b. Add "GPS-like" measurements
   // We will use our custom UnaryFactor for this.
   noiseModel::Diagonal::shared_ptr unaryNoise = noiseModel::Diagonal::Sigmas((Vector(2) << 0.1, 0.1)); // 10cm std on x,y
-  graph.push_back(boost::make_shared(1, 0.0, 0.0, unaryNoise));
-  graph.push_back(boost::make_shared(2, 2.0, 0.0, unaryNoise));
-  graph.push_back(boost::make_shared(3, 4.0, 0.0, unaryNoise));
+  graph.add(boost::make_shared(1, 0.0, 0.0, unaryNoise));
+  graph.add(boost::make_shared(2, 2.0, 0.0, unaryNoise));
+  graph.add(boost::make_shared(3, 4.0, 0.0, unaryNoise));
   graph.print("\nFactor Graph:\n"); // print
 
   // 3. Create the data structure to hold the initialEstimate estimate to the solution
diff --git a/examples/OdometryExample.cpp b/examples/OdometryExample.cpp
index f2d4c6497..70c6e6fb0 100644
--- a/examples/OdometryExample.cpp
+++ b/examples/OdometryExample.cpp
@@ -65,15 +65,15 @@ int main(int argc, char** argv) {
   // A prior factor consists of a mean and a noise model (covariance matrix)
   Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
   noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.3, 0.3, 0.1));
-  graph.push_back(PriorFactor(1, priorMean, priorNoise));
+  graph.add(PriorFactor(1, priorMean, priorNoise));
 
   // Add odometry factors
   Pose2 odometry(2.0, 0.0, 0.0);
   // For simplicity, we will use the same noise model for each odometry factor
   noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.2, 0.2, 0.1));
   // Create odometry (Between) factors between consecutive poses
-  graph.push_back(BetweenFactor(1, 2, odometry, odometryNoise));
-  graph.push_back(BetweenFactor(2, 3, odometry, odometryNoise));
+  graph.add(BetweenFactor(1, 2, odometry, odometryNoise));
+  graph.add(BetweenFactor(2, 3, odometry, odometryNoise));
   graph.print("\nFactor Graph:\n"); // print
 
   // Create the data structure to hold the initialEstimate estimate to the solution
diff --git a/examples/PlanarSLAMExample.cpp b/examples/PlanarSLAMExample.cpp
index a1c75eab7..91ca423a2 100644
--- a/examples/PlanarSLAMExample.cpp
+++ b/examples/PlanarSLAMExample.cpp
@@ -81,13 +81,13 @@ int main(int argc, char** argv) {
   // Add a prior on pose x1 at the origin. A prior factor consists of a mean and a noise model (covariance matrix)
   Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
   noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
-  graph.push_back(PriorFactor(x1, prior, priorNoise)); // add directly to graph
+  graph.add(PriorFactor(x1, prior, priorNoise)); // add directly to graph
 
   // Add two odometry factors
   Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case)
   noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta
-  graph.push_back(BetweenFactor(x1, x2, odometry, odometryNoise));
-  graph.push_back(BetweenFactor(x2, x3, odometry, odometryNoise));
+  graph.add(BetweenFactor(x1, x2, odometry, odometryNoise));
+  graph.add(BetweenFactor(x2, x3, odometry, odometryNoise));
 
   // Add Range-Bearing measurements to two different landmarks
   // create a noise model for the landmark measurements
@@ -101,9 +101,9 @@ int main(int argc, char** argv) {
          range32 = 2.0;
 
   // Add Bearing-Range factors
-  graph.push_back(BearingRangeFactor(x1, l1, bearing11, range11, measurementNoise));
-  graph.push_back(BearingRangeFactor(x2, l1, bearing21, range21, measurementNoise));
-  graph.push_back(BearingRangeFactor(x3, l2, bearing32, range32, measurementNoise));
+  graph.add(BearingRangeFactor(x1, l1, bearing11, range11, measurementNoise));
+  graph.add(BearingRangeFactor(x2, l1, bearing21, range21, measurementNoise));
+  graph.add(BearingRangeFactor(x3, l2, bearing32, range32, measurementNoise));
 
   // Print
   graph.print("Factor Graph:\n");
diff --git a/examples/Pose2SLAMExample.cpp b/examples/Pose2SLAMExample.cpp
index e1a51a493..ae34278ec 100644
--- a/examples/Pose2SLAMExample.cpp
+++ b/examples/Pose2SLAMExample.cpp
@@ -72,23 +72,23 @@ int main(int argc, char** argv) {
   // 2a. Add a prior on the first pose, setting it to the origin
   // A prior factor consists of a mean and a noise model (covariance matrix)
   noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.3, 0.3, 0.1));
-  graph.push_back(PriorFactor(1, Pose2(0, 0, 0), priorNoise));
+  graph.add(PriorFactor(1, Pose2(0, 0, 0), priorNoise));
 
   // For simplicity, we will use the same noise model for odometry and loop closures
   noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.2, 0.2, 0.1));
 
   // 2b. Add odometry factors
   // Create odometry (Between) factors between consecutive poses
-  graph.push_back(BetweenFactor(1, 2, Pose2(2, 0, 0     ), model));
-  graph.push_back(BetweenFactor(2, 3, Pose2(2, 0, M_PI_2), model));
-  graph.push_back(BetweenFactor(3, 4, Pose2(2, 0, M_PI_2), model));
-  graph.push_back(BetweenFactor(4, 5, Pose2(2, 0, M_PI_2), model));
+  graph.add(BetweenFactor(1, 2, Pose2(2, 0, 0     ), model));
+  graph.add(BetweenFactor(2, 3, Pose2(2, 0, M_PI_2), model));
+  graph.add(BetweenFactor(3, 4, Pose2(2, 0, M_PI_2), model));
+  graph.add(BetweenFactor(4, 5, Pose2(2, 0, M_PI_2), model));
 
   // 2c. Add the loop closure constraint
   // This factor encodes the fact that we have returned to the same pose. In real systems,
   // these constraints may be identified in many ways, such as appearance-based techniques
   // with camera images. We will use another Between Factor to enforce this constraint:
-  graph.push_back(BetweenFactor(5, 2, Pose2(2, 0, M_PI_2), model));
+  graph.add(BetweenFactor(5, 2, Pose2(2, 0, M_PI_2), model));
   graph.print("\nFactor Graph:\n"); // print
 
   // 3. Create the data structure to hold the initialEstimate estimate to the solution
diff --git a/examples/Pose3SLAMExample_changeKeys.cpp b/examples/Pose3SLAMExample_changeKeys.cpp
index ae4ee5a8c..f3f770750 100644
--- a/examples/Pose3SLAMExample_changeKeys.cpp
+++ b/examples/Pose3SLAMExample_changeKeys.cpp
@@ -17,7 +17,6 @@
  * @author Luca Carlone
  */
 
-#include 
 #include 
 #include 
 #include 
diff --git a/examples/Pose3SLAMExample_g2o.cpp b/examples/Pose3SLAMExample_g2o.cpp
index c2acb8091..f992c78b1 100644
--- a/examples/Pose3SLAMExample_g2o.cpp
+++ b/examples/Pose3SLAMExample_g2o.cpp
@@ -17,7 +17,6 @@
  * @author Luca Carlone
  */
 
-#include 
 #include 
 #include 
 #include 
diff --git a/examples/Pose3SLAMExample_rotOnlyGN.cpp b/examples/Pose3SLAMExample_rotOnlyGN.cpp
deleted file mode 100644
index 293fa1a09..000000000
--- a/examples/Pose3SLAMExample_rotOnlyGN.cpp
+++ /dev/null
@@ -1,95 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Pose3SLAMExample_initializePose3.cpp
- * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the Pose3 using InitializePose3
- * Syntax for the script is ./Pose3SLAMExample_initializePose3 input.g2o output.g2o
- * @date Aug 25, 2014
- * @author Luca Carlone
- */
-
-#include 
-#include 
-#include 
-#include 
-#include 
-#include 
-
-using namespace std;
-using namespace gtsam;
-
-int main(const int argc, const char *argv[]) {
-
-  // Read graph from file
-  string g2oFile;
-  if (argc < 2)
-    g2oFile = findExampleDataFile("pose3example.txt");
-  else
-    g2oFile = argv[1];
-
-  NonlinearFactorGraph::shared_ptr graph;
-  Values::shared_ptr initial;
-  bool is3D = true;
-  boost::tie(graph, initial) = readG2o(g2oFile, is3D);
-
-  Values initialRot;
-  BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, *initial) {
-    Key key = key_value.key;
-    Pose3 pose = initial->at(key);
-    Rot3 R = pose.rotation();
-    initialRot.insert(key,R);
-  }
-
-  noiseModel::Unit::shared_ptr identityModel = noiseModel::Unit::Create(3);
-  NonlinearFactorGraph graphRot;
-  BOOST_FOREACH(const NonlinearFactor::shared_ptr& factor, *graph) {
-    boost::shared_ptr > pose3Between =
-        boost::dynamic_pointer_cast >(factor);
-    if(pose3Between){
-      Key key1 = pose3Between->key1();
-      Key key2 = pose3Between->key2();
-      Pose3 Pij = pose3Between->measured();
-      Rot3 Rij = Pij.rotation();
-      NonlinearFactor::shared_ptr factorRot(new BetweenFactor(key1, key2, Rij, identityModel));
-      graphRot.add(factorRot);
-    }else{
-      std::cout << "Found a factor that is not a Between: not admitted" << std::endl;
-      return 1;
-    }
-  }
-  // Add prior on the first key
-  graphRot.add(PriorFactor(0, Rot3(), identityModel));
-
-  std::cout << "Optimizing Rot3 via GN" << std::endl;
-  // GaussNewtonParams params;
-  GaussNewtonOptimizer optimizer(graphRot, initialRot);
-  Values GNrot = optimizer.optimize();
-  std::cout << "done!" << std::endl;
-
-  // Wrap estimate as poses to write in g2o format
-  Values GNposes;
-  BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, GNrot) {
-    Key key = key_value.key;
-    Rot3 R = GNrot.at(key);
-    GNposes.insert(key,Pose3(R,Point3()));
-  }
-
-  if (argc < 3) {
-    GNrot.print("initialization");
-  } else {
-    const string outputFile = argv[2];
-    std::cout << "Writing results to file: " << outputFile << std::endl;
-    writeG2o(*graph, GNposes, outputFile);
-    std::cout << "done! " << std::endl;
-  }
-  return 0;
-}
diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp
index 2f0c71a40..26abfff85 100644
--- a/examples/SolverComparer.cpp
+++ b/examples/SolverComparer.cpp
@@ -13,6 +13,22 @@
 * @brief   Incremental and batch solving, timing, and accuracy comparisons
 * @author  Richard Roberts
 * @date    August, 2013
+*
+* Here is an example. Below, to run in batch mode, we first generate an initialization in incremental mode.
+*
+* Solve in incremental and write to file w_inc:
+* ./SolverComparer --incremental -d w10000 -o w_inc
+*
+* You can then perturb that initialization to get batch something to optimize.
+* Read in w_inc, perturb it with noise of stddev 0.6, and write to w_pert:
+* ./SolverComparer --perturb 0.6 -i w_inc -o w_pert
+*
+* Then optimize with batch, read in w_pert, solve in batch, and write to w_batch:
+* ./SolverComparer --batch -d w10000 -i w_pert -o w_batch
+*
+* And finally compare solutions in w_inc and w_batch to check that batch converged to the global minimum
+* ./SolverComparer --compare w_inc w_batch
+*
 */
 
 #include 
diff --git a/examples/VisualISAMExample.cpp b/examples/VisualISAMExample.cpp
index b5645e214..8a32f5dcc 100644
--- a/examples/VisualISAMExample.cpp
+++ b/examples/VisualISAMExample.cpp
@@ -14,6 +14,7 @@
  * @brief   A visualSLAM example for the structure-from-motion problem on a simulated dataset
  * This version uses iSAM to solve the problem incrementally
  * @author  Duy-Nguyen Ta
+ * @author  Frank Dellaert
  */
 
 /**
@@ -61,7 +62,8 @@ int main(int argc, char* argv[]) {
   Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
 
   // Define the camera observation noise model
-  noiseModel::Isotropic::shared_ptr measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
+  noiseModel::Isotropic::shared_ptr noise = //
+      noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
 
   // Create the set of ground-truth landmarks
   vector points = createPoints();
@@ -69,7 +71,8 @@ int main(int argc, char* argv[]) {
   // Create the set of ground-truth poses
   vector poses = createPoses();
 
-  // Create a NonlinearISAM object which will relinearize and reorder the variables every "relinearizeInterval" updates
+  // Create a NonlinearISAM object which will relinearize and reorder the variables
+  // every "relinearizeInterval" updates
   int relinearizeInterval = 3;
   NonlinearISAM isam(relinearizeInterval);
 
@@ -82,32 +85,44 @@ int main(int argc, char* argv[]) {
 
     // Add factors for each landmark observation
     for (size_t j = 0; j < points.size(); ++j) {
+      // Create ground truth measurement
       SimpleCamera camera(poses[i], *K);
       Point2 measurement = camera.project(points[j]);
-      graph.push_back(GenericProjectionFactor(measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K));
+      // Add measurement
+      graph.add(
+          GenericProjectionFactor(measurement, noise,
+              Symbol('x', i), Symbol('l', j), K));
     }
 
-    // Add an initial guess for the current pose
     // Intentionally initialize the variables off from the ground truth
-    initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
+    Pose3 noise(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
+    Pose3 initial_xi = poses[i].compose(noise);
+
+    // Add an initial guess for the current pose
+    initialEstimate.insert(Symbol('x', i), initial_xi);
 
     // If this is the first iteration, add a prior on the first pose to set the coordinate frame
     // and a prior on the first landmark to set the scale
     // Also, as iSAM solves incrementally, we must wait until each is observed at least twice before
     // adding it to iSAM.
-    if( i == 0) {
-      // Add a prior on pose x0
-      noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1))); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
-      graph.push_back(PriorFactor(Symbol('x', 0), poses[0], poseNoise));
+    if (i == 0) {
+      // Add a prior on pose x0, with 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
+      noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas(
+          (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)));
+      graph.add(PriorFactor(Symbol('x', 0), poses[0], poseNoise));
 
       // Add a prior on landmark l0
-      noiseModel::Isotropic::shared_ptr pointNoise = noiseModel::Isotropic::Sigma(3, 0.1);
-      graph.push_back(PriorFactor(Symbol('l', 0), points[0], pointNoise)); // add directly to graph
+      noiseModel::Isotropic::shared_ptr pointNoise =
+          noiseModel::Isotropic::Sigma(3, 0.1);
+      graph.add(PriorFactor(Symbol('l', 0), points[0], pointNoise));
 
       // Add initial guesses to all observed landmarks
-      // Intentionally initialize the variables off from the ground truth
-      for (size_t j = 0; j < points.size(); ++j)
-        initialEstimate.insert(Symbol('l', j), points[j].compose(Point3(-0.25, 0.20, 0.15)));
+      Point3 noise(-0.25, 0.20, 0.15);
+      for (size_t j = 0; j < points.size(); ++j) {
+        // Intentionally initialize the variables off from the ground truth
+        Point3 initial_lj = points[j].compose(noise);
+        initialEstimate.insert(Symbol('l', j), initial_lj);
+      }
 
     } else {
       // Update iSAM with the new factors
diff --git a/gtsam/3rdparty/Eigen/CTestConfig.cmake b/gtsam/3rdparty/Eigen/CTestConfig.cmake
index 4c0027824..0557c491a 100644
--- a/gtsam/3rdparty/Eigen/CTestConfig.cmake
+++ b/gtsam/3rdparty/Eigen/CTestConfig.cmake
@@ -4,14 +4,10 @@
 ## # The following are required to uses Dart and the Cdash dashboard
 ##   ENABLE_TESTING()
 ##   INCLUDE(CTest)
-set(CTEST_PROJECT_NAME "Eigen")
+set(CTEST_PROJECT_NAME "Eigen3.2")
 set(CTEST_NIGHTLY_START_TIME "00:00:00 UTC")
 
 set(CTEST_DROP_METHOD "http")
 set(CTEST_DROP_SITE "manao.inria.fr")
-set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen")
+set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen3.2")
 set(CTEST_DROP_SITE_CDASH TRUE)
-set(CTEST_PROJECT_SUBPROJECTS
-Official
-Unsupported
-)
diff --git a/gtsam/3rdparty/Eigen/Eigen/Core b/gtsam/3rdparty/Eigen/Eigen/Core
index 9131cc3fc..c87f99df3 100644
--- a/gtsam/3rdparty/Eigen/Eigen/Core
+++ b/gtsam/3rdparty/Eigen/Eigen/Core
@@ -95,7 +95,7 @@
     extern "C" {
       // In theory we should only include immintrin.h and not the other *mmintrin.h header files directly.
       // Doing so triggers some issues with ICC. However old gcc versions seems to not have this file, thus:
-      #ifdef __INTEL_COMPILER
+      #if defined(__INTEL_COMPILER) && __INTEL_COMPILER >= 1110
         #include 
       #else
         #include 
@@ -165,7 +165,7 @@
 #endif
 
 // required for __cpuid, needs to be included after cmath
-#if defined(_MSC_VER) && (defined(_M_IX86)||defined(_M_X64))
+#if defined(_MSC_VER) && (defined(_M_IX86)||defined(_M_X64)) && (!defined(_WIN32_WCE))
   #include 
 #endif
 
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h
index d026418f8..c52b7d1a6 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h
@@ -274,30 +274,13 @@ template<> struct ldlt_inplace
       return true;
     }
 
-    RealScalar cutoff(0), biggest_in_corner;
-
     for (Index k = 0; k < size; ++k)
     {
       // Find largest diagonal element
       Index index_of_biggest_in_corner;
-      biggest_in_corner = mat.diagonal().tail(size-k).cwiseAbs().maxCoeff(&index_of_biggest_in_corner);
+      mat.diagonal().tail(size-k).cwiseAbs().maxCoeff(&index_of_biggest_in_corner);
       index_of_biggest_in_corner += k;
 
-      if(k == 0)
-      {
-        // The biggest overall is the point of reference to which further diagonals
-        // are compared; if any diagonal is negligible compared
-        // to the largest overall, the algorithm bails.
-        cutoff = abs(NumTraits::epsilon() * biggest_in_corner);
-      }
-
-      // Finish early if the matrix is not full rank.
-      if(biggest_in_corner < cutoff)
-      {
-        for(Index i = k; i < size; i++) transpositions.coeffRef(i) = i;
-        break;
-      }
-
       transpositions.coeffRef(k) = index_of_biggest_in_corner;
       if(k != index_of_biggest_in_corner)
       {
@@ -328,15 +311,20 @@ template<> struct ldlt_inplace
 
       if(k>0)
       {
-        temp.head(k) = mat.diagonal().head(k).asDiagonal() * A10.adjoint();
+        temp.head(k) = mat.diagonal().real().head(k).asDiagonal() * A10.adjoint();
         mat.coeffRef(k,k) -= (A10 * temp.head(k)).value();
         if(rs>0)
           A21.noalias() -= A20 * temp.head(k);
       }
-      if((rs>0) && (abs(mat.coeffRef(k,k)) > cutoff))
-        A21 /= mat.coeffRef(k,k);
-
+      
+      // In some previous versions of Eigen (e.g., 3.2.1), the scaling was omitted if the pivot
+      // was smaller than the cutoff value. However, soince LDLT is not rank-revealing
+      // we should only make sure we do not introduce INF or NaN values.
+      // LAPACK also uses 0 as the cutoff value.
       RealScalar realAkk = numext::real(mat.coeffRef(k,k));
+      if((rs>0) && (abs(realAkk) > RealScalar(0)))
+        A21 /= realAkk;
+
       if (sign == PositiveSemiDef) {
         if (realAkk < 0) sign = Indefinite;
       } else if (sign == NegativeSemiDef) {
@@ -516,14 +504,20 @@ struct solve_retval, Rhs>
     typedef typename LDLTType::MatrixType MatrixType;
     typedef typename LDLTType::Scalar Scalar;
     typedef typename LDLTType::RealScalar RealScalar;
-    const Diagonal vectorD = dec().vectorD();
-    RealScalar tolerance = (max)(vectorD.array().abs().maxCoeff() * NumTraits::epsilon(),
-				 RealScalar(1) / NumTraits::highest()); // motivated by LAPACK's xGELSS
+    const typename Diagonal::RealReturnType vectorD(dec().vectorD());
+    // In some previous versions, tolerance was set to the max of 1/highest and the maximal diagonal entry * epsilon
+    // as motivated by LAPACK's xGELSS:
+    // RealScalar tolerance = (max)(vectorD.array().abs().maxCoeff() *NumTraits::epsilon(),RealScalar(1) / NumTraits::highest());
+    // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest
+    // diagonal element is not well justified and to numerical issues in some cases.
+    // Moreover, Lapack's xSYTRS routines use 0 for the tolerance.
+    RealScalar tolerance = RealScalar(1) / NumTraits::highest();
+    
     for (Index i = 0; i < vectorD.size(); ++i) {
       if(abs(vectorD(i)) > tolerance)
-	dst.row(i) /= vectorD(i);
+        dst.row(i) /= vectorD(i);
       else
-	dst.row(i).setZero();
+        dst.row(i).setZero();
     }
 
     // dst = L^-T (D^-1 L^-1 P b)
@@ -576,7 +570,7 @@ MatrixType LDLT::reconstructedMatrix() const
   // L^* P
   res = matrixU() * res;
   // D(L^*P)
-  res = vectorD().asDiagonal() * res;
+  res = vectorD().real().asDiagonal() * res;
   // L(DL^*P)
   res = matrixL() * res;
   // P^T (LDL^*P)
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h
index 358b3188b..87bedfa46 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h
@@ -81,7 +81,7 @@ struct traits > : traits::Flags&LinearAccessBit))) ? LinearAccessBit : 0,
     FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0,
     FlagsRowMajorBit = IsRowMajor ? RowMajorBit : 0,
     Flags0 = traits::Flags & ( (HereditaryBits & ~RowMajorBit) |
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h
index 46e3a960a..cb66caf5e 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h
@@ -47,6 +47,17 @@ struct CommaInitializer :
     m_xpr.block(0, 0, other.rows(), other.cols()) = other;
   }
 
+  /* Copy/Move constructor which transfers ownership. This is crucial in 
+   * absence of return value optimization to avoid assertions during destruction. */
+  // FIXME in C++11 mode this could be replaced by a proper RValue constructor
+  inline CommaInitializer(const CommaInitializer& o)
+  : m_xpr(o.m_xpr), m_row(o.m_row), m_col(o.m_col), m_currentBlockRows(o.m_currentBlockRows) {
+    // Mark original object as finished. In absence of R-value references we need to const_cast:
+    const_cast(o).m_row = m_xpr.rows();
+    const_cast(o).m_col = m_xpr.cols();
+    const_cast(o).m_currentBlockRows = 0;
+  }
+
   /* inserts a scalar value in the target matrix */
   CommaInitializer& operator,(const Scalar& s)
   {
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig
new file mode 100644
index 000000000..a036d8c3b
--- /dev/null
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig
@@ -0,0 +1,154 @@
+// This file is part of Eigen, a lightweight C++ template library
+// for linear algebra.
+//
+// Copyright (C) 2008 Gael Guennebaud 
+// Copyright (C) 2006-2008 Benoit Jacob 
+//
+// This Source Code Form is subject to the terms of the Mozilla
+// Public License v. 2.0. If a copy of the MPL was not distributed
+// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
+
+#ifndef EIGEN_COMMAINITIALIZER_H
+#define EIGEN_COMMAINITIALIZER_H
+
+namespace Eigen { 
+
+/** \class CommaInitializer
+  * \ingroup Core_Module
+  *
+  * \brief Helper class used by the comma initializer operator
+  *
+  * This class is internally used to implement the comma initializer feature. It is
+  * the return type of MatrixBase::operator<<, and most of the time this is the only
+  * way it is used.
+  *
+  * \sa \ref MatrixBaseCommaInitRef "MatrixBase::operator<<", CommaInitializer::finished()
+  */
+template
+struct CommaInitializer
+{
+  typedef typename XprType::Scalar Scalar;
+  typedef typename XprType::Index Index;
+
+  inline CommaInitializer(XprType& xpr, const Scalar& s)
+    : m_xpr(xpr), m_row(0), m_col(1), m_currentBlockRows(1)
+  {
+    m_xpr.coeffRef(0,0) = s;
+  }
+
+  template
+  inline CommaInitializer(XprType& xpr, const DenseBase& other)
+    : m_xpr(xpr), m_row(0), m_col(other.cols()), m_currentBlockRows(other.rows())
+  {
+    m_xpr.block(0, 0, other.rows(), other.cols()) = other;
+  }
+
+  /* Copy/Move constructor which transfers ownership. This is crucial in 
+   * absence of return value optimization to avoid assertions during destruction. */
+  // FIXME in C++11 mode this could be replaced by a proper RValue constructor
+  inline CommaInitializer(const CommaInitializer& o)
+  : m_xpr(o.m_xpr), m_row(o.m_row), m_col(o.m_col), m_currentBlockRows(o.m_currentBlockRows) {
+    // Mark original object as finished. In absence of R-value references we need to const_cast:
+    const_cast(o).m_row = m_xpr.rows();
+    const_cast(o).m_col = m_xpr.cols();
+    const_cast(o).m_currentBlockRows = 0;
+  }
+
+  /* inserts a scalar value in the target matrix */
+  CommaInitializer& operator,(const Scalar& s)
+  {
+    if (m_col==m_xpr.cols())
+    {
+      m_row+=m_currentBlockRows;
+      m_col = 0;
+      m_currentBlockRows = 1;
+      eigen_assert(m_row
+  CommaInitializer& operator,(const DenseBase& other)
+  {
+    if(other.cols()==0 || other.rows()==0)
+      return *this;
+    if (m_col==m_xpr.cols())
+    {
+      m_row+=m_currentBlockRows;
+      m_col = 0;
+      m_currentBlockRows = other.rows();
+      eigen_assert(m_row+m_currentBlockRows<=m_xpr.rows()
+        && "Too many rows passed to comma initializer (operator<<)");
+    }
+    eigen_assert(m_col
+                    (m_row, m_col) = other;
+    else
+      m_xpr.block(m_row, m_col, other.rows(), other.cols()) = other;
+    m_col += other.cols();
+    return *this;
+  }
+
+  inline ~CommaInitializer()
+  {
+    eigen_assert((m_row+m_currentBlockRows) == m_xpr.rows()
+         && m_col == m_xpr.cols()
+         && "Too few coefficients passed to comma initializer (operator<<)");
+  }
+
+  /** \returns the built matrix once all its coefficients have been set.
+    * Calling finished is 100% optional. Its purpose is to write expressions
+    * like this:
+    * \code
+    * quaternion.fromRotationMatrix((Matrix3f() << axis0, axis1, axis2).finished());
+    * \endcode
+    */
+  inline XprType& finished() { return m_xpr; }
+
+  XprType& m_xpr;   // target expression
+  Index m_row;              // current row id
+  Index m_col;              // current col id
+  Index m_currentBlockRows; // current block height
+};
+
+/** \anchor MatrixBaseCommaInitRef
+  * Convenient operator to set the coefficients of a matrix.
+  *
+  * The coefficients must be provided in a row major order and exactly match
+  * the size of the matrix. Otherwise an assertion is raised.
+  *
+  * Example: \include MatrixBase_set.cpp
+  * Output: \verbinclude MatrixBase_set.out
+  * 
+  * \note According the c++ standard, the argument expressions of this comma initializer are evaluated in arbitrary order.
+  *
+  * \sa CommaInitializer::finished(), class CommaInitializer
+  */
+template
+inline CommaInitializer DenseBase::operator<< (const Scalar& s)
+{
+  return CommaInitializer(*static_cast(this), s);
+}
+
+/** \sa operator<<(const Scalar&) */
+template
+template
+inline CommaInitializer
+DenseBase::operator<<(const DenseBase& other)
+{
+  return CommaInitializer(*static_cast(this), other);
+}
+
+} // end namespace Eigen
+
+#endif // EIGEN_COMMAINITIALIZER_H
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h
index 3e7f9c1b7..a72738e55 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h
@@ -24,6 +24,14 @@ namespace internal {
 
 struct constructor_without_unaligned_array_assert {};
 
+template void check_static_allocation_size()
+{
+  // if EIGEN_STACK_ALLOCATION_LIMIT is defined to 0, then no limit
+  #if EIGEN_STACK_ALLOCATION_LIMIT
+  EIGEN_STATIC_ASSERT(Size * sizeof(T) <= EIGEN_STACK_ALLOCATION_LIMIT, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG);
+  #endif
+}
+
 /** \internal
   * Static array. If the MatrixOrArrayOptions require auto-alignment, the array will be automatically aligned:
   * to 16 bytes boundary if the total size is a multiple of 16 bytes.
@@ -38,12 +46,12 @@ struct plain_array
 
   plain_array() 
   { 
-    EIGEN_STATIC_ASSERT(Size * sizeof(T) <= 128 * 128 * 8, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG);
+    check_static_allocation_size();
   }
 
   plain_array(constructor_without_unaligned_array_assert) 
   { 
-    EIGEN_STATIC_ASSERT(Size * sizeof(T) <= 128 * 128 * 8, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG);
+    check_static_allocation_size();
   }
 };
 
@@ -76,12 +84,12 @@ struct plain_array
   plain_array() 
   { 
     EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(0xf);
-    EIGEN_STATIC_ASSERT(Size * sizeof(T) <= 128 * 128 * 8, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG);
+    check_static_allocation_size();
   }
 
   plain_array(constructor_without_unaligned_array_assert) 
   { 
-    EIGEN_STATIC_ASSERT(Size * sizeof(T) <= 128 * 128 * 8, OBJECT_ALLOCATED_ON_STACK_IS_TOO_BIG);
+    check_static_allocation_size();
   }
 };
 
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h
index 04fb21732..b08b967ff 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h
@@ -589,7 +589,7 @@ struct linspaced_op_impl
 
   template
   EIGEN_STRONG_INLINE const Packet packetOp(Index i) const
-  { return internal::padd(m_lowPacket, pmul(m_stepPacket, padd(pset1(i),m_interPacket))); }
+  { return internal::padd(m_lowPacket, pmul(m_stepPacket, padd(pset1(Scalar(i)),m_interPacket))); }
 
   const Scalar m_low;
   const Scalar m_step;
@@ -609,7 +609,7 @@ template  struct functor_traits< linspaced_o
 template  struct linspaced_op
 {
   typedef typename packet_traits::type Packet;
-  linspaced_op(const Scalar& low, const Scalar& high, DenseIndex num_steps) : impl((num_steps==1 ? high : low), (num_steps==1 ? Scalar() : (high-low)/(num_steps-1))) {}
+  linspaced_op(const Scalar& low, const Scalar& high, DenseIndex num_steps) : impl((num_steps==1 ? high : low), (num_steps==1 ? Scalar() : (high-low)/Scalar(num_steps-1))) {}
 
   template
   EIGEN_STRONG_INLINE const Scalar operator() (Index i) const { return impl(i); }
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h
index 6876de588..ab50c9b81 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h
@@ -237,6 +237,8 @@ template class MapBase
     using Base::Base::operator=;
 };
 
+#undef EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS
+
 } // end namespace Eigen
 
 #endif // EIGEN_MAPBASE_H
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h
index 00d9e6d2b..cd6d949c4 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h
@@ -101,7 +101,7 @@ struct traits[ >
   template struct match {
     enum {
       HasDirectAccess = internal::has_direct_access::ret,
-      StorageOrderMatch = PlainObjectType::IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)),
+      StorageOrderMatch = PlainObjectType::IsVectorAtCompileTime || Derived::IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)),
       InnerStrideMatch = int(StrideType::InnerStrideAtCompileTime)==int(Dynamic)
                       || int(StrideType::InnerStrideAtCompileTime)==int(Derived::InnerStrideAtCompileTime)
                       || (int(StrideType::InnerStrideAtCompileTime)==0 && int(Derived::InnerStrideAtCompileTime)==1),
@@ -172,8 +172,12 @@ protected:
     }
     else
       ::new (static_cast(this)) Base(expr.data(), expr.rows(), expr.cols());
-    ::new (&m_stride) StrideBase(StrideType::OuterStrideAtCompileTime==0?0:expr.outerStride(),
-                                 StrideType::InnerStrideAtCompileTime==0?0:expr.innerStride());    
+    
+    if(Expression::IsVectorAtCompileTime && (!PlainObjectType::IsVectorAtCompileTime) && ((Expression::Flags&RowMajorBit)!=(PlainObjectType::Flags&RowMajorBit)))
+      ::new (&m_stride) StrideBase(expr.innerStride(), StrideType::InnerStrideAtCompileTime==0?0:1);
+    else
+      ::new (&m_stride) StrideBase(StrideType::OuterStrideAtCompileTime==0?0:expr.outerStride(),
+                                   StrideType::InnerStrideAtCompileTime==0?0:expr.innerStride());    
   }
 
   StrideBase m_stride;
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h
index fba07365f..845ae1aec 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/TriangularMatrix.h
@@ -278,21 +278,21 @@ template class TriangularView
 
     /** Efficient triangular matrix times vector/matrix product */
     template
-    TriangularProduct
+    TriangularProduct
     operator*(const MatrixBase& rhs) const
     {
       return TriangularProduct
-              
+              
               (m_matrix, rhs.derived());
     }
 
     /** Efficient vector/matrix times triangular matrix product */
     template friend
-    TriangularProduct
+    TriangularProduct
     operator*(const MatrixBase& lhs, const TriangularView& rhs)
     {
       return TriangularProduct
-              
+              
               (lhs.derived(),rhs.m_matrix);
     }
 
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h
index 1e6e355d6..8acca9c8c 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h
@@ -54,8 +54,25 @@
 #endif
 
 #if defined EIGEN_USE_MKL
+#   include  
+/*Check IMKL version for compatibility: < 10.3 is not usable with Eigen*/
+#   ifndef INTEL_MKL_VERSION
+#       undef EIGEN_USE_MKL /* INTEL_MKL_VERSION is not even defined on older versions */
+#   elif INTEL_MKL_VERSION < 100305    /* the intel-mkl-103-release-notes say this was when the lapacke.h interface was added*/
+#       undef EIGEN_USE_MKL
+#   endif
+#   ifndef EIGEN_USE_MKL
+    /*If the MKL version is too old, undef everything*/
+#       undef   EIGEN_USE_MKL_ALL
+#       undef   EIGEN_USE_BLAS
+#       undef   EIGEN_USE_LAPACKE
+#       undef   EIGEN_USE_MKL_VML
+#       undef   EIGEN_USE_LAPACKE_STRICT
+#       undef   EIGEN_USE_LAPACKE
+#   endif
+#endif
 
-#include 
+#if defined EIGEN_USE_MKL
 #include 
 #define EIGEN_MKL_VML_THRESHOLD 128
 
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h
index 0088621ac..3a010ec6a 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h
@@ -13,7 +13,7 @@
 
 #define EIGEN_WORLD_VERSION 3
 #define EIGEN_MAJOR_VERSION 2
-#define EIGEN_MINOR_VERSION 1
+#define EIGEN_MINOR_VERSION 2
 
 #define EIGEN_VERSION_AT_LEAST(x,y,z) (EIGEN_WORLD_VERSION>x || (EIGEN_WORLD_VERSION>=x && \
                                       (EIGEN_MAJOR_VERSION>y || (EIGEN_MAJOR_VERSION>=y && \
@@ -289,7 +289,8 @@ namespace Eigen {
 #endif
 
 #ifndef EIGEN_STACK_ALLOCATION_LIMIT
-#define EIGEN_STACK_ALLOCATION_LIMIT 20000
+// 131072 == 128 KB
+#define EIGEN_STACK_ALLOCATION_LIMIT 131072
 #endif
 
 #ifndef EIGEN_DEFAULT_IO_FORMAT
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h
index cacbd02fd..6c2461725 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h
@@ -272,12 +272,12 @@ inline void* aligned_realloc(void *ptr, size_t new_size, size_t old_size)
   // The defined(_mm_free) is just here to verify that this MSVC version
   // implements _mm_malloc/_mm_free based on the corresponding _aligned_
   // functions. This may not always be the case and we just try to be safe.
-  #if defined(_MSC_VER) && defined(_mm_free)
+  #if defined(_MSC_VER) && (!defined(_WIN32_WCE)) && defined(_mm_free)
     result = _aligned_realloc(ptr,new_size,16);
   #else
     result = generic_aligned_realloc(ptr,new_size,old_size);
   #endif
-#elif defined(_MSC_VER)
+#elif defined(_MSC_VER) && (!defined(_WIN32_WCE))
   result = _aligned_realloc(ptr,new_size,16);
 #else
   result = handmade_aligned_realloc(ptr,new_size,old_size);
@@ -630,6 +630,8 @@ template class aligned_stack_memory_handler
       } \
       void operator delete(void * ptr) throw() { Eigen::internal::conditional_aligned_free(ptr); } \
       void operator delete[](void * ptr) throw() { Eigen::internal::conditional_aligned_free(ptr); } \
+      void operator delete(void * ptr, std::size_t /* sz */) throw() { Eigen::internal::conditional_aligned_free(ptr); } \
+      void operator delete[](void * ptr, std::size_t /* sz */) throw() { Eigen::internal::conditional_aligned_free(ptr); } \
       /* in-place new and delete. since (at least afaik) there is no actual   */ \
       /* memory allocated we can safely let the default implementation handle */ \
       /* this particular case. */ \
@@ -777,9 +779,9 @@ namespace internal {
 
 #ifdef EIGEN_CPUID
 
-inline bool cpuid_is_vendor(int abcd[4], const char* vendor)
+inline bool cpuid_is_vendor(int abcd[4], const int vendor[3])
 {
-  return abcd[1]==(reinterpret_cast(vendor))[0] && abcd[3]==(reinterpret_cast(vendor))[1] && abcd[2]==(reinterpret_cast(vendor))[2];
+  return abcd[1]==vendor[0] && abcd[3]==vendor[1] && abcd[2]==vendor[2];
 }
 
 inline void queryCacheSizes_intel_direct(int& l1, int& l2, int& l3)
@@ -921,13 +923,16 @@ inline void queryCacheSizes(int& l1, int& l2, int& l3)
 {
   #ifdef EIGEN_CPUID
   int abcd[4];
+  const int GenuineIntel[] = {0x756e6547, 0x49656e69, 0x6c65746e};
+  const int AuthenticAMD[] = {0x68747541, 0x69746e65, 0x444d4163};
+  const int AMDisbetter_[] = {0x69444d41, 0x74656273, 0x21726574}; // "AMDisbetter!"
 
   // identify the CPU vendor
   EIGEN_CPUID(abcd,0x0,0);
   int max_std_funcs = abcd[1];
-  if(cpuid_is_vendor(abcd,"GenuineIntel"))
+  if(cpuid_is_vendor(abcd,GenuineIntel))
     queryCacheSizes_intel(l1,l2,l3,max_std_funcs);
-  else if(cpuid_is_vendor(abcd,"AuthenticAMD") || cpuid_is_vendor(abcd,"AMDisbetter!"))
+  else if(cpuid_is_vendor(abcd,AuthenticAMD) || cpuid_is_vendor(abcd,AMDisbetter_))
     queryCacheSizes_amd(l1,l2,l3);
   else
     // by default let's use Intel's API
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h
index 9fee0c919..f06653f1c 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h
@@ -203,6 +203,8 @@ public:
   * \li \c Quaternionf for \c float
   * \li \c Quaterniond for \c double
   *
+  * \warning Operations interpreting the quaternion as rotation have undefined behavior if the quaternion is not normalized.
+  *
   * \sa  class AngleAxis, class Transform
   */
 
@@ -344,7 +346,7 @@ class Map, _Options >
 
     /** Constructs a Mapped Quaternion object from the pointer \a coeffs
       *
-      * The pointer \a coeffs must reference the four coeffecients of Quaternion in the following order:
+      * The pointer \a coeffs must reference the four coefficients of Quaternion in the following order:
       * \code *coeffs == {x, y, z, w} \endcode
       *
       * If the template parameter _Options is set to #Aligned, then the pointer coeffs must be aligned. */
@@ -464,7 +466,7 @@ QuaternionBase::_transformVector(Vector3 v) const
     // Note that this algorithm comes from the optimization by hand
     // of the conversion to a Matrix followed by a Matrix/Vector product.
     // It appears to be much faster than the common algorithm found
-    // in the litterature (30 versus 39 flops). It also requires two
+    // in the literature (30 versus 39 flops). It also requires two
     // Vector3 as temporaries.
     Vector3 uv = this->vec().cross(v);
     uv += uv;
@@ -584,7 +586,7 @@ inline Derived& QuaternionBase::setFromTwoVectors(const MatrixBase::dummy_precision())
   {
-    c = max(c,-1);
+    c = (max)(c,Scalar(-1));
     Matrix m; m << v0.transpose(), v1.transpose();
     JacobiSVD > svd(m, ComputeFullV);
     Vector3 axis = svd.matrixV().col(2);
@@ -667,10 +669,10 @@ QuaternionBase::angularDistance(const QuaternionBase& oth
 {
   using std::acos;
   using std::abs;
-  double d = abs(this->dot(other));
-  if (d>=1.0)
+  Scalar d = abs(this->dot(other));
+  if (d>=Scalar(1))
     return Scalar(0);
-  return static_cast(2 * acos(d));
+  return Scalar(2) * acos(d);
 }
 
  
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h
index 498fea41a..56f361566 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Transform.h
@@ -194,9 +194,9 @@ public:
   /** type of the matrix used to represent the linear part of the transformation */
   typedef Matrix LinearMatrixType;
   /** type of read/write reference to the linear part of the transformation */
-  typedef Block LinearPart;
+  typedef Block LinearPart;
   /** type of read reference to the linear part of the transformation */
-  typedef const Block ConstLinearPart;
+  typedef const Block ConstLinearPart;
   /** type of read/write reference to the affine part of the transformation */
   typedef typename internal::conditional& src, const MatrixBase& dst, boo
   const Index n = src.cols(); // number of measurements
 
   // required for demeaning ...
-  const RealScalar one_over_n = 1 / static_cast(n);
+  const RealScalar one_over_n = RealScalar(1) / static_cast(n);
 
   // computation of mean
   const VectorType src_mean = src.rowwise().sum() * one_over_n;
@@ -136,16 +136,16 @@ umeyama(const MatrixBase& src, const MatrixBase& dst, boo
 
   // Eq. (39)
   VectorType S = VectorType::Ones(m);
-  if (sigma.determinant()<0) S(m-1) = -1;
+  if (sigma.determinant() 0 ) {
+    if ( svd.matrixU().determinant() * svd.matrixV().determinant() > Scalar(0) ) {
       Rt.block(0,0,m,m).noalias() = svd.matrixU()*svd.matrixV().transpose();
     } else {
-      const Scalar s = S(m-1); S(m-1) = -1;
+      const Scalar s = S(m-1); S(m-1) = Scalar(-1);
       Rt.block(0,0,m,m).noalias() = svd.matrixU() * S.asDiagonal() * svd.matrixV().transpose();
       S(m-1) = s;
     }
@@ -156,7 +156,7 @@ umeyama(const MatrixBase& src, const MatrixBase& dst, boo
   if (with_scaling)
   {
     // Eq. (42)
-    const Scalar c = 1/src_var * svd.singularValues().dot(S);
+    const Scalar c = Scalar(1)/src_var * svd.singularValues().dot(S);
 
     // Eq. (41)
     Rt.col(m).head(m) = dst_mean;
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h b/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h
index 1991c6527..60dbea5f5 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/Householder/BlockHouseholder.h
@@ -48,7 +48,7 @@ void apply_block_householder_on_the_left(MatrixType& mat, const VectorsType& vec
   typedef typename MatrixType::Index Index;
   enum { TFactorSize = MatrixType::ColsAtCompileTime };
   Index nbVecs = vectors.cols();
-  Matrix T(nbVecs,nbVecs);
+  Matrix T(nbVecs,nbVecs);
   make_block_householder_triangular_factor(T, vectors, hCoeffs);
 
   const TriangularView& V(vectors);
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
index 6fc6ab852..2b9fb7f88 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
@@ -61,6 +61,7 @@ bool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x,
   VectorType s(n), t(n);
 
   RealScalar tol2 = tol*tol;
+  RealScalar eps2 = NumTraits::epsilon()*NumTraits::epsilon();
   int i = 0;
   int restarts = 0;
 
@@ -69,7 +70,7 @@ bool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x,
     Scalar rho_old = rho;
 
     rho = r0.dot(r);
-    if (internal::isMuchSmallerThan(rho,r0_sqnorm))
+    if (abs(rho) < eps2*r0_sqnorm)
     {
       // The new residual vector became too orthogonal to the arbitrarily choosen direction r0
       // Let's restart with a new r0:
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h
index dfe25f424..79ab6a8c8 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h
@@ -20,10 +20,11 @@ namespace Eigen {
   *
   * \param MatrixType the type of the matrix of which we are computing the LU decomposition
   *
-  * This class represents a LU decomposition of any matrix, with complete pivoting: the matrix A
-  * is decomposed as A = PLUQ where L is unit-lower-triangular, U is upper-triangular, and P and Q
-  * are permutation matrices. This is a rank-revealing LU decomposition. The eigenvalues (diagonal
-  * coefficients) of U are sorted in such a way that any zeros are at the end.
+  * This class represents a LU decomposition of any matrix, with complete pivoting: the matrix A is
+  * decomposed as \f$ A = P^{-1} L U Q^{-1} \f$ where L is unit-lower-triangular, U is
+  * upper-triangular, and P and Q are permutation matrices. This is a rank-revealing LU
+  * decomposition. The eigenvalues (diagonal coefficients) of U are sorted in such a way that any
+  * zeros are at the end.
   *
   * This decomposition provides the generic approach to solving systems of linear equations, computing
   * the rank, invertibility, inverse, kernel, and determinant.
@@ -511,8 +512,8 @@ typename internal::traits::Scalar FullPivLU::determinant
 }
 
 /** \returns the matrix represented by the decomposition,
- * i.e., it returns the product: P^{-1} L U Q^{-1}.
- * This function is provided for debug purpose. */
+ * i.e., it returns the product: \f$ P^{-1} L U Q^{-1} \f$.
+ * This function is provided for debug purposes. */
 template
 MatrixType FullPivLU::reconstructedMatrix() const
 {
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Ordering.h b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Ordering.h
index b4da6531a..f3c31f9cb 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Ordering.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Ordering.h
@@ -109,7 +109,7 @@ class NaturalOrdering
   * \class COLAMDOrdering
   *
   * Functor computing the \em column \em approximate \em minimum \em degree ordering 
-  * The matrix should be in column-major format
+  * The matrix should be in column-major and \b compressed format (see SparseMatrix::makeCompressed()).
   */
 template
 class COLAMDOrdering
@@ -118,10 +118,14 @@ class COLAMDOrdering
     typedef PermutationMatrix PermutationType; 
     typedef Matrix IndexVector;
     
-    /** Compute the permutation vector form a sparse matrix */
+    /** Compute the permutation vector \a perm form the sparse matrix \a mat
+      * \warning The input sparse matrix \a mat must be in compressed mode (see SparseMatrix::makeCompressed()).
+      */
     template 
     void operator() (const MatrixType& mat, PermutationType& perm)
     {
+      eigen_assert(mat.isCompressed() && "COLAMDOrdering requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to COLAMDOrdering");
+      
       Index m = mat.rows();
       Index n = mat.cols();
       Index nnz = mat.nonZeros();
@@ -132,12 +136,12 @@ class COLAMDOrdering
       Index stats [COLAMD_STATS];
       internal::colamd_set_defaults(knobs);
       
-      Index info;
       IndexVector p(n+1), A(Alen); 
       for(Index i=0; i <= n; i++)   p(i) = mat.outerIndexPtr()[i];
       for(Index i=0; i < nnz; i++)  A(i) = mat.innerIndexPtr()[i];
       // Call Colamd routine to compute the ordering 
-      info = internal::colamd(m, n, Alen, A.data(), p.data(), knobs, stats); 
+      Index info = internal::colamd(m, n, Alen, A.data(), p.data(), knobs, stats); 
+      EIGEN_UNUSED_VARIABLE(info);
       eigen_assert( info && "COLAMD failed " );
       
       perm.resize(n);
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h
index bec85810c..773d1df8f 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h
@@ -76,7 +76,8 @@ template class ColPivHouseholderQR
         m_colsTranspositions(),
         m_temp(),
         m_colSqNorms(),
-        m_isInitialized(false) {}
+        m_isInitialized(false),
+        m_usePrescribedThreshold(false) {}
 
     /** \brief Default Constructor with memory preallocation
       *
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h
index f44995cd3..dff9e44eb 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h
@@ -375,17 +375,19 @@ struct svd_precondition_2x2_block_to_be_real
     Scalar z;
     JacobiRotation rot;
     RealScalar n = sqrt(numext::abs2(work_matrix.coeff(p,p)) + numext::abs2(work_matrix.coeff(q,p)));
+    
     if(n==0)
     {
       z = abs(work_matrix.coeff(p,q)) / work_matrix.coeff(p,q);
       work_matrix.row(p) *= z;
       if(svd.computeU()) svd.m_matrixU.col(p) *= conj(z);
       if(work_matrix.coeff(q,q)!=Scalar(0))
+      {
         z = abs(work_matrix.coeff(q,q)) / work_matrix.coeff(q,q);
-      else
-        z = Scalar(0);
-      work_matrix.row(q) *= z;
-      if(svd.computeU()) svd.m_matrixU.col(q) *= conj(z);
+        work_matrix.row(q) *= z;
+        if(svd.computeU()) svd.m_matrixU.col(q) *= conj(z);
+      }
+      // otherwise the second row is already zero, so we have nothing to do.
     }
     else
     {
@@ -415,6 +417,7 @@ void real_2x2_jacobi_svd(const MatrixType& matrix, Index p, Index q,
                             JacobiRotation *j_right)
 {
   using std::sqrt;
+  using std::abs;
   Matrix m;
   m << numext::real(matrix.coeff(p,p)), numext::real(matrix.coeff(p,q)),
        numext::real(matrix.coeff(q,p)), numext::real(matrix.coeff(q,q));
@@ -428,9 +431,11 @@ void real_2x2_jacobi_svd(const MatrixType& matrix, Index p, Index q,
   }
   else
   {
-    RealScalar u = d / t;
-    rot1.c() = RealScalar(1) / sqrt(RealScalar(1) + numext::abs2(u));
-    rot1.s() = rot1.c() * u;
+    RealScalar t2d2 = numext::hypot(t,d);
+    rot1.c() = abs(t)/t2d2;
+    rot1.s() = d/t2d2;
+    if(tmakeJacobi(m,0,1);
@@ -531,8 +536,9 @@ template class JacobiSVD
     JacobiSVD()
       : m_isInitialized(false),
         m_isAllocated(false),
+        m_usePrescribedThreshold(false),
         m_computationOptions(0),
-        m_rows(-1), m_cols(-1)
+        m_rows(-1), m_cols(-1), m_diagSize(0)
     {}
 
 
@@ -545,6 +551,7 @@ template class JacobiSVD
     JacobiSVD(Index rows, Index cols, unsigned int computationOptions = 0)
       : m_isInitialized(false),
         m_isAllocated(false),
+        m_usePrescribedThreshold(false),
         m_computationOptions(0),
         m_rows(-1), m_cols(-1)
     {
@@ -564,6 +571,7 @@ template class JacobiSVD
     JacobiSVD(const MatrixType& matrix, unsigned int computationOptions = 0)
       : m_isInitialized(false),
         m_isAllocated(false),
+        m_usePrescribedThreshold(false),
         m_computationOptions(0),
         m_rows(-1), m_cols(-1)
     {
@@ -665,6 +673,69 @@ template class JacobiSVD
       eigen_assert(m_isInitialized && "JacobiSVD is not initialized.");
       return m_nonzeroSingularValues;
     }
+    
+    /** \returns the rank of the matrix of which \c *this is the SVD.
+      *
+      * \note This method has to determine which singular values should be considered nonzero.
+      *       For that, it uses the threshold value that you can control by calling
+      *       setThreshold(const RealScalar&).
+      */
+    inline Index rank() const
+    {
+      using std::abs;
+      eigen_assert(m_isInitialized && "JacobiSVD is not initialized.");
+      if(m_singularValues.size()==0) return 0;
+      RealScalar premultiplied_threshold = m_singularValues.coeff(0) * threshold();
+      Index i = m_nonzeroSingularValues-1;
+      while(i>=0 && m_singularValues.coeff(i) < premultiplied_threshold) --i;
+      return i+1;
+    }
+    
+    /** Allows to prescribe a threshold to be used by certain methods, such as rank() and solve(),
+      * which need to determine when singular values are to be considered nonzero.
+      * This is not used for the SVD decomposition itself.
+      *
+      * When it needs to get the threshold value, Eigen calls threshold().
+      * The default is \c NumTraits::epsilon()
+      *
+      * \param threshold The new value to use as the threshold.
+      *
+      * A singular value will be considered nonzero if its value is strictly greater than
+      *  \f$ \vert singular value \vert \leqslant threshold \times \vert max singular value \vert \f$.
+      *
+      * If you want to come back to the default behavior, call setThreshold(Default_t)
+      */
+    JacobiSVD& setThreshold(const RealScalar& threshold)
+    {
+      m_usePrescribedThreshold = true;
+      m_prescribedThreshold = threshold;
+      return *this;
+    }
+
+    /** Allows to come back to the default behavior, letting Eigen use its default formula for
+      * determining the threshold.
+      *
+      * You should pass the special object Eigen::Default as parameter here.
+      * \code svd.setThreshold(Eigen::Default); \endcode
+      *
+      * See the documentation of setThreshold(const RealScalar&).
+      */
+    JacobiSVD& setThreshold(Default_t)
+    {
+      m_usePrescribedThreshold = false;
+      return *this;
+    }
+
+    /** Returns the threshold that will be used by certain methods such as rank().
+      *
+      * See the documentation of setThreshold(const RealScalar&).
+      */
+    RealScalar threshold() const
+    {
+      eigen_assert(m_isInitialized || m_usePrescribedThreshold);
+      return m_usePrescribedThreshold ? m_prescribedThreshold
+                                      : (std::max)(1,m_diagSize)*NumTraits::epsilon();
+    }
 
     inline Index rows() const { return m_rows; }
     inline Index cols() const { return m_cols; }
@@ -677,11 +748,12 @@ template class JacobiSVD
     MatrixVType m_matrixV;
     SingularValuesType m_singularValues;
     WorkMatrixType m_workMatrix;
-    bool m_isInitialized, m_isAllocated;
+    bool m_isInitialized, m_isAllocated, m_usePrescribedThreshold;
     bool m_computeFullU, m_computeThinU;
     bool m_computeFullV, m_computeThinV;
     unsigned int m_computationOptions;
     Index m_nonzeroSingularValues, m_rows, m_cols, m_diagSize;
+    RealScalar m_prescribedThreshold;
 
     template
     friend struct internal::svd_precondition_2x2_block_to_be_real;
@@ -764,6 +836,11 @@ JacobiSVD::compute(const MatrixType& matrix, unsig
     if(m_computeFullV) m_matrixV.setIdentity(m_cols,m_cols);
     if(m_computeThinV) m_matrixV.setIdentity(m_cols, m_diagSize);
   }
+  
+  // Scaling factor to reduce over/under-flows
+  RealScalar scale = m_workMatrix.cwiseAbs().maxCoeff();
+  if(scale==RealScalar(0)) scale = RealScalar(1);
+  m_workMatrix /= scale;
 
   /*** step 2. The main Jacobi SVD iteration. ***/
 
@@ -833,6 +910,8 @@ JacobiSVD::compute(const MatrixType& matrix, unsig
       if(computeV()) m_matrixV.col(pos).swap(m_matrixV.col(i));
     }
   }
+  
+  m_singularValues *= scale;
 
   m_isInitialized = true;
   return *this;
@@ -854,11 +933,11 @@ struct solve_retval, Rhs>
     // So A^{-1} = V S^{-1} U^*
 
     Matrix tmp;
-    Index nonzeroSingVals = dec().nonzeroSingularValues();
+    Index rank = dec().rank();
     
-    tmp.noalias() = dec().matrixU().leftCols(nonzeroSingVals).adjoint() * rhs();
-    tmp = dec().singularValues().head(nonzeroSingVals).asDiagonal().inverse() * tmp;
-    dst = dec().matrixV().leftCols(nonzeroSingVals) * tmp;
+    tmp.noalias() = dec().matrixU().leftCols(rank).adjoint() * rhs();
+    tmp = dec().singularValues().head(rank).asDiagonal().inverse() * tmp;
+    dst = dec().matrixV().leftCols(rank) * tmp;
   }
 };
 } // end namespace internal
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h
index f41d7e010..e1f96ba5a 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h
@@ -37,6 +37,7 @@ class SimplicialCholeskyBase : internal::noncopyable
 {
   public:
     typedef typename internal::traits::MatrixType MatrixType;
+    typedef typename internal::traits::OrderingType OrderingType;
     enum { UpLo = internal::traits::UpLo };
     typedef typename MatrixType::Scalar Scalar;
     typedef typename MatrixType::RealScalar RealScalar;
@@ -240,15 +241,16 @@ class SimplicialCholeskyBase : internal::noncopyable
     RealScalar m_shiftScale;
 };
 
-template class SimplicialLLT;
-template class SimplicialLDLT;
-template class SimplicialCholesky;
+template > class SimplicialLLT;
+template > class SimplicialLDLT;
+template > class SimplicialCholesky;
 
 namespace internal {
 
-template struct traits >
+template struct traits >
 {
   typedef _MatrixType MatrixType;
+  typedef _Ordering OrderingType;
   enum { UpLo = _UpLo };
   typedef typename MatrixType::Scalar                         Scalar;
   typedef typename MatrixType::Index                          Index;
@@ -259,9 +261,10 @@ template struct traits struct traits >
+template struct traits >
 {
   typedef _MatrixType MatrixType;
+  typedef _Ordering OrderingType;
   enum { UpLo = _UpLo };
   typedef typename MatrixType::Scalar                             Scalar;
   typedef typename MatrixType::Index                              Index;
@@ -272,9 +275,10 @@ template struct traits struct traits >
+template struct traits >
 {
   typedef _MatrixType MatrixType;
+  typedef _Ordering OrderingType;
   enum { UpLo = _UpLo };
 };
 
@@ -294,11 +298,12 @@ template struct traits
   * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower
   *               or Upper. Default is Lower.
+  * \tparam _Ordering The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<>
   *
-  * \sa class SimplicialLDLT
+  * \sa class SimplicialLDLT, class AMDOrdering, class NaturalOrdering
   */
-template
-    class SimplicialLLT : public SimplicialCholeskyBase >
+template
+    class SimplicialLLT : public SimplicialCholeskyBase >
 {
 public:
     typedef _MatrixType MatrixType;
@@ -382,11 +387,12 @@ public:
   * \tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>
   * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower
   *               or Upper. Default is Lower.
+  * \tparam _Ordering The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<>
   *
-  * \sa class SimplicialLLT
+  * \sa class SimplicialLLT, class AMDOrdering, class NaturalOrdering
   */
-template
-    class SimplicialLDLT : public SimplicialCholeskyBase >
+template
+    class SimplicialLDLT : public SimplicialCholeskyBase >
 {
 public:
     typedef _MatrixType MatrixType;
@@ -467,8 +473,8 @@ public:
   *
   * \sa class SimplicialLDLT, class SimplicialLLT
   */
-template
-    class SimplicialCholesky : public SimplicialCholeskyBase >
+template
+    class SimplicialCholesky : public SimplicialCholeskyBase >
 {
 public:
     typedef _MatrixType MatrixType;
@@ -612,15 +618,13 @@ void SimplicialCholeskyBase::ordering(const MatrixType& a, CholMatrixTy
 {
   eigen_assert(a.rows()==a.cols());
   const Index size = a.rows();
-  // TODO allows to configure the permutation
   // Note that amd compute the inverse permutation
   {
     CholMatrixType C;
     C = a.template selfadjointView();
-    // remove diagonal entries:
-    // seems not to be needed
-    // C.prune(keep_diag());
-    internal::minimum_degree_ordering(C, m_Pinv);
+    
+    OrderingType ordering;
+    ordering(C,m_Pinv);
   }
 
   if(m_Pinv.size()>0)
diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h
index 3321fab4a..a667cb56e 100644
--- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h
+++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CompressedStorage.h
@@ -51,8 +51,8 @@ class CompressedStorage
     CompressedStorage& operator=(const CompressedStorage& other)
     {
       resize(other.size());
-      memcpy(m_values, other.m_values, m_size * sizeof(Scalar));
-      memcpy(m_indices, other.m_indices, m_size * sizeof(Index));
+      internal::smart_copy(other.m_values,  other.m_values  + m_size, m_values);
+      internal::smart_copy(other.m_indices, other.m_indices + m_size, m_indices);
       return *this;
     }
 
@@ -83,10 +83,10 @@ class CompressedStorage
         reallocate(m_size);
     }
 
-    void resize(size_t size, float reserveSizeFactor = 0)
+    void resize(size_t size, double reserveSizeFactor = 0)
     {
       if (m_allocatedSize]