Add TinySolverCostFunctionAdapter

Change-Id: I1905044d09abe5c927cd7e2cda804cba516fd961
diff --git a/include/ceres/tiny_solver_cost_function_adapter.h b/include/ceres/tiny_solver_cost_function_adapter.h
new file mode 100644
index 0000000..fac0784
--- /dev/null
+++ b/include/ceres/tiny_solver_cost_function_adapter.h
@@ -0,0 +1,137 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2017 Google Inc. All rights reserved.
+// http://ceres-solver.org/
+//
+// 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)
+
+
+#ifndef CERES_PUBLIC_TINY_SOLVER_COST_FUNCTION_ADAPTER_H_
+#define CERES_PUBLIC_TINY_SOLVER_COST_FUNCTION_ADAPTER_H_
+
+#include <Eigen/Core>
+#include "ceres/cost_function.h"
+#include "glog/logging.h"
+
+namespace ceres {
+
+// An adapter class that lets users of TinySolver use
+// ceres::CostFunction objects that have exactly one parameter block.
+//
+// The adapter allows for the number of residuals and the size of the
+// parameter block to be specified at compile or run-time.
+//
+// WARNING: This object is not thread-safe.
+//
+// Example usage:
+//
+//  CostFunction* cost_function = ...
+//
+// Number of residuals and parameter block size known at compile time:
+//
+//   TinySolverCostFunctionAdapter<kNumResiduals, kNumParameters>
+//   cost_function_adapter(*cost_function);
+//
+// Number of residuals known at compile time and the parameter block
+// size not known at compile time.
+//
+//   TinySolverCostFunctionAdapter<kNumResiduals, Eigen::Dynamic>
+//   cost_function_adapter(*cost_function);
+//
+// Number of residuals not known at compile time and the parameter
+// block size known at compile time.
+//
+//   TinySolverCostFunctionAdapter<Eigen::Dynamic, kParameterBlockSize>
+//   cost_function_adapter(*cost_function);
+//
+// Number of residuals not known at compile time and the parameter
+// block size not known at compile time.
+//
+//   TinySolverCostFunctionAdapter cost_function_adapter(*cost_function);
+//
+template <int kNumResiduals = Eigen::Dynamic, int kNumParameters = Eigen::Dynamic>
+class TinySolverCostFunctionAdapter {
+ public:
+  typedef double Scalar;
+  enum {
+    NUM_PARAMETERS = kNumParameters,
+    NUM_RESIDUALS = kNumResiduals
+  };
+
+  TinySolverCostFunctionAdapter(const CostFunction& cost_function)
+      : cost_function_(cost_function) {
+    CHECK_EQ(cost_function_.parameter_block_sizes().size(), 1)
+        << "Only CostFunctions with exactly one parameter blocks are allowed.";
+
+    const int parameter_block_size = cost_function_.parameter_block_sizes()[0];
+    if (NUM_PARAMETERS == Eigen::Dynamic || NUM_RESIDUALS == Eigen::Dynamic) {
+      if (NUM_RESIDUALS != Eigen::Dynamic) {
+        CHECK_EQ(cost_function_.num_residuals(), NUM_RESIDUALS);
+      }
+      if (NUM_PARAMETERS != Eigen::Dynamic) {
+        CHECK_EQ(parameter_block_size, NUM_PARAMETERS);
+      }
+
+      row_major_jacobian_.resize(cost_function_.num_residuals(),
+                                 parameter_block_size);
+    }
+  }
+
+  bool operator()(const double* parameters,
+                  double* residuals,
+                  double* jacobian) const {
+    if (!jacobian) {
+      return cost_function_.Evaluate(&parameters, residuals, NULL);
+    }
+
+    double* jacobians[1] = {row_major_jacobian_.data()};
+    if (!cost_function_.Evaluate(&parameters, residuals, jacobians)) {
+      return false;
+    }
+
+    // The Function object used by TinySolver takes its Jacobian in a
+    // column-major layout, and the CostFunction objects use row-major
+    // Jacobian matrices. So the following bit of code does the
+    // conversion from row-major Jacobians to column-major Jacobians.
+    Eigen::Map<Eigen::Matrix<double, NUM_RESIDUALS, NUM_PARAMETERS>>
+        col_major_jacobian(jacobian, NumResiduals(), NumParameters());
+    col_major_jacobian = row_major_jacobian_;
+    return true;
+  }
+
+  int NumResiduals() const { return cost_function_.num_residuals(); }
+  int NumParameters() const {
+    return cost_function_.parameter_block_sizes()[0];
+  }
+
+  const CostFunction& cost_function_;
+  mutable Eigen::Matrix<double, NUM_RESIDUALS, NUM_PARAMETERS, Eigen::RowMajor>
+      row_major_jacobian_;
+};
+
+}  // namespace ceres
+
+#endif  // CERES_PUBLIC_TINY_SOLVER_COST_FUNCTION_ADAPTER_H_
diff --git a/internal/ceres/CMakeLists.txt b/internal/ceres/CMakeLists.txt
index a31c5a2..e78de48 100644
--- a/internal/ceres/CMakeLists.txt
+++ b/internal/ceres/CMakeLists.txt
@@ -359,6 +359,7 @@
   ceres_test(sparse_normal_cholesky_solver)
   ceres_test(system)
   ceres_test(tiny_solver)
