Update ceres to the latest version in google3.

Change-Id: I0165fffa55f60714f23e0096eac89fa68df75a05
diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt
index 2307a03..9dfc80b 100644
--- a/examples/CMakeLists.txt
+++ b/examples/CMakeLists.txt
@@ -28,39 +28,51 @@
 #
 # Author: keir@google.com (Keir Mierle)
 
-IF (${GFLAGS})
-  ADD_EXECUTABLE(quadratic quadratic.cc)
-  TARGET_LINK_LIBRARIES(quadratic ceres)
+ADD_EXECUTABLE(helloworld helloworld.cc)
+TARGET_LINK_LIBRARIES(helloworld ceres)
+
+ADD_EXECUTABLE(helloworld_numeric_diff helloworld_numeric_diff.cc)
+TARGET_LINK_LIBRARIES(helloworld_numeric_diff ceres)
+
+ADD_EXECUTABLE(helloworld_analytic_diff helloworld_analytic_diff.cc)
+TARGET_LINK_LIBRARIES(helloworld_analytic_diff ceres)
+
+ADD_EXECUTABLE(curve_fitting curve_fitting.cc)
+TARGET_LINK_LIBRARIES(curve_fitting ceres)
+
+ADD_EXECUTABLE(curve_fitting_c curve_fitting.c)
+TARGET_LINK_LIBRARIES(curve_fitting_c ceres)
+
+
+ADD_EXECUTABLE(robust_curve_fitting robust_curve_fitting.cc)
+TARGET_LINK_LIBRARIES(robust_curve_fitting ceres)
+
+ADD_EXECUTABLE(simple_bundle_adjuster
+               simple_bundle_adjuster.cc)
+TARGET_LINK_LIBRARIES(simple_bundle_adjuster ceres)
+
+IF (GFLAGS)
+  ADD_EXECUTABLE(powell powell.cc)
+  TARGET_LINK_LIBRARIES(powell ceres)
 
   ADD_EXECUTABLE(nist nist.cc)
   TARGET_LINK_LIBRARIES(nist ceres)
 
-  ADD_EXECUTABLE(quadratic_auto_diff quadratic_auto_diff.cc)
-  TARGET_LINK_LIBRARIES(quadratic_auto_diff ceres)
-
-  ADD_EXECUTABLE(quadratic_numeric_diff quadratic_numeric_diff.cc)
-  TARGET_LINK_LIBRARIES(quadratic_numeric_diff ceres)
-
-  ADD_EXECUTABLE(powell powell.cc)
-  TARGET_LINK_LIBRARIES(powell ceres)
-
   ADD_EXECUTABLE(circle_fit circle_fit.cc)
   TARGET_LINK_LIBRARIES(circle_fit ceres)
 
-  ADD_EXECUTABLE(data_fitting data_fitting.cc)
-  TARGET_LINK_LIBRARIES(data_fitting ceres)
-
   ADD_EXECUTABLE(bundle_adjuster
                  bundle_adjuster.cc
                  bal_problem.cc)
   TARGET_LINK_LIBRARIES(bundle_adjuster ceres)
 
+  ADD_EXECUTABLE(libmv_bundle_adjuster
+                 libmv_bundle_adjuster.cc)
+  TARGET_LINK_LIBRARIES(libmv_bundle_adjuster ceres)
+
   ADD_EXECUTABLE(denoising
                  denoising.cc
                  fields_of_experts.cc)
   TARGET_LINK_LIBRARIES(denoising ceres)
-ENDIF (${GFLAGS})
+ENDIF (GFLAGS)
 
-ADD_EXECUTABLE(simple_bundle_adjuster
-               simple_bundle_adjuster.cc)
-TARGET_LINK_LIBRARIES(simple_bundle_adjuster ceres)
diff --git a/examples/bal_problem.cc b/examples/bal_problem.cc
index 5733f46..c118f88 100644
--- a/examples/bal_problem.cc
+++ b/examples/bal_problem.cc
@@ -35,7 +35,6 @@
 #include <string>
 #include <vector>
 #include "Eigen/Core"
-#include "ceres/random.h"
 #include "ceres/rotation.h"
 #include "glog/logging.h"
 
@@ -45,6 +44,25 @@
 typedef Eigen::Map<Eigen::VectorXd> VectorRef;
 typedef Eigen::Map<const Eigen::VectorXd> ConstVectorRef;
 
+inline double RandDouble() {
+  double r = static_cast<double>(rand());
+  return r / RAND_MAX;
+}
+
+// Box-Muller algorithm for normal random number generation.
+// http://en.wikipedia.org/wiki/Box-Muller_transform
+inline double RandNormal() {
+  double x1, x2, w;
+  do {
+    x1 = 2.0 * RandDouble() - 1.0;
+    x2 = 2.0 * RandDouble() - 1.0;
+    w = x1 * x1 + x2 * x2;
+  } while ( w >= 1.0 || w == 0.0 );
+
+  w = sqrt((-2.0 * log(w)) / w);
+  return x1 * w;
+}
+
 template<typename T>
 void FscanfOrDie(FILE* fptr, const char* format, T* value) {
   int num_scanned = fscanf(fptr, format, value);
diff --git a/examples/bundle_adjuster.cc b/examples/bundle_adjuster.cc
index 78dbd01..c060aed 100644
--- a/examples/bundle_adjuster.cc
+++ b/examples/bundle_adjuster.cc
@@ -60,7 +60,6 @@
 
 #include "bal_problem.h"
 #include "ceres/ceres.h"
-#include "ceres/random.h"
 #include "gflags/gflags.h"
 #include "glog/logging.h"
 #include "snavely_reprojection_error.h"
@@ -97,9 +96,6 @@
              "accuracy of each linear solve of the truncated newton step. "
              "Changing this parameter can affect solve performance.");
 
-DEFINE_bool(use_block_amd, true, "Use a block oriented fill reducing "
-            "ordering.");
-
 DEFINE_int32(num_threads, 1, "Number of threads.");
 DEFINE_int32(num_iterations, 5, "Number of iterations.");
 DEFINE_double(max_solver_time, 1e32, "Maximum solve time in seconds.");
@@ -116,6 +112,8 @@
              "of the pseudo random number generator used to generate "
              "the pertubations.");
 DEFINE_string(solver_log, "", "File to record the solver execution to.");
