Rationalize some of the variable names in Solver::Options.

lm_max_diagonal -> max_lm_diagonal
lm_min_diagonal -> min_lm_diagonal
linear_solver_max_num_iterations -> max_linear_solver_iterations
linear_solver_min_num_iterations -> min_linear_solver_iterations

This follows the pattern for the other parameters in Solver::Options
where, the max/min is the first word followed by the name of the
parameter.

Change-Id: I0893610fceb6b7983fdb458a65522ba7079596a7
diff --git a/internal/ceres/dogleg_strategy.cc b/internal/ceres/dogleg_strategy.cc
index 957f58f..c85c8e5 100644
--- a/internal/ceres/dogleg_strategy.cc
+++ b/internal/ceres/dogleg_strategy.cc
@@ -53,8 +53,8 @@
     : linear_solver_(options.linear_solver),
       radius_(options.initial_radius),
       max_radius_(options.max_radius),
-      min_diagonal_(options.lm_min_diagonal),
-      max_diagonal_(options.lm_max_diagonal),
+      min_diagonal_(options.min_lm_diagonal),
+      max_diagonal_(options.max_lm_diagonal),
       mu_(kMinMu),
       min_mu_(kMinMu),
       max_mu_(kMaxMu),
diff --git a/internal/ceres/dogleg_strategy_test.cc b/internal/ceres/dogleg_strategy_test.cc
index caa397e..ace635f 100644
--- a/internal/ceres/dogleg_strategy_test.cc
+++ b/internal/ceres/dogleg_strategy_test.cc
@@ -84,8 +84,8 @@
     x_.resize(6);
     x_.setZero();
 
-    options_.lm_min_diagonal = 1.0;
-    options_.lm_max_diagonal = 1.0;
+    options_.min_lm_diagonal = 1.0;
+    options_.max_lm_diagonal = 1.0;
   }
 };
 
@@ -112,8 +112,8 @@
     x_.resize(6);
     x_.setZero();
 
-    options_.lm_min_diagonal = 1.0;
-    options_.lm_max_diagonal = 1.0;
+    options_.min_lm_diagonal = 1.0;
+    options_.max_lm_diagonal = 1.0;
   }
 };
 
diff --git a/internal/ceres/levenberg_marquardt_strategy.cc b/internal/ceres/levenberg_marquardt_strategy.cc
index 6b29244..fad7c1f 100644
--- a/internal/ceres/levenberg_marquardt_strategy.cc
+++ b/internal/ceres/levenberg_marquardt_strategy.cc
@@ -49,8 +49,8 @@
     : linear_solver_(options.linear_solver),
       radius_(options.initial_radius),
       max_radius_(options.max_radius),