+  ceres_test(tiny_solver_cost_function_adapter)
   ceres_test(triplet_sparse_matrix)
   ceres_test(trust_region_minimizer)
   ceres_test(trust_region_preprocessor)
diff --git a/internal/ceres/tiny_solver_cost_function_adapter_test.cc b/internal/ceres/tiny_solver_cost_function_adapter_test.cc
new file mode 100644
index 0000000..364fea9
--- /dev/null
+++ b/internal/ceres/tiny_solver_cost_function_adapter_test.cc
@@ -0,0 +1,132 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2017 Google Inc. All rights reserved.
+// http://ceres-solver.org/
+//
+// 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/tiny_solver_cost_function_adapter.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include "ceres/cost_function.h"
+#include "ceres/internal/scoped_ptr.h"
+#include "ceres/sized_cost_function.h"
+#include "gtest/gtest.h"
+
+namespace ceres {
+
+class CostFunction2x3 : public SizedCostFunction<2,3> {
+  virtual bool Evaluate(double const* const* parameters,
+                        double* residuals,
+                        double** jacobians) const {
+    double x = parameters[0][0];
+    double y = parameters[0][1];
+    double z = parameters[0][2];
+
+    residuals[0] = x + 2*y + 4*z;
+    residuals[1] = y * z;
+
+    if (jacobians && jacobians[0]) {
+      jacobians[0][0] = 1;
+      jacobians[0][1] = 2;
+      jacobians[0][2] = 4;
+
+      jacobians[0][3 + 0] = 0;
+      jacobians[0][3 + 1] = z;
+      jacobians[0][3 + 2] = y;
+    }
+
+    return true;
+  }
+};
+
+template<int kNumResiduals, int kNumParameters>
+void TestHelper() {
+  internal::scoped_ptr<CostFunction> cost_function(new CostFunction2x3);
+  typedef  TinySolverCostFunctionAdapter<kNumResiduals, kNumParameters> CostFunctionAdapter;
+  CostFunctionAdapter cfa(*cost_function);
+  EXPECT_EQ(CostFunctionAdapter::NUM_RESIDUALS, kNumResiduals);
+  EXPECT_EQ(CostFunctionAdapter::NUM_PARAMETERS, kNumParameters);
+
+  EXPECT_EQ(cfa.NumResiduals(), 2);
+  EXPECT_EQ(cfa.NumParameters(), 3);
+
+  Eigen::Matrix<double, 2, 1> actual_residuals, expected_residuals;
+  Eigen::Matrix<double, 2, 3, Eigen::ColMajor> actual_jacobian;
+  Eigen::Matrix<double, 2, 3, Eigen::RowMajor> expected_jacobian;
+
+  double xyz[3] = { 1.0, -1.0, 2.0};
+  double* parameters[1] = {xyz};
+
+  // Check that residual only evaluation works.
+  cost_function->Evaluate(parameters, expected_residuals.data(), NULL);
+  cfa(xyz, actual_residuals.data(), NULL);
+  EXPECT_NEAR(
+      (expected_residuals - actual_residuals).norm() / actual_residuals.norm(),
+      0.0,
+      std::numeric_limits<double>::epsilon())
+      << "\nExpected residuals: " << expected_residuals.transpose()
+      << "\nActual residuals: " << actual_residuals.transpose();
+
+  // Check that residual and jacobian evaluation works.
+  double* jacobians[1] = {expected_jacobian.data()};
+  cost_function->Evaluate(parameters, expected_residuals.data(), jacobians);
+  cfa(xyz, actual_residuals.data(), actual_jacobian.data());
+
+  EXPECT_NEAR(
+      (expected_residuals - actual_residuals).norm() / actual_residuals.norm(),
+      0.0,
+      std::numeric_limits<double>::epsilon())
+      << "\nExpected residuals: " << expected_residuals.transpose()
+      << "\nActual residuals: " << actual_residuals.transpose();
+
+  EXPECT_NEAR(
+      (expected_jacobian - actual_jacobian).norm() / actual_jacobian.norm(),
+      0.0,
+      std::numeric_limits<double>::epsilon())
+      << "\nExpected jacobian: " << expected_jacobian.transpose()
+      << "\nActual jacobian: " << actual_jacobian.transpose();
+}
+
+TEST(TinySolverCostFunctionAdapter, StaticResidualsStaticParameterBlock) {
+  TestHelper<2, 3>();
+}
+
+TEST(TinySolverCostFunctionAdapter, DynamicResidualsStaticParameterBlock) {
+  TestHelper<Eigen::Dynamic, 3>();
+}
+
+TEST(TinySolverCostFunctionAdapter, StaticResidualsDynamicParameterBlock) {
+  TestHelper<2, Eigen::Dynamic>();
+}
+
+TEST(TinySolverCostFunctionAdapter, DynamicResidualsDynamicParameterBlock) {
+  TestHelper<Eigen::Dynamic, Eigen::Dynamic>();
+}
+
+}  // namespace ceres