+DEFINE_bool(line_search, false, "Use a line search instead of trust region "
+            "algorithm.");
 
 namespace ceres {
 namespace examples {
@@ -140,8 +138,6 @@
   const int camera_block_size = bal_problem->camera_block_size();
   double* cameras = bal_problem->mutable_cameras();
 
-  options->use_block_amd = FLAGS_use_block_amd;
-
   if (options->use_inner_iterations) {
     if (FLAGS_blocks_for_inner_iterations == "cameras") {
       LOG(INFO) << "Camera blocks for inner iterations";
@@ -225,6 +221,10 @@
   options->eta = FLAGS_eta;
   options->max_solver_time_in_seconds = FLAGS_max_solver_time;
   options->use_nonmonotonic_steps = FLAGS_nonmonotonic_steps;
+  if (FLAGS_line_search) {
+    options->minimizer_type = ceres::LINE_SEARCH;
+  }
+
   CHECK(StringToTrustRegionStrategyType(FLAGS_trust_region_strategy,
                                         &options->trust_region_strategy_type));
   CHECK(StringToDoglegType(FLAGS_dogleg, &options->dogleg_type));
@@ -305,7 +305,7 @@
   BALProblem bal_problem(filename, FLAGS_use_quaternions);
   Problem problem;
 
-  SetRandomState(FLAGS_random_seed);
+  srand(FLAGS_random_seed);
   bal_problem.Normalize();
   bal_problem.Perturb(FLAGS_rotation_sigma,
                       FLAGS_translation_sigma,
diff --git a/examples/curve_fitting.c b/examples/curve_fitting.c
new file mode 100644
index 0000000..3ea2ef1
--- /dev/null
+++ b/examples/curve_fitting.c
@@ -0,0 +1,187 @@
+/* Ceres Solver - A fast non-linear least squares minimizer
+ * Copyright 2013 Google Inc. All rights reserved.
+ * http://code.google.com/p/ceres-solver/
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * - Redistributions of source code must retain the above copyright notice,
+ *   this list of conditions and the following disclaimer.
+ * - Redistributions in binary form must reproduce the above copyright notice,
+ *   this list of conditions and the following disclaimer in the documentation
+ *   and/or other materials provided with the distribution.
+ * - Neither the name of Google Inc. nor the names of its contributors may be
+ *   used to endorse or promote products derived from this software without
+ *   specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ * Author: mierle@gmail.com (Keir Mierle)
+ *
+ * This is a port of curve_fitting.cc to the minimal C API for Ceres.
+ */
+
+#include <math.h>
+#include <stdio.h>
+#include <string.h>  // For NULL
+#include "ceres/c_api.h"
+
+/* Data generated using the following octave code.
+ *
+ *   randn('seed', 23497);
+ *   m = 0.3;
+ *   c = 0.1;
+ *   x=[0:0.075:5];
+ *   y = exp(m * x + c);
+ *   noise = randn(size(x)) * 0.2;
+ *   y_observed = y + noise;
+ *   data = [x', y_observed'];
+ *
+ */
+
+int num_observations = 67;
+double data[] = {
+  0.000000e+00, 1.133898e+00,
+  7.500000e-02, 1.334902e+00,
+  1.500000e-01, 1.213546e+00,
+  2.250000e-01, 1.252016e+00,
+  3.000000e-01, 1.392265e+00,
+  3.750000e-01, 1.314458e+00,
+  4.500000e-01, 1.472541e+00,
+  5.250000e-01, 1.536218e+00,
+  6.000000e-01, 1.355679e+00,
+  6.750000e-01, 1.463566e+00,
+  7.500000e-01, 1.490201e+00,
+  8.250000e-01, 1.658699e+00,
+  9.000000e-01, 1.067574e+00,
+  9.750000e-01, 1.464629e+00,
+  1.050000e+00, 1.402653e+00,
+  1.125000e+00, 1.713141e+00,
+  1.200000e+00, 1.527021e+00,
+  1.275000e+00, 1.702632e+00,
+  1.350000e+00, 1.423899e+00,
+  1.425000e+00, 1.543078e+00,
+  1.500000e+00, 1.664015e+00,
+  1.575000e+00, 1.732484e+00,
+  1.650000e+00, 1.543296e+00,
+  1.725000e+00, 1.959523e+00,
+  1.800000e+00, 1.685132e+00,
+  1.875000e+00, 1.951791e+00,
+  1.950000e+00, 2.095346e+00,
+  2.025000e+00, 2.361460e+00,
+  2.100000e+00, 2.169119e+00,
+  2.175000e+00, 2.061745e+00,
+  2.250000e+00, 2.178641e+00,
+  2.325000e+00, 2.104346e+00,
+  2.400000e+00, 2.584470e+00,
+  2.475000e+00, 1.914158e+00,
+  2.550000e+00, 2.368375e+00,
+  2.625000e+00, 2.686125e+00,
+  2.700000e+00, 2.712395e+00,
+  2.775000e+00, 2.499511e+00,
+  2.850000e+00, 2.558897e+00,
+  2.925000e+00, 2.309154e+00,
+  3.000000e+00, 2.869503e+00,
+  3.075000e+00, 3.116645e+00,
+  3.150000e+00, 3.094907e+00,
+  3.225000e+00, 2.471759e+00,
+  3.300000e+00, 3.017131e+00,
+  3.375000e+00, 3.232381e+00,
+  3.450000e+00, 2.944596e+00,
+  3.525000e+00, 3.385343e+00,
+  3.600000e+00, 3.199826e+00,
+  3.675000e+00, 3.423039e+00,
+  3.750000e+00, 3.621552e+00,
+  3.825000e+00, 3.559255e+00,
+  3.900000e+00, 3.530713e+00,
+  3.975000e+00, 3.561766e+00,
+  4.050000e+00, 3.544574e+00,
+  4.125000e+00, 3.867945e+00,
+  4.200000e+00, 4.049776e+00,
+  4.275000e+00, 3.885601e+00,
+  4.350000e+00, 4.110505e+00,
+  4.425000e+00, 4.345320e+00,
+  4.500000e+00, 4.161241e+00,
+  4.575000e+00, 4.363407e+00,
+  4.650000e+00, 4.161576e+00,
+  4.725000e+00, 4.619728e+00,
+  4.800000e+00, 4.737410e+00,
+  4.875000e+00, 4.727863e+00,
+  4.950000e+00, 4.669206e+00,
+};
+
+/* This is the equivalent of a use-defined CostFunction in the C++ Ceres API.
+ * This is passed as a callback to the Ceres C API, which internally converts
+ * the callback into a CostFunction. */
+int exponential_residual(void* user_data,
+                         double** parameters,
+                         double* residuals,
+                         double** jacobians) {
+  double* measurement = (double*) user_data;
+  double x = measurement[0];
+  double y = measurement[1];
+  double m = parameters[0][0];
+  double c = parameters[1][0];
+
+  residuals[0] = y - exp(m * x + c);
+  if (jacobians == NULL) {
+    return 1;
+  }
+  if (jacobians[0] != NULL) {
+    jacobians[0][0] = - x * exp(m * x + c);  /* dr/dm */
+  }
+  if (jacobians[1] != NULL) {
+    jacobians[1][0] =     - exp(m * x + c);  /* dr/dc */
+  }
+  return 1;
+}
+
+int main(int argc, char** argv) {
+  /* Note: Typically it is better to compact m and c into one block,
+   * but in this case use separate blocks to illustrate the use of
+   * multiple parameter blocks. */
+  double m = 0.0;
+  double c = 0.0;
+
+  double *parameter_pointers[] = { &m, &c };
+  int parameter_sizes[] = { 1, 1 };
+  int i;
+
+  ceres_problem_t* problem;
+
+  /* Ceres has some internal stuff that needs to get initialized. */
+  ceres_init();
+
+  problem = ceres_create_problem();
+
+  /* Add all the residuals. */
+  for (i = 0; i < num_observations; ++i) {
+    ceres_problem_add_residual_block(
+        problem,
+        exponential_residual,  /* Cost function */
+        &data[2 * i],          /* Points to the (x,y) measurement */
+        NULL,                  /* No loss function */
+        NULL,                  /* No loss function user data */
+        1,                     /* Number of residuals */
+        2,                     /* Number of parameter blocks */
+        parameter_sizes,
+        parameter_pointers);
+  }
+
+  ceres_solve(problem);
+  ceres_free_problem(problem);
+
+  printf("Initial m: 0.0, c: 0.0\n");
+  printf("Final m: %g, c: %g\n", m, c);
+  return 0;
+}
diff --git a/examples/curve_fitting.cc b/examples/curve_fitting.cc
new file mode 100644
index 0000000..3e3adcd
--- /dev/null
+++ b/examples/curve_fitting.cc
@@ -0,0 +1,163 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2010, 2011, 2012 Google Inc. All rights reserved.
+// http://code.google.com/p/ceres-solver/
+//
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+//
+// * Redistributions of source code must retain the above copyright notice,
+//   this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright notice,
+//   this list of conditions and the following disclaimer in the documentation
+//   and/or other materials provided with the distribution.
+// * Neither the name of Google Inc. nor the names of its contributors may be
+//   used to endorse or promote products derived from this software without
+//   specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+//
+// Author: sameeragarwal@google.com (Sameer Agarwal)
+
+#include "ceres/ceres.h"
+#include "glog/logging.h"
+
+using ceres::AutoDiffCostFunction;
+using ceres::CostFunction;
+using ceres::Problem;
+using ceres::Solver;
+using ceres::Solve;
+
+// Data generated using the following octave code.
+//   randn('seed', 23497);
+//   m = 0.3;
+//   c = 0.1;
+//   x=[0:0.075:5];
+//   y = exp(m * x + c);
+//   noise = randn(size(x)) * 0.2;
+//   y_observed = y + noise;
+//   data = [x', y_observed'];
+
+const int kNumObservations = 67;
+const double data[] = {
+  0.000000e+00, 1.133898e+00,
+  7.500000e-02, 1.334902e+00,
+  1.500000e-01, 1.213546e+00,
+  2.250000e-01, 1.252016e+00,
+  3.000000e-01, 1.392265e+00,
+  3.750000e-01, 1.314458e+00,
+  4.500000e-01, 1.472541e+00,
+  5.250000e-01, 1.536218e+00,
+  6.000000e-01, 1.355679e+00,
+  6.750000e-01, 1.463566e+00,
+  7.500000e-01, 1.490201e+00,
+  8.250000e-01, 1.658699e+00,
+  9.000000e-01, 1.067574e+00,
+  9.750000e-01, 1.464629e+00,
+  1.050000e+00, 1.402653e+00,
+  1.125000e+00, 1.713141e+00,
+  1.200000e+00, 1.527021e+00,
+  1.275000e+00, 1.702632e+00,
+  1.350000e+00, 1.423899e+00,
+  1.425000e+00, 1.543078e+00,
+  1.500000e+00, 1.664015e+00,
+  1.575000e+00, 1.732484e+00,
+  1.650000e+00, 1.543296e+00,
+  1.725000e+00, 1.959523e+00,
+  1.800000e+00, 1.685132e+00,
+  1.875000e+00, 1.951791e+00,
+  1.950000e+00, 2.095346e+00,
+  2.025000e+00, 2.361460e+00,
+  2.100000e+00, 2.169119e+00,
+  2.175000e+00, 2.061745e+00,
+  2.250000e+00, 2.178641e+00,
+  2.325000e+00, 2.104346e+00,
+  2.400000e+00, 2.584470e+00,
+  2.475000e+00, 1.914158e+00,
+  2.550000e+00, 2.368375e+00,
+  2.625000e+00, 2.686125e+00,
+  2.700000e+00, 2.712395e+00,
+  2.775000e+00, 2.499511e+00,
+  2.850000e+00, 2.558897e+00,
+  2.925000e+00, 2.309154e+00,
+  3.000000e+00, 2.869503e+00,
+  3.075000e+00, 3.116645e+00,
+  3.150000e+00, 3.094907e+00,
+  3.225000e+00, 2.471759e+00,
+  3.300000e+00, 3.017131e+00,
+  3.375000e+00, 3.232381e+00,
+  3.450000e+00, 2.944596e+00,
+  3.525000e+00, 3.385343e+00,
+  3.600000e+00, 3.199826e+00,
+  3.675000e+00, 3.423039e+00,
+  3.750000e+00, 3.621552e+00,
+  3.825000e+00, 3.559255e+00,
+  3.900000e+00, 3.530713e+00,
+  3.975000e+00, 3.561766e+00,
+  4.050000e+00, 3.544574e+00,
+  4.125000e+00, 3.867945e+00,
+  4.200000e+00, 4.049776e+00,
+  4.275000e+00, 3.885601e+00,
+  4.350000e+00, 4.110505e+00,
+  4.425000e+00, 4.345320e+00,
+  4.500000e+00, 4.161241e+00,
+  4.575000e+00, 4.363407e+00,
+  4.650000e+00, 4.161576e+00,
+  4.725000e+00, 4.619728e+00,
+  4.800000e+00, 4.737410e+00,
+  4.875000e+00, 4.727863e+00,
+  4.950000e+00, 4.669206e+00,
+};
+
+struct ExponentialResidual {
+  ExponentialResidual(double x, double y)
+      : x_(x), y_(y) {}
+
+  template <typename T> bool operator()(const T* const m,
+                                        const T* const c,
+                                        T* residual) const {
+    residual[0] = T(y_) - exp(m[0] * T(x_) + c[0]);
+    return true;
+  }
+
+ private:
+  const double x_;
+  const double y_;
+};
+
+int main(int argc, char** argv) {
+  google::InitGoogleLogging(argv[0]);
+
+  double m = 0.0;
+  double c = 0.0;
+
+  Problem problem;
+  for (int i = 0; i < kNumObservations; ++i) {
+    problem.AddResidualBlock(
+        new AutoDiffCostFunction<ExponentialResidual, 1, 1, 1>(
+            new ExponentialResidual(data[2 * i], data[2 * i + 1])),
+        NULL,
+        &m, &c);
+  }
+
+  Solver::Options options;
+  options.max_num_iterations = 25;
+  options.linear_solver_type = ceres::DENSE_QR;
+  options.minimizer_progress_to_stdout = true;
+
+  Solver::Summary summary;
+  Solve(options, &problem, &summary);
+  std::cout << summary.BriefReport() << "\n";
+  std::cout << "Initial m: " << 0.0 << " c: " << 0.0 << "\n";
+  std::cout << "Final   m: " << m << " c: " << c << "\n";
+  return 0;
+}
diff --git a/examples/denoising.cc b/examples/denoising.cc
index 086be00..bfd8118 100644
--- a/examples/denoising.cc
+++ b/examples/denoising.cc
@@ -57,6 +57,8 @@
 DEFINE_string(output, "", "File to which the output image should be written");
 DEFINE_double(sigma, 20.0, "Standard deviation of noise");
 DEFINE_bool(verbose, false, "Prints information about the solver progress.");
+DEFINE_bool(line_search, false, "Use a line search instead of trust region "
+            "algorithm.");
 
 namespace ceres {
 namespace examples {
@@ -143,7 +145,11 @@
   if (FLAGS_verbose) {
     options.minimizer_progress_to_stdout = true;
   }
-  options.trust_region_strategy_type = ceres::LEVENBERG_MARQUARDT;
+
+  if (FLAGS_line_search) {
+    options.minimizer_type = ceres::LINE_SEARCH;
+  }
+
   options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
   options.function_tolerance = 1e-3;  // Enough for denoising.
 
diff --git a/examples/helloworld.cc b/examples/helloworld.cc
new file mode 100644
index 0000000..6341918
--- /dev/null
+++ b/examples/helloworld.cc
@@ -0,0 +1,83 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2010, 2011, 2012 Google Inc. All rights reserved.
+// http://code.google.com/p/ceres-solver/
+//
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+//
+// * Redistributions of source code must retain the above copyright notice,
+//   this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright notice,
+//   this list of conditions and the following disclaimer in the documentation
+//   and/or other materials provided with the distribution.
+// * Neither the name of Google Inc. nor the names of its contributors may be
+//   used to endorse or promote products derived from this software without
+//   specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+//
+// Author: keir@google.com (Keir Mierle)
+//
+// A simple example of using the Ceres minimizer.
+//
+// Minimize 0.5 (10 - x)^2 using jacobian matrix computed using
+// automatic differentiation.
+
+#include "ceres/ceres.h"
+#include "glog/logging.h"
+
+using ceres::AutoDiffCostFunction;
+using ceres::CostFunction;
+using ceres::Problem;
+using ceres::Solver;
+using ceres::Solve;
+
+// A templated cost functor that implements the residual r = 10 -
+// x. The method operator() is templated so that we can then use an
+// automatic differentiation wrapper around it to generate its
+// derivatives.
+struct CostFunctor {
+  template <typename T> bool operator()(const T* const x, T* residual) const {
+    residual[0] = T(10.0) - x[0];
+    return true;
+  }
+};
+
+int main(int argc, char** argv) {
+  google::InitGoogleLogging(argv[0]);
+
+  // The variable to solve for with its initial value. It will be
+  // mutated in place by the solver.
+  double x = 0.5;
+  const double initial_x = x;
+
+  // Build the problem.
+  Problem problem;
+
+  // Set up the only cost function (also known as residual). This uses
+  // auto-differentiation to obtain the derivative (jacobian).
+  CostFunction* cost_function =
+      new AutoDiffCostFunction<CostFunctor, 1, 1>(new CostFunctor);
+  problem.AddResidualBlock(cost_function, NULL, &x);
+
+  // Run the solver!
+  Solver::Options options;
+  options.minimizer_progress_to_stdout = true;
+  Solver::Summary summary;
+  Solve(options, &problem, &summary);
+
+  std::cout << summary.BriefReport() << "\n";
+  std::cout << "x : " << initial_x
+            << " -> " << x << "\n";
+  return 0;
+}
diff --git a/examples/helloworld_analytic_diff.cc b/examples/helloworld_analytic_diff.cc
new file mode 100644
index 0000000..bff4804
--- /dev/null
+++ b/examples/helloworld_analytic_diff.cc
@@ -0,0 +1,107 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2010, 2011, 2012 Google Inc. All rights reserved.
+// http://code.google.com/p/ceres-solver/
+//
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+//
+// * Redistributions of source code must retain the above copyright notice,
+//   this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright notice,
+//   this list of conditions and the following disclaimer in the documentation
+//   and/or other materials provided with the distribution.
+// * Neither the name of Google Inc. nor the names of its contributors may be
+//   used to endorse or promote products derived from this software without
+//   specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+//
+// Author: keir@google.com (Keir Mierle)
+//
+// A simple example of using the Ceres minimizer.
+//
+// Minimize 0.5 (10 - x)^2 using analytic jacobian matrix.
+
+#include <vector>
+#include "ceres/ceres.h"
+#include "glog/logging.h"
+
+using ceres::CostFunction;
+using ceres::SizedCostFunction;
+using ceres::Problem;
+using ceres::Solver;
+using ceres::Solve;
+
+// A CostFunction implementing analytically derivatives for the
+// function f(x) = 10 - x.
+class QuadraticCostFunction
+  : public SizedCostFunction<1 /* number of residuals */,
+                             1 /* size of first parameter */> {
+ public:
+  virtual ~QuadraticCostFunction() {}
+
+  virtual bool Evaluate(double const* const* parameters,
+                        double* residuals,
+                        double** jacobians) const {
+    double x = parameters[0][0];
+
+    // f(x) = 10 - x.
+    residuals[0] = 10 - x;
+
+    // f'(x) = -1. Since there's only 1 parameter and that parameter
+    // has 1 dimension, there is only 1 element to fill in the
+    // jacobians.
+    //
+    // Since the Evaluate function can be called with the jacobians
+    // pointer equal to NULL, the Evaluate function must check to see
+    // if jacobians need to be computed.
+    //
+    // For this simple problem it is overkill to check if jacobians[0]
+    // is NULL, but in general when writing more complex
+    // CostFunctions, it is possible that Ceres may only demand the
+    // derivatives w.r.t. a subset of the parameter blocks.
+    if (jacobians != NULL && jacobians[0] != NULL) {
+      jacobians[0][0] = -1;
+    }
+
+    return true;
+  }
+};
+
+int main(int argc, char** argv) {
+  google::InitGoogleLogging(argv[0]);
+
+  // The variable to solve for with its initial value. It will be
+  // mutated in place by the solver.
+  double x = 0.5;
+  const double initial_x = x;
+
+  // Build the problem.
+  Problem problem;
+
+  // Set up the only cost function (also known as residual).
+  CostFunction* cost_function = new QuadraticCostFunction;
+  problem.AddResidualBlock(cost_function, NULL, &x);
+
+  // Run the solver!
+  Solver::Options options;
+  options.minimizer_progress_to_stdout = true;
+  Solver::Summary summary;
+  Solve(options, &problem, &summary);
+
+  std::cout << summary.BriefReport() << "\n";
+  std::cout << "x : " << initial_x
+            << " -> " << x << "\n";
+
+  return 0;
+}
diff --git a/examples/helloworld_numeric_diff.cc b/examples/helloworld_numeric_diff.cc
new file mode 100644
index 0000000..026b155
--- /dev/null
+++ b/examples/helloworld_numeric_diff.cc
@@ -0,0 +1,79 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2010, 2011, 2012 Google Inc. All rights reserved.
+// http://code.google.com/p/ceres-solver/
+//
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+//
+// * Redistributions of source code must retain the above copyright notice,
+//   this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright notice,
+//   this list of conditions and the following disclaimer in the documentation
+//   and/or other materials provided with the distribution.
+// * Neither the name of Google Inc. nor the names of its contributors may be
+//   used to endorse or promote products derived from this software without
+//   specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+//
+// Author: keir@google.com (Keir Mierle)
+//
+// Minimize 0.5 (10 - x)^2 using jacobian matrix computed using
+// numeric differentiation.
+
+#include "ceres/ceres.h"
+#include "glog/logging.h"
+
+using ceres::NumericDiffCostFunction;
+using ceres::CENTRAL;
+using ceres::CostFunction;
+using ceres::Problem;
+using ceres::Solver;
+using ceres::Solve;
+
+// A cost functor that implements the residual r = 10 - x.
+struct CostFunctor {
+  bool operator()(const double* const x, double* residual) const {
+    residual[0] = 10.0 - x[0];
+    return true;
+  }
+};
+
+int main(int argc, char** argv) {
+  google::InitGoogleLogging(argv[0]);
+
+  // The variable to solve for with its initial value. It will be
+  // mutated in place by the solver.
+  double x = 0.5;
+  const double initial_x = x;
+
+  // Build the problem.
+  Problem problem;
+
+  // Set up the only cost function (also known as residual). This uses
+  // numeric differentiation to obtain the derivative (jacobian).
+  CostFunction* cost_function =
+      new NumericDiffCostFunction<CostFunctor, CENTRAL, 1, 1> (new CostFunctor);
+  problem.AddResidualBlock(cost_function, NULL, &x);
+
+  // Run the solver!
+  Solver::Options options;
+  options.minimizer_progress_to_stdout = true;
+  Solver::Summary summary;
+  Solve(options, &problem, &summary);
+
+  std::cout << summary.BriefReport() << "\n";
+  std::cout << "x : " << initial_x
+            << " -> " << x << "\n";
+  return 0;
+}
diff --git a/examples/libmv_bundle_adjuster.cc b/examples/libmv_bundle_adjuster.cc
new file mode 100644
index 0000000..4b01202
--- /dev/null
+++ b/examples/libmv_bundle_adjuster.cc
@@ -0,0 +1,842 @@
+// Copyright (c) 2013 libmv authors.
+//
+// Permission is hereby granted, free of charge, to any person obtaining a copy
+// of this software and associated documentation files (the "Software"), to
+// deal in the Software without restriction, including without limitation the
+// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+// sell copies of the Software, and to permit persons to whom the Software is
+// furnished to do so, subject to the following conditions:
+//
+// The above copyright notice and this permission notice shall be included in
+// all copies or substantial portions of the Software.
+//
+// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+// IN THE SOFTWARE.
+//
+// Author: mierle@gmail.com (Keir Mierle)
+//         sergey.vfx@gmail.com (Sergey Sharybin)
+//
+// This is an example application which contains bundle adjustment code used
+// in the Libmv library and Blender. It reads problems from files passed via
+// the command line and runs the bundle adjuster on the problem.
+//
+// File with problem a binary file, for which it is crucial to know in which
+// order bytes of float values are stored in. This information is provided
+// by a single character in the beginning of the file. There're two possible
+// values of this byte:
+//  - V, which means values in the file are stored with big endian type
+//  - v, which means values in the file are stored with little endian type
+//
+// The rest of the file contains data in the following order:
+//   - Space in which markers' coordinates are stored in
+//   - Camera intrinsics
+//   - Number of cameras
+//   - Cameras
+//   - Number of 3D points
+//   - 3D points
+//   - Number of markers
+//   - Markers
+//
+// Markers' space could either be normalized or image (pixels). This is defined
+// by the single character in the file. P means markers in the file is in image
+// space, and N means markers are in normalized space.
+//
+// Camera intrinsics are 8 described by 8 float 8.
+// This values goes in the following order:
+//
+//   - Focal length, principal point X, principal point Y, k1, k2, k3, p1, p2
+//
+// Every camera is described by:
+//
+//   - Image for which camera belongs to (single 4 bytes integer value).
+//   - Column-major camera rotation matrix, 9 float values.
+//   - Camera translation, 3-component vector of float values.
+//
+// Image number shall be greater or equal to zero. Order of cameras does not
+// matter and gaps are possible.
+//
+// Every 3D point is decribed by:
+//
+//  - Track number point belongs to (single 4 bytes integer value).
+//  - 3D position vector, 3-component vector of float values.
+//
+// Track number shall be greater or equal to zero. Order of tracks does not
+// matter and gaps are possible.
+//
+// Finally every marker is described by:
+//
+//  - Image marker belongs to single 4 bytes integer value).
+//  - Track marker belongs to single 4 bytes integer value).
+//  - 2D marker position vector, (two float values).
+//
+// Marker's space is used a default value for refine_intrinsics command line
+// flag. This means if there's no refine_intrinsics flag passed via command
+// line, camera intrinsics will be refined if markers in the problem are
+// stored in image space and camera intrinsics will not be refined if markers
+// are in normalized space.
+//
+// Passing refine_intrinsics command line flag defines explicitly whether
+// refinement of intrinsics will happen. Currently, only none and all
+// intrinsics refinement is supported.
+//
+// There're existing problem files dumped from blender stored in folder
+// ../data/libmv-ba-problems.
+
+#include <cstdio>
+#include <fcntl.h>
+#include <sstream>
+#include <string>
+#include <vector>
+
+#ifdef _MSC_VER
+#  include <io.h>
+#  define open _open
+#  define close _close
+typedef unsigned __int32 uint32_t;
+#else
+# include <stdint.h>
+
+// O_BINARY is not defined on unix like platforms, as there is no
+// difference between binary and text files.
+#define O_BINARY 0
+
+#endif
+
+#include "ceres/ceres.h"
+#include "ceres/rotation.h"
+#include "gflags/gflags.h"
+#include "glog/logging.h"
+
+typedef Eigen::Matrix<double, 3, 3> Mat3;
+typedef Eigen::Matrix<double, 6, 1> Vec6;
+typedef Eigen::Vector3d Vec3;
+typedef Eigen::Vector4d Vec4;
+
+using std::vector;
+
+DEFINE_string(input, "", "Input File name");
+DEFINE_string(refine_intrinsics, "", "Camera intrinsics to be refined. "
+              "Options are: none, radial.");
+
+namespace {
+
+// A EuclideanCamera is the location and rotation of the camera
+// viewing an image.
+//
+// image identifies which image this camera represents.
+// R is a 3x3 matrix representing the rotation of the camera.
+// t is a translation vector representing its positions.
+struct EuclideanCamera {
+  EuclideanCamera() : image(-1) {}
+  EuclideanCamera(const EuclideanCamera &c) : image(c.image), R(c.R), t(c.t) {}
+
+  int image;
+  Mat3 R;
+  Vec3 t;
+};
+
+// A Point is the 3D location of a track.
+//
+// track identifies which track this point corresponds to.
+// X represents the 3D position of the track.
+struct EuclideanPoint {
+  EuclideanPoint() : track(-1) {}
+  EuclideanPoint(const EuclideanPoint &p) : track(p.track), X(p.X) {}
+  int track;
+  Vec3 X;
+};
+
+// A Marker is the 2D location of a tracked point in an image.
+//
+// x and y is the position of the marker in pixels from the top left corner
+// in the image identified by an image. All markers for to the same target
+// form a track identified by a common track number.
+struct Marker {
+  int image;
+  int track;
+  double x, y;
+};
+
+// Cameras intrinsics to be bundled.
+//
+// BUNDLE_RADIAL actually implies bundling of k1 and k2 coefficients only,
+// no bundling of k3 is possible at this moment.
+enum BundleIntrinsics {
+  BUNDLE_NO_INTRINSICS = 0,
+  BUNDLE_FOCAL_LENGTH = 1,
+  BUNDLE_PRINCIPAL_POINT = 2,
+  BUNDLE_RADIAL_K1 = 4,
+  BUNDLE_RADIAL_K2 = 8,
+  BUNDLE_RADIAL = 12,
+  BUNDLE_TANGENTIAL_P1 = 16,
+  BUNDLE_TANGENTIAL_P2 = 32,
+  BUNDLE_TANGENTIAL = 48,
+};
+
+// Denotes which blocks to keep constant during bundling.
+// For example it is useful to keep camera translations constant
+// when bundling tripod motions.
+enum BundleConstraints {
+  BUNDLE_NO_CONSTRAINTS = 0,
+  BUNDLE_NO_TRANSLATION = 1,
+};
+
+// The intrinsics need to get combined into a single parameter block; use these
+// enums to index instead of numeric constants.
+enum {
+  OFFSET_FOCAL_LENGTH,
+  OFFSET_PRINCIPAL_POINT_X,
+  OFFSET_PRINCIPAL_POINT_Y,
+  OFFSET_K1,
+  OFFSET_K2,
+  OFFSET_K3,
+  OFFSET_P1,
+  OFFSET_P2,
+};
+
+// Returns a pointer to the camera corresponding to a image.
+EuclideanCamera *CameraForImage(vector<EuclideanCamera> *all_cameras,
+                                const int image) {
+  if (image < 0 || image >= all_cameras->size()) {
+    return NULL;
+  }
+  EuclideanCamera *camera = &(*all_cameras)[image];
+  if (camera->image == -1) {
+    return NULL;
+  }
+  return camera;
+}
+
+const EuclideanCamera *CameraForImage(
+    const vector<EuclideanCamera> &all_cameras,
+    const int image) {
+  if (image < 0 || image >= all_cameras.size()) {
+    return NULL;
+  }
+  const EuclideanCamera *camera = &all_cameras[image];
+  if (camera->image == -1) {
+    return NULL;
+  }
+  return camera;
+}
+
+// Returns maximal image number at which marker exists.
+int MaxImage(const vector<Marker> &all_markers) {
+  if (all_markers.size() == 0) {
+    return -1;
+  }
+
+  int max_image = all_markers[0].image;
+  for (int i = 1; i < all_markers.size(); i++) {
+    max_image = std::max(max_image, all_markers[i].image);
+  }
+  return max_image;
+}
+
+// Returns a pointer to the point corresponding to a track.
+EuclideanPoint *PointForTrack(vector<EuclideanPoint> *all_points,
+                              const int track) {
+  if (track < 0 || track >= all_points->size()) {
+    return NULL;
+  }
+  EuclideanPoint *point = &(*all_points)[track];
+  if (point->track == -1) {
+    return NULL;
+  }
+  return point;
+}
+
+// Reader of binary file which makes sure possibly needed endian
+// conversion happens when loading values like floats and integers.
+//
+// File's endian type is reading from a first character of file, which
+// could either be V for big endian or v for little endian.  This
+// means you need to design file format assuming first character
+// denotes file endianness in this way.
+class EndianAwareFileReader {
+ public:
+  EndianAwareFileReader(void) : file_descriptor_(-1) {
+    // Get an endian type of the host machine.
+    union {
+      unsigned char bytes[4];
+      uint32_t value;
+    } endian_test = { { 0, 1, 2, 3 } };
+    host_endian_type_ = endian_test.value;
+    file_endian_type_ = host_endian_type_;
+  }
+
+  ~EndianAwareFileReader(void) {
+    if (file_descriptor_ > 0) {
+      close(file_descriptor_);
+    }
+  }
+
+  bool OpenFile(const std::string &file_name) {
+    file_descriptor_ = open(file_name.c_str(), O_RDONLY | O_BINARY);
+    if (file_descriptor_ < 0) {
+      return false;
+    }
+    // Get an endian tpye of data in the file.
+    unsigned char file_endian_type_flag = Read<unsigned char>();
+    if (file_endian_type_flag == 'V') {
+      file_endian_type_ = kBigEndian;
+    } else if (file_endian_type_flag == 'v') {
+      file_endian_type_ = kLittleEndian;
+    } else {
+      LOG(FATAL) << "Problem file is stored in unknown endian type.";
+    }
+    return true;
+  }
+
+  // Read value from the file, will switch endian if needed.
+  template <typename T>
+  T Read(void) const {
+    T value;
+    CHECK_GT(read(file_descriptor_, &value, sizeof(value)), 0);
+    // Switch endian type if file contains data in different type
+    // that current machine.
+    if (file_endian_type_ != host_endian_type_) {
+      value = SwitchEndian<T>(value);
+    }
+    return value;
+  }
+ private:
+  static const long int kLittleEndian = 0x03020100ul;
+  static const long int kBigEndian = 0x00010203ul;
+
+  // Switch endian type between big to little.
+  template <typename T>
+  T SwitchEndian(const T value) const {
+    if (sizeof(T) == 4) {
+      unsigned int temp_value = static_cast<unsigned int>(value);
+      return ((temp_value >> 24)) |
+             ((temp_value << 8) & 0x00ff0000) |
+             ((temp_value >> 8) & 0x0000ff00) |
+             ((temp_value << 24));
+    } else if (sizeof(T) == 1) {
+      return value;
+    } else {
+      LOG(FATAL) << "Entered non-implemented part of endian switching function.";
+    }
+  }
+
+  int host_endian_type_;
+  int file_endian_type_;
+  int file_descriptor_;
+};
+
+// Read 3x3 column-major matrix from the file
+void ReadMatrix3x3(const EndianAwareFileReader &file_reader,
+                   Mat3 *matrix) {
+  for (int i = 0; i < 9; i++) {
+    (*matrix)(i % 3, i / 3) = file_reader.Read<float>();
+  }
+}
+
+// Read 3-vector from file
+void ReadVector3(const EndianAwareFileReader &file_reader,
+                 Vec3 *vector) {
+  for (int i = 0; i < 3; i++) {
+    (*vector)(i) = file_reader.Read<float>();
+  }
+}
+
+// Reads a bundle adjustment problem from the file.
+//
+// file_name denotes from which file to read the problem.
+// camera_intrinsics will contain initial camera intrinsics values.
+//
+// all_cameras is a vector of all reconstructed cameras to be optimized,
+// vector element with number i will contain camera for image i.
+//
+// all_points is a vector of all reconstructed 3D points to be optimized,
+// vector element with number i will contain point for track i.
+//
+// all_markers is a vector of all tracked markers existing in
+// the problem. Only used for reprojection error calculation, stay
+// unchanged during optimization.
+//
+// Returns false if any kind of error happened during
+// reading.
+bool ReadProblemFromFile(const std::string &file_name,
+                         double camera_intrinsics[8],
+                         vector<EuclideanCamera> *all_cameras,
+                         vector<EuclideanPoint> *all_points,
+                         bool *is_image_space,
+                         vector<Marker> *all_markers) {
+  EndianAwareFileReader file_reader;
+  if (!file_reader.OpenFile(file_name)) {
+    return false;
+  }
+
+  // Read markers' space flag.
+  unsigned char is_image_space_flag = file_reader.Read<unsigned char>();
+  if (is_image_space_flag == 'P') {
+    *is_image_space = true;
+  } else if (is_image_space_flag == 'N') {
+    *is_image_space = false;
+  } else {
+    LOG(FATAL) << "Problem file contains markers stored in unknown space.";
+  }
+
+  // Read camera intrinsics.
+  for (int i = 0; i < 8; i++) {
+    camera_intrinsics[i] = file_reader.Read<float>();
+  }
+
+  // Read all cameras.
+  int number_of_cameras = file_reader.Read<int>();
+  for (int i = 0; i < number_of_cameras; i++) {
+    EuclideanCamera camera;
+
+    camera.image = file_reader.Read<int>();
+    ReadMatrix3x3(file_reader, &camera.R);
+    ReadVector3(file_reader, &camera.t);
+
+    if (camera.image >= all_cameras->size()) {
+      all_cameras->resize(camera.image + 1);
+    }
+
+    (*all_cameras)[camera.image].image = camera.image;
+    (*all_cameras)[camera.image].R = camera.R;
+    (*all_cameras)[camera.image].t = camera.t;
+  }
+
+  LOG(INFO) << "Read " << number_of_cameras << " cameras.";
+
+  // Read all reconstructed 3D points.
+  int number_of_points = file_reader.Read<int>();
+  for (int i = 0; i < number_of_points; i++) {
+    EuclideanPoint point;
+
+    point.track = file_reader.Read<int>();
+    ReadVector3(file_reader, &point.X);
+
+    if (point.track >= all_points->size()) {
+      all_points->resize(point.track + 1);
+    }
+
+    (*all_points)[point.track].track = point.track;
+    (*all_points)[point.track].X = point.X;
+  }
+
+  LOG(INFO) << "Read " << number_of_points << " points.";
+
+  // And finally read all markers.
+  int number_of_markers = file_reader.Read<int>();
+  for (int i = 0; i < number_of_markers; i++) {
+    Marker marker;
+
+    marker.image = file_reader.Read<int>();
+    marker.track = file_reader.Read<int>();
+    marker.x = file_reader.Read<float>();
+    marker.y = file_reader.Read<float>();
+
+    all_markers->push_back(marker);
+  }
+
+  LOG(INFO) << "Read " << number_of_markers << " markers.";
+
+  return true;
+}
+
+// Apply camera intrinsics to the normalized point to get image coordinates.
+// This applies the radial lens distortion to a point which is in normalized
+// camera coordinates (i.e. the principal point is at (0, 0)) to get image
+// coordinates in pixels. Templated for use with autodifferentiation.
+template <typename T>
+inline void ApplyRadialDistortionCameraIntrinsics(const T &focal_length_x,
+                                                  const T &focal_length_y,
+                                                  const T &principal_point_x,
+                                                  const T &principal_point_y,
+                                                  const T &k1,
+                                                  const T &k2,
+                                                  const T &k3,
+                                                  const T &p1,
+                                                  const T &p2,
+                                                  const T &normalized_x,
+                                                  const T &normalized_y,
+                                                  T *image_x,
+                                                  T *image_y) {
+  T x = normalized_x;
+  T y = normalized_y;
+
+  // Apply distortion to the normalized points to get (xd, yd).
+  T r2 = x*x + y*y;
+  T r4 = r2 * r2;
+  T r6 = r4 * r2;
+  T r_coeff = (T(1) + k1*r2 + k2*r4 + k3*r6);
+  T xd = x * r_coeff + T(2)*p1*x*y + p2*(r2 + T(2)*x*x);
+  T yd = y * r_coeff + T(2)*p2*x*y + p1*(r2 + T(2)*y*y);
+
+  // Apply focal length and principal point to get the final image coordinates.
+  *image_x = focal_length_x * xd + principal_point_x;
+  *image_y = focal_length_y * yd + principal_point_y;
+}
+
+// Cost functor which computes reprojection error of 3D point X
+// on camera defined by angle-axis rotation and it's translation
+// (which are in the same block due to optimization reasons).
+//
+// This functor uses a radial distortion model.
+struct OpenCVReprojectionError {
+  OpenCVReprojectionError(const double observed_x, const double observed_y)
+      : observed_x(observed_x), observed_y(observed_y) {}
+
+  template <typename T>
+  bool operator()(const T* const intrinsics,
+                  const T* const R_t,  // Rotation denoted by angle axis
+                                       // followed with translation
+                  const T* const X,    // Point coordinates 3x1.
+                  T* residuals) const {
+    // Unpack the intrinsics.
+    const T& focal_length      = intrinsics[OFFSET_FOCAL_LENGTH];
+    const T& principal_point_x = intrinsics[OFFSET_PRINCIPAL_POINT_X];
+    const T& principal_point_y = intrinsics[OFFSET_PRINCIPAL_POINT_Y];
+    const T& k1                = intrinsics[OFFSET_K1];
+    const T& k2                = intrinsics[OFFSET_K2];
+    const T& k3                = intrinsics[OFFSET_K3];
+    const T& p1                = intrinsics[OFFSET_P1];
+    const T& p2                = intrinsics[OFFSET_P2];
+
+    // Compute projective coordinates: x = RX + t.
+    T x[3];
+
+    ceres::AngleAxisRotatePoint(R_t, X, x);
+    x[0] += R_t[3];
+    x[1] += R_t[4];
+    x[2] += R_t[5];
+
+    // Compute normalized coordinates: x /= x[2].
+    T xn = x[0] / x[2];
+    T yn = x[1] / x[2];
+
+    T predicted_x, predicted_y;
+
+    // Apply distortion to the normalized points to get (xd, yd).
+    // TODO(keir): Do early bailouts for zero distortion; these are expensive
+    // jet operations.
+    ApplyRadialDistortionCameraIntrinsics(focal_length,
+                                          focal_length,
+                                          principal_point_x,
+                                          principal_point_y,
+                                          k1, k2, k3,
+                                          p1, p2,
+                                          xn, yn,
+                                          &predicted_x,
+                                          &predicted_y);
+
+    // The error is the difference between the predicted and observed position.
+    residuals[0] = predicted_x - T(observed_x);
+    residuals[1] = predicted_y - T(observed_y);
+
+    return true;
+  }
+
+  const double observed_x;
+  const double observed_y;
+};
+
+// Print a message to the log which camera intrinsics are gonna to be optimized.
+void BundleIntrinsicsLogMessage(const int bundle_intrinsics) {
+  if (bundle_intrinsics == BUNDLE_NO_INTRINSICS) {
+    LOG(INFO) << "Bundling only camera positions.";
+  } else {
+    std::string bundling_message = "";
+
+#define APPEND_BUNDLING_INTRINSICS(name, flag) \
+    if (bundle_intrinsics & flag) { \
+      if (!bundling_message.empty()) { \
+        bundling_message += ", "; \
+      } \
+      bundling_message += name; \
+    } (void)0
+
+    APPEND_BUNDLING_INTRINSICS("f",      BUNDLE_FOCAL_LENGTH);
+    APPEND_BUNDLING_INTRINSICS("px, py", BUNDLE_PRINCIPAL_POINT);
+    APPEND_BUNDLING_INTRINSICS("k1",     BUNDLE_RADIAL_K1);
+    APPEND_BUNDLING_INTRINSICS("k2",     BUNDLE_RADIAL_K2);
+    APPEND_BUNDLING_INTRINSICS("p1",     BUNDLE_TANGENTIAL_P1);
+    APPEND_BUNDLING_INTRINSICS("p2",     BUNDLE_TANGENTIAL_P2);
+
+    LOG(INFO) << "Bundling " << bundling_message << ".";
+  }
+}
+
+// Print a message to the log containing all the camera intriniscs values.
+void PrintCameraIntrinsics(const char *text, const double *camera_intrinsics) {
+  std::ostringstream intrinsics_output;
+
+  intrinsics_output << "f=" << camera_intrinsics[OFFSET_FOCAL_LENGTH];
+
+  intrinsics_output <<
+    " cx=" << camera_intrinsics[OFFSET_PRINCIPAL_POINT_X] <<
+    " cy=" << camera_intrinsics[OFFSET_PRINCIPAL_POINT_Y];
+
+#define APPEND_DISTORTION_COEFFICIENT(name, offset) \
+  { \
+    if (camera_intrinsics[offset] != 0.0) { \
+      intrinsics_output << " " name "=" << camera_intrinsics[offset];  \
+    } \
+  } (void)0
+
+  APPEND_DISTORTION_COEFFICIENT("k1", OFFSET_K1);
+  APPEND_DISTORTION_COEFFICIENT("k2", OFFSET_K2);
+  APPEND_DISTORTION_COEFFICIENT("k3", OFFSET_K3);
+  APPEND_DISTORTION_COEFFICIENT("p1", OFFSET_P1);
+  APPEND_DISTORTION_COEFFICIENT("p2", OFFSET_P2);
+
+#undef APPEND_DISTORTION_COEFFICIENT
+
+  LOG(INFO) << text << intrinsics_output.str();
+}
+
+// Get a vector of camera's rotations denoted by angle axis
+// conjuncted with translations into single block
+//
+// Element with index i matches to a rotation+translation for
+// camera at image i.
+vector<Vec6> PackCamerasRotationAndTranslation(
+    const vector<Marker> &all_markers,
+    const vector<EuclideanCamera> &all_cameras) {
+  vector<Vec6> all_cameras_R_t;
+  int max_image = MaxImage(all_markers);
+
+  all_cameras_R_t.resize(max_image + 1);
+
+  for (int i = 0; i <= max_image; i++) {
+    const EuclideanCamera *camera = CameraForImage(all_cameras, i);
+
+    if (!camera) {
+      continue;
+    }
+
+    ceres::RotationMatrixToAngleAxis(&camera->R(0, 0),
+                                     &all_cameras_R_t[i](0));
+    all_cameras_R_t[i].tail<3>() = camera->t;
+  }
+
+  return all_cameras_R_t;
+}
+
+// Convert cameras rotations fro mangle axis back to rotation matrix.
+void UnpackCamerasRotationAndTranslation(
+    const vector<Marker> &all_markers,
+    const vector<Vec6> &all_cameras_R_t,
+    vector<EuclideanCamera> *all_cameras) {
+  int max_image = MaxImage(all_markers);
+
+  for (int i = 0; i <= max_image; i++) {
+    EuclideanCamera *camera = CameraForImage(all_cameras, i);
+
+    if (!camera) {
+      continue;
+    }
+
+    ceres::AngleAxisToRotationMatrix(&all_cameras_R_t[i](0),
+                                     &camera->R(0, 0));
+    camera->t = all_cameras_R_t[i].tail<3>();
+  }
+}
+
+void EuclideanBundleCommonIntrinsics(const vector<Marker> &all_markers,
+                                     const int bundle_intrinsics,
+                                     const int bundle_constraints,
+                                     double *camera_intrinsics,
+                                     vector<EuclideanCamera> *all_cameras,
+                                     vector<EuclideanPoint> *all_points) {
+  PrintCameraIntrinsics("Original intrinsics: ", camera_intrinsics);
+
+  ceres::Problem::Options problem_options;
+  ceres::Problem problem(problem_options);
+
+  // Convert cameras rotations to angle axis and merge with translation
+  // into single parameter block for maximal minimization speed
+  //
+  // Block for minimization has got the following structure:
+  //   <3 elements for angle-axis> <3 elements for translation>
+  vector<Vec6> all_cameras_R_t =
+    PackCamerasRotationAndTranslation(all_markers, *all_cameras);
+
+  // Parameterization used to restrict camera motion for modal solvers.
+  ceres::SubsetParameterization *constant_transform_parameterization = NULL;
+  if (bundle_constraints & BUNDLE_NO_TRANSLATION) {
+      std::vector<int> constant_translation;
+
+      // First three elements are rotation, last three are translation.
+      constant_translation.push_back(3);
+      constant_translation.push_back(4);
+      constant_translation.push_back(5);
+
+      constant_transform_parameterization =
+        new ceres::SubsetParameterization(6, constant_translation);
+  }
+
+  int num_residuals = 0;
+  bool have_locked_camera = false;
+  for (int i = 0; i < all_markers.size(); ++i) {
+    const Marker &marker = all_markers[i];
+    EuclideanCamera *camera = CameraForImage(all_cameras, marker.image);
+    EuclideanPoint *point = PointForTrack(all_points, marker.track);
+    if (camera == NULL || point == NULL) {
+      continue;
+    }
+
+    // Rotation of camera denoted in angle axis followed with
+    // camera translaiton.
+    double *current_camera_R_t = &all_cameras_R_t[camera->image](0);
+
+    problem.AddResidualBlock(new ceres::AutoDiffCostFunction<
+        OpenCVReprojectionError, 2, 8, 6, 3>(
+            new OpenCVReprojectionError(
+                marker.x,
+                marker.y)),
+        NULL,
+        camera_intrinsics,
+        current_camera_R_t,
+        &point->X(0));
+
+    // We lock the first camera to better deal with scene orientation ambiguity.
+    if (!have_locked_camera) {
+      problem.SetParameterBlockConstant(current_camera_R_t);
+      have_locked_camera = true;
+    }
+
+    if (bundle_constraints & BUNDLE_NO_TRANSLATION) {
+      problem.SetParameterization(current_camera_R_t,
+                                  constant_transform_parameterization);
+    }
+
+    num_residuals++;
+  }
+  LOG(INFO) << "Number of residuals: " << num_residuals;
+
+  if (!num_residuals) {
+    LOG(INFO) << "Skipping running minimizer with zero residuals";
+    return;
+  }
+
+  BundleIntrinsicsLogMessage(bundle_intrinsics);
+
+  if (bundle_intrinsics == BUNDLE_NO_INTRINSICS) {
+    // No camera intrinsics are being refined,
+    // set the whole parameter block as constant for best performance.
+    problem.SetParameterBlockConstant(camera_intrinsics);
+  } else {
+    // Set the camera intrinsics that are not to be bundled as
+    // constant using some macro trickery.
+
+    std::vector<int> constant_intrinsics;
+#define MAYBE_SET_CONSTANT(bundle_enum, offset) \
+    if (!(bundle_intrinsics & bundle_enum)) { \
+      constant_intrinsics.push_back(offset); \
+    }
+    MAYBE_SET_CONSTANT(BUNDLE_FOCAL_LENGTH,    OFFSET_FOCAL_LENGTH);
+    MAYBE_SET_CONSTANT(BUNDLE_PRINCIPAL_POINT, OFFSET_PRINCIPAL_POINT_X);
+    MAYBE_SET_CONSTANT(BUNDLE_PRINCIPAL_POINT, OFFSET_PRINCIPAL_POINT_Y);
+    MAYBE_SET_CONSTANT(BUNDLE_RADIAL_K1,       OFFSET_K1);
+    MAYBE_SET_CONSTANT(BUNDLE_RADIAL_K2,       OFFSET_K2);
+    MAYBE_SET_CONSTANT(BUNDLE_TANGENTIAL_P1,   OFFSET_P1);
+    MAYBE_SET_CONSTANT(BUNDLE_TANGENTIAL_P2,   OFFSET_P2);
+#undef MAYBE_SET_CONSTANT
+
+    // Always set K3 constant, it's not used at the moment.
+    constant_intrinsics.push_back(OFFSET_K3);
+
+    ceres::SubsetParameterization *subset_parameterization =
+      new ceres::SubsetParameterization(8, constant_intrinsics);
+
+    problem.SetParameterization(camera_intrinsics, subset_parameterization);
+  }
+
+  // Configure the solver.
+  ceres::Solver::Options options;
+  options.use_nonmonotonic_steps = true;
+  options.preconditioner_type = ceres::SCHUR_JACOBI;
+  options.linear_solver_type = ceres::ITERATIVE_SCHUR;
+  options.use_inner_iterations = true;
+  options.max_num_iterations = 100;
+  options.minimizer_progress_to_stdout = true;
+
+  // Solve!
+  ceres::Solver::Summary summary;
+  ceres::Solve(options, &problem, &summary);
+
+  std::cout << "Final report:\n" << summary.FullReport();
+
+  // Copy rotations and translations back.
+  UnpackCamerasRotationAndTranslation(all_markers,
+                                      all_cameras_R_t,
+                                      all_cameras);
+
+  PrintCameraIntrinsics("Final intrinsics: ", camera_intrinsics);
+}
+}  // namespace
+
+int main(int argc, char **argv) {
+  google::ParseCommandLineFlags(&argc, &argv, true);
+  google::InitGoogleLogging(argv[0]);
+
+  if (FLAGS_input.empty()) {
+    LOG(ERROR) << "Usage: libmv_bundle_adjuster --input=blender_problem";
+    return EXIT_FAILURE;
+  }
+
+  double camera_intrinsics[8];
+  vector<EuclideanCamera> all_cameras;
+  vector<EuclideanPoint> all_points;
+  bool is_image_space;
+  vector<Marker> all_markers;
+
+  if (!ReadProblemFromFile(FLAGS_input,
+                           camera_intrinsics,
+                           &all_cameras,
+                           &all_points,
+                           &is_image_space,
+                           &all_markers)) {
+    LOG(ERROR) << "Error reading problem file";
+    return EXIT_FAILURE;
+  }
+
+  // If there's no refine_intrinsics passed via command line
+  // (in this case FLAGS_refine_intrinsics will be an empty string)
+  // we use problem's settings to detect whether intrinsics
+  // shall be refined or not.
+  //
+  // Namely, if problem has got markers stored in image (pixel)
+  // space, we do full intrinsics refinement. If markers are
+  // stored in normalized space, and refine_intrinsics is not
+  // set, no refining will happen.
+  //
+  // Using command line argument refine_intrinsics will explicitly
+  // declare which intrinsics need to be refined and in this case
+  // refining flags does not depend on problem at all.
+  int bundle_intrinsics = BUNDLE_NO_INTRINSICS;
+  if (FLAGS_refine_intrinsics.empty()) {
+    if (is_image_space) {
+      bundle_intrinsics = BUNDLE_FOCAL_LENGTH | BUNDLE_RADIAL;
+    }
+  } else {
+    if (FLAGS_refine_intrinsics == "radial") {
+      bundle_intrinsics = BUNDLE_FOCAL_LENGTH | BUNDLE_RADIAL;
+    } else if (FLAGS_refine_intrinsics != "none") {
+      LOG(ERROR) << "Unsupported value for refine-intrinsics";
+      return EXIT_FAILURE;
+    }
+  }
+
+  // Run the bundler.
+  EuclideanBundleCommonIntrinsics(all_markers,
+                                  bundle_intrinsics,
+                                  BUNDLE_NO_CONSTRAINTS,
+                                  camera_intrinsics,
+                                  &all_cameras,
+                                  &all_points);
+
+  return EXIT_SUCCESS;
+}
diff --git a/examples/nist.cc b/examples/nist.cc
index 440ab5c..1773a0f 100644
--- a/examples/nist.cc
+++ b/examples/nist.cc
@@ -28,29 +28,61 @@
 //
 // Author: sameeragarwal@google.com (Sameer Agarwal)
 //
-// NIST non-linear regression problems solved using Ceres.
+// The National Institute of Standards and Technology has released a
+// set of problems to test non-linear least squares solvers.
 //
-// The data was obtained from
-// http://www.itl.nist.gov/div898/strd/nls/nls_main.shtml, where more
-// background on these problems can also be found.
+// More information about the background on these problems and
+// suggested evaluation methodology can be found at:
 //
-// Currently not all problems are solved successfully. Some of the
-// failures are due to convergence to a local minimum, and some fail
-// because of numerical issues.
+//   http://www.itl.nist.gov/div898/strd/nls/nls_info.shtml
 //
-// TODO(sameeragarwal): Fix numerical issues so that all the problems
-// converge and then look at convergence to the wrong solution issues.
+// The problem data themselves can be found at
+//
+//   http://www.itl.nist.gov/div898/strd/nls/nls_main.shtml
+//
+// The problems are divided into three levels of difficulty, Easy,
+// Medium and Hard. For each problem there are two starting guesses,
+// the first one far away from the global minimum and the second
+// closer to it.
+//
+// A problem is considered successfully solved, if every components of
+// the solution matches the globally optimal solution in at least 4
+// digits or more.
+//
+// This dataset was used for an evaluation of Non-linear least squares
+// solvers:
+//
+// P. F. Mondragon & B. Borchers, A Comparison of Nonlinear Regression
+// Codes, Journal of Modern Applied Statistical Methods, 4(1):343-351,
+// 2005.
+//
+// The results from Mondragon & Borchers can be summarized as
+//               Excel  Gnuplot  GaussFit  HBN  MinPack
+// Average LRE     2.3      4.3       4.0  6.8      4.4
+//      Winner       1        5        12   29       12
+//
+// Where the row Winner counts, the number of problems for which the
+// solver had the highest LRE.
+
+// In this file, we implement the same evaluation methodology using
+// Ceres. Currently using Levenberg-Marquard with DENSE_QR, we get
+//
+//               Excel  Gnuplot  GaussFit  HBN  MinPack  Ceres
+// Average LRE     2.3      4.3       4.0  6.8      4.4    9.4
+//      Winner       0        0         5   11        2     41
 
 #include <iostream>
+#include <iterator>
 #include <fstream>
 #include "ceres/ceres.h"
-#include "ceres/split.h"
 #include "gflags/gflags.h"
 #include "glog/logging.h"
 #include "Eigen/Core"
 
 DEFINE_string(nist_data_dir, "", "Directory containing the NIST non-linear"
               "regression examples");
+DEFINE_string(minimizer, "trust_region",
+              "Minimizer type to use, choices are: line_search & trust_region");
 DEFINE_string(trust_region_strategy, "levenberg_marquardt",
               "Options are: levenberg_marquardt, dogleg");
 DEFINE_string(dogleg, "traditional_dogleg",
@@ -60,21 +92,63 @@
               "cgnr");
 DEFINE_string(preconditioner, "jacobi", "Options are: "
               "identity, jacobi");
+DEFINE_string(line_search, "armijo",
+              "Line search algorithm to use, choices are: armijo and wolfe.");
+DEFINE_string(line_search_direction, "lbfgs",
+              "Line search direction algorithm to use, choices: lbfgs, bfgs");
+DEFINE_int32(max_line_search_iterations, 20,
+             "Maximum number of iterations for each line search.");
+DEFINE_int32(max_line_search_restarts, 10,
+             "Maximum number of restarts of line search direction algorithm.");
+DEFINE_string(line_search_interpolation, "cubic",
+              "Degree of polynomial aproximation in line search, "
+              "choices are: bisection, quadratic & cubic.");
+DEFINE_int32(lbfgs_rank, 20,
+             "Rank of L-BFGS inverse Hessian approximation in line search.");
+DEFINE_bool(approximate_eigenvalue_bfgs_scaling, false,
+            "Use approximate eigenvalue scaling in (L)BFGS line search.");
+DEFINE_double(sufficient_decrease, 1.0e-4,
+              "Line search Armijo sufficient (function) decrease factor.");
+DEFINE_double(sufficient_curvature_decrease, 0.9,
+              "Line search Wolfe sufficient curvature decrease factor.");
 DEFINE_int32(num_iterations, 10000, "Number of iterations");
 DEFINE_bool(nonmonotonic_steps, false, "Trust region algorithm can use"
             " nonmonotic steps");
 DEFINE_double(initial_trust_region_radius, 1e4, "Initial trust region radius");
 
+namespace ceres {
+namespace examples {
+
 using Eigen::Dynamic;
 using Eigen::RowMajor;
 typedef Eigen::Matrix<double, Dynamic, 1> Vector;
 typedef Eigen::Matrix<double, Dynamic, Dynamic, RowMajor> Matrix;
 
+void SplitStringUsingChar(const string& full,
+                          const char delim,
+                          vector<string>* result) {
+  back_insert_iterator< vector<string> > it(*result);
+
+  const char* p = full.data();
+  const char* end = p + full.size();
+  while (p != end) {
+    if (*p == delim) {
+      ++p;
+    } else {
+      const char* start = p;
+      while (++p != end && *p != delim) {
+        // Skip to the next occurence of the delimiter.
+      }
+      *it++ = string(start, p - start);
+    }
+  }
+}
+
 bool GetAndSplitLine(std::ifstream& ifs, std::vector<std::string>* pieces) {
   pieces->clear();
   char buf[256];
   ifs.getline(buf, 256);
-  ceres::SplitStringUsing(std::string(buf), " ", pieces);
+  SplitStringUsingChar(std::string(buf), ' ', pieces);
   return true;
 }
 
@@ -339,7 +413,7 @@
 
 template <typename Model, int num_residuals, int num_parameters>
 int RegressionDriver(const std::string& filename,
-                      const ceres::Solver::Options& options) {
+                     const ceres::Solver::Options& options) {
   NISTProblem nist_problem(FLAGS_nist_data_dir + filename);
   CHECK_EQ(num_residuals, nist_problem.response_size());
   CHECK_EQ(num_parameters, nist_problem.num_parameters());
@@ -347,11 +421,12 @@
   Matrix predictor = nist_problem.predictor();
   Matrix response = nist_problem.response();
   Matrix final_parameters = nist_problem.final_parameters();
-  std::vector<ceres::Solver::Summary> summaries(nist_problem.num_starts() + 1);
-  std::cerr << filename << std::endl;
+
+  printf("%s\n", filename.c_str());
 
   // Each NIST problem comes with multiple starting points, so we
   // construct the problem from scratch for each case and solve it.
+  int num_success = 0;
   for (int start = 0; start < nist_problem.num_starts(); ++start) {
     Matrix initial_parameters = nist_problem.initial_parameters(start);
 
@@ -365,43 +440,49 @@
           initial_parameters.data());
     }
 
-    Solve(options, &problem, &summaries[start]);
-  }
+    ceres::Solver::Summary summary;
+    Solve(options, &problem, &summary);
 
-  const double certified_cost = nist_problem.certified_cost();
-
-  int num_success = 0;
-  const int kMinNumMatchingDigits = 4;
-  for (int start = 0; start < nist_problem.num_starts(); ++start) {
-    const ceres::Solver::Summary& summary = summaries[start];
-
-    int num_matching_digits = 0;
-    if (IsSuccessfulTermination(summary.termination_type)
-        && summary.final_cost < certified_cost) {
-      num_matching_digits = kMinNumMatchingDigits + 1;
-    } else {
-      num_matching_digits =
-          -std::log10(fabs(summary.final_cost - certified_cost) / certified_cost);
+    // Compute the LRE by comparing each component of the solution
+    // with the ground truth, and taking the minimum.
+    Matrix final_parameters = nist_problem.final_parameters();
+    const double kMaxNumSignificantDigits = 11;
+    double log_relative_error = kMaxNumSignificantDigits + 1;
+    for (int i = 0; i < num_parameters; ++i) {
+      const double tmp_lre =
+          -std::log10(std::fabs(final_parameters(i) - initial_parameters(i)) /
+                      std::fabs(final_parameters(i)));
+      // The maximum LRE is capped at 11 - the precision at which the
+      // ground truth is known.
+      //
+      // The minimum LRE is capped at 0 - no digits match between the
+      // computed solution and the ground truth.
+      log_relative_error =
+          std::min(log_relative_error,
+                   std::max(0.0, std::min(kMaxNumSignificantDigits, tmp_lre)));
     }
 
-    std::cerr << "start " << start + 1 << " " ;
-    if (num_matching_digits <= kMinNumMatchingDigits) {
-      std::cerr <<  "FAILURE";
-    } else {
-      std::cerr <<  "SUCCESS";
+    const int kMinNumMatchingDigits = 4;
+    if (log_relative_error >= kMinNumMatchingDigits) {
       ++num_success;
     }
-    std::cerr << " summary: "
-              << summary.BriefReport()
-              << " Certified cost: " << certified_cost
-              << std::endl;
 
+    printf("start: %d status: %s lre: %4.1f initial cost: %e final cost:%e "
+           "certified cost: %e total iterations: %d\n",
+           start + 1,
+           log_relative_error < kMinNumMatchingDigits ? "FAILURE" : "SUCCESS",
+           log_relative_error,
+           summary.initial_cost,
+           summary.final_cost,
+           nist_problem.certified_cost(),
+           (summary.num_successful_steps + summary.num_unsuccessful_steps));
   }
-
   return num_success;
 }
 
 void SetMinimizerOptions(ceres::Solver::Options* options) {
+  CHECK(ceres::StringToMinimizerType(FLAGS_minimizer,
+                                     &options->minimizer_type));
   CHECK(ceres::StringToLinearSolverType(FLAGS_linear_solver,
                                         &options->linear_solver_type));
   CHECK(ceres::StringToPreconditionerType(FLAGS_preconditioner,
@@ -410,10 +491,28 @@
             FLAGS_trust_region_strategy,
             &options->trust_region_strategy_type));
   CHECK(ceres::StringToDoglegType(FLAGS_dogleg, &options->dogleg_type));
+  CHECK(ceres::StringToLineSearchDirectionType(
+      FLAGS_line_search_direction,
+      &options->line_search_direction_type));
+  CHECK(ceres::StringToLineSearchType(FLAGS_line_search,
+                                      &options->line_search_type));
+  CHECK(ceres::StringToLineSearchInterpolationType(
+      FLAGS_line_search_interpolation,
+      &options->line_search_interpolation_type));
 
   options->max_num_iterations = FLAGS_num_iterations;
   options->use_nonmonotonic_steps = FLAGS_nonmonotonic_steps;
   options->initial_trust_region_radius = FLAGS_initial_trust_region_radius;
+  options->max_lbfgs_rank = FLAGS_lbfgs_rank;
+  options->line_search_sufficient_function_decrease = FLAGS_sufficient_decrease;
+  options->line_search_sufficient_curvature_decrease =
+      FLAGS_sufficient_curvature_decrease;
+  options->max_num_line_search_step_size_iterations =
+      FLAGS_max_line_search_iterations;
+  options->max_num_line_search_direction_restarts =
+      FLAGS_max_line_search_restarts;
+  options->use_approximate_eigenvalue_bfgs_scaling =
+      FLAGS_approximate_eigenvalue_bfgs_scaling;
   options->function_tolerance = 1e-18;
   options->gradient_tolerance = 1e-18;
   options->parameter_tolerance = 1e-18;
@@ -427,7 +526,7 @@
   ceres::Solver::Options options;
   SetMinimizerOptions(&options);
 
-  std::cerr << "Lower Difficulty\n";
+  std::cout << "Lower Difficulty\n";
   int easy_success = 0;
   easy_success += RegressionDriver<Misra1a,  1, 2>("Misra1a.dat",  options);
   easy_success += RegressionDriver<Chwirut,  1, 3>("Chwirut1.dat", options);
@@ -438,7 +537,7 @@
   easy_success += RegressionDriver<DanWood,  1, 2>("DanWood.dat",  options);
   easy_success += RegressionDriver<Misra1b,  1, 2>("Misra1b.dat",  options);
 
-  std::cerr << "\nMedium Difficulty\n";
+  std::cout << "\nMedium Difficulty\n";
   int medium_success = 0;
   medium_success += RegressionDriver<Kirby2,   1, 5>("Kirby2.dat",   options);
   medium_success += RegressionDriver<Hahn1,    1, 7>("Hahn1.dat",    options);
@@ -452,7 +551,7 @@
   medium_success += RegressionDriver<Roszman1, 1, 4>("Roszman1.dat", options);
   medium_success += RegressionDriver<ENSO,     1, 9>("ENSO.dat",     options);
 
-  std::cerr << "\nHigher Difficulty\n";
+  std::cout << "\nHigher Difficulty\n";
   int hard_success = 0;
   hard_success += RegressionDriver<MGH09,    1, 4>("MGH09.dat",    options);
   hard_success += RegressionDriver<Thurber,  1, 7>("Thurber.dat",  options);
@@ -464,16 +563,19 @@
   hard_success += RegressionDriver<Rat43,    1, 4>("Rat43.dat",    options);
   hard_success += RegressionDriver<Bennet5,  1, 3>("Bennett5.dat", options);
 
-  std::cerr << "\n";
-  std::cerr << "Easy    : " << easy_success << "/16\n";
-  std::cerr << "Medium  : " << medium_success << "/22\n";
-  std::cerr << "Hard    : " << hard_success << "/16\n";
-  std::cerr << "Total   : " << easy_success + medium_success + hard_success << "/54\n";
+  std::cout << "\n";
+  std::cout << "Easy    : " << easy_success << "/16\n";
+  std::cout << "Medium  : " << medium_success << "/22\n";
+  std::cout << "Hard    : " << hard_success << "/16\n";
+  std::cout << "Total   : " << easy_success + medium_success + hard_success << "/54\n";
 }
 
+}  // namespace examples
+}  // namespace ceres
+
 int main(int argc, char** argv) {
   google::ParseCommandLineFlags(&argc, &argv, true);
   google::InitGoogleLogging(argv[0]);
-  SolveNISTProblems();
+  ceres::examples::SolveNISTProblems();
   return 0;
 };
diff --git a/examples/powell.cc b/examples/powell.cc
index 6cd3611..c0cba02 100644
--- a/examples/powell.cc
+++ b/examples/powell.cc
@@ -55,8 +55,7 @@
 using ceres::Solver;
 using ceres::Solve;
 
-class F1 {
- public:
+struct F1 {
   template <typename T> bool operator()(const T* const x1,
                                         const T* const x2,
                                         T* residual) const {
@@ -66,8 +65,7 @@
   }
 };
 
-class F2 {
- public:
+struct F2 {
   template <typename T> bool operator()(const T* const x3,
                                         const T* const x4,
                                         T* residual) const {
@@ -77,8 +75,7 @@
   }
 };
 
-class F3 {
- public:
+struct F3 {
   template <typename T> bool operator()(const T* const x2,
                                         const T* const x4,
                                         T* residual) const {
@@ -88,8 +85,7 @@
   }
 };
 
-class F4 {
- public:
+struct F4 {
   template <typename T> bool operator()(const T* const x1,
                                         const T* const x4,
                                         T* residual) const {
@@ -99,6 +95,9 @@
   }
 };
 
+DEFINE_string(minimizer, "trust_region",
+              "Minimizer type to use, choices are: line_search & trust_region");
+
 int main(int argc, char** argv) {
   google::ParseCommandLineFlags(&argc, &argv, true);
   google::InitGoogleLogging(argv[0]);
@@ -125,23 +124,27 @@
                            NULL,
                            &x1, &x4);
 
-  // Run the solver!
   Solver::Options options;
-  options.max_num_iterations = 30;
+  LOG_IF(FATAL, !ceres::StringToMinimizerType(FLAGS_minimizer,
+                                              &options.minimizer_type))
+      << "Invalid minimizer: " << FLAGS_minimizer
+      << ", valid options are: trust_region and line_search.";
+
+  options.max_num_iterations = 100;
   options.linear_solver_type = ceres::DENSE_QR;
   options.minimizer_progress_to_stdout = true;
 
-  Solver::Summary summary;
-
   std::cout << "Initial x1 = " << x1
             << ", x2 = " << x2
             << ", x3 = " << x3
             << ", x4 = " << x4
             << "\n";
 
+  // Run the solver!
+  Solver::Summary summary;
   Solve(options, &problem, &summary);
 
-  std::cout << summary.BriefReport() << "\n";
+  std::cout << summary.FullReport() << "\n";
   std::cout << "Final x1 = " << x1
             << ", x2 = " << x2
             << ", x3 = " << x3
diff --git a/examples/quadratic_auto_diff.cc b/examples/quadratic_auto_diff.cc
index ea7fae9..1e2f3ef 100644
--- a/examples/quadratic_auto_diff.cc
+++ b/examples/quadratic_auto_diff.cc
@@ -44,10 +44,11 @@
 using ceres::Solver;
 using ceres::Solve;
 
-// A templated cost function that implements the residual r = 10 - x. The method
-// Map is templated so that we can then use an automatic differentiation wrapper
-// around it to generate its derivatives.
-class QuadraticCostFunction {
+// A templated cost functor that implements the residual r = 10 -
+// x. The method operator() is templated so that we can then use an
+// automatic differentiation wrapper around it to generate its
+// derivatives.
+class QuadraticCostFunctor {
  public:
   template <typename T> bool operator()(const T* const x, T* residual) const {
     residual[0] = T(10.0) - x[0];
@@ -69,8 +70,8 @@
   // Set up the only cost function (also known as residual). This uses
   // auto-differentiation to obtain the derivative (jacobian).
   problem.AddResidualBlock(
-      new AutoDiffCostFunction<QuadraticCostFunction, 1, 1>(
-          new QuadraticCostFunction),
+      new AutoDiffCostFunction<QuadraticCostFunctor, 1, 1>(
+          new QuadraticCostFunctor),
       NULL,
       &x);
 
diff --git a/examples/quadratic_numeric_diff.cc b/examples/quadratic_numeric_diff.cc
index 8ec88ef..1082616 100644
--- a/examples/quadratic_numeric_diff.cc
+++ b/examples/quadratic_numeric_diff.cc
@@ -38,24 +38,16 @@
 
 using ceres::NumericDiffCostFunction;
 using ceres::CENTRAL;
-using ceres::SizedCostFunction;
 using ceres::CostFunction;
 using ceres::Problem;
 using ceres::Solver;
 using ceres::Solve;
 
-class ResidualWithNoDerivative
-  : public SizedCostFunction<1 /* number of residuals */,
-                             1 /* size of first parameter */> {
+// A cost functor that implements the residual r = 10 - x.
+class QuadraticCostFunctor {
  public:
-  virtual ~ResidualWithNoDerivative() {}
-  virtual bool Evaluate(double const* const* parameters,
-                        double* residuals,
-                        double** jacobians) const {
-    (void) jacobians;  // Ignored; filled in by numeric differentiation.
-
-    // f(x) = 10 - x.
-    residuals[0] = 10 - parameters[0][0];
+  bool operator()(const double* const x, double* residual) const {
+    residual[0] = 10.0 - x[0];
     return true;
   }
 };
@@ -71,8 +63,8 @@
   // Set up the only cost function (also known as residual). This uses
   // numeric differentiation to obtain the derivative (jacobian).
   CostFunction* cost =
-      new NumericDiffCostFunction<ResidualWithNoDerivative, CENTRAL, 1, 1> (
-          new ResidualWithNoDerivative, ceres::TAKE_OWNERSHIP);
+      new NumericDiffCostFunction<QuadraticCostFunctor, CENTRAL, 1, 1> (
+          new QuadraticCostFunctor);
 
   // Build the problem.
   Problem problem;
diff --git a/examples/robust_curve_fitting.cc b/examples/robust_curve_fitting.cc
new file mode 100644
index 0000000..ad71a5d
--- /dev/null
+++ b/examples/robust_curve_fitting.cc
@@ -0,0 +1,163 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2010, 2011, 2012 Google Inc. All rights reserved.
+// http://code.google.com/p/ceres-solver/
+//
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+//
+// * Redistributions of source code must retain the above copyright notice,
+//   this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright notice,
+//   this list of conditions and the following disclaimer in the documentation
+//   and/or other materials provided with the distribution.
+// * Neither the name of Google Inc. nor the names of its contributors may be
+//   used to endorse or promote products derived from this software without
+//   specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+//
+// Author: sameeragarwal@google.com (Sameer Agarwal)
+
+#include "ceres/ceres.h"
+#include "glog/logging.h"
+
+// Data generated using the following octave code.
+//   randn('seed', 23497);
+//   m = 0.3;
+//   c = 0.1;
+//   x=[0:0.075:5];
+//   y = exp(m * x + c);
+//   noise = randn(size(x)) * 0.2;
+//   outlier_noise = rand(size(x)) < 0.05;
+//   y_observed = y + noise + outlier_noise;
+//   data = [x', y_observed'];
+
+const int kNumObservations = 67;
+const double data[] = {
+0.000000e+00, 1.133898e+00,
+7.500000e-02, 1.334902e+00,
+1.500000e-01, 1.213546e+00,
+2.250000e-01, 1.252016e+00,
+3.000000e-01, 1.392265e+00,
+3.750000e-01, 1.314458e+00,
+4.500000e-01, 1.472541e+00,
+5.250000e-01, 1.536218e+00,
+6.000000e-01, 1.355679e+00,
+6.750000e-01, 1.463566e+00,
+7.500000e-01, 1.490201e+00,
+8.250000e-01, 1.658699e+00,
+9.000000e-01, 1.067574e+00,
+9.750000e-01, 1.464629e+00,
+1.050000e+00, 1.402653e+00,
+1.125000e+00, 1.713141e+00,
+1.200000e+00, 1.527021e+00,
+1.275000e+00, 1.702632e+00,
+1.350000e+00, 1.423899e+00,
+1.425000e+00, 5.543078e+00, // Outlier point
+1.500000e+00, 5.664015e+00, // Outlier point
+1.575000e+00, 1.732484e+00,
+1.650000e+00, 1.543296e+00,
+1.725000e+00, 1.959523e+00,
+1.800000e+00, 1.685132e+00,
+1.875000e+00, 1.951791e+00,
+1.950000e+00, 2.095346e+00,
+2.025000e+00, 2.361460e+00,
+2.100000e+00, 2.169119e+00,
+2.175000e+00, 2.061745e+00,
+2.250000e+00, 2.178641e+00,
+2.325000e+00, 2.104346e+00,
+2.400000e+00, 2.584470e+00,
+2.475000e+00, 1.914158e+00,
+2.550000e+00, 2.368375e+00,
+2.625000e+00, 2.686125e+00,
+2.700000e+00, 2.712395e+00,
+2.775000e+00, 2.499511e+00,
+2.850000e+00, 2.558897e+00,
+2.925000e+00, 2.309154e+00,
+3.000000e+00, 2.869503e+00,
+3.075000e+00, 3.116645e+00,
+3.150000e+00, 3.094907e+00,
+3.225000e+00, 2.471759e+00,
+3.300000e+00, 3.017131e+00,
+3.375000e+00, 3.232381e+00,
+3.450000e+00, 2.944596e+00,
+3.525000e+00, 3.385343e+00,
+3.600000e+00, 3.199826e+00,
+3.675000e+00, 3.423039e+00,
+3.750000e+00, 3.621552e+00,
+3.825000e+00, 3.559255e+00,
+3.900000e+00, 3.530713e+00,
+3.975000e+00, 3.561766e+00,
+4.050000e+00, 3.544574e+00,
+4.125000e+00, 3.867945e+00,
+4.200000e+00, 4.049776e+00,
+4.275000e+00, 3.885601e+00,
+4.350000e+00, 4.110505e+00,
+4.425000e+00, 4.345320e+00,
+4.500000e+00, 4.161241e+00,
+4.575000e+00, 4.363407e+00,
+4.650000e+00, 4.161576e+00,
+4.725000e+00, 4.619728e+00,
+4.800000e+00, 4.737410e+00,
+4.875000e+00, 4.727863e+00,
+4.950000e+00, 4.669206e+00
+};
+
+using ceres::AutoDiffCostFunction;
+using ceres::CostFunction;
+using ceres::CauchyLoss;
+using ceres::Problem;
+using ceres::Solve;
+using ceres::Solver;
+
+struct ExponentialResidual {
+  ExponentialResidual(double x, double y)
+      : x_(x), y_(y) {}
+
+  template <typename T> bool operator()(const T* const m,
+                                        const T* const c,
+                                        T* residual) const {
+    residual[0] = T(y_) - exp(m[0] * T(x_) + c[0]);
+    return true;
+  }
+
+ private:
+  const double x_;
+  const double y_;
+};
+
+int main(int argc, char** argv) {
+  google::InitGoogleLogging(argv[0]);
+
+  double m = 0.0;
+  double c = 0.0;
+
+  Problem problem;
+  for (int i = 0; i < kNumObservations; ++i) {
+    CostFunction* cost_function =
+        new AutoDiffCostFunction<ExponentialResidual, 1, 1, 1>(
+            new ExponentialResidual(data[2 * i], data[2 * i + 1]));
+    problem.AddResidualBlock(cost_function, NULL, &m, &c);
+  }
+
+  Solver::Options options;
+  options.linear_solver_type = ceres::DENSE_QR;
+  options.minimizer_progress_to_stdout = true;
+
+  Solver::Summary summary;
+  Solve(options, &problem, &summary);
+  std::cout << summary.BriefReport() << "\n";
+  std::cout << "Initial m: " << 0.0 << " c: " << 0.0 << "\n";
+  std::cout << "Final   m: " << m << " c: " << c << "\n";
+  return 0;
+}
diff --git a/examples/simple_bundle_adjuster.cc b/examples/simple_bundle_adjuster.cc
index cc6f04a..736d4a2 100644
--- a/examples/simple_bundle_adjuster.cc
+++ b/examples/simple_bundle_adjuster.cc
@@ -160,6 +160,14 @@
     return true;
   }
 
+  // Factory to hide the construction of the CostFunction object from
+  // the client code.
+  static ceres::CostFunction* Create(const double observed_x,
+                                     const double observed_y) {
+    return (new ceres::AutoDiffCostFunction<SnavelyReprojectionError, 2, 9, 3>(
+                new SnavelyReprojectionError(observed_x, observed_y)));
+  }
+
   double observed_x;
   double observed_y;
 };
@@ -177,6 +185,8 @@
     return 1;
   }
 
+  const double* observations = bal_problem.observations();
+
   // Create residuals for each observation in the bundle adjustment problem. The
   // parameters for cameras and points are added automatically.
   ceres::Problem problem;
@@ -184,12 +194,10 @@
     // Each Residual block takes a point and a camera as input and outputs a 2
     // dimensional residual. Internally, the cost function stores the observed
     // image location and compares the reprojection against the observation.
-    ceres::CostFunction* cost_function =
-        new ceres::AutoDiffCostFunction<SnavelyReprojectionError, 2, 9, 3>(
-            new SnavelyReprojectionError(
-                bal_problem.observations()[2 * i + 0],
-                bal_problem.observations()[2 * i + 1]));
 
+    ceres::CostFunction* cost_function =
+        SnavelyReprojectionError::Create(observations[2 * i + 0],
+                                         observations[2 * i + 1]);
     problem.AddResidualBlock(cost_function,
                              NULL /* squared loss */,
                              bal_problem.mutable_camera_for_observation(i),