Armijo line search.

An interface for line search and an initial implementation of
Armijo line search with and without interpolation.

Change-Id: I234da141be36172819a6df87ce5625aa8b58ed47
diff --git a/internal/ceres/CMakeLists.txt b/internal/ceres/CMakeLists.txt
index 0960b95..f48189f 100644
--- a/internal/ceres/CMakeLists.txt
+++ b/internal/ceres/CMakeLists.txt
@@ -58,6 +58,7 @@
     implicit_schur_complement.cc
     iterative_schur_complement_solver.cc
     levenberg_marquardt_strategy.cc
+    line_search.cc
     linear_least_squares_problems.cc
     linear_operator.cc
     linear_solver.cc
diff --git a/internal/ceres/line_search.cc b/internal/ceres/line_search.cc
new file mode 100644
index 0000000..fbb75a0
--- /dev/null
+++ b/internal/ceres/line_search.cc
@@ -0,0 +1,201 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 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/line_search.h"
+
+#include <glog/logging.h>
+#include "ceres/fpclassify.h"
+#include "ceres/evaluator.h"
+#include "ceres/internal/eigen.h"
+#include "ceres/polynomial.h"
+
+
+namespace ceres {
+namespace internal {
+namespace {
+
+FunctionSample ValueSample(const double x, const double value) {
+  FunctionSample sample;
+  sample.x = x;
+  sample.value = value;
+  sample.value_is_valid = true;
+  return sample;
+};
+
+FunctionSample ValueAndGradientSample(const double x,
+                                      const double value,
+                                      const double gradient) {
+  FunctionSample sample;
+  sample.x = x;
+  sample.value = value;
+  sample.gradient = gradient;
+  sample.value_is_valid = true;
+  sample.gradient_is_valid = true;
+  return sample;
+};
+
+}  // namespace
+
+LineSearchFunction::LineSearchFunction(Evaluator* evaluator)
+    : evaluator_(evaluator),
+      position_(evaluator->NumParameters()),
+      direction_(evaluator->NumEffectiveParameters()),
+      evaluation_point_(evaluator->NumParameters()),
+      scaled_direction_(evaluator->NumEffectiveParameters()),
+      gradient_(evaluator->NumEffectiveParameters()) {
+}
+
+void LineSearchFunction::Init(const Vector& position,
+                               const Vector& direction) {
+  position_ = position;
+  direction_ = direction;
+}
+
+bool LineSearchFunction::Evaluate(const double x, double* f, double* g) {
+  scaled_direction_ = x * direction_;
+  if (evaluator_->Plus(position_.data(),
+                       scaled_direction_.data(),
+                       evaluation_point_.data()) &&
+      evaluator_->Evaluate(evaluation_point_.data(),
+                           f,
+                           NULL,
+                           gradient_.data(), NULL)) {
+    *g = direction_.dot(gradient_);
+    return IsFinite(*f) && IsFinite(*g);
+  }
+  return false;
+}
+
+void ArmijoLineSearch::Search(const LineSearch::Options& options,
+                              double initial_step_size,
+                              Summary* summary) {
+  *CHECK_NOTNULL(summary) = LineSearch::Summary();
+  Function* function = options.function;
+  double initial_cost = 0.0;
+  double initial_gradient = 0.0;
+  summary->num_evaluations = 1;
+  if (!function->Evaluate(0.0, &initial_cost, &initial_gradient)) {
+    LOG(WARNING) << "Line search failed. "
+                 << "Evaluation at the initial point failed.";
+    return;
+  }
+
+  double previous_step_size = 0.0;
+  double previous_cost = 0.0;
+  double previous_gradient = 0.0;
+  bool previous_step_size_is_valid = false;
+
+  double step_size = initial_step_size;
+  double cost = 0.0;
+  double gradient = 0.0;
+  bool step_size_is_valid = false;
+
+  ++summary->num_evaluations;
+  step_size_is_valid = function->Evaluate(step_size, &cost, &gradient);
+  while (!step_size_is_valid || cost > (initial_cost
+                                        + options.sufficient_decrease
+                                        * initial_gradient
+                                        * step_size)) {
+    // If step_size_is_valid is not true we treat it as if the cost at
+    // that point is not large enough to satisfy the sufficient
+    // decrease condition.
+
+    const double current_step_size = step_size;
+    // Backtracking search. Each iteration of this loop finds a new point
+
+    if ((options.interpolation_degree == 0) || !step_size_is_valid) {
+      // Backtrack by halving the step_size;
+      step_size *= 0.5;
+    } else {
+      // Backtrack by interpolating the function and gradient values
+      // and minimizing the corresponding polynomial.
+
+      vector<FunctionSample> samples;
+      samples.push_back(ValueAndGradientSample(0.0,
+                                               initial_cost,
+                                               initial_gradient));
+
+      if (options.interpolation_degree == 1) {
+        // Two point interpolation using function values and the
+        // initial gradient.
+        samples.push_back(ValueSample(step_size, cost));
+
+        if (options.use_higher_degree_interpolation_when_possible &&
+            summary->num_evaluations > 2 &&
+            previous_step_size_is_valid) {
+          // Three point interpolation, using function values and the
+          // initial gradient.
+          samples.push_back(ValueSample(previous_step_size, previous_cost));
+        }
+      } else {
+        // Two point interpolation using the function values and the gradients.
+        samples.push_back(ValueAndGradientSample(step_size,
+                                                 cost,
+                                                 gradient));
+
+        if (options.use_higher_degree_interpolation_when_possible &&
+            summary->num_evaluations > 2 &&
+            previous_step_size_is_valid) {
+          // Three point interpolation using the function values and
+          // the gradients.
+          samples.push_back(ValueAndGradientSample(previous_step_size,
+                                                   previous_cost,
+                                                   previous_gradient));
+        }
+      }
+
+      double min_value;
+      MinimizeInterpolatingPolynomial(samples, 0.0, current_step_size,
+                                      &step_size, &min_value);
+      step_size =
+          min(max(step_size,
+                  options.min_relative_step_size_change * current_step_size),
+              options.max_relative_step_size_change * current_step_size);
+    }
+
+    previous_step_size = current_step_size;
+    previous_cost = cost;
+    previous_gradient = gradient;
+
+    if (fabs(initial_gradient) * step_size < options.step_size_threshold) {
+      LOG(WARNING) << "Line search failed: step_size too small: " << step_size;
+      return;
+    }
+
+    ++summary->num_evaluations;
+    step_size_is_valid = function->Evaluate(step_size, &cost, &gradient);
+  }
+
+  summary->optimal_step_size = step_size;
+  summary->success = true;
+}
+
+}  // namespace internal
+}  // namespace ceres
diff --git a/internal/ceres/line_search.h b/internal/ceres/line_search.h
new file mode 100644
index 0000000..bc43329
--- /dev/null
+++ b/internal/ceres/line_search.h
@@ -0,0 +1,204 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 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)
+//
+// Interface for and implementation of various Line search algorithms.
+
+#ifndef CERES_INTERNAL_LINE_SEARCH_H_
+#define CERES_INTERNAL_LINE_SEARCH_H_
+
+#include <glog/logging.h>
+#include <vector>
+#include "ceres/internal/eigen.h"
+#include "ceres/internal/port.h"
+
+namespace ceres {
+namespace internal {
+
+class Evaluator;
+
+// Line search is another name for a one dimensional optimization
+// algorithm. The name "line search" comes from the fact one
+// dimensional optimization problems that arise as subproblems of
+// general multidimensional optimization problems.
+//
+// While finding the exact minimum of a one dimensionl function is
+// hard, instances of LineSearch find a point that satisfies a
+// sufficient decrease condition. Depending on the particular
+// condition used, we get a variety of different line search
+// algorithms, e.g., Armijo, Wolfe etc.
+class LineSearch {
+ public:
+  class Function;
+
+  struct Options {
+    Options()
+        : interpolation_degree(1),
+          use_higher_degree_interpolation_when_possible(false),
+          sufficient_decrease(1e-4),
+          min_relative_step_size_change(1e-3),
+          max_relative_step_size_change(0.6),
+          step_size_threshold(1e-9),
+          function(NULL) {}
+
+    // TODO(sameeragarwal): Replace this with enums which are common
+    // across various line searches.
+    //
+    // Degree of the polynomial used to approximate the objective
+    // function. Valid values are {0, 1, 2}.
+    //
+    // For Armijo line search
+    //
+    // 0: Bisection based backtracking search.
+    // 1: Quadratic interpolation.
+    // 2: Cubic interpolation.
+    int interpolation_degree;
+
+    // Usually its possible to increase the degree of the
+    // interpolation polynomial by storing and using an extra point.
+    bool use_higher_degree_interpolation_when_possible;
+
+    // Armijo line search parameters.
+
+    // Solving the line search problem exactly is computationally
+    // prohibitive. Fortunately, line search based optimization
+    // algorithms can still guarantee convergence if instead of an
+    // exact solution, the line search algorithm returns a solution
+    // which decreases the value of the objective function
+    // sufficiently. More precisely, we are looking for a step_size
+    // s.t.
+    //
+    //  f(step_size) <= f(0) + sufficient_decrease * f'(0) * step_size
+    double sufficient_decrease;
+
+    // In each iteration of the Armijo line search,
+    //
+    // new_step_size >= min_relative_step_size_change * step_size
+    double min_relative_step_size_change;
+
+    // In each iteration of the Armijo line search,
+    //
+    // new_step_size <= max_relative_step_size_change * step_size
+    double max_relative_step_size_change;
+
+    // If during the line search, the step_size falls below this
+    // value, it is truncated to zero.
+    double step_size_threshold;
+
+    // The one dimensional function that the line search algorithm
+    // minimizes.
+    Function* function;
+  };
+
+  // An object used by the line search to access the function values
+  // and gradient of the one dimensional function being optimized.
+  //
+  // In practice, this object will provide access to the objective
+  // function value and the directional derivative of the underlying
+  // optimization problem along a specific search direction.
+  //
+  // See LineSearchFunction for an example implementation.
+  class Function {
+   public:
+    virtual ~Function() {}
+    // Evaluate the line search objective
+    //
+    //   f(x) = p(position + x * direction)
+    //
+    // Where, p is the objective function of the general optimization
+    // problem.
+    //
+    // g is the gradient f'(x) at x.
+    //
+    // Both f and g must not be NULL;
+    virtual bool Evaluate(double x, double* f, double* g) = 0;
+  };
+
+  // Result of the line search.
+  struct Summary {
+    Summary()
+        : success(false),
+          optimal_step_size(0.0),
+          num_evaluations(0) {}
+
+    bool success;
+    double optimal_step_size;
+    int num_evaluations;
+  };
+
+  virtual ~LineSearch() {}
+
+  // Perform the line search.
+  //
+  // initial_step_size must be a positive number.  summary must not be
+  // null and will contain the result of the line search.
+  //
+  // Summary::success is true if a non-zero step size is found.
+  virtual void Search(const LineSearch::Options& options,
+                      double initial_step_size,
+                      Summary* summary) = 0;
+};
+
+class LineSearchFunction : public LineSearch::Function {
+ public:
+  explicit LineSearchFunction(Evaluator* evaluator);
+  virtual ~LineSearchFunction() {}
+  void Init(const Vector& position, const Vector& direction);
+  virtual bool Evaluate(const double x, double* f, double* g);
+
+ private:
+  Evaluator* evaluator_;
+  Vector position_;
+  Vector direction_;
+
+  // evaluation_point = Evaluator::Plus(position_,  x * direction_);
+  Vector evaluation_point_;
+
+  // scaled_direction = x * direction_;
+  Vector scaled_direction_;
+  Vector gradient_;
+};
+
+// Backtracking and interpolation based Armijo line search. This
+// implementation is based on the Armijo line search that ships in the
+// minFunc package by Mark Schmidt.
+//
+// For more details: http://www.di.ens.fr/~mschmidt/Software/minFunc.html
+class ArmijoLineSearch : public LineSearch {
+ public:
+  virtual ~ArmijoLineSearch() {}
+  virtual void Search(const LineSearch::Options& options,
+                      double initial_step_size,
+                      Summary* summary);
+};
+
+}  // namespace internal
+}  // namespace ceres
+
+#endif  // CERES_INTERNAL_LINE_SEARCH_H_