Add Apple's Accelerate framework as a sparse linear algebra library.
- Currently DynamicSparseNormalCholeskySolver is unsupported for
Accelerate.
Change-Id: I03b5a86bb22fef249c4aecd48947a613e8eff7a5
diff --git a/internal/ceres/CMakeLists.txt b/internal/ceres/CMakeLists.txt
index 9d8b923..38ba9d4 100644
--- a/internal/ceres/CMakeLists.txt
+++ b/internal/ceres/CMakeLists.txt
@@ -56,6 +56,7 @@
set(CERES_INTERNAL_SRC
${CERES_PARALLEL_FOR_SRC}
+ accelerate_sparse.cc
array_utils.cc
blas.cc
block_evaluate_preparer.cc
@@ -206,6 +207,10 @@
list(APPEND CERES_LIBRARY_PRIVATE_DEPENDENCIES ${CXSPARSE_LIBRARIES})
endif (CXSPARSE AND CXSPARSE_FOUND)
+if (ACCELERATESPARSE AND AccelerateSparse_FOUND)
+ list(APPEND CERES_LIBRARY_PRIVATE_DEPENDENCIES ${AccelerateSparse_LIBRARIES})
+endif()
+
if (LAPACK_FOUND)
list(APPEND CERES_LIBRARY_PRIVATE_DEPENDENCIES ${LAPACK_LIBRARIES})
endif ()
diff --git a/internal/ceres/accelerate_sparse.cc b/internal/ceres/accelerate_sparse.cc
new file mode 100644
index 0000000..a82d90b
--- /dev/null
+++ b/internal/ceres/accelerate_sparse.cc
@@ -0,0 +1,238 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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: alexs.mac@gmail.com (Alex Stewart)
+
+// This include must come before any #ifndef check on Ceres compile options.
+#include "ceres/internal/port.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+#include "ceres/accelerate_sparse.h"
+
+#include <algorithm>
+#include <string>
+#include <vector>
+
+#include "ceres/compressed_col_sparse_matrix_utils.h"
+#include "ceres/compressed_row_sparse_matrix.h"
+#include "ceres/triplet_sparse_matrix.h"
+#include "glog/logging.h"
+
+#define CASESTR(x) case x: return #x
+
+namespace ceres {
+namespace internal {
+
+const char* SparseStatusToString(SparseStatus_t status) {
+ switch (status) {
+ CASESTR(SparseStatusOK);
+ CASESTR(SparseFactorizationFailed);
+ CASESTR(SparseMatrixIsSingular);
+ CASESTR(SparseInternalError);
+ CASESTR(SparseParameterError);
+ CASESTR(SparseStatusReleased);
+ default:
+ return "UKNOWN";
+ }
+}
+
+template<typename Scalar>
+void AccelerateSparse<Scalar>::Solve(NumericFactorization* numeric_factor,
+ DenseVector* rhs_and_solution) {
+ SparseSolve(*numeric_factor, *rhs_and_solution);
+}
+
+template<typename Scalar>
+typename AccelerateSparse<Scalar>::ASSparseMatrix
+AccelerateSparse<Scalar>::CreateSparseMatrixTransposeView(
+ CompressedRowSparseMatrix* A) {
+ // Accelerate uses CSC as its sparse storage format whereas Ceres uses CSR.
+ // As this method returns the transpose view we can flip rows/cols to map
+ // from CSR to CSC^T.
+ //
+ // Accelerate's columnStarts is a long*, not an int*. These types might be
+ // different (e.g. ARM on iOS) so always make a copy.
+ column_starts_.resize(A->num_rows() +1); // +1 for final column length.
+ std::copy_n(A->rows(), column_starts_.size(), &column_starts_[0]);
+
+ ASSparseMatrix At;
+ At.structure.rowCount = A->num_cols();
+ At.structure.columnCount = A->num_rows();
+ At.structure.columnStarts = &column_starts_[0];
+ At.structure.rowIndices = A->mutable_cols();
+ At.structure.attributes.transpose = false;
+ At.structure.attributes.triangle = SparseUpperTriangle;
+ At.structure.attributes.kind = SparseSymmetric;
+ At.structure.attributes._reserved = 0;
+ At.structure.attributes._allocatedBySparse = 0;
+ At.structure.blockSize = 1;
+ if (std::is_same<Scalar, double>::value) {
+ At.data = reinterpret_cast<Scalar*>(A->mutable_values());
+ } else {
+ values_ =
+ ConstVectorRef(A->values(), A->num_nonzeros()).template cast<Scalar>();
+ At.data = values_.data();
+ }
+ return At;
+}
+
+template<typename Scalar>
+typename AccelerateSparse<Scalar>::SymbolicFactorization
+AccelerateSparse<Scalar>::AnalyzeCholesky(ASSparseMatrix* A) {
+ return SparseFactor(SparseFactorizationCholesky, A->structure);
+}
+
+template<typename Scalar>
+typename AccelerateSparse<Scalar>::NumericFactorization
+AccelerateSparse<Scalar>::Cholesky(ASSparseMatrix* A,
+ SymbolicFactorization* symbolic_factor) {
+ return SparseFactor(*symbolic_factor, *A);
+}
+
+// Instantiate only for the specific template types required/supported s/t the
+// definition can be in the .cc file.
+template class AccelerateSparse<double>;
+template class AccelerateSparse<float>;
+
+template<typename Scalar>
+std::unique_ptr<SparseCholesky>
+AppleAccelerateCholesky<Scalar>::Create(OrderingType ordering_type) {
+ return std::unique_ptr<SparseCholesky>(
+ new AppleAccelerateCholesky<Scalar>(ordering_type));
+}
+
+template<typename Scalar>
+AppleAccelerateCholesky<Scalar>::AppleAccelerateCholesky(
+ const OrderingType ordering_type)
+ : ordering_type_(ordering_type) {}
+
+template<typename Scalar>
+AppleAccelerateCholesky<Scalar>::~AppleAccelerateCholesky() {
+ FreeSymbolicFactorization();
+ FreeNumericFactorization();
+}
+
+template<typename Scalar>
+CompressedRowSparseMatrix::StorageType
+AppleAccelerateCholesky<Scalar>::StorageType() const {
+ return CompressedRowSparseMatrix::LOWER_TRIANGULAR;
+}
+
+template<typename Scalar>
+LinearSolverTerminationType
+AppleAccelerateCholesky<Scalar>::Factorize(CompressedRowSparseMatrix* lhs,
+ std::string* message) {
+ CHECK_EQ(lhs->storage_type(), StorageType());
+ if (lhs == NULL) {
+ *message = "Failure: Input lhs is NULL.";
+ return LINEAR_SOLVER_FATAL_ERROR;
+ }
+ typename SparseTypesTrait<Scalar>::SparseMatrix as_lhs =
+ as_.CreateSparseMatrixTransposeView(lhs);
+
+ if (!symbolic_factor_) {
+ symbolic_factor_.reset(
+ new typename SparseTypesTrait<Scalar>::SymbolicFactorization(
+ as_.AnalyzeCholesky(&as_lhs)));
+ if (symbolic_factor_->status != SparseStatusOK) {
+ *message = StringPrintf(
+ "Apple Accelerate Failure : Symbolic factorisation failed: %s",
+ SparseStatusToString(symbolic_factor_->status));
+ FreeSymbolicFactorization();
+ return LINEAR_SOLVER_FATAL_ERROR;
+ }
+ }
+
+ FreeNumericFactorization();
+ numeric_factor_.reset(
+ new typename SparseTypesTrait<Scalar>::NumericFactorization(
+ as_.Cholesky(&as_lhs, symbolic_factor_.get())));
+ if (numeric_factor_->status != SparseStatusOK) {
+ *message = StringPrintf(
+ "Apple Accelerate Failure : Numeric factorisation failed: %s",
+ SparseStatusToString(numeric_factor_->status));
+ return LINEAR_SOLVER_FAILURE;
+ }
+
+ return LINEAR_SOLVER_SUCCESS;
+}
+
+template<typename Scalar>
+LinearSolverTerminationType
+AppleAccelerateCholesky<Scalar>::Solve(const double* rhs,
+ double* solution,
+ std::string* message) {
+ CHECK_EQ(numeric_factor_->status, SparseStatusOK)
+ << "Solve called without a call to Factorize first ("
+ << SparseStatusToString(numeric_factor_->status) << ").";
+ const int num_cols = numeric_factor_->symbolicFactorization.columnCount;
+
+ typename SparseTypesTrait<Scalar>::DenseVector as_rhs_and_solution;
+ as_rhs_and_solution.count = num_cols;
+ if (std::is_same<Scalar, double>::value) {
+ as_rhs_and_solution.data = reinterpret_cast<Scalar*>(solution);
+ std::copy_n(rhs, num_cols, solution);
+ } else {
+ scalar_rhs_and_solution_ =
+ ConstVectorRef(rhs, num_cols).template cast<Scalar>();
+ as_rhs_and_solution.data = scalar_rhs_and_solution_.data();
+ }
+ as_.Solve(numeric_factor_.get(), &as_rhs_and_solution);
+ if (!std::is_same<Scalar, double>::value) {
+ VectorRef(solution, num_cols) =
+ scalar_rhs_and_solution_.template cast<double>();
+ }
+ return LINEAR_SOLVER_SUCCESS;
+}
+
+template<typename Scalar>
+void AppleAccelerateCholesky<Scalar>::FreeSymbolicFactorization() {
+ if (symbolic_factor_) {
+ SparseCleanup(*symbolic_factor_);
+ symbolic_factor_.reset();
+ }
+}
+
+template<typename Scalar>
+void AppleAccelerateCholesky<Scalar>::FreeNumericFactorization() {
+ if (numeric_factor_) {
+ SparseCleanup(*numeric_factor_);
+ numeric_factor_.reset();
+ }
+}
+
+// Instantiate only for the specific template types required/supported s/t the
+// definition can be in the .cc file.
+template class AppleAccelerateCholesky<double>;
+template class AppleAccelerateCholesky<float>;
+
+}
+}
+
+#endif // CERES_NO_ACCELERATE_SPARSE
diff --git a/internal/ceres/accelerate_sparse.h b/internal/ceres/accelerate_sparse.h
new file mode 100644
index 0000000..cb5d084
--- /dev/null
+++ b/internal/ceres/accelerate_sparse.h
@@ -0,0 +1,142 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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: alexs.mac@gmail.com (Alex Stewart)
+
+#ifndef CERES_INTERNAL_ACCELERATE_SPARSE_H_
+#define CERES_INTERNAL_ACCELERATE_SPARSE_H_
+
+// This include must come before any #ifndef check on Ceres compile options.
+#include "ceres/internal/port.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include "ceres/linear_solver.h"
+#include "ceres/sparse_cholesky.h"
+#include "Accelerate.h"
+
+namespace ceres {
+namespace internal {
+
+class CompressedRowSparseMatrix;
+class TripletSparseMatrix;
+
+template<typename Scalar>
+struct SparseTypesTrait {
+};
+
+template<>
+struct SparseTypesTrait<double> {
+ typedef DenseVector_Double DenseVector;
+ typedef SparseMatrix_Double SparseMatrix;
+ typedef SparseOpaqueSymbolicFactorization SymbolicFactorization;
+ typedef SparseOpaqueFactorization_Double NumericFactorization;
+};
+
+template<>
+struct SparseTypesTrait<float> {
+ typedef DenseVector_Float DenseVector;
+ typedef SparseMatrix_Float SparseMatrix;
+ typedef SparseOpaqueSymbolicFactorization SymbolicFactorization;
+ typedef SparseOpaqueFactorization_Float NumericFactorization;
+};
+
+template<typename Scalar>
+class AccelerateSparse {
+ public:
+ using DenseVector = typename SparseTypesTrait<Scalar>::DenseVector;
+ // Use ASSparseMatrix to avoid collision with ceres::internal::SparseMatrix.
+ using ASSparseMatrix = typename SparseTypesTrait<Scalar>::SparseMatrix;
+ using SymbolicFactorization = typename SparseTypesTrait<Scalar>::SymbolicFactorization;
+ using NumericFactorization = typename SparseTypesTrait<Scalar>::NumericFactorization;
+
+ // Solves a linear system given its symbolic (reference counted within
+ // NumericFactorization) and numeric factorization.
+ void Solve(NumericFactorization* numeric_factor,
+ DenseVector* rhs_and_solution);
+
+ // Note: Accelerate's API passes/returns its objects by value, but as the
+ // objects contain pointers to the underlying data these copies are
+ // all shallow (in some cases Accelerate also reference counts the
+ // objects internally).
+ ASSparseMatrix CreateSparseMatrixTransposeView(CompressedRowSparseMatrix* A);
+ // Computes a symbolic factorisation of A that can be used in Solve().
+ SymbolicFactorization AnalyzeCholesky(ASSparseMatrix* A);
+ // Compute the numeric Cholesky factorization of A, given its
+ // symbolic factorization.
+ NumericFactorization Cholesky(ASSparseMatrix* A,
+ SymbolicFactorization* symbolic_factor);
+
+ private:
+ std::vector<long> column_starts_;
+ // Storage for the values of A if Scalar != double (necessitating a copy).
+ Eigen::Matrix<Scalar, Eigen::Dynamic, 1> values_;
+};
+
+// An implementation of SparseCholesky interface using Apple's Accelerate
+// framework.
+template<typename Scalar>
+class AppleAccelerateCholesky : public SparseCholesky {
+ public:
+ // Factory
+ static std::unique_ptr<SparseCholesky> Create(OrderingType ordering_type);
+
+ // SparseCholesky interface.
+ virtual ~AppleAccelerateCholesky();
+ virtual CompressedRowSparseMatrix::StorageType StorageType() const;
+ virtual LinearSolverTerminationType Factorize(CompressedRowSparseMatrix* lhs,
+ std::string* message);
+ virtual LinearSolverTerminationType Solve(const double* rhs,
+ double* solution,
+ std::string* message);
+
+ private:
+ AppleAccelerateCholesky(const OrderingType ordering_type);
+ void FreeSymbolicFactorization();
+ void FreeNumericFactorization();
+
+ const OrderingType ordering_type_;
+ AccelerateSparse<Scalar> as_;
+ std::unique_ptr<typename AccelerateSparse<Scalar>::SymbolicFactorization>
+ symbolic_factor_;
+ std::unique_ptr<typename AccelerateSparse<Scalar>::NumericFactorization>
+ numeric_factor_;
+ // Copy of rhs/solution if Scalar != double (necessitating a copy).
+ Eigen::Matrix<Scalar, Eigen::Dynamic, 1> scalar_rhs_and_solution_;
+};
+
+}
+}
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
+#endif // CERES_INTERNAL_ACCELERATE_SPARSE_H_
diff --git a/internal/ceres/dynamic_sparse_normal_cholesky_solver.h b/internal/ceres/dynamic_sparse_normal_cholesky_solver.h
index 7032ce7..17be90c 100644
--- a/internal/ceres/dynamic_sparse_normal_cholesky_solver.h
+++ b/internal/ceres/dynamic_sparse_normal_cholesky_solver.h
@@ -48,6 +48,9 @@
// sparsity is not constant across calls to Solve. This means that
// there is no benefit to symbolically factorizing the matrix and
// caching this factorization.
+//
+// TODO(alex): Add support for Accelerate sparse solvers:
+// https://github.com/ceres-solver/ceres-solver/issues/397
class DynamicSparseNormalCholeskySolver
: public CompressedRowSparseMatrixSolver {
public:
diff --git a/internal/ceres/generate_bundle_adjustment_tests.py b/internal/ceres/generate_bundle_adjustment_tests.py
index 86452b5..2f3375a 100644
--- a/internal/ceres/generate_bundle_adjustment_tests.py
+++ b/internal/ceres/generate_bundle_adjustment_tests.py
@@ -49,15 +49,19 @@
('ITERATIVE_SCHUR', 'SUITE_SPARSE', 'CLUSTER_JACOBI'),
('ITERATIVE_SCHUR', 'EIGEN_SPARSE', 'CLUSTER_JACOBI'),
('ITERATIVE_SCHUR', 'CX_SPARSE', 'CLUSTER_JACOBI'),
+ ('ITERATIVE_SCHUR', 'ACCELERATE_SPARSE','CLUSTER_JACOBI'),
('ITERATIVE_SCHUR', 'SUITE_SPARSE', 'CLUSTER_TRIDIAGONAL'),
('ITERATIVE_SCHUR', 'EIGEN_SPARSE', 'CLUSTER_TRIDIAGONAL'),
('ITERATIVE_SCHUR', 'CX_SPARSE', 'CLUSTER_TRIDIAGONAL'),
+ ('ITERATIVE_SCHUR', 'ACCELERATE_SPARSE','CLUSTER_TRIDIAGONAL'),
('SPARSE_NORMAL_CHOLESKY', 'SUITE_SPARSE', 'IDENTITY'),
('SPARSE_NORMAL_CHOLESKY', 'EIGEN_SPARSE', 'IDENTITY'),
('SPARSE_NORMAL_CHOLESKY', 'CX_SPARSE', 'IDENTITY'),
+ ('SPARSE_NORMAL_CHOLESKY', 'ACCELERATE_SPARSE','IDENTITY'),
('SPARSE_SCHUR', 'SUITE_SPARSE', 'IDENTITY'),
('SPARSE_SCHUR', 'EIGEN_SPARSE', 'IDENTITY'),
('SPARSE_SCHUR', 'CX_SPARSE', 'IDENTITY'),
+ ('SPARSE_SCHUR', 'ACCELERATE_SPARSE','IDENTITY'),
]
FILENAME_SHORTENING_MAP = dict(
@@ -69,6 +73,7 @@
SUITE_SPARSE='suitesparse',
EIGEN_SPARSE='eigensparse',
CX_SPARSE='cxsparse',
+ ACCELERATE_SPARSE='acceleratesparse',
IDENTITY='identity',
JACOBI='jacobi',
SCHUR_JACOBI='schurjacobi',
@@ -192,6 +197,9 @@
elif sparse_backend == 'CX_SPARSE':
preprocessor_conditions_begin.append('#ifndef CERES_NO_CXSPARSE')
preprocessor_conditions_end.insert(0, '#endif // CERES_NO_CXSPARSE')
+ elif sparse_backend == 'ACCELERATE_SPARSE':
+ preprocessor_conditions_begin.append('#ifndef CERES_NO_ACCELERATE_SPARSE')
+ preprocessor_conditions_end.insert(0, '#endif // CERES_NO_ACCELERATE_SPARSE')
elif sparse_backend == 'EIGEN_SPARSE':
preprocessor_conditions_begin.append('#ifdef CERES_USE_EIGEN_SPARSE')
preprocessor_conditions_end.insert(0, '#endif // CERES_USE_EIGEN_SPARSE')
diff --git a/internal/ceres/generated_bundle_adjustment_tests/CMakeLists.txt b/internal/ceres/generated_bundle_adjustment_tests/CMakeLists.txt
index 0a9cf59..db2d233 100644
--- a/internal/ceres/generated_bundle_adjustment_tests/CMakeLists.txt
+++ b/internal/ceres/generated_bundle_adjustment_tests/CMakeLists.txt
@@ -59,6 +59,10 @@
ceres_test(ba_iterschur_cxsparse_clustjacobi_auto_threads)
ceres_test(ba_iterschur_cxsparse_clustjacobi_user)
ceres_test(ba_iterschur_cxsparse_clustjacobi_user_threads)
+ceres_test(ba_iterschur_acceleratesparse_clustjacobi_auto)
+ceres_test(ba_iterschur_acceleratesparse_clustjacobi_auto_threads)
+ceres_test(ba_iterschur_acceleratesparse_clustjacobi_user)
+ceres_test(ba_iterschur_acceleratesparse_clustjacobi_user_threads)
ceres_test(ba_iterschur_suitesparse_clusttri_auto)
ceres_test(ba_iterschur_suitesparse_clusttri_auto_threads)
ceres_test(ba_iterschur_suitesparse_clusttri_user)
@@ -71,6 +75,10 @@
ceres_test(ba_iterschur_cxsparse_clusttri_auto_threads)
ceres_test(ba_iterschur_cxsparse_clusttri_user)
ceres_test(ba_iterschur_cxsparse_clusttri_user_threads)
+ceres_test(ba_iterschur_acceleratesparse_clusttri_auto)
+ceres_test(ba_iterschur_acceleratesparse_clusttri_auto_threads)
+ceres_test(ba_iterschur_acceleratesparse_clusttri_user)
+ceres_test(ba_iterschur_acceleratesparse_clusttri_user_threads)
ceres_test(ba_sparsecholesky_suitesparse_auto)
ceres_test(ba_sparsecholesky_suitesparse_auto_threads)
ceres_test(ba_sparsecholesky_suitesparse_user)
@@ -83,6 +91,10 @@
ceres_test(ba_sparsecholesky_cxsparse_auto_threads)
ceres_test(ba_sparsecholesky_cxsparse_user)
ceres_test(ba_sparsecholesky_cxsparse_user_threads)
+ceres_test(ba_sparsecholesky_acceleratesparse_auto)
+ceres_test(ba_sparsecholesky_acceleratesparse_auto_threads)
+ceres_test(ba_sparsecholesky_acceleratesparse_user)
+ceres_test(ba_sparsecholesky_acceleratesparse_user_threads)
ceres_test(ba_sparseschur_suitesparse_auto)
ceres_test(ba_sparseschur_suitesparse_auto_threads)
ceres_test(ba_sparseschur_suitesparse_user)
@@ -95,3 +107,7 @@
ceres_test(ba_sparseschur_cxsparse_auto_threads)
ceres_test(ba_sparseschur_cxsparse_user)
ceres_test(ba_sparseschur_cxsparse_user_threads)
+ceres_test(ba_sparseschur_acceleratesparse_auto)
+ceres_test(ba_sparseschur_acceleratesparse_auto_threads)
+ceres_test(ba_sparseschur_acceleratesparse_user)
+ceres_test(ba_sparseschur_acceleratesparse_user_threads)
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_auto_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_auto_test.cc
new file mode 100644
index 0000000..30443af
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_auto_test.cc
@@ -0,0 +1,65 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ IterativeSchur_AccelerateSparse_ClusterJacobi_AutomaticOrdering) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 1;
+ options->linear_solver_type = ITERATIVE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = CLUSTER_JACOBI;
+ if (kAutomaticOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_auto_threads_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_auto_threads_test.cc
new file mode 100644
index 0000000..f61e1d6
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_auto_threads_test.cc
@@ -0,0 +1,67 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+#ifndef CERES_NO_THREADS
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ IterativeSchur_AccelerateSparse_ClusterJacobi_AutomaticOrdering_Threads) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 4;
+ options->linear_solver_type = ITERATIVE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = CLUSTER_JACOBI;
+ if (kAutomaticOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_THREADS
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_user_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_user_test.cc
new file mode 100644
index 0000000..6de1e4b
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_user_test.cc
@@ -0,0 +1,65 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ IterativeSchur_AccelerateSparse_ClusterJacobi_UserOrdering) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 1;
+ options->linear_solver_type = ITERATIVE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = CLUSTER_JACOBI;
+ if (kUserOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_user_threads_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_user_threads_test.cc
new file mode 100644
index 0000000..74cb674
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clustjacobi_user_threads_test.cc
@@ -0,0 +1,67 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+#ifndef CERES_NO_THREADS
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ IterativeSchur_AccelerateSparse_ClusterJacobi_UserOrdering_Threads) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 4;
+ options->linear_solver_type = ITERATIVE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = CLUSTER_JACOBI;
+ if (kUserOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_THREADS
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_auto_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_auto_test.cc
new file mode 100644
index 0000000..4168466
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_auto_test.cc
@@ -0,0 +1,65 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ IterativeSchur_AccelerateSparse_ClusterTridiagonal_AutomaticOrdering) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 1;
+ options->linear_solver_type = ITERATIVE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = CLUSTER_TRIDIAGONAL;
+ if (kAutomaticOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_auto_threads_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_auto_threads_test.cc
new file mode 100644
index 0000000..11c962b
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_auto_threads_test.cc
@@ -0,0 +1,67 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+#ifndef CERES_NO_THREADS
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ IterativeSchur_AccelerateSparse_ClusterTridiagonal_AutomaticOrdering_Threads) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 4;
+ options->linear_solver_type = ITERATIVE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = CLUSTER_TRIDIAGONAL;
+ if (kAutomaticOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_THREADS
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_user_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_user_test.cc
new file mode 100644
index 0000000..b8cb11d
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_user_test.cc
@@ -0,0 +1,65 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ IterativeSchur_AccelerateSparse_ClusterTridiagonal_UserOrdering) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 1;
+ options->linear_solver_type = ITERATIVE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = CLUSTER_TRIDIAGONAL;
+ if (kUserOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_user_threads_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_user_threads_test.cc
new file mode 100644
index 0000000..ff2e8de
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_iterschur_acceleratesparse_clusttri_user_threads_test.cc
@@ -0,0 +1,67 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+#ifndef CERES_NO_THREADS
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ IterativeSchur_AccelerateSparse_ClusterTridiagonal_UserOrdering_Threads) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 4;
+ options->linear_solver_type = ITERATIVE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = CLUSTER_TRIDIAGONAL;
+ if (kUserOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_THREADS
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_auto_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_auto_test.cc
new file mode 100644
index 0000000..4683d2b
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_auto_test.cc
@@ -0,0 +1,65 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ SparseNormalCholesky_AccelerateSparse_AutomaticOrdering) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 1;
+ options->linear_solver_type = SPARSE_NORMAL_CHOLESKY;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = IDENTITY;
+ if (kAutomaticOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_auto_threads_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_auto_threads_test.cc
new file mode 100644
index 0000000..1b63415
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_auto_threads_test.cc
@@ -0,0 +1,67 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+#ifndef CERES_NO_THREADS
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ SparseNormalCholesky_AccelerateSparse_AutomaticOrdering_Threads) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 4;
+ options->linear_solver_type = SPARSE_NORMAL_CHOLESKY;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = IDENTITY;
+ if (kAutomaticOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_THREADS
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_user_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_user_test.cc
new file mode 100644
index 0000000..bdc7d62
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_user_test.cc
@@ -0,0 +1,65 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ SparseNormalCholesky_AccelerateSparse_UserOrdering) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 1;
+ options->linear_solver_type = SPARSE_NORMAL_CHOLESKY;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = IDENTITY;
+ if (kUserOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_user_threads_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_user_threads_test.cc
new file mode 100644
index 0000000..36567f1
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_sparsecholesky_acceleratesparse_user_threads_test.cc
@@ -0,0 +1,67 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+#ifndef CERES_NO_THREADS
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ SparseNormalCholesky_AccelerateSparse_UserOrdering_Threads) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 4;
+ options->linear_solver_type = SPARSE_NORMAL_CHOLESKY;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = IDENTITY;
+ if (kUserOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_THREADS
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_auto_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_auto_test.cc
new file mode 100644
index 0000000..b43a26a
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_auto_test.cc
@@ -0,0 +1,65 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ SparseSchur_AccelerateSparse_AutomaticOrdering) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 1;
+ options->linear_solver_type = SPARSE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = IDENTITY;
+ if (kAutomaticOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_auto_threads_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_auto_threads_test.cc
new file mode 100644
index 0000000..7e330c4
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_auto_threads_test.cc
@@ -0,0 +1,67 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+#ifndef CERES_NO_THREADS
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ SparseSchur_AccelerateSparse_AutomaticOrdering_Threads) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 4;
+ options->linear_solver_type = SPARSE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = IDENTITY;
+ if (kAutomaticOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_THREADS
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_user_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_user_test.cc
new file mode 100644
index 0000000..b5738b7
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_user_test.cc
@@ -0,0 +1,65 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ SparseSchur_AccelerateSparse_UserOrdering) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 1;
+ options->linear_solver_type = SPARSE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = IDENTITY;
+ if (kUserOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_user_threads_test.cc b/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_user_threads_test.cc
new file mode 100644
index 0000000..b5c6105
--- /dev/null
+++ b/internal/ceres/generated_bundle_adjustment_tests/ba_sparseschur_acceleratesparse_user_threads_test.cc
@@ -0,0 +1,67 @@
+// Ceres Solver - A fast non-linear least squares minimizer
+// Copyright 2018 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.
+//
+// ========================================
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// THIS FILE IS AUTOGENERATED. DO NOT EDIT.
+// ========================================
+//
+// This file is generated using generate_bundle_adjustment_tests.py.
+
+#include "bundle_adjustment_test_util.h"
+
+#ifndef CERES_NO_ACCELERATE_SPARSE
+#ifndef CERES_NO_THREADS
+
+namespace ceres {
+namespace internal {
+
+TEST_F(BundleAdjustmentTest,
+ SparseSchur_AccelerateSparse_UserOrdering_Threads) { // NOLINT
+ BundleAdjustmentProblem bundle_adjustment_problem;
+ Solver::Options* options =
+ bundle_adjustment_problem.mutable_solver_options();
+ options->num_threads = 4;
+ options->linear_solver_type = SPARSE_SCHUR;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options->preconditioner_type = IDENTITY;
+ if (kUserOrdering) {
+ options->linear_solver_ordering.reset();
+ }
+ Problem* problem = bundle_adjustment_problem.mutable_problem();
+ RunSolverForConfigAndExpectResidualsMatch(*options, problem);
+}
+
+} // namespace internal
+} // namespace ceres
+
+#endif // CERES_NO_THREADS
+#endif // CERES_NO_ACCELERATE_SPARSE
+
diff --git a/internal/ceres/linear_solver.cc b/internal/ceres/linear_solver.cc
index da14d3d..107af6a 100644
--- a/internal/ceres/linear_solver.cc
+++ b/internal/ceres/linear_solver.cc
@@ -78,9 +78,7 @@
return new CgnrSolver(options);
case SPARSE_NORMAL_CHOLESKY:
-#if defined(CERES_NO_SUITESPARSE) && \
- defined(CERES_NO_CXSPARSE) && \
- !defined(CERES_USE_EIGEN_SPARSE)
+#if defined(CERES_NO_SPARSE)
return NULL;
#else
if (options.dynamic_sparsity) {
@@ -91,9 +89,7 @@
#endif
case SPARSE_SCHUR:
-#if defined(CERES_NO_SUITESPARSE) && \
- defined(CERES_NO_CXSPARSE) && \
- !defined(CERES_USE_EIGEN_SPARSE)
+#if defined(CERES_NO_SPARSE)
return NULL;
#else
return new SparseSchurComplementSolver(options);
diff --git a/internal/ceres/reorder_program.cc b/internal/ceres/reorder_program.cc
index 86c1368..49e0449 100644
--- a/internal/ceres/reorder_program.cc
+++ b/internal/ceres/reorder_program.cc
@@ -568,6 +568,12 @@
OrderingForSparseNormalCholeskyUsingCXSparse(
*tsm_block_jacobian_transpose,
&ordering[0]);
+ } else if (sparse_linear_algebra_library_type == ACCELERATE_SPARSE) {
+ // TODO(alex): Investigate what analysis on pre-ordered matrices
+ // Accelerate supports, but for now disable.
+ // https://github.com/ceres-solver/ceres-solver/issues/394.
+ return true;
+
} else if (sparse_linear_algebra_library_type == EIGEN_SPARSE) {
#if EIGEN_VERSION_AT_LEAST(3, 2, 2)
OrderingForSparseNormalCholeskyUsingEigenSparse(
diff --git a/internal/ceres/schur_complement_solver_test.cc b/internal/ceres/schur_complement_solver_test.cc
index 2350858..a86c8ef 100644
--- a/internal/ceres/schur_complement_solver_test.cc
+++ b/internal/ceres/schur_complement_solver_test.cc
@@ -220,6 +220,20 @@
}
#endif // CERES_NO_CXSPARSE
+#ifndef CERES_NO_ACCELERATE_SPARSE
+TEST_F(SchurComplementSolverTest,
+ SparseSchurWithAccelerateSparseSmallProblem) {
+ ComputeAndCompareSolutions(2, false, SPARSE_SCHUR, EIGEN, ACCELERATE_SPARSE, true);
+ ComputeAndCompareSolutions(2, true, SPARSE_SCHUR, EIGEN, ACCELERATE_SPARSE, true);
+}
+
+TEST_F(SchurComplementSolverTest,
+ SparseSchurWithAccelerateSparseLargeProblem) {
+ ComputeAndCompareSolutions(3, false, SPARSE_SCHUR, EIGEN, ACCELERATE_SPARSE, true);
+ ComputeAndCompareSolutions(3, true, SPARSE_SCHUR, EIGEN, ACCELERATE_SPARSE, true);
+}
+#endif // CERES_NO_ACCELERATE_SPARSE
+
#ifdef CERES_USE_EIGEN_SPARSE
TEST_F(SchurComplementSolverTest,
SparseSchurWithEigenSparseSmallProblem) {
diff --git a/internal/ceres/solver_test.cc b/internal/ceres/solver_test.cc
index 8f68fec..d11fef4 100644
--- a/internal/ceres/solver_test.cc
+++ b/internal/ceres/solver_test.cc
@@ -320,6 +320,24 @@
}
#endif
+#if defined(CERES_NO_ACCELERATE_SPARSE)
+TEST(Solver, SparseNormalCholeskyNoAccelerateSparse) {
+ Solver::Options options;
+ options.sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options.linear_solver_type = SPARSE_NORMAL_CHOLESKY;
+ string message;
+ EXPECT_FALSE(options.IsValid(&message));
+}
+
+TEST(Solver, SparseSchurNoAccelerateSparse) {
+ Solver::Options options;
+ options.sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options.linear_solver_type = SPARSE_SCHUR;
+ string message;
+ EXPECT_FALSE(options.IsValid(&message));
+}
+#endif
+
#if !defined(CERES_USE_EIGEN_SPARSE)
TEST(Solver, SparseNormalCholeskyNoEigenSparse) {
Solver::Options options;
diff --git a/internal/ceres/solver_utils.cc b/internal/ceres/solver_utils.cc
index 084caeb..4b400d3 100644
--- a/internal/ceres/solver_utils.cc
+++ b/internal/ceres/solver_utils.cc
@@ -70,6 +70,10 @@
value += "-cxsparse-(" + std::string(CERES_CXSPARSE_VERSION) + ")";
#endif
+#ifndef CERES_NO_ACCELERATE_SPARSE
+ value += "-acceleratesparse";
+#endif
+
#ifdef CERES_USE_EIGEN_SPARSE
value += "-eigensparse";
#endif
diff --git a/internal/ceres/sparse_cholesky.cc b/internal/ceres/sparse_cholesky.cc
index e18f380..3275cc0 100644
--- a/internal/ceres/sparse_cholesky.cc
+++ b/internal/ceres/sparse_cholesky.cc
@@ -30,6 +30,7 @@
#include "ceres/sparse_cholesky.h"
+#include "ceres/accelerate_sparse.h"
#include "ceres/cxsparse.h"
#include "ceres/eigensparse.h"
#include "ceres/float_cxsparse.h"
@@ -78,10 +79,24 @@
} else {
sparse_cholesky = CXSparseCholesky::Create(ordering_type);
}
+ break;
#else
LOG(FATAL) << "Ceres was compiled without support for CXSparse.";
#endif
+
+ case ACCELERATE_SPARSE:
+#ifndef CERES_NO_ACCELERATE_SPARSE
+ if (options.use_mixed_precision_solves) {
+ sparse_cholesky = AppleAccelerateCholesky<float>::Create(ordering_type);
+ } else {
+ sparse_cholesky = AppleAccelerateCholesky<double>::Create(ordering_type);
+ }
break;
+#else
+ LOG(FATAL) << "Ceres was compiled without support for Apple's Accelerate "
+ << "framework solvers.";
+#endif
+
default:
LOG(FATAL) << "Unknown sparse linear algebra library type : "
<< SparseLinearAlgebraLibraryTypeToString(
diff --git a/internal/ceres/sparse_cholesky_test.cc b/internal/ceres/sparse_cholesky_test.cc
index 34098f3..60dae64 100644
--- a/internal/ceres/sparse_cholesky_test.cc
+++ b/internal/ceres/sparse_cholesky_test.cc
@@ -204,6 +204,22 @@
ParamInfoToString);
#endif
+#ifndef CERES_NO_ACCELERATE_SPARSE
+INSTANTIATE_TEST_CASE_P(AccelerateSparseCholesky,
+ SparseCholeskyTest,
+ ::testing::Combine(::testing::Values(ACCELERATE_SPARSE),
+ ::testing::Values(AMD, NATURAL),
+ ::testing::Values(true, false)),
+ ParamInfoToString);
+
+INSTANTIATE_TEST_CASE_P(AccelerateSparseCholeskySingle,
+ SparseCholeskyTest,
+ ::testing::Combine(::testing::Values(ACCELERATE_SPARSE),
+ ::testing::Values(AMD, NATURAL),
+ ::testing::Values(true, false)),
+ ParamInfoToString);
+#endif
+
#ifdef CERES_USE_EIGEN_SPARSE
INSTANTIATE_TEST_CASE_P(EigenSparseCholesky,
SparseCholeskyTest,
diff --git a/internal/ceres/sparse_normal_cholesky_solver_test.cc b/internal/ceres/sparse_normal_cholesky_solver_test.cc
index 1b836a5..aa9dc62 100644
--- a/internal/ceres/sparse_normal_cholesky_solver_test.cc
+++ b/internal/ceres/sparse_normal_cholesky_solver_test.cc
@@ -154,6 +154,30 @@
}
#endif
+#ifndef CERES_NO_ACCELERATE_SPARSE
+TEST_F(SparseNormalCholeskySolverTest,
+ SparseNormalCholeskyUsingAccelerateSparsePreOrdering) {
+ LinearSolver::Options options;
+ options.sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options.type = SPARSE_NORMAL_CHOLESKY;
+ options.use_postordering = false;
+ ContextImpl context;
+ options.context = &context;
+ TestSolver(options);
+}
+
+TEST_F(SparseNormalCholeskySolverTest,
+ SparseNormalCholeskyUsingAcceleratePostOrdering) {
+ LinearSolver::Options options;
+ options.sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ options.type = SPARSE_NORMAL_CHOLESKY;
+ options.use_postordering = true;
+ ContextImpl context;
+ options.context = &context;
+ TestSolver(options);
+}
+#endif
+
#ifdef CERES_USE_EIGEN_SPARSE
TEST_F(SparseNormalCholeskySolverTest,
SparseNormalCholeskyUsingEigenPreOrdering) {
diff --git a/internal/ceres/subset_preconditioner_test.cc b/internal/ceres/subset_preconditioner_test.cc
index b159e0f..0285680 100644
--- a/internal/ceres/subset_preconditioner_test.cc
+++ b/internal/ceres/subset_preconditioner_test.cc
@@ -182,6 +182,14 @@
ParamInfoToString);
#endif
+#ifndef CERES_NO_ACCELERATE_SPARSE
+INSTANTIATE_TEST_CASE_P(SubsetPreconditionerWithAccelerateSparse,
+ SubsetPreconditionerTest,
+ ::testing::Combine(::testing::Values(ACCELERATE_SPARSE),
+ ::testing::Values(true, false)),
+ ParamInfoToString);
+#endif
+
#ifdef CERES_USE_EIGEN_SPARSE
INSTANTIATE_TEST_CASE_P(SubsetPreconditionerWithEigenSparse,
SubsetPreconditionerTest,
diff --git a/internal/ceres/system_test.cc b/internal/ceres/system_test.cc
index ca0f529..3f635d0 100644
--- a/internal/ceres/system_test.cc
+++ b/internal/ceres/system_test.cc
@@ -201,6 +201,17 @@
}
#endif // CERES_NO_CXSPARSE
+#ifndef CERES_NO_ACCELERATE_SPARSE
+TEST_F(PowellTest, SparseNormalCholeskyUsingAccelerateSparse) {
+ PowellsFunction powells_function;
+ Solver::Options* options = powells_function.mutable_solver_options();
+ options->linear_solver_type = SPARSE_NORMAL_CHOLESKY;
+ options->sparse_linear_algebra_library_type = ACCELERATE_SPARSE;
+ RunSolverForConfigAndExpectResidualsMatch(*options,
+ powells_function.mutable_problem());
+}
+#endif // CERES_NO_ACCELERATE_SPARSE
+
#ifdef CERES_USE_EIGEN_SPARSE
TEST_F(PowellTest, SparseNormalCholeskyUsingEigenSparse) {
PowellsFunction powells_function;
diff --git a/internal/ceres/trust_region_preprocessor_test.cc b/internal/ceres/trust_region_preprocessor_test.cc
index 92162c1..0c91e21 100644
--- a/internal/ceres/trust_region_preprocessor_test.cc
+++ b/internal/ceres/trust_region_preprocessor_test.cc
@@ -200,17 +200,13 @@
PreprocessForGivenLinearSolverAndVerify(DENSE_SCHUR);
}
-#if defined(CERES_USE_EIGEN_SPARSE) || \
- !defined(CERES_NO_SUITESPARSE) || \
- !defined(CERES_NO_CXSPARSE)
+#if !defined(CERES_NO_SPARSE)
TEST_F(LinearSolverAndEvaluatorCreationTest, SparseNormalCholesky) {
PreprocessForGivenLinearSolverAndVerify(SPARSE_NORMAL_CHOLESKY);
}
#endif
-#if defined(CERES_USE_EIGEN_SPARSE) || \
- !defined(CERES_NO_SUITESPARSE) || \
- !defined(CERES_NO_CXSPARSE)
+#if !defined(CERES_NO_SPARSE)
TEST_F(LinearSolverAndEvaluatorCreationTest, SparseSchur) {
PreprocessForGivenLinearSolverAndVerify(SPARSE_SCHUR);
}
diff --git a/internal/ceres/types.cc b/internal/ceres/types.cc
index b833928..932ec7d 100644
--- a/internal/ceres/types.cc
+++ b/internal/ceres/types.cc
@@ -99,6 +99,7 @@
CASESTR(SUITE_SPARSE);
CASESTR(CX_SPARSE);
CASESTR(EIGEN_SPARSE);
+ CASESTR(ACCELERATE_SPARSE);
CASESTR(NO_SPARSE);
default:
return "UNKNOWN";
@@ -112,6 +113,7 @@
STRENUM(SUITE_SPARSE);
STRENUM(CX_SPARSE);
STRENUM(EIGEN_SPARSE);
+ STRENUM(ACCELERATE_SPARSE);
STRENUM(NO_SPARSE);
return false;
}
@@ -361,6 +363,14 @@
#endif
}
+ if (type == ACCELERATE_SPARSE) {
+#ifdef CERES_NO_ACCELERATE_SPARSE
+ return false;
+#else
+ return true;
+#endif
+ }
+
if (type == EIGEN_SPARSE) {
#ifdef CERES_USE_EIGEN_SPARSE
return true;