-      min_diagonal_(options.lm_min_diagonal),
-      max_diagonal_(options.lm_max_diagonal),
+      min_diagonal_(options.min_lm_diagonal),
+      max_diagonal_(options.max_lm_diagonal),
       decrease_factor_(2.0),
       reuse_diagonal_(false) {
   CHECK_NOTNULL(linear_solver_);
diff --git a/internal/ceres/levenberg_marquardt_strategy_test.cc b/internal/ceres/levenberg_marquardt_strategy_test.cc
index a5ce6a0..86302b7 100644
--- a/internal/ceres/levenberg_marquardt_strategy_test.cc
+++ b/internal/ceres/levenberg_marquardt_strategy_test.cc
@@ -82,8 +82,8 @@
   TrustRegionStrategy::Options options;
   options.initial_radius = 2.0;
   options.max_radius = 20.0;
-  options.lm_min_diagonal = 1e-8;
-  options.lm_max_diagonal = 1e8;
+  options.min_lm_diagonal = 1e-8;
+  options.max_lm_diagonal = 1e8;
 
   // We need a non-null pointer here, so anything should do.
   scoped_ptr<LinearSolver> linear_solver(
@@ -125,13 +125,13 @@
   TrustRegionStrategy::Options options;
   options.initial_radius = 2.0;
   options.max_radius = 20.0;
-  options.lm_min_diagonal = 1e-2;
-  options.lm_max_diagonal = 1e2;
+  options.min_lm_diagonal = 1e-2;
+  options.max_lm_diagonal = 1e2;
 
   double diagonal[3];
-  diagonal[0] = options.lm_min_diagonal;
+  diagonal[0] = options.min_lm_diagonal;
   diagonal[1] = 2.0;
-  diagonal[2] = options.lm_max_diagonal;
+  diagonal[2] = options.max_lm_diagonal;
   for (int i = 0; i < 3; ++i) {
     diagonal[i] = sqrt(diagonal[i] / options.initial_radius);
   }
diff --git a/internal/ceres/solver_impl.cc b/internal/ceres/solver_impl.cc
index 1cc19db..3d58de7 100644
--- a/internal/ceres/solver_impl.cc
+++ b/internal/ceres/solver_impl.cc
@@ -255,8 +255,8 @@
   trust_region_strategy_options.initial_radius =
       options.initial_trust_region_radius;
   trust_region_strategy_options.max_radius = options.max_trust_region_radius;
-  trust_region_strategy_options.lm_min_diagonal = options.lm_min_diagonal;
-  trust_region_strategy_options.lm_max_diagonal = options.lm_max_diagonal;
+  trust_region_strategy_options.min_lm_diagonal = options.min_lm_diagonal;
+  trust_region_strategy_options.max_lm_diagonal = options.max_lm_diagonal;
   trust_region_strategy_options.trust_region_strategy_type =
       options.trust_region_strategy_type;
   trust_region_strategy_options.dogleg_type = options.dogleg_type;
@@ -1091,26 +1091,26 @@
   }
 #endif
 
-  if (options->linear_solver_max_num_iterations <= 0) {
-    *error = "Solver::Options::linear_solver_max_num_iterations is 0.";
+  if (options->max_linear_solver_iterations <= 0) {
+    *error = "Solver::Options::max_linear_solver_iterations is not positive.";
     return NULL;
   }
-  if (options->linear_solver_min_num_iterations <= 0) {
-    *error = "Solver::Options::linear_solver_min_num_iterations is 0.";
+  if (options->min_linear_solver_iterations <= 0) {
+    *error = "Solver::Options::min_linear_solver_iterations is not positive.";
     return NULL;
   }
-  if (options->linear_solver_min_num_iterations >
-      options->linear_solver_max_num_iterations) {
-    *error = "Solver::Options::linear_solver_min_num_iterations > "
-        "Solver::Options::linear_solver_max_num_iterations.";
+  if (options->min_linear_solver_iterations >
+      options->max_linear_solver_iterations) {
+    *error = "Solver::Options::min_linear_solver_iterations > "
+        "Solver::Options::max_linear_solver_iterations.";
     return NULL;
   }
 
   LinearSolver::Options linear_solver_options;
   linear_solver_options.min_num_iterations =
-        options->linear_solver_min_num_iterations;
+        options->min_linear_solver_iterations;
   linear_solver_options.max_num_iterations =
-      options->linear_solver_max_num_iterations;
+      options->max_linear_solver_iterations;
   linear_solver_options.type = options->linear_solver_type;
   linear_solver_options.preconditioner_type = options->preconditioner_type;
   linear_solver_options.sparse_linear_algebra_library =
diff --git a/internal/ceres/solver_impl_test.cc b/internal/ceres/solver_impl_test.cc
index 7413ca8..d81858c 100644
--- a/internal/ceres/solver_impl_test.cc
+++ b/internal/ceres/solver_impl_test.cc
@@ -509,7 +509,7 @@
 TEST(SolverImpl, CreateLinearSolverNegativeMaxNumIterations) {
   Solver::Options options;
   options.linear_solver_type = DENSE_QR;
-  options.linear_solver_max_num_iterations = -1;
+  options.max_linear_solver_iterations = -1;
   // CreateLinearSolver assumes a non-empty ordering.
   options.linear_solver_ordering = new ParameterBlockOrdering;
   string error;
@@ -520,7 +520,7 @@
 TEST(SolverImpl, CreateLinearSolverNegativeMinNumIterations) {
   Solver::Options options;
   options.linear_solver_type = DENSE_QR;
-  options.linear_solver_min_num_iterations = -1;
+  options.min_linear_solver_iterations = -1;
   // CreateLinearSolver assumes a non-empty ordering.
   options.linear_solver_ordering = new ParameterBlockOrdering;
   string error;
@@ -531,8 +531,8 @@
 TEST(SolverImpl, CreateLinearSolverMaxLessThanMinIterations) {
   Solver::Options options;
   options.linear_solver_type = DENSE_QR;
-  options.linear_solver_min_num_iterations = 10;
-  options.linear_solver_max_num_iterations = 5;
+  options.min_linear_solver_iterations = 10;
+  options.max_linear_solver_iterations = 5;
   options.linear_solver_ordering = new ParameterBlockOrdering;
   string error;
   EXPECT_EQ(SolverImpl::CreateLinearSolver(&options, &error),
diff --git a/internal/ceres/trust_region_minimizer_test.cc b/internal/ceres/trust_region_minimizer_test.cc
index ed00ab2..ef49206 100644
--- a/internal/ceres/trust_region_minimizer_test.cc
+++ b/internal/ceres/trust_region_minimizer_test.cc
@@ -238,8 +238,8 @@
   trust_region_strategy_options.linear_solver = &linear_solver;
   trust_region_strategy_options.initial_radius = 1e4;
   trust_region_strategy_options.max_radius = 1e20;
-  trust_region_strategy_options.lm_min_diagonal = 1e-6;
-  trust_region_strategy_options.lm_max_diagonal = 1e32;
+  trust_region_strategy_options.min_lm_diagonal = 1e-6;
+  trust_region_strategy_options.max_lm_diagonal = 1e32;
   scoped_ptr<TrustRegionStrategy> strategy(
       TrustRegionStrategy::Create(trust_region_strategy_options));
   minimizer_options.trust_region_strategy = strategy.get();
diff --git a/internal/ceres/trust_region_strategy.h b/internal/ceres/trust_region_strategy.h
index f7fd25a..0dcdbfe 100644
--- a/internal/ceres/trust_region_strategy.h
+++ b/internal/ceres/trust_region_strategy.h
@@ -60,8 +60,8 @@
         : trust_region_strategy_type(LEVENBERG_MARQUARDT),
           initial_radius(1e4),
           max_radius(1e32),
-          lm_min_diagonal(1e-6),
-          lm_max_diagonal(1e32),
+          min_lm_diagonal(1e-6),
+          max_lm_diagonal(1e32),
           dogleg_type(TRADITIONAL_DOGLEG) {
     }
 
@@ -75,8 +75,8 @@
     // by LevenbergMarquardtStrategy. The DoglegStrategy also uses
     // these bounds to construct a regularizing diagonal to ensure
     // that the Gauss-Newton step computation is of full rank.
-    double lm_min_diagonal;
-    double lm_max_diagonal;
+    double min_lm_diagonal;
+    double max_lm_diagonal;
 
     // Further specify which dogleg method to use
     DoglegType dogleg_type;