Replace scoped_ptr with C++11's unique_ptr
Change-Id: Ib5a504c491e3a79af52a95accf009df473470c6b
diff --git a/cmake/config.h.in b/cmake/config.h.in
index c712050..32c4a52 100644
--- a/cmake/config.h.in
+++ b/cmake/config.h.in
@@ -69,9 +69,6 @@
// If defined Ceres was compiled with C++11 thread support.
@CERES_USE_CXX11_THREADS@
-// If defined, the memory header is in <tr1/memory>, otherwise <memory>.
-@CERES_TR1_MEMORY_HEADER@
-
// If defined, Ceres was built as a shared library.
@CERES_USING_SHARED_LIBRARY@
diff --git a/docs/source/numerical_derivatives.rst b/docs/source/numerical_derivatives.rst
index c52c039..9edc008 100644
--- a/docs/source/numerical_derivatives.rst
+++ b/docs/source/numerical_derivatives.rst
@@ -125,7 +125,7 @@
}
private:
- scoped_ptr<Rat43Functor> functor_;
+ std::unique_ptr<Rat43Functor> functor_;
};
diff --git a/include/ceres/autodiff_cost_function.h b/include/ceres/autodiff_cost_function.h
index 490fb3d..a106e3e 100644
--- a/include/ceres/autodiff_cost_function.h
+++ b/include/ceres/autodiff_cost_function.h
@@ -129,8 +129,8 @@
#ifndef CERES_PUBLIC_AUTODIFF_COST_FUNCTION_H_
#define CERES_PUBLIC_AUTODIFF_COST_FUNCTION_H_
+#include <memory>
#include "ceres/internal/autodiff.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/sized_cost_function.h"
#include "ceres/types.h"
#include "glog/logging.h"
@@ -219,7 +219,7 @@
}
private:
- internal::scoped_ptr<CostFunctor> functor_;
+ std::unique_ptr<CostFunctor> functor_;
};
} // namespace ceres
diff --git a/include/ceres/autodiff_local_parameterization.h b/include/ceres/autodiff_local_parameterization.h
index 27397e2..257e937 100644
--- a/include/ceres/autodiff_local_parameterization.h
+++ b/include/ceres/autodiff_local_parameterization.h
@@ -33,9 +33,9 @@
#ifndef CERES_PUBLIC_AUTODIFF_LOCAL_PARAMETERIZATION_H_
#define CERES_PUBLIC_AUTODIFF_LOCAL_PARAMETERIZATION_H_
+#include <memory>
#include "ceres/local_parameterization.h"
#include "ceres/internal/autodiff.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
@@ -146,7 +146,7 @@
virtual int LocalSize() const { return kLocalSize; }
private:
- internal::scoped_ptr<Functor> functor_;
+ std::unique_ptr<Functor> functor_;
};
} // namespace ceres
diff --git a/include/ceres/conditioned_cost_function.h b/include/ceres/conditioned_cost_function.h
index 29597d9..e5f5fc4 100644
--- a/include/ceres/conditioned_cost_function.h
+++ b/include/ceres/conditioned_cost_function.h
@@ -36,8 +36,8 @@
#include <vector>
+#include <memory>
#include "ceres/cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
#include "ceres/internal/disable_warnings.h"
@@ -87,7 +87,7 @@
double** jacobians) const;
private:
- internal::scoped_ptr<CostFunction> wrapped_cost_function_;
+ std::unique_ptr<CostFunction> wrapped_cost_function_;
std::vector<CostFunction*> conditioners_;
Ownership ownership_;
};
diff --git a/include/ceres/cost_function_to_functor.h b/include/ceres/cost_function_to_functor.h
index d2dc947..8e30543 100644
--- a/include/ceres/cost_function_to_functor.h
+++ b/include/ceres/cost_function_to_functor.h
@@ -94,7 +94,6 @@
#include "ceres/dynamic_cost_function_to_functor.h"
#include "ceres/internal/fixed_array.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
diff --git a/include/ceres/covariance.h b/include/ceres/covariance.h
index 685e9f0..971175c 100644
--- a/include/ceres/covariance.h
+++ b/include/ceres/covariance.h
@@ -31,11 +31,11 @@
#ifndef CERES_PUBLIC_COVARIANCE_H_
#define CERES_PUBLIC_COVARIANCE_H_
+#include <memory>
#include <utility>
#include <vector>
#include "ceres/internal/disable_warnings.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
namespace ceres {
@@ -457,7 +457,7 @@
double* covariance_matrix);
private:
- internal::scoped_ptr<internal::CovarianceImpl> impl_;
+ std::unique_ptr<internal::CovarianceImpl> impl_;
};
} // namespace ceres
diff --git a/include/ceres/dynamic_autodiff_cost_function.h b/include/ceres/dynamic_autodiff_cost_function.h
index 4a31236..f1eb0d3 100644
--- a/include/ceres/dynamic_autodiff_cost_function.h
+++ b/include/ceres/dynamic_autodiff_cost_function.h
@@ -36,8 +36,8 @@
#include <numeric>
#include <vector>
+#include <memory>
#include "ceres/dynamic_cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/jet.h"
#include "glog/logging.h"
@@ -244,7 +244,7 @@
}
private:
- internal::scoped_ptr<CostFunctor> functor_;
+ std::unique_ptr<CostFunctor> functor_;
};
} // namespace ceres
diff --git a/include/ceres/dynamic_cost_function_to_functor.h b/include/ceres/dynamic_cost_function_to_functor.h
index 10bc99a..f6ff888 100644
--- a/include/ceres/dynamic_cost_function_to_functor.h
+++ b/include/ceres/dynamic_cost_function_to_functor.h
@@ -32,13 +32,13 @@
#ifndef CERES_PUBLIC_DYNAMIC_COST_FUNCTION_TO_FUNCTOR_H_
#define CERES_PUBLIC_DYNAMIC_COST_FUNCTION_TO_FUNCTOR_H_
+#include <memory>
#include <numeric>
#include <vector>
#include "ceres/dynamic_cost_function.h"
#include "ceres/internal/fixed_array.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
@@ -182,7 +182,7 @@
}
private:
- internal::scoped_ptr<CostFunction> cost_function_;
+ std::unique_ptr<CostFunction> cost_function_;
};
} // namespace ceres
diff --git a/include/ceres/dynamic_numeric_diff_cost_function.h b/include/ceres/dynamic_numeric_diff_cost_function.h
index a011ac3..4c2766f 100644
--- a/include/ceres/dynamic_numeric_diff_cost_function.h
+++ b/include/ceres/dynamic_numeric_diff_cost_function.h
@@ -35,11 +35,11 @@
#define CERES_PUBLIC_DYNAMIC_NUMERIC_DIFF_COST_FUNCTION_H_
#include <cmath>
+#include <memory>
#include <numeric>
#include <vector>
#include "ceres/dynamic_cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/numeric_diff.h"
#include "ceres/numeric_diff_options.h"
@@ -170,7 +170,7 @@
return functor->Evaluate(parameters, residuals, NULL);
}
- internal::scoped_ptr<const CostFunctor> functor_;
+ std::unique_ptr<const CostFunctor> functor_;
Ownership ownership_;
NumericDiffOptions options_;
};
diff --git a/include/ceres/gradient_checker.h b/include/ceres/gradient_checker.h
index c8ac729..48f7bc4 100644
--- a/include/ceres/gradient_checker.h
+++ b/include/ceres/gradient_checker.h
@@ -34,15 +34,15 @@
#ifndef CERES_PUBLIC_GRADIENT_CHECKER_H_
#define CERES_PUBLIC_GRADIENT_CHECKER_H_
-#include <vector>
+#include <memory>
#include <string>
+#include <vector>
#include "ceres/cost_function.h"
#include "ceres/dynamic_numeric_diff_cost_function.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/fixed_array.h"
#include "ceres/internal/macros.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/local_parameterization.h"
#include "glog/logging.h"
@@ -141,7 +141,7 @@
std::vector<const LocalParameterization*> local_parameterizations_;
const CostFunction* function_;
- internal::scoped_ptr<CostFunction> finite_diff_cost_function_;
+ std::unique_ptr<CostFunction> finite_diff_cost_function_;
};
} // namespace ceres
diff --git a/include/ceres/gradient_problem.h b/include/ceres/gradient_problem.h
index 1226a4c..2a08c5d 100644
--- a/include/ceres/gradient_problem.h
+++ b/include/ceres/gradient_problem.h
@@ -31,9 +31,9 @@
#ifndef CERES_PUBLIC_GRADIENT_PROBLEM_H_
#define CERES_PUBLIC_GRADIENT_PROBLEM_H_
+#include <memory>
#include "ceres/internal/macros.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/local_parameterization.h"
namespace ceres {
@@ -105,9 +105,9 @@
bool Plus(const double* x, const double* delta, double* x_plus_delta) const;
private:
- internal::scoped_ptr<FirstOrderFunction> function_;
- internal::scoped_ptr<LocalParameterization> parameterization_;
- internal::scoped_array<double> scratch_;
+ std::unique_ptr<FirstOrderFunction> function_;
+ std::unique_ptr<LocalParameterization> parameterization_;
+ std::unique_ptr<double[]> scratch_;
};
// A FirstOrderFunction object implements the evaluation of a function
diff --git a/include/ceres/internal/numeric_diff.h b/include/ceres/internal/numeric_diff.h
index 11e8275..ab1abc0 100644
--- a/include/ceres/internal/numeric_diff.h
+++ b/include/ceres/internal/numeric_diff.h
@@ -41,7 +41,6 @@
#include "Eigen/StdVector"
#include "ceres/cost_function.h"
#include "ceres/internal/fixed_array.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/internal/variadic_evaluate.h"
#include "ceres/numeric_diff_options.h"
#include "ceres/types.h"
diff --git a/include/ceres/internal/port.h b/include/ceres/internal/port.h
index f0f706c..9aa041a 100644
--- a/include/ceres/internal/port.h
+++ b/include/ceres/internal/port.h
@@ -56,12 +56,6 @@
# error One of CERES_USE_OPENMP, CERES_USE_TBB,CERES_USE_CXX11_THREADS or CERES_NO_THREADS must be defined.
#endif
-#if defined(CERES_TR1_MEMORY_HEADER)
-#include <tr1/memory>
-#else
-#include <memory>
-#endif
-
namespace ceres {
// We allocate some Eigen objects on the stack and other places they
diff --git a/include/ceres/internal/scoped_ptr.h b/include/ceres/internal/scoped_ptr.h
deleted file mode 100644
index fa0ac25..0000000
--- a/include/ceres/internal/scoped_ptr.h
+++ /dev/null
@@ -1,310 +0,0 @@
-// Ceres Solver - A fast non-linear least squares minimizer
-// Copyright 2015 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: jorg@google.com (Jorg Brown)
-//
-// This is an implementation designed to match the anticipated future TR2
-// implementation of the scoped_ptr class, and its closely-related brethren,
-// scoped_array, scoped_ptr_malloc, and make_scoped_ptr.
-
-#ifndef CERES_PUBLIC_INTERNAL_SCOPED_PTR_H_
-#define CERES_PUBLIC_INTERNAL_SCOPED_PTR_H_
-
-#include <assert.h>
-#include <stdlib.h>
-#include <cstddef>
-#include <algorithm>
-
-namespace ceres {
-namespace internal {
-
-template <class C> class scoped_ptr;
-template <class C, class Free> class scoped_ptr_malloc;
-template <class C> class scoped_array;
-
-template <class C>
-scoped_ptr<C> make_scoped_ptr(C *);
-
-// A scoped_ptr<T> is like a T*, except that the destructor of
-// scoped_ptr<T> automatically deletes the pointer it holds (if
-// any). That is, scoped_ptr<T> owns the T object that it points
-// to. Like a T*, a scoped_ptr<T> may hold either NULL or a pointer to
-// a T object. Also like T*, scoped_ptr<T> is thread-compatible, and
-// once you dereference it, you get the threadsafety guarantees of T.
-//
-// The size of a scoped_ptr is small: sizeof(scoped_ptr<C>) == sizeof(C*)
-template <class C>
-class scoped_ptr {
- public:
- // The element type
- typedef C element_type;
-
- // Constructor. Defaults to intializing with NULL.
- // There is no way to create an uninitialized scoped_ptr.
- // The input parameter must be allocated with new.
- explicit scoped_ptr(C* p = NULL) : ptr_(p) { }
-
- // Destructor. If there is a C object, delete it.
- // We don't need to test ptr_ == NULL because C++ does that for us.
- ~scoped_ptr() {
- enum { type_must_be_complete = sizeof(C) };
- delete ptr_;
- }
-
- // Reset. Deletes the current owned object, if any.
- // Then takes ownership of a new object, if given.
- // this->reset(this->get()) works.
- void reset(C* p = NULL) {
- if (p != ptr_) {
- enum { type_must_be_complete = sizeof(C) };
- delete ptr_;
- ptr_ = p;
- }
- }
-
- // Accessors to get the owned object.
- // operator* and operator-> will assert() if there is no current object.
- C& operator*() const {
- assert(ptr_ != NULL);
- return *ptr_;
- }
- C* operator->() const {
- assert(ptr_ != NULL);
- return ptr_;
- }
- C* get() const { return ptr_; }
-
- // Comparison operators.
- // These return whether a scoped_ptr and a raw pointer refer to
- // the same object, not just to two different but equal objects.
- bool operator==(const C* p) const { return ptr_ == p; }
- bool operator!=(const C* p) const { return ptr_ != p; }
-
- // Swap two scoped pointers.
- void swap(scoped_ptr& p2) {
- C* tmp = ptr_;
- ptr_ = p2.ptr_;
- p2.ptr_ = tmp;
- }
-
- // Release a pointer.
- // The return value is the current pointer held by this object.
- // If this object holds a NULL pointer, the return value is NULL.
- // After this operation, this object will hold a NULL pointer,
- // and will not own the object any more.
- C* release() {
- C* retVal = ptr_;
- ptr_ = NULL;
- return retVal;
- }
-
- private:
- C* ptr_;
-
- // google3 friend class that can access copy ctor (although if it actually
- // calls a copy ctor, there will be a problem) see below
- friend scoped_ptr<C> make_scoped_ptr<C>(C *p);
-
- // Forbid comparison of scoped_ptr types. If C2 != C, it totally doesn't
- // make sense, and if C2 == C, it still doesn't make sense because you should
- // never have the same object owned by two different scoped_ptrs.
- template <class C2> bool operator==(scoped_ptr<C2> const& p2) const;
- template <class C2> bool operator!=(scoped_ptr<C2> const& p2) const;
-
- // Disallow evil constructors
- scoped_ptr(const scoped_ptr&);
- void operator=(const scoped_ptr&);
-};
-
-// Free functions
-template <class C>
-inline void swap(scoped_ptr<C>& p1, scoped_ptr<C>& p2) {
- p1.swap(p2);
-}
-
-template <class C>
-inline bool operator==(const C* p1, const scoped_ptr<C>& p2) {
- return p1 == p2.get();
-}
-
-template <class C>
-inline bool operator==(const C* p1, const scoped_ptr<const C>& p2) {
- return p1 == p2.get();
-}
-
-template <class C>
-inline bool operator!=(const C* p1, const scoped_ptr<C>& p2) {
- return p1 != p2.get();
-}
-
-template <class C>
-inline bool operator!=(const C* p1, const scoped_ptr<const C>& p2) {
- return p1 != p2.get();
-}
-
-template <class C>
-scoped_ptr<C> make_scoped_ptr(C *p) {
- // This does nothing but to return a scoped_ptr of the type that the passed
- // pointer is of. (This eliminates the need to specify the name of T when
- // making a scoped_ptr that is used anonymously/temporarily.) From an
- // access control point of view, we construct an unnamed scoped_ptr here
- // which we return and thus copy-construct. Hence, we need to have access
- // to scoped_ptr::scoped_ptr(scoped_ptr const &). However, it is guaranteed
- // that we never actually call the copy constructor, which is a good thing
- // as we would call the temporary's object destructor (and thus delete p)
- // if we actually did copy some object, here.
- return scoped_ptr<C>(p);
-}
-
-// scoped_array<C> is like scoped_ptr<C>, except that the caller must allocate
-// with new [] and the destructor deletes objects with delete [].
-//
-// As with scoped_ptr<C>, a scoped_array<C> either points to an object
-// or is NULL. A scoped_array<C> owns the object that it points to.
-// scoped_array<T> is thread-compatible, and once you index into it,
-// the returned objects have only the threadsafety guarantees of T.
-//
-// Size: sizeof(scoped_array<C>) == sizeof(C*)
-template <class C>
-class scoped_array {
- public:
- // The element type
- typedef C element_type;
-
- // Constructor. Defaults to intializing with NULL.
- // There is no way to create an uninitialized scoped_array.
- // The input parameter must be allocated with new [].
- explicit scoped_array(C* p = NULL) : array_(p) { }
-
- // Destructor. If there is a C object, delete it.
- // We don't need to test ptr_ == NULL because C++ does that for us.
- ~scoped_array() {
- enum { type_must_be_complete = sizeof(C) };
- delete[] array_;
- }
-
- // Reset. Deletes the current owned object, if any.
- // Then takes ownership of a new object, if given.
- // this->reset(this->get()) works.
- void reset(C* p = NULL) {
- if (p != array_) {
- enum { type_must_be_complete = sizeof(C) };
- delete[] array_;
- array_ = p;
- }
- }
-
- // Get one element of the current object.
- // Will assert() if there is no current object, or index i is negative.
- C& operator[](std::ptrdiff_t i) const {
- assert(i >= 0);
- assert(array_ != NULL);
- return array_[i];
- }
-
- // Get a pointer to the zeroth element of the current object.
- // If there is no current object, return NULL.
- C* get() const {
- return array_;
- }
-
- // Comparison operators.
- // These return whether a scoped_array and a raw pointer refer to
- // the same array, not just to two different but equal arrays.
- bool operator==(const C* p) const { return array_ == p; }
- bool operator!=(const C* p) const { return array_ != p; }
-
- // Swap two scoped arrays.
- void swap(scoped_array& p2) {
- C* tmp = array_;
- array_ = p2.array_;
- p2.array_ = tmp;
- }
-
- // Release an array.
- // The return value is the current pointer held by this object.
- // If this object holds a NULL pointer, the return value is NULL.
- // After this operation, this object will hold a NULL pointer,
- // and will not own the object any more.
- C* release() {
- C* retVal = array_;
- array_ = NULL;
- return retVal;
- }
-
- private:
- C* array_;
-
- // Forbid comparison of different scoped_array types.
- template <class C2> bool operator==(scoped_array<C2> const& p2) const;
- template <class C2> bool operator!=(scoped_array<C2> const& p2) const;
-
- // Disallow evil constructors
- scoped_array(const scoped_array&);
- void operator=(const scoped_array&);
-};
-
-// Free functions
-template <class C>
-inline void swap(scoped_array<C>& p1, scoped_array<C>& p2) {
- p1.swap(p2);
-}
-
-template <class C>
-inline bool operator==(const C* p1, const scoped_array<C>& p2) {
- return p1 == p2.get();
-}
-
-template <class C>
-inline bool operator==(const C* p1, const scoped_array<const C>& p2) {
- return p1 == p2.get();
-}
-
-template <class C>
-inline bool operator!=(const C* p1, const scoped_array<C>& p2) {
- return p1 != p2.get();
-}
-
-template <class C>
-inline bool operator!=(const C* p1, const scoped_array<const C>& p2) {
- return p1 != p2.get();
-}
-
-// This class wraps the c library function free() in a class that can be
-// passed as a template argument to scoped_ptr_malloc below.
-class ScopedPtrMallocFree {
- public:
- inline void operator()(void* x) const {
- free(x);
- }
-};
-
-} // namespace internal
-} // namespace ceres
-
-#endif // CERES_PUBLIC_INTERNAL_SCOPED_PTR_H_
diff --git a/include/ceres/local_parameterization.h b/include/ceres/local_parameterization.h
index 8a4ca56..fd13c0e 100644
--- a/include/ceres/local_parameterization.h
+++ b/include/ceres/local_parameterization.h
@@ -34,7 +34,6 @@
#include <vector>
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/internal/disable_warnings.h"
namespace ceres {
diff --git a/include/ceres/loss_function.h b/include/ceres/loss_function.h
index 0512c13..1f057e6 100644
--- a/include/ceres/loss_function.h
+++ b/include/ceres/loss_function.h
@@ -75,9 +75,9 @@
#ifndef CERES_PUBLIC_LOSS_FUNCTION_H_
#define CERES_PUBLIC_LOSS_FUNCTION_H_
+#include <memory>
#include "glog/logging.h"
#include "ceres/internal/macros.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
#include "ceres/internal/disable_warnings.h"
@@ -303,7 +303,7 @@
virtual void Evaluate(double, double*) const;
private:
- internal::scoped_ptr<const LossFunction> f_, g_;
+ std::unique_ptr<const LossFunction> f_, g_;
const Ownership ownership_f_, ownership_g_;
};
@@ -340,7 +340,7 @@
virtual void Evaluate(double, double*) const;
private:
- internal::scoped_ptr<const LossFunction> rho_;
+ std::unique_ptr<const LossFunction> rho_;
const double a_;
const Ownership ownership_;
CERES_DISALLOW_COPY_AND_ASSIGN(ScaledLoss);
@@ -416,7 +416,7 @@
}
private:
- internal::scoped_ptr<const LossFunction> rho_;
+ std::unique_ptr<const LossFunction> rho_;
Ownership ownership_;
CERES_DISALLOW_COPY_AND_ASSIGN(LossFunctionWrapper);
};
diff --git a/include/ceres/numeric_diff_cost_function.h b/include/ceres/numeric_diff_cost_function.h
index 5dfaeab..7cab267 100644
--- a/include/ceres/numeric_diff_cost_function.h
+++ b/include/ceres/numeric_diff_cost_function.h
@@ -161,10 +161,10 @@
#ifndef CERES_PUBLIC_NUMERIC_DIFF_COST_FUNCTION_H_
#define CERES_PUBLIC_NUMERIC_DIFF_COST_FUNCTION_H_
+#include <memory>
#include "Eigen/Dense"
#include "ceres/cost_function.h"
#include "ceres/internal/numeric_diff.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/numeric_diff_options.h"
#include "ceres/sized_cost_function.h"
#include "ceres/types.h"
@@ -309,7 +309,7 @@
}
private:
- internal::scoped_ptr<CostFunctor> functor_;
+ std::unique_ptr<CostFunctor> functor_;
Ownership ownership_;
NumericDiffOptions options_;
};
diff --git a/include/ceres/problem.h b/include/ceres/problem.h
index e941fff..344685d 100644
--- a/include/ceres/problem.h
+++ b/include/ceres/problem.h
@@ -36,6 +36,7 @@
#include <cstddef>
#include <map>
+#include <memory>
#include <set>
#include <vector>
@@ -43,7 +44,6 @@
#include "ceres/internal/disable_warnings.h"
#include "ceres/internal/macros.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
#include "glog/logging.h"
@@ -485,7 +485,7 @@
private:
friend class Solver;
friend class Covariance;
- internal::scoped_ptr<internal::ProblemImpl> problem_impl_;
+ std::unique_ptr<internal::ProblemImpl> problem_impl_;
CERES_DISALLOW_COPY_AND_ASSIGN(Problem);
};
diff --git a/internal/ceres/autodiff_cost_function_test.cc b/internal/ceres/autodiff_cost_function_test.cc
index d14fb82..1192808 100644
--- a/internal/ceres/autodiff_cost_function_test.cc
+++ b/internal/ceres/autodiff_cost_function_test.cc
@@ -31,6 +31,7 @@
#include "ceres/autodiff_cost_function.h"
#include <cstddef>
+#include <memory>
#include "gtest/gtest.h"
#include "ceres/cost_function.h"
@@ -158,7 +159,7 @@
double* parameters[] = {¶meter};
double* jacobians[] = {jacobian};
- scoped_ptr<CostFunction> cost_function(
+ std::unique_ptr<CostFunction> cost_function(
new AutoDiffCostFunction<OnlyFillsOneOutputFunctor, 2, 1>(
new OnlyFillsOneOutputFunctor));
InvalidateArray(2, jacobian);
diff --git a/internal/ceres/block_jacobi_preconditioner.h b/internal/ceres/block_jacobi_preconditioner.h
index 0541db5..a67879a 100644
--- a/internal/ceres/block_jacobi_preconditioner.h
+++ b/internal/ceres/block_jacobi_preconditioner.h
@@ -31,8 +31,8 @@
#ifndef CERES_INTERNAL_BLOCK_JACOBI_PRECONDITIONER_H_
#define CERES_INTERNAL_BLOCK_JACOBI_PRECONDITIONER_H_
+#include <memory>
#include "ceres/block_random_access_diagonal_matrix.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/preconditioner.h"
namespace ceres {
@@ -66,7 +66,7 @@
private:
virtual bool UpdateImpl(const BlockSparseMatrix& A, const double* D);
- scoped_ptr<BlockRandomAccessDiagonalMatrix> m_;
+ std::unique_ptr<BlockRandomAccessDiagonalMatrix> m_;
};
} // namespace internal
diff --git a/internal/ceres/block_jacobi_preconditioner_test.cc b/internal/ceres/block_jacobi_preconditioner_test.cc
index 0fb9dc6..80e5fba 100644
--- a/internal/ceres/block_jacobi_preconditioner_test.cc
+++ b/internal/ceres/block_jacobi_preconditioner_test.cc
@@ -30,11 +30,11 @@
#include "ceres/block_jacobi_preconditioner.h"
+#include <memory>
#include <vector>
#include "ceres/block_random_access_diagonal_matrix.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/block_sparse_matrix.h"
-#include "ceres/internal/scoped_ptr.h"
#include "gtest/gtest.h"
#include "Eigen/Dense"
@@ -45,7 +45,7 @@
class BlockJacobiPreconditionerTest : public ::testing::Test {
protected:
void SetUpFromProblemId(int problem_id) {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(problem_id));
CHECK_NOTNULL(problem.get());
@@ -88,8 +88,8 @@
}
}
- scoped_ptr<BlockSparseMatrix> A;
- scoped_array<double> D;
+ std::unique_ptr<BlockSparseMatrix> A;
+ std::unique_ptr<double[]> D;
Matrix dense_ata;
};
diff --git a/internal/ceres/block_jacobian_writer.cc b/internal/ceres/block_jacobian_writer.cc
index 7a3fee4..5714ada 100644
--- a/internal/ceres/block_jacobian_writer.cc
+++ b/internal/ceres/block_jacobian_writer.cc
@@ -37,7 +37,6 @@
#include "ceres/residual_block.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
namespace internal {
diff --git a/internal/ceres/block_random_access_dense_matrix.cc b/internal/ceres/block_random_access_dense_matrix.cc
index 61748ef..f567aa5 100644
--- a/internal/ceres/block_random_access_dense_matrix.cc
+++ b/internal/ceres/block_random_access_dense_matrix.cc
@@ -32,7 +32,6 @@
#include <vector>
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "glog/logging.h"
namespace ceres {
diff --git a/internal/ceres/block_random_access_dense_matrix.h b/internal/ceres/block_random_access_dense_matrix.h
index 8968908..161dab2 100644
--- a/internal/ceres/block_random_access_dense_matrix.h
+++ b/internal/ceres/block_random_access_dense_matrix.h
@@ -33,11 +33,11 @@
#include "ceres/block_random_access_matrix.h"
+#include <memory>
#include <vector>
#include "ceres/internal/macros.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
namespace internal {
@@ -86,8 +86,8 @@
private:
int num_rows_;
std::vector<int> block_layout_;
- scoped_array<double> values_;
- scoped_array<CellInfo> cell_infos_;
+ std::unique_ptr<double[]> values_;
+ std::unique_ptr<CellInfo[]> cell_infos_;
CERES_DISALLOW_COPY_AND_ASSIGN(BlockRandomAccessDenseMatrix);
};
diff --git a/internal/ceres/block_random_access_diagonal_matrix.cc b/internal/ceres/block_random_access_diagonal_matrix.cc
index 052690d..9866e75 100644
--- a/internal/ceres/block_random_access_diagonal_matrix.cc
+++ b/internal/ceres/block_random_access_diagonal_matrix.cc
@@ -34,9 +34,9 @@
#include <set>
#include <utility>
#include <vector>
+
#include "Eigen/Dense"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/stl_util.h"
#include "ceres/triplet_sparse_matrix.h"
#include "ceres/types.h"
diff --git a/internal/ceres/block_random_access_diagonal_matrix.h b/internal/ceres/block_random_access_diagonal_matrix.h
index 62e17e8..fd43eb0 100644
--- a/internal/ceres/block_random_access_diagonal_matrix.h
+++ b/internal/ceres/block_random_access_diagonal_matrix.h
@@ -31,15 +31,16 @@
#ifndef CERES_INTERNAL_BLOCK_RANDOM_ACCESS_DIAGONAL_MATRIX_H_
#define CERES_INTERNAL_BLOCK_RANDOM_ACCESS_DIAGONAL_MATRIX_H_
+#include <memory>
#include <set>
-#include <vector>
#include <utility>
+#include <vector>
+
#include "ceres/block_random_access_matrix.h"
-#include "ceres/triplet_sparse_matrix.h"
#include "ceres/integral_types.h"
#include "ceres/internal/macros.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
+#include "ceres/triplet_sparse_matrix.h"
#include "ceres/types.h"
namespace ceres {
@@ -87,7 +88,7 @@
std::vector<CellInfo*> layout_;
// The underlying matrix object which actually stores the cells.
- scoped_ptr<TripletSparseMatrix> tsm_;
+ std::unique_ptr<TripletSparseMatrix> tsm_;
friend class BlockRandomAccessDiagonalMatrixTest;
CERES_DISALLOW_COPY_AND_ASSIGN(BlockRandomAccessDiagonalMatrix);
diff --git a/internal/ceres/block_random_access_diagonal_matrix_test.cc b/internal/ceres/block_random_access_diagonal_matrix_test.cc
index 8fa3798..a54595c 100644
--- a/internal/ceres/block_random_access_diagonal_matrix_test.cc
+++ b/internal/ceres/block_random_access_diagonal_matrix_test.cc
@@ -29,6 +29,7 @@
// Author: sameeragarwal@google.com (Sameer Agarwal)
#include <limits>
+#include <memory>
#include <vector>
#include "ceres/block_random_access_diagonal_matrix.h"
@@ -92,7 +93,7 @@
protected:
int num_nonzeros_;
- scoped_ptr<BlockRandomAccessDiagonalMatrix> m_;
+ std::unique_ptr<BlockRandomAccessDiagonalMatrix> m_;
};
TEST_F(BlockRandomAccessDiagonalMatrixTest, MatrixContents) {
diff --git a/internal/ceres/block_random_access_sparse_matrix.cc b/internal/ceres/block_random_access_sparse_matrix.cc
index b8b4a75..a822d69 100644
--- a/internal/ceres/block_random_access_sparse_matrix.cc
+++ b/internal/ceres/block_random_access_sparse_matrix.cc
@@ -31,11 +31,12 @@
#include "ceres/block_random_access_sparse_matrix.h"
#include <algorithm>
+#include <memory>
#include <set>
#include <utility>
#include <vector>
+
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/triplet_sparse_matrix.h"
#include "ceres/types.h"
#include "glog/logging.h"
diff --git a/internal/ceres/block_random_access_sparse_matrix.h b/internal/ceres/block_random_access_sparse_matrix.h
index c8a8927..fb24900 100644
--- a/internal/ceres/block_random_access_sparse_matrix.h
+++ b/internal/ceres/block_random_access_sparse_matrix.h
@@ -31,16 +31,17 @@
#ifndef CERES_INTERNAL_BLOCK_RANDOM_ACCESS_SPARSE_MATRIX_H_
#define CERES_INTERNAL_BLOCK_RANDOM_ACCESS_SPARSE_MATRIX_H_
+#include <memory>
#include <set>
#include <unordered_map>
-#include <vector>
#include <utility>
+#include <vector>
+
#include "ceres/block_random_access_matrix.h"
#include "ceres/triplet_sparse_matrix.h"
#include "ceres/integral_types.h"
#include "ceres/internal/macros.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
#include "ceres/small_blas.h"
@@ -116,7 +117,7 @@
// iterator in the Layout object instead.
std::vector<std::pair<std::pair<int, int>, double*> > cell_values_;
// The underlying matrix object which actually stores the cells.
- scoped_ptr<TripletSparseMatrix> tsm_;
+ std::unique_ptr<TripletSparseMatrix> tsm_;
friend class BlockRandomAccessSparseMatrixTest;
CERES_DISALLOW_COPY_AND_ASSIGN(BlockRandomAccessSparseMatrix);
diff --git a/internal/ceres/block_random_access_sparse_matrix_test.cc b/internal/ceres/block_random_access_sparse_matrix_test.cc
index 688b09d..c5816d5 100644
--- a/internal/ceres/block_random_access_sparse_matrix_test.cc
+++ b/internal/ceres/block_random_access_sparse_matrix_test.cc
@@ -29,7 +29,9 @@
// Author: sameeragarwal@google.com (Sameer Agarwal)
#include <limits>
+#include <memory>
#include <vector>
+
#include "ceres/block_random_access_sparse_matrix.h"
#include "ceres/internal/eigen.h"
#include "glog/logging.h"
@@ -168,7 +170,7 @@
}
private:
- scoped_ptr<BlockRandomAccessSparseMatrix> m_;
+ std::unique_ptr<BlockRandomAccessSparseMatrix> m_;
};
TEST_F(BlockRandomAccessSparseMatrixTest, IntPairToLongOverflow) {
diff --git a/internal/ceres/block_sparse_matrix.h b/internal/ceres/block_sparse_matrix.h
index abde2a6..b93a6fa 100644
--- a/internal/ceres/block_sparse_matrix.h
+++ b/internal/ceres/block_sparse_matrix.h
@@ -34,11 +34,11 @@
#ifndef CERES_INTERNAL_BLOCK_SPARSE_MATRIX_H_
#define CERES_INTERNAL_BLOCK_SPARSE_MATRIX_H_
+#include <memory>
#include "ceres/block_structure.h"
#include "ceres/sparse_matrix.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/macros.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
namespace internal {
@@ -137,8 +137,8 @@
int num_cols_;
int num_nonzeros_;
int max_num_nonzeros_;
- scoped_array<double> values_;
- scoped_ptr<CompressedRowBlockStructure> block_structure_;
+ std::unique_ptr<double[]> values_;
+ std::unique_ptr<CompressedRowBlockStructure> block_structure_;
CERES_DISALLOW_COPY_AND_ASSIGN(BlockSparseMatrix);
};
diff --git a/internal/ceres/block_sparse_matrix_test.cc b/internal/ceres/block_sparse_matrix_test.cc
index b3d21d0..50b6766 100644
--- a/internal/ceres/block_sparse_matrix_test.cc
+++ b/internal/ceres/block_sparse_matrix_test.cc
@@ -30,10 +30,10 @@
#include "ceres/block_sparse_matrix.h"
+#include <memory>
#include <string>
#include "ceres/casts.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/triplet_sparse_matrix.h"
#include "glog/logging.h"
@@ -45,7 +45,7 @@
class BlockSparseMatrixTest : public ::testing::Test {
protected :
virtual void SetUp() {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(2));
CHECK_NOTNULL(problem.get());
A_.reset(down_cast<BlockSparseMatrix*>(problem->A.release()));
@@ -59,8 +59,8 @@
CHECK_EQ(A_->num_nonzeros(), B_->num_nonzeros());
}
- scoped_ptr<BlockSparseMatrix> A_;
- scoped_ptr<TripletSparseMatrix> B_;
+ std::unique_ptr<BlockSparseMatrix> A_;
+ std::unique_ptr<TripletSparseMatrix> B_;
};
TEST_F(BlockSparseMatrixTest, SetZeroTest) {
@@ -109,16 +109,16 @@
}
TEST_F(BlockSparseMatrixTest, AppendRows) {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(2));
- scoped_ptr<BlockSparseMatrix> m(
+ std::unique_ptr<BlockSparseMatrix> m(
down_cast<BlockSparseMatrix*>(problem->A.release()));
A_->AppendRows(*m);
EXPECT_EQ(A_->num_rows(), 2 * m->num_rows());
EXPECT_EQ(A_->num_cols(), m->num_cols());
problem.reset(CreateLinearLeastSquaresProblemFromId(1));
- scoped_ptr<TripletSparseMatrix> m2(
+ std::unique_ptr<TripletSparseMatrix> m2(
down_cast<TripletSparseMatrix*>(problem->A.release()));
B_->AppendRows(*m2);
@@ -144,7 +144,7 @@
for (int i = 0; i < num_cols; ++i) {
diagonal(i) = 2 * i * i + 1;
}
- scoped_ptr<BlockSparseMatrix> appendage(
+ std::unique_ptr<BlockSparseMatrix> appendage(
BlockSparseMatrix::CreateDiagonalMatrix(diagonal.data(), column_blocks));
A_->AppendRows(*appendage);
@@ -196,7 +196,7 @@
diagonal(i) = 2 * i * i + 1;
}
- scoped_ptr<BlockSparseMatrix> m(
+ std::unique_ptr<BlockSparseMatrix> m(
BlockSparseMatrix::CreateDiagonalMatrix(diagonal.data(), column_blocks));
const CompressedRowBlockStructure* bs = m->block_structure();
EXPECT_EQ(bs->cols.size(), column_blocks.size());
diff --git a/internal/ceres/cgnr_linear_operator.h b/internal/ceres/cgnr_linear_operator.h
index 44c07ca..ad0c627 100644
--- a/internal/ceres/cgnr_linear_operator.h
+++ b/internal/ceres/cgnr_linear_operator.h
@@ -32,8 +32,8 @@
#define CERES_INTERNAL_CGNR_LINEAR_OPERATOR_H_
#include <algorithm>
+#include <memory>
#include "ceres/linear_operator.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/internal/eigen.h"
namespace ceres {
@@ -111,7 +111,7 @@
private:
const LinearOperator& A_;
const double* D_;
- scoped_array<double> z_;
+ std::unique_ptr<double[]> z_;
};
} // namespace internal
diff --git a/internal/ceres/cgnr_solver.cc b/internal/ceres/cgnr_solver.cc
index 61fae75..3a7ed3c 100644
--- a/internal/ceres/cgnr_solver.cc
+++ b/internal/ceres/cgnr_solver.cc
@@ -42,8 +42,7 @@
namespace internal {
CgnrSolver::CgnrSolver(const LinearSolver::Options& options)
- : options_(options),
- preconditioner_(NULL) {
+ : options_(options) {
if (options_.preconditioner_type != JACOBI &&
options_.preconditioner_type != IDENTITY) {
LOG(FATAL) << "CGNR only supports IDENTITY and JACOBI preconditioners.";
diff --git a/internal/ceres/cgnr_solver.h b/internal/ceres/cgnr_solver.h
index f7a1573..7d9f8ef 100644
--- a/internal/ceres/cgnr_solver.h
+++ b/internal/ceres/cgnr_solver.h
@@ -31,7 +31,7 @@
#ifndef CERES_INTERNAL_CGNR_SOLVER_H_
#define CERES_INTERNAL_CGNR_SOLVER_H_
-#include "ceres/internal/scoped_ptr.h"
+#include <memory>
#include "ceres/linear_solver.h"
namespace ceres {
@@ -59,7 +59,7 @@
private:
const LinearSolver::Options options_;
- scoped_ptr<Preconditioner> preconditioner_;
+ std::unique_ptr<Preconditioner> preconditioner_;
CERES_DISALLOW_COPY_AND_ASSIGN(CgnrSolver);
};
diff --git a/internal/ceres/compressed_row_sparse_matrix_test.cc b/internal/ceres/compressed_row_sparse_matrix_test.cc
index 8ebf6cf..4351e3d 100644
--- a/internal/ceres/compressed_row_sparse_matrix_test.cc
+++ b/internal/ceres/compressed_row_sparse_matrix_test.cc
@@ -30,11 +30,11 @@
#include "ceres/compressed_row_sparse_matrix.h"
+#include <memory>
#include <numeric>
#include "ceres/casts.h"
#include "ceres/crs_matrix.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/random.h"
#include "ceres/triplet_sparse_matrix.h"
@@ -72,7 +72,7 @@
class CompressedRowSparseMatrixTest : public ::testing::Test {
protected:
virtual void SetUp() {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(1));
CHECK_NOTNULL(problem.get());
@@ -95,8 +95,8 @@
int num_rows;
int num_cols;
- scoped_ptr<TripletSparseMatrix> tsm;
- scoped_ptr<CompressedRowSparseMatrix> crsm;
+ std::unique_ptr<TripletSparseMatrix> tsm;
+ std::unique_ptr<CompressedRowSparseMatrix> crsm;
};
TEST_F(CompressedRowSparseMatrixTest, Scale) {
@@ -132,7 +132,7 @@
tsm_appendage.Resize(i, num_cols);
tsm->AppendRows(tsm_appendage);
- scoped_ptr<CompressedRowSparseMatrix> crsm_appendage(
+ std::unique_ptr<CompressedRowSparseMatrix> crsm_appendage(
CompressedRowSparseMatrix::FromTripletSparseMatrix(tsm_appendage));
crsm->AppendRows(*crsm_appendage);
@@ -143,7 +143,7 @@
TEST_F(CompressedRowSparseMatrixTest, AppendAndDeleteBlockDiagonalMatrix) {
int num_diagonal_rows = crsm->num_cols();
- scoped_array<double> diagonal(new double[num_diagonal_rows]);
+ std::unique_ptr<double[]> diagonal(new double[num_diagonal_rows]);
for (int i = 0; i < num_diagonal_rows; ++i) {
diagonal[i] = i;
}
@@ -156,7 +156,7 @@
const vector<int> pre_row_blocks = crsm->row_blocks();
const vector<int> pre_col_blocks = crsm->col_blocks();
- scoped_ptr<CompressedRowSparseMatrix> appendage(
+ std::unique_ptr<CompressedRowSparseMatrix> appendage(
CompressedRowSparseMatrix::CreateBlockDiagonalMatrix(
diagonal.get(), row_and_column_blocks));
@@ -220,7 +220,7 @@
diagonal(i) = i + 1;
}
- scoped_ptr<CompressedRowSparseMatrix> matrix(
+ std::unique_ptr<CompressedRowSparseMatrix> matrix(
CompressedRowSparseMatrix::CreateBlockDiagonalMatrix(diagonal.data(),
blocks));
@@ -305,7 +305,7 @@
std::copy(values, values + 17, cols);
- scoped_ptr<CompressedRowSparseMatrix> transpose(matrix.Transpose());
+ std::unique_ptr<CompressedRowSparseMatrix> transpose(matrix.Transpose());
ASSERT_EQ(transpose->row_blocks().size(), matrix.col_blocks().size());
for (int i = 0; i < transpose->row_blocks().size(); ++i) {
@@ -333,9 +333,9 @@
const int kNumTrials = 10;
for (int i = 0; i < kNumTrials; ++i) {
- scoped_ptr<TripletSparseMatrix> tsm(
+ std::unique_ptr<TripletSparseMatrix> tsm(
TripletSparseMatrix::CreateRandomMatrix(options));
- scoped_ptr<CompressedRowSparseMatrix> crsm(
+ std::unique_ptr<CompressedRowSparseMatrix> crsm(
CompressedRowSparseMatrix::FromTripletSparseMatrix(*tsm));
Matrix expected;
@@ -359,9 +359,9 @@
const int kNumTrials = 10;
for (int i = 0; i < kNumTrials; ++i) {
- scoped_ptr<TripletSparseMatrix> tsm(
+ std::unique_ptr<TripletSparseMatrix> tsm(
TripletSparseMatrix::CreateRandomMatrix(options));
- scoped_ptr<CompressedRowSparseMatrix> crsm(
+ std::unique_ptr<CompressedRowSparseMatrix> crsm(
CompressedRowSparseMatrix::FromTripletSparseMatrixTransposed(*tsm));
Matrix tmp;
@@ -416,7 +416,7 @@
options.max_row_block_size = kMaxBlockSize;
options.block_density = std::max(0.5, RandDouble());
options.storage_type = ::testing::get<0>(param);
- scoped_ptr<CompressedRowSparseMatrix> matrix(
+ std::unique_ptr<CompressedRowSparseMatrix> matrix(
CompressedRowSparseMatrix::CreateRandomMatrix(options));
const int num_rows = matrix->num_rows();
const int num_cols = matrix->num_cols();
@@ -484,7 +484,7 @@
options.max_row_block_size = kMaxBlockSize;
options.block_density = std::max(0.5, RandDouble());
options.storage_type = ::testing::get<0>(param);
- scoped_ptr<CompressedRowSparseMatrix> matrix(
+ std::unique_ptr<CompressedRowSparseMatrix> matrix(
CompressedRowSparseMatrix::CreateRandomMatrix(options));
const int num_rows = matrix->num_rows();
const int num_cols = matrix->num_cols();
@@ -552,7 +552,7 @@
options.max_row_block_size = kMaxBlockSize;
options.block_density = std::max(0.5, RandDouble());
options.storage_type = ::testing::get<0>(param);
- scoped_ptr<CompressedRowSparseMatrix> matrix(
+ std::unique_ptr<CompressedRowSparseMatrix> matrix(
CompressedRowSparseMatrix::CreateRandomMatrix(options));
const int num_cols = matrix->num_cols();
diff --git a/internal/ceres/conjugate_gradients_solver_test.cc b/internal/ceres/conjugate_gradients_solver_test.cc
index 1f5c3ae..9311998 100644
--- a/internal/ceres/conjugate_gradients_solver_test.cc
+++ b/internal/ceres/conjugate_gradients_solver_test.cc
@@ -31,12 +31,12 @@
// TODO(sameeragarwal): More comprehensive testing with larger and
// more badly conditioned problem.
+#include <memory>
#include "gtest/gtest.h"
#include "ceres/conjugate_gradients_solver.h"
#include "ceres/linear_solver.h"
#include "ceres/triplet_sparse_matrix.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
namespace ceres {
@@ -44,7 +44,7 @@
TEST(ConjugateGradientTest, Solves3x3IdentitySystem) {
double diagonal[] = { 1.0, 1.0, 1.0 };
- scoped_ptr<TripletSparseMatrix>
+ std::unique_ptr<TripletSparseMatrix>
A(TripletSparseMatrix::CreateSparseDiagonalMatrix(diagonal, 3));
Vector b(3);
Vector x(3);
@@ -77,7 +77,7 @@
TEST(ConjuateGradientTest, Solves3x3SymmetricSystem) {
- scoped_ptr<TripletSparseMatrix> A(new TripletSparseMatrix(3, 3, 9));
+ std::unique_ptr<TripletSparseMatrix> A(new TripletSparseMatrix(3, 3, 9));
Vector b(3);
Vector x(3);
diff --git a/internal/ceres/coordinate_descent_minimizer.cc b/internal/ceres/coordinate_descent_minimizer.cc
index e5569d4..48fd04c 100644
--- a/internal/ceres/coordinate_descent_minimizer.cc
+++ b/internal/ceres/coordinate_descent_minimizer.cc
@@ -35,8 +35,10 @@
#endif
#include <iterator>
+#include <memory>
#include <numeric>
#include <vector>
+
#include "ceres/evaluator.h"
#include "ceres/linear_solver.h"
#include "ceres/minimizer.h"
@@ -137,7 +139,7 @@
parameter_block->SetConstant();
}
- scoped_array<LinearSolver*> linear_solvers(
+ std::unique_ptr<LinearSolver*[]> linear_solvers(
new LinearSolver*[options.num_threads]);
LinearSolver::Options linear_solver_options;
@@ -281,7 +283,7 @@
// points.
ParameterBlockOrdering* CoordinateDescentMinimizer::CreateOrdering(
const Program& program) {
- scoped_ptr<ParameterBlockOrdering> ordering(new ParameterBlockOrdering);
+ std::unique_ptr<ParameterBlockOrdering> ordering(new ParameterBlockOrdering);
ComputeRecursiveIndependentSetOrdering(program, ordering.get());
ordering->Reverse();
return ordering.release();
diff --git a/internal/ceres/cost_function_to_functor_test.cc b/internal/ceres/cost_function_to_functor_test.cc
index 6c9a940..5878d3b 100644
--- a/internal/ceres/cost_function_to_functor_test.cc
+++ b/internal/ceres/cost_function_to_functor_test.cc
@@ -29,6 +29,8 @@
// Author: sameeragarwal@google.com (Sameer Agarwal)
#include "ceres/cost_function_to_functor.h"
+
+#include <memory>
#include "ceres/dynamic_autodiff_cost_function.h"
#include "ceres/dynamic_cost_function_to_functor.h"
#include "ceres/autodiff_cost_function.h"
@@ -58,23 +60,23 @@
num_parameters += parameter_block_sizes[i];
}
- scoped_array<double> parameters(new double[num_parameters]);
+ std::unique_ptr<double[]> parameters(new double[num_parameters]);
for (int i = 0; i < num_parameters; ++i) {
parameters[i] = static_cast<double>(i) + 1.0;
}
- scoped_array<double> residuals(new double[num_residuals]);
- scoped_array<double> jacobians(new double[num_parameters * num_residuals]);
+ std::unique_ptr<double[]> residuals(new double[num_residuals]);
+ std::unique_ptr<double[]> jacobians(new double[num_parameters * num_residuals]);
- scoped_array<double> actual_residuals(new double[num_residuals]);
- scoped_array<double> actual_jacobians
+ std::unique_ptr<double[]> actual_residuals(new double[num_residuals]);
+ std::unique_ptr<double[]> actual_jacobians
(new double[num_parameters * num_residuals]);
- scoped_array<double*> parameter_blocks(
+ std::unique_ptr<double*[]> parameter_blocks(
new double*[parameter_block_sizes.size()]);
- scoped_array<double*> jacobian_blocks(
+ std::unique_ptr<double*[]> jacobian_blocks(
new double*[parameter_block_sizes.size()]);
- scoped_array<double*> actual_jacobian_blocks(
+ std::unique_ptr<double*[]> actual_jacobian_blocks(
new double*[parameter_block_sizes.size()]);
num_parameters = 0;
@@ -258,7 +260,7 @@
#define TEST_BODY(NAME) \
TEST(CostFunctionToFunctor, NAME) { \
- scoped_ptr<CostFunction> cost_function( \
+ std::unique_ptr<CostFunction> cost_function( \
new AutoDiffCostFunction< \
CostFunctionToFunctor<2, PARAMETER_BLOCK_SIZES >, \
2, PARAMETER_BLOCK_SIZES>(new CostFunctionToFunctor< \
@@ -267,7 +269,7 @@
NAME##Functor, 2, PARAMETER_BLOCK_SIZES >( \
new NAME##Functor)))); \
\
-scoped_ptr<CostFunction> actual_cost_function( \
+std::unique_ptr<CostFunction> actual_cost_function( \
new AutoDiffCostFunction<NAME##Functor, 2, PARAMETER_BLOCK_SIZES >( \
new NAME##Functor)); \
ExpectCostFunctionsAreEqual(*cost_function, *actual_cost_function); \
@@ -316,14 +318,14 @@
#undef TEST_BODY
TEST(CostFunctionToFunctor, DynamicNumberOfResiduals) {
- scoped_ptr<CostFunction> cost_function(
+ std::unique_ptr<CostFunction> cost_function(
new AutoDiffCostFunction<
CostFunctionToFunctor<ceres::DYNAMIC, 2, 2 >, ceres::DYNAMIC, 2, 2>(
new CostFunctionToFunctor<ceres::DYNAMIC, 2, 2 >(
new AutoDiffCostFunction<TwoParameterBlockFunctor, 2, 2, 2 >(
new TwoParameterBlockFunctor)), 2));
- scoped_ptr<CostFunction> actual_cost_function(
+ std::unique_ptr<CostFunction> actual_cost_function(
new AutoDiffCostFunction<TwoParameterBlockFunctor, 2, 2, 2 >(
new TwoParameterBlockFunctor));
ExpectCostFunctionsAreEqual(*cost_function, *actual_cost_function);
diff --git a/internal/ceres/covariance_impl.cc b/internal/ceres/covariance_impl.cc
index 484c94f..70719b0 100644
--- a/internal/ceres/covariance_impl.cc
+++ b/internal/ceres/covariance_impl.cc
@@ -36,6 +36,7 @@
#include <algorithm>
#include <cstdlib>
+#include <memory>
#include <numeric>
#include <sstream>
#include <unordered_set>
@@ -337,7 +338,7 @@
// Assemble the blocks in the covariance matrix.
MatrixRef covariance(covariance_matrix, covariance_size, covariance_size);
const int num_threads = options_.num_threads;
- scoped_array<double> workspace(
+ std::unique_ptr<double[]> workspace(
new double[num_threads * max_covariance_block_size *
max_covariance_block_size]);
@@ -706,7 +707,7 @@
// Since the covariance matrix is symmetric, the i^th row and column
// are equal.
const int num_threads = options_.num_threads;
- scoped_array<double> workspace(new double[num_threads * num_cols]);
+ std::unique_ptr<double[]> workspace(new double[num_threads * num_cols]);
#if !(defined(CERES_USE_TBB) || defined(CERES_USE_CXX11_THREADS))
ThreadTokenProvider thread_token_provider(num_threads);
@@ -915,7 +916,7 @@
// are equal.
const int num_cols = jacobian.num_cols;
const int num_threads = options_.num_threads;
- scoped_array<double> workspace(new double[num_threads * num_cols]);
+ std::unique_ptr<double[]> workspace(new double[num_threads * num_cols]);
#if !(defined(CERES_USE_TBB) || defined(CERES_USE_CXX11_THREADS))
ThreadTokenProvider thread_token_provider(num_threads);
diff --git a/internal/ceres/covariance_impl.h b/internal/ceres/covariance_impl.h
index a3f0761..c3a9bc1 100644
--- a/internal/ceres/covariance_impl.h
+++ b/internal/ceres/covariance_impl.h
@@ -32,11 +32,11 @@
#define CERES_INTERNAL_COVARIANCE_IMPL_H_
#include <map>
+#include <memory>
#include <set>
#include <utility>
#include <vector>
#include "ceres/covariance.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/problem_impl.h"
#include "ceres/suitesparse.h"
@@ -92,7 +92,7 @@
bool is_valid_;
std::map<const double*, int> parameter_block_to_row_index_;
std::set<const double*> constant_parameter_blocks_;
- scoped_ptr<CompressedRowSparseMatrix> covariance_matrix_;
+ std::unique_ptr<CompressedRowSparseMatrix> covariance_matrix_;
};
} // namespace internal
diff --git a/internal/ceres/covariance_test.cc b/internal/ceres/covariance_test.cc
index 96c962a..afa9bb6 100644
--- a/internal/ceres/covariance_test.cc
+++ b/internal/ceres/covariance_test.cc
@@ -33,7 +33,9 @@
#include <algorithm>
#include <cmath>
#include <map>
+#include <memory>
#include <utility>
+
#include "ceres/compressed_row_sparse_matrix.h"
#include "ceres/cost_function.h"
#include "ceres/covariance_impl.h"
@@ -1256,7 +1258,7 @@
}
}
- scoped_array<double> parameters_;
+ std::unique_ptr<double[]> parameters_;
int parameter_block_size_;
int num_parameter_blocks_;
diff --git a/internal/ceres/cubic_interpolation_test.cc b/internal/ceres/cubic_interpolation_test.cc
index df43696..fd56016 100644
--- a/internal/ceres/cubic_interpolation_test.cc
+++ b/internal/ceres/cubic_interpolation_test.cc
@@ -30,8 +30,8 @@
#include "ceres/cubic_interpolation.h"
+#include <memory>
#include "ceres/jet.h"
-#include "ceres/internal/scoped_ptr.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
@@ -257,7 +257,7 @@
private:
static const int kNumSamples = 10;
static const int kNumTestSamples = 100;
- scoped_array<double> values_;
+ std::unique_ptr<double[]> values_;
};
TEST_F(CubicInterpolatorTest, ConstantFunction) {
@@ -375,7 +375,7 @@
static const int kNumCols = 10;
static const int kNumRowSamples = 100;
static const int kNumColSamples = 100;
- scoped_array<double> values_;
+ std::unique_ptr<double[]> values_;
};
TEST_F(BiCubicInterpolatorTest, ZeroFunction) {
diff --git a/internal/ceres/dense_linear_solver_test.cc b/internal/ceres/dense_linear_solver_test.cc
index f8b64f8..e2e02ca 100644
--- a/internal/ceres/dense_linear_solver_test.cc
+++ b/internal/ceres/dense_linear_solver_test.cc
@@ -28,9 +28,9 @@
//
// Author: sameeragarwal@google.com (Sameer Agarwal)
+#include <memory>
#include "ceres/casts.h"
#include "ceres/context_impl.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/linear_solver.h"
#include "ceres/triplet_sparse_matrix.h"
@@ -61,7 +61,7 @@
Param param = GetParam();
const bool regularized = testing::get<2>(param);
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(testing::get<3>(param)));
DenseSparseMatrix lhs(*down_cast<TripletSparseMatrix*>(problem->A.get()));
@@ -76,7 +76,7 @@
options.dense_linear_algebra_library_type = ::testing::get<1>(param);
ContextImpl context;
options.context = &context;
- scoped_ptr<LinearSolver> solver(LinearSolver::Create(options));
+ std::unique_ptr<LinearSolver> solver(LinearSolver::Create(options));
LinearSolver::PerSolveOptions per_solve_options;
if (regularized) {
diff --git a/internal/ceres/dense_normal_cholesky_solver.cc b/internal/ceres/dense_normal_cholesky_solver.cc
index b13cf3f..fe7d931 100644
--- a/internal/ceres/dense_normal_cholesky_solver.cc
+++ b/internal/ceres/dense_normal_cholesky_solver.cc
@@ -36,7 +36,6 @@
#include "ceres/blas.h"
#include "ceres/dense_sparse_matrix.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/lapack.h"
#include "ceres/linear_solver.h"
#include "ceres/types.h"
diff --git a/internal/ceres/dense_qr_solver.cc b/internal/ceres/dense_qr_solver.cc
index e85fdfc..161e9c6 100644
--- a/internal/ceres/dense_qr_solver.cc
+++ b/internal/ceres/dense_qr_solver.cc
@@ -30,12 +30,10 @@
#include "ceres/dense_qr_solver.h"
-
#include <cstddef>
#include "Eigen/Dense"
#include "ceres/dense_sparse_matrix.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/lapack.h"
#include "ceres/linear_solver.h"
#include "ceres/types.h"
diff --git a/internal/ceres/dense_sparse_matrix.h b/internal/ceres/dense_sparse_matrix.h
index b011bfd..9639a4a 100644
--- a/internal/ceres/dense_sparse_matrix.h
+++ b/internal/ceres/dense_sparse_matrix.h
@@ -33,10 +33,9 @@
#ifndef CERES_INTERNAL_DENSE_SPARSE_MATRIX_H_
#define CERES_INTERNAL_DENSE_SPARSE_MATRIX_H_
-#include "ceres/sparse_matrix.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/macros.h"
-#include "ceres/internal/scoped_ptr.h"
+#include "ceres/sparse_matrix.h"
#include "ceres/types.h"
namespace ceres {
diff --git a/internal/ceres/dense_sparse_matrix_test.cc b/internal/ceres/dense_sparse_matrix_test.cc
index a77f5e3..7c7e69a 100644
--- a/internal/ceres/dense_sparse_matrix_test.cc
+++ b/internal/ceres/dense_sparse_matrix_test.cc
@@ -34,11 +34,11 @@
#include "ceres/dense_sparse_matrix.h"
+#include <memory>
#include "ceres/casts.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/triplet_sparse_matrix.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
@@ -69,7 +69,7 @@
class DenseSparseMatrixTest : public ::testing::Test {
protected :
virtual void SetUp() {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(1));
CHECK_NOTNULL(problem.get());
@@ -84,8 +84,8 @@
int num_rows;
int num_cols;
- scoped_ptr<TripletSparseMatrix> tsm;
- scoped_ptr<DenseSparseMatrix> dsm;
+ std::unique_ptr<TripletSparseMatrix> tsm;
+ std::unique_ptr<DenseSparseMatrix> dsm;
};
TEST_F(DenseSparseMatrixTest, RightMultiply) {
diff --git a/internal/ceres/dogleg_strategy_test.cc b/internal/ceres/dogleg_strategy_test.cc
index f1fe05a..c435be6 100644
--- a/internal/ceres/dogleg_strategy_test.cc
+++ b/internal/ceres/dogleg_strategy_test.cc
@@ -29,8 +29,8 @@
// Author: moll.markus@arcor.de (Markus Moll)
#include <limits>
+#include <memory>
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/dense_qr_solver.h"
#include "ceres/dogleg_strategy.h"
#include "ceres/linear_solver.h"
@@ -44,7 +44,7 @@
class Fixture : public testing::Test {
protected:
- scoped_ptr<DenseSparseMatrix> jacobian_;
+ std::unique_ptr<DenseSparseMatrix> jacobian_;
Vector residual_;
Vector x_;
TrustRegionStrategy::Options options_;
@@ -126,7 +126,7 @@
// The DoglegStrategy must never return a step that is longer than the current
// trust region radius.
TEST_F(DoglegStrategyFixtureEllipse, TrustRegionObeyedTraditional) {
- scoped_ptr<LinearSolver> linear_solver(
+ std::unique_ptr<LinearSolver> linear_solver(
new DenseQRSolver(LinearSolver::Options()));
options_.linear_solver = linear_solver.get();
// The global minimum is at (1, 1, ..., 1), so the distance to it is
@@ -149,7 +149,7 @@
}
TEST_F(DoglegStrategyFixtureEllipse, TrustRegionObeyedSubspace) {
- scoped_ptr<LinearSolver> linear_solver(
+ std::unique_ptr<LinearSolver> linear_solver(
new DenseQRSolver(LinearSolver::Options()));
options_.linear_solver = linear_solver.get();
options_.dogleg_type = SUBSPACE_DOGLEG;
@@ -169,7 +169,7 @@
}
TEST_F(DoglegStrategyFixtureEllipse, CorrectGaussNewtonStep) {
- scoped_ptr<LinearSolver> linear_solver(
+ std::unique_ptr<LinearSolver> linear_solver(
new DenseQRSolver(LinearSolver::Options()));
options_.linear_solver = linear_solver.get();
options_.dogleg_type = SUBSPACE_DOGLEG;
@@ -196,7 +196,7 @@
// Test if the subspace basis is a valid orthonormal basis of the space spanned
// by the gradient and the Gauss-Newton point.
TEST_F(DoglegStrategyFixtureEllipse, ValidSubspaceBasis) {
- scoped_ptr<LinearSolver> linear_solver(
+ std::unique_ptr<LinearSolver> linear_solver(
new DenseQRSolver(LinearSolver::Options()));
options_.linear_solver = linear_solver.get();
options_.dogleg_type = SUBSPACE_DOGLEG;
@@ -231,7 +231,7 @@
// in the same direction and the Gauss-Newton step is outside the trust region,
// i.e. the trust region is active.
TEST_F(DoglegStrategyFixtureValley, CorrectStepLocalOptimumAlongGradient) {
- scoped_ptr<LinearSolver> linear_solver(
+ std::unique_ptr<LinearSolver> linear_solver(
new DenseQRSolver(LinearSolver::Options()));
options_.linear_solver = linear_solver.get();
options_.dogleg_type = SUBSPACE_DOGLEG;
@@ -259,7 +259,7 @@
// in the same direction and the Gauss-Newton step is inside the trust region,
// i.e. the trust region is inactive.
TEST_F(DoglegStrategyFixtureValley, CorrectStepGlobalOptimumAlongGradient) {
- scoped_ptr<LinearSolver> linear_solver(
+ std::unique_ptr<LinearSolver> linear_solver(
new DenseQRSolver(LinearSolver::Options()));
options_.linear_solver = linear_solver.get();
options_.dogleg_type = SUBSPACE_DOGLEG;
diff --git a/internal/ceres/dynamic_autodiff_cost_function_test.cc b/internal/ceres/dynamic_autodiff_cost_function_test.cc
index ea51c2d..626cdee 100644
--- a/internal/ceres/dynamic_autodiff_cost_function_test.cc
+++ b/internal/ceres/dynamic_autodiff_cost_function_test.cc
@@ -32,8 +32,8 @@
#include <cstddef>
+#include <memory>
#include "ceres/dynamic_autodiff_cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "gtest/gtest.h"
namespace ceres {
@@ -418,7 +418,7 @@
vector<double*> parameter_blocks_;
- scoped_ptr<CostFunction> cost_function_;
+ std::unique_ptr<CostFunction> cost_function_;
vector<vector<double> > jacobian_vect_;
@@ -665,7 +665,7 @@
vector<double*> parameter_blocks_;
- scoped_ptr<CostFunction> cost_function_;
+ std::unique_ptr<CostFunction> cost_function_;
vector<vector<double> > jacobian_vect_;
diff --git a/internal/ceres/dynamic_compressed_row_sparse_matrix_test.cc b/internal/ceres/dynamic_compressed_row_sparse_matrix_test.cc
index 4030142..3592557 100644
--- a/internal/ceres/dynamic_compressed_row_sparse_matrix_test.cc
+++ b/internal/ceres/dynamic_compressed_row_sparse_matrix_test.cc
@@ -30,10 +30,10 @@
#include "ceres/dynamic_compressed_row_sparse_matrix.h"
+#include <memory>
#include "ceres/casts.h"
#include "ceres/compressed_row_sparse_matrix.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/triplet_sparse_matrix.h"
#include "gtest/gtest.h"
@@ -167,10 +167,10 @@
int expected_num_nonzeros;
Matrix dense;
- scoped_ptr<TripletSparseMatrix> tsm;
- scoped_ptr<CompressedRowSparseMatrix> crsm;
+ std::unique_ptr<TripletSparseMatrix> tsm;
+ std::unique_ptr<CompressedRowSparseMatrix> crsm;
- scoped_ptr<DynamicCompressedRowSparseMatrix> dcrsm;
+ std::unique_ptr<DynamicCompressedRowSparseMatrix> dcrsm;
};
TEST_F(DynamicCompressedRowSparseMatrixTest, Initialization) {
diff --git a/internal/ceres/dynamic_numeric_diff_cost_function_test.cc b/internal/ceres/dynamic_numeric_diff_cost_function_test.cc
index 760fdeb..e4db3c1 100644
--- a/internal/ceres/dynamic_numeric_diff_cost_function_test.cc
+++ b/internal/ceres/dynamic_numeric_diff_cost_function_test.cc
@@ -31,8 +31,8 @@
#include <cstddef>
+#include <memory>
#include "ceres/dynamic_numeric_diff_cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "gtest/gtest.h"
namespace ceres {
@@ -419,7 +419,7 @@
vector<double*> parameter_blocks_;
- scoped_ptr<CostFunction> cost_function_;
+ std::unique_ptr<CostFunction> cost_function_;
vector<vector<double> > jacobian_vect_;
diff --git a/internal/ceres/dynamic_sparse_normal_cholesky_solver.cc b/internal/ceres/dynamic_sparse_normal_cholesky_solver.cc
index 6d39616..451cfde 100644
--- a/internal/ceres/dynamic_sparse_normal_cholesky_solver.cc
+++ b/internal/ceres/dynamic_sparse_normal_cholesky_solver.cc
@@ -33,13 +33,13 @@
#include <algorithm>
#include <cstring>
#include <ctime>
+#include <memory>
#include <sstream>
#include "Eigen/SparseCore"
#include "ceres/compressed_row_sparse_matrix.h"
#include "ceres/cxsparse.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/suitesparse.h"
#include "ceres/triplet_sparse_matrix.h"
@@ -69,7 +69,7 @@
if (per_solve_options.D != NULL) {
// Temporarily append a diagonal block to the A matrix, but undo
// it before returning the matrix to the user.
- scoped_ptr<CompressedRowSparseMatrix> regularizer;
+ std::unique_ptr<CompressedRowSparseMatrix> regularizer;
if (!A->col_blocks().empty()) {
regularizer.reset(CompressedRowSparseMatrix::CreateBlockDiagonalMatrix(
per_solve_options.D, A->col_blocks()));
diff --git a/internal/ceres/dynamic_sparse_normal_cholesky_solver_test.cc b/internal/ceres/dynamic_sparse_normal_cholesky_solver_test.cc
index 1e5d179..4fe06f8 100644
--- a/internal/ceres/dynamic_sparse_normal_cholesky_solver_test.cc
+++ b/internal/ceres/dynamic_sparse_normal_cholesky_solver_test.cc
@@ -28,10 +28,10 @@
//
// Author: sameeragarwal@google.com (Sameer Agarwal)
+#include <memory>
#include "ceres/casts.h"
#include "ceres/compressed_row_sparse_matrix.h"
#include "ceres/context_impl.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/linear_solver.h"
#include "ceres/triplet_sparse_matrix.h"
@@ -50,7 +50,7 @@
class DynamicSparseNormalCholeskySolverTest : public ::testing::Test {
protected:
virtual void SetUp() {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(1));
A_.reset(CompressedRowSparseMatrix::FromTripletSparseMatrix(
*down_cast<TripletSparseMatrix*>(problem->A.get())));
@@ -74,7 +74,7 @@
A_->LeftMultiply(b_.get(), rhs.data());
Vector expected_solution = lhs.llt().solve(rhs);
- scoped_ptr<LinearSolver> solver(LinearSolver::Create(options));
+ std::unique_ptr<LinearSolver> solver(LinearSolver::Create(options));
LinearSolver::PerSolveOptions per_solve_options;
per_solve_options.D = D;
Vector actual_solution(A_->num_cols());
@@ -104,9 +104,9 @@
TestSolver(options, D_.get());
}
- scoped_ptr<CompressedRowSparseMatrix> A_;
- scoped_array<double> b_;
- scoped_array<double> D_;
+ std::unique_ptr<CompressedRowSparseMatrix> A_;
+ std::unique_ptr<double[]> b_;
+ std::unique_ptr<double[]> D_;
};
#ifndef CERES_NO_SUITESPARSE
diff --git a/internal/ceres/evaluation_callback_test.cc b/internal/ceres/evaluation_callback_test.cc
index 57e09f0..cec88d6 100644
--- a/internal/ceres/evaluation_callback_test.cc
+++ b/internal/ceres/evaluation_callback_test.cc
@@ -30,11 +30,11 @@
#include "ceres/solver.h"
-#include <limits>
#include <cmath>
+#include <limits>
#include <vector>
+
#include "gtest/gtest.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/sized_cost_function.h"
#include "ceres/problem.h"
#include "ceres/problem_impl.h"
diff --git a/internal/ceres/evaluator_test.cc b/internal/ceres/evaluator_test.cc
index 7cec00a..79006f7 100644
--- a/internal/ceres/evaluator_test.cc
+++ b/internal/ceres/evaluator_test.cc
@@ -33,12 +33,12 @@
#include "ceres/evaluator.h"
+#include <memory>
#include "ceres/casts.h"
#include "ceres/cost_function.h"
#include "ceres/crs_matrix.h"
#include "ceres/evaluator_test_utils.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/local_parameterization.h"
#include "ceres/problem_impl.h"
#include "ceres/program.h"
@@ -143,7 +143,7 @@
const double* expected_residuals,
const double* expected_gradient,
const double* expected_jacobian) {
- scoped_ptr<Evaluator> evaluator(
+ std::unique_ptr<Evaluator> evaluator(
CreateEvaluator(problem->mutable_program()));
int num_residuals = expected_num_rows;
int num_parameters = expected_num_cols;
@@ -156,7 +156,7 @@
Vector gradient(num_parameters);
gradient.setConstant(-3000);
- scoped_ptr<SparseMatrix> jacobian(evaluator->CreateJacobian());
+ std::unique_ptr<SparseMatrix> jacobian(evaluator->CreateJacobian());
ASSERT_EQ(expected_num_rows, evaluator->NumResiduals());
ASSERT_EQ(expected_num_cols, evaluator->NumEffectiveParameters());
@@ -531,8 +531,8 @@
// The values are ignored.
double state[9];
- scoped_ptr<Evaluator> evaluator(CreateEvaluator(problem.mutable_program()));
- scoped_ptr<SparseMatrix> jacobian(evaluator->CreateJacobian());
+ std::unique_ptr<Evaluator> evaluator(CreateEvaluator(problem.mutable_program()));
+ std::unique_ptr<SparseMatrix> jacobian(evaluator->CreateJacobian());
double cost;
EXPECT_FALSE(evaluator->Evaluate(state, &cost, NULL, NULL, NULL));
}
@@ -607,8 +607,8 @@
options.num_eliminate_blocks = 0;
options.context = problem.context();
string error;
- scoped_ptr<Evaluator> evaluator(Evaluator::Create(options, program, &error));
- scoped_ptr<SparseMatrix> jacobian(evaluator->CreateJacobian());
+ std::unique_ptr<Evaluator> evaluator(Evaluator::Create(options, program, &error));
+ std::unique_ptr<SparseMatrix> jacobian(evaluator->CreateJacobian());
ASSERT_EQ(2, jacobian->num_rows());
ASSERT_EQ(2, jacobian->num_cols());
diff --git a/internal/ceres/gradient_checking_cost_function.cc b/internal/ceres/gradient_checking_cost_function.cc
index eda1524..2336ffe 100644
--- a/internal/ceres/gradient_checking_cost_function.cc
+++ b/internal/ceres/gradient_checking_cost_function.cc
@@ -39,7 +39,6 @@
#include "ceres/gradient_checker.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/parameter_block.h"
#include "ceres/problem.h"
#include "ceres/problem_impl.h"
diff --git a/internal/ceres/gradient_checking_cost_function_test.cc b/internal/ceres/gradient_checking_cost_function_test.cc
index 887922e..7cf1e45 100644
--- a/internal/ceres/gradient_checking_cost_function_test.cc
+++ b/internal/ceres/gradient_checking_cost_function_test.cc
@@ -31,9 +31,10 @@
#include "ceres/gradient_checking_cost_function.h"
#include <cmath>
+#include <memory>
#include <vector>
+
#include "ceres/cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/local_parameterization.h"
#include "ceres/loss_function.h"
#include "ceres/parameter_block.h"
@@ -161,7 +162,7 @@
TestTerm<-1, -1> term(arity, dim);
GradientCheckingIterationCallback callback;
- scoped_ptr<CostFunction> gradient_checking_cost_function(
+ std::unique_ptr<CostFunction> gradient_checking_cost_function(
CreateGradientCheckingCostFunction(&term, NULL,
kRelativeStepSize,
kRelativePrecision,
@@ -218,7 +219,7 @@
{
TestTerm<1, 2> term(arity, dim);
GradientCheckingIterationCallback callback;
- scoped_ptr<CostFunction> gradient_checking_cost_function(
+ std::unique_ptr<CostFunction> gradient_checking_cost_function(
CreateGradientCheckingCostFunction(&term, NULL,
kRelativeStepSize,
kRelativePrecision,
@@ -237,7 +238,7 @@
{
TestTerm<-1, -1> term(arity, dim);
GradientCheckingIterationCallback callback;
- scoped_ptr<CostFunction> gradient_checking_cost_function(
+ std::unique_ptr<CostFunction> gradient_checking_cost_function(
CreateGradientCheckingCostFunction(&term, NULL,
kRelativeStepSize,
kRelativePrecision,
@@ -358,7 +359,7 @@
NULL, z, x, y);
GradientCheckingIterationCallback callback;
- scoped_ptr<ProblemImpl> gradient_checking_problem_impl(
+ std::unique_ptr<ProblemImpl> gradient_checking_problem_impl(
CreateGradientCheckingProblemImpl(&problem_impl, 1.0, 1.0, &callback));
// The dimensions of the two problems match.
diff --git a/internal/ceres/gradient_problem_solver.cc b/internal/ceres/gradient_problem_solver.cc
index 0d41375..5ef36ad 100644
--- a/internal/ceres/gradient_problem_solver.cc
+++ b/internal/ceres/gradient_problem_solver.cc
@@ -30,6 +30,7 @@
#include "ceres/gradient_problem_solver.h"
+#include <memory>
#include "ceres/callbacks.h"
#include "ceres/gradient_problem.h"
#include "ceres/gradient_problem_evaluator.h"
@@ -103,7 +104,6 @@
using internal::GradientProblemSolverStateUpdatingCallback;
using internal::LoggingCallback;
using internal::Minimizer;
- using internal::scoped_ptr;
using internal::SetSummaryFinalCost;
using internal::WallTimeInSeconds;
@@ -135,7 +135,7 @@
Minimizer::Options(GradientProblemSolverOptionsToSolverOptions(options));
minimizer_options.evaluator.reset(new GradientProblemEvaluator(problem));
- scoped_ptr<IterationCallback> logging_callback;
+ std::unique_ptr<IterationCallback> logging_callback;
if (options.logging_type != SILENT) {
logging_callback.reset(
new LoggingCallback(LINE_SEARCH, options.minimizer_progress_to_stdout));
@@ -143,7 +143,7 @@
logging_callback.get());
}
- scoped_ptr<IterationCallback> state_updating_callback;
+ std::unique_ptr<IterationCallback> state_updating_callback;
if (options.update_state_every_iteration) {
state_updating_callback.reset(
new GradientProblemSolverStateUpdatingCallback(
@@ -152,7 +152,7 @@
state_updating_callback.get());
}
- scoped_ptr<Minimizer> minimizer(Minimizer::Create(LINE_SEARCH));
+ std::unique_ptr<Minimizer> minimizer(Minimizer::Create(LINE_SEARCH));
Solver::Summary solver_summary;
solver_summary.fixed_cost = 0.0;
diff --git a/internal/ceres/graph_algorithms_test.cc b/internal/ceres/graph_algorithms_test.cc
index 160ece1..6440544 100644
--- a/internal/ceres/graph_algorithms_test.cc
+++ b/internal/ceres/graph_algorithms_test.cc
@@ -31,11 +31,12 @@
#include "ceres/graph_algorithms.h"
#include <algorithm>
+#include <memory>
#include <unordered_set>
-#include "gtest/gtest.h"
+
#include "ceres/graph.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
+#include "gtest/gtest.h"
namespace ceres {
namespace internal {
@@ -110,7 +111,7 @@
graph.AddEdge(0, 1, 0.5);
graph.AddEdge(1, 0, 0.5);
- scoped_ptr<WeightedGraph<int> > forest(Degree2MaximumSpanningForest(graph));
+ std::unique_ptr<WeightedGraph<int> > forest(Degree2MaximumSpanningForest(graph));
const std::unordered_set<int>& vertices = forest->vertices();
EXPECT_EQ(vertices.size(), 2);
@@ -133,7 +134,7 @@
graph.AddEdge(0, 3, 3.0);
graph.AddEdge(0, 4, 4.0);
- scoped_ptr<WeightedGraph<int> > forest(Degree2MaximumSpanningForest(graph));
+ std::unique_ptr<WeightedGraph<int> > forest(Degree2MaximumSpanningForest(graph));
const std::unordered_set<int>& vertices = forest->vertices();
EXPECT_EQ(vertices.size(), 5);
diff --git a/internal/ceres/graph_test.cc b/internal/ceres/graph_test.cc
index 0907f86..8f05475 100644
--- a/internal/ceres/graph_test.cc
+++ b/internal/ceres/graph_test.cc
@@ -32,7 +32,6 @@
#include <unordered_set>
#include "gtest/gtest.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
namespace internal {
diff --git a/internal/ceres/implicit_schur_complement.cc b/internal/ceres/implicit_schur_complement.cc
index d05f038..bf680d1 100644
--- a/internal/ceres/implicit_schur_complement.cc
+++ b/internal/ceres/implicit_schur_complement.cc
@@ -34,7 +34,6 @@
#include "ceres/block_sparse_matrix.h"
#include "ceres/block_structure.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/types.h"
#include "glog/logging.h"
diff --git a/internal/ceres/implicit_schur_complement.h b/internal/ceres/implicit_schur_complement.h
index 5d822eb..1fac72c 100644
--- a/internal/ceres/implicit_schur_complement.h
+++ b/internal/ceres/implicit_schur_complement.h
@@ -34,11 +34,11 @@
#ifndef CERES_INTERNAL_IMPLICIT_SCHUR_COMPLEMENT_H_
#define CERES_INTERNAL_IMPLICIT_SCHUR_COMPLEMENT_H_
+#include <memory>
#include "ceres/linear_operator.h"
#include "ceres/linear_solver.h"
#include "ceres/partitioned_matrix_view.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
namespace ceres {
@@ -145,12 +145,12 @@
const LinearSolver::Options& options_;
- scoped_ptr<PartitionedMatrixViewBase> A_;
+ std::unique_ptr<PartitionedMatrixViewBase> A_;
const double* D_;
const double* b_;
- scoped_ptr<BlockSparseMatrix> block_diagonal_EtE_inverse_;
- scoped_ptr<BlockSparseMatrix> block_diagonal_FtF_inverse_;
+ std::unique_ptr<BlockSparseMatrix> block_diagonal_EtE_inverse_;
+ std::unique_ptr<BlockSparseMatrix> block_diagonal_FtF_inverse_;
Vector rhs_;
diff --git a/internal/ceres/implicit_schur_complement_test.cc b/internal/ceres/implicit_schur_complement_test.cc
index 4f54a1e..cbc0aee 100644
--- a/internal/ceres/implicit_schur_complement_test.cc
+++ b/internal/ceres/implicit_schur_complement_test.cc
@@ -31,13 +31,13 @@
#include "ceres/implicit_schur_complement.h"
#include <cstddef>
+#include <memory>
#include "Eigen/Dense"
#include "ceres/block_random_access_dense_matrix.h"
#include "ceres/block_sparse_matrix.h"
#include "ceres/casts.h"
#include "ceres/context_impl.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/linear_solver.h"
#include "ceres/schur_eliminator.h"
@@ -56,7 +56,7 @@
class ImplicitSchurComplementTest : public ::testing::Test {
protected :
virtual void SetUp() {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(2));
CHECK_NOTNULL(problem.get());
@@ -89,7 +89,7 @@
ContextImpl context;
options.context = &context;
- scoped_ptr<SchurEliminatorBase> eliminator(
+ std::unique_ptr<SchurEliminatorBase> eliminator(
SchurEliminatorBase::Create(options));
CHECK_NOTNULL(eliminator.get());
const bool kFullRankETE = true;
@@ -185,9 +185,9 @@
int num_cols_;
int num_eliminate_blocks_;
- scoped_ptr<BlockSparseMatrix> A_;
- scoped_array<double> b_;
- scoped_array<double> D_;
+ std::unique_ptr<BlockSparseMatrix> A_;
+ std::unique_ptr<double[]> b_;
+ std::unique_ptr<double[]> D_;
};
// Verify that the Schur Complement matrix implied by the
diff --git a/internal/ceres/inner_product_computer.h b/internal/ceres/inner_product_computer.h
index d206707..73073f8 100644
--- a/internal/ceres/inner_product_computer.h
+++ b/internal/ceres/inner_product_computer.h
@@ -31,11 +31,11 @@
#ifndef CERES_INTERNAL_INNER_PRODUCT_COMPUTER_H_
#define CERES_INTERNAL_INNER_PRODUCT_COMPUTER_H_
+#include <memory>
#include <vector>
#include "ceres/block_sparse_matrix.h"
#include "ceres/compressed_row_sparse_matrix.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
namespace internal {
@@ -140,7 +140,7 @@
const BlockSparseMatrix& m_;
const int start_row_block_;
const int end_row_block_;
- scoped_ptr<CompressedRowSparseMatrix> result_;
+ std::unique_ptr<CompressedRowSparseMatrix> result_;
// For each term in the inner product, result_offsets_ contains the
// location in the values array of the result_ matrix where it
diff --git a/internal/ceres/inner_product_computer_test.cc b/internal/ceres/inner_product_computer_test.cc
index 863f3ef..8b2ff91 100644
--- a/internal/ceres/inner_product_computer_test.cc
+++ b/internal/ceres/inner_product_computer_test.cc
@@ -30,10 +30,10 @@
#include "ceres/inner_product_computer.h"
+#include <memory>
#include <numeric>
#include "ceres/block_sparse_matrix.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/random.h"
#include "ceres/triplet_sparse_matrix.h"
#include "glog/logging.h"
@@ -108,7 +108,7 @@
VLOG(2) << "max col block size: " << options.max_col_block_size;
VLOG(2) << "block density: " << options.block_density;
- scoped_ptr<BlockSparseMatrix> random_matrix(
+ std::unique_ptr<BlockSparseMatrix> random_matrix(
BlockSparseMatrix::CreateRandomMatrix(options));
TripletSparseMatrix tsm(random_matrix->num_rows(),
@@ -126,7 +126,7 @@
Matrix expected_inner_product =
eigen_random_matrix.transpose() * eigen_random_matrix;
- scoped_ptr<InnerProductComputer> inner_product_computer;
+ std::unique_ptr<InnerProductComputer> inner_product_computer;
inner_product_computer.reset(InnerProductComputer::Create(
*random_matrix, CompressedRowSparseMatrix::LOWER_TRIANGULAR));
@@ -168,7 +168,7 @@
VLOG(2) << "max col block size: " << options.max_col_block_size;
VLOG(2) << "block density: " << options.block_density;
- scoped_ptr<BlockSparseMatrix> random_matrix(
+ std::unique_ptr<BlockSparseMatrix> random_matrix(
BlockSparseMatrix::CreateRandomMatrix(options));
const std::vector<CompressedRow>& row_blocks =
@@ -202,7 +202,7 @@
Matrix expected_inner_product =
eigen_random_matrix.transpose() * eigen_random_matrix;
- scoped_ptr<InnerProductComputer> inner_product_computer;
+ std::unique_ptr<InnerProductComputer> inner_product_computer;
inner_product_computer.reset(InnerProductComputer::Create(
*random_matrix,
start_row_block,
diff --git a/internal/ceres/iterative_schur_complement_solver.cc b/internal/ceres/iterative_schur_complement_solver.cc
index 7a1e7a6..8ce9075 100644
--- a/internal/ceres/iterative_schur_complement_solver.cc
+++ b/internal/ceres/iterative_schur_complement_solver.cc
@@ -41,7 +41,6 @@
#include "ceres/detect_structure.h"
#include "ceres/implicit_schur_complement.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/preconditioner.h"
#include "ceres/schur_jacobi_preconditioner.h"
diff --git a/internal/ceres/iterative_schur_complement_solver.h b/internal/ceres/iterative_schur_complement_solver.h
index ffcfd8d..f898f02 100644
--- a/internal/ceres/iterative_schur_complement_solver.h
+++ b/internal/ceres/iterative_schur_complement_solver.h
@@ -31,9 +31,9 @@
#ifndef CERES_INTERNAL_ITERATIVE_SCHUR_COMPLEMENT_SOLVER_H_
#define CERES_INTERNAL_ITERATIVE_SCHUR_COMPLEMENT_SOLVER_H_
+#include <memory>
#include "ceres/linear_solver.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
namespace ceres {
@@ -82,8 +82,8 @@
void CreatePreconditioner(BlockSparseMatrix* A);
LinearSolver::Options options_;
- scoped_ptr<internal::ImplicitSchurComplement> schur_complement_;
- scoped_ptr<Preconditioner> preconditioner_;
+ std::unique_ptr<internal::ImplicitSchurComplement> schur_complement_;
+ std::unique_ptr<Preconditioner> preconditioner_;
Vector reduced_linear_system_solution_;
CERES_DISALLOW_COPY_AND_ASSIGN(IterativeSchurComplementSolver);
};
diff --git a/internal/ceres/iterative_schur_complement_solver_test.cc b/internal/ceres/iterative_schur_complement_solver_test.cc
index f5a545c..28c0d99 100644
--- a/internal/ceres/iterative_schur_complement_solver_test.cc
+++ b/internal/ceres/iterative_schur_complement_solver_test.cc
@@ -35,13 +35,13 @@
#include "ceres/iterative_schur_complement_solver.h"
#include <cstddef>
+#include <memory>
#include "Eigen/Dense"
#include "ceres/block_random_access_dense_matrix.h"
#include "ceres/block_sparse_matrix.h"
#include "ceres/casts.h"
#include "ceres/context_impl.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/linear_solver.h"
#include "ceres/schur_eliminator.h"
@@ -60,7 +60,7 @@
class IterativeSchurComplementSolverTest : public ::testing::Test {
protected :
void SetUpProblem(int problem_id) {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(problem_id));
CHECK_NOTNULL(problem.get());
@@ -85,7 +85,7 @@
options.type = DENSE_QR;
ContextImpl context;
options.context = &context;
- scoped_ptr<LinearSolver> qr(LinearSolver::Create(options));
+ std::unique_ptr<LinearSolver> qr(LinearSolver::Create(options));
LinearSolver::PerSolveOptions per_solve_options;
per_solve_options.D = D;
@@ -114,9 +114,9 @@
int num_rows_;
int num_cols_;
int num_eliminate_blocks_;
- scoped_ptr<BlockSparseMatrix> A_;
- scoped_array<double> b_;
- scoped_array<double> D_;
+ std::unique_ptr<BlockSparseMatrix> A_;
+ std::unique_ptr<double[]> b_;
+ std::unique_ptr<double[]> D_;
};
TEST_F(IterativeSchurComplementSolverTest, NormalProblem) {
diff --git a/internal/ceres/levenberg_marquardt_strategy_test.cc b/internal/ceres/levenberg_marquardt_strategy_test.cc
index 45e4da4..d5f746e 100644
--- a/internal/ceres/levenberg_marquardt_strategy_test.cc
+++ b/internal/ceres/levenberg_marquardt_strategy_test.cc
@@ -28,8 +28,8 @@
//
// Author: sameeragarwal@google.com (Sameer Agarwal)
+#include <memory>
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/levenberg_marquardt_strategy.h"
#include "ceres/linear_solver.h"
#include "ceres/trust_region_strategy.h"
@@ -86,7 +86,7 @@
options.max_lm_diagonal = 1e8;
// We need a non-null pointer here, so anything should do.
- scoped_ptr<LinearSolver> linear_solver(
+ std::unique_ptr<LinearSolver> linear_solver(
new RegularizationCheckingLinearSolver(0, NULL));
options.linear_solver = linear_solver.get();
diff --git a/internal/ceres/line_search_minimizer.cc b/internal/ceres/line_search_minimizer.cc
index 5b5b837..38e6452 100644
--- a/internal/ceres/line_search_minimizer.cc
+++ b/internal/ceres/line_search_minimizer.cc
@@ -43,6 +43,7 @@
#include <algorithm>
#include <cstdlib>
#include <cmath>
+#include <memory>
#include <string>
#include <vector>
@@ -51,7 +52,6 @@
#include "ceres/evaluator.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/line_search.h"
#include "ceres/line_search_direction.h"
#include "ceres/stringprintf.h"
@@ -164,7 +164,7 @@
line_search_direction_options.max_lbfgs_rank = options.max_lbfgs_rank;
line_search_direction_options.use_approximate_eigenvalue_bfgs_scaling =
options.use_approximate_eigenvalue_bfgs_scaling;
- scoped_ptr<LineSearchDirection> line_search_direction(
+ std::unique_ptr<LineSearchDirection> line_search_direction(
LineSearchDirection::Create(line_search_direction_options));
LineSearchFunction line_search_function(evaluator);
@@ -188,7 +188,7 @@
line_search_options.is_silent = options.is_silent;
line_search_options.function = &line_search_function;
- scoped_ptr<LineSearch>
+ std::unique_ptr<LineSearch>
line_search(LineSearch::Create(options.line_search_type,
line_search_options,
&summary->message));
diff --git a/internal/ceres/linear_least_squares_problems.cc b/internal/ceres/linear_least_squares_problems.cc
index 0a69375..fb72d63 100644
--- a/internal/ceres/linear_least_squares_problems.cc
+++ b/internal/ceres/linear_least_squares_problems.cc
@@ -31,13 +31,14 @@
#include "ceres/linear_least_squares_problems.h"
#include <cstdio>
+#include <memory>
#include <string>
#include <vector>
+
#include "ceres/block_sparse_matrix.h"
#include "ceres/block_structure.h"
#include "ceres/casts.h"
#include "ceres/file.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/stringprintf.h"
#include "ceres/triplet_sparse_matrix.h"
#include "ceres/types.h"
@@ -297,7 +298,7 @@
problem->num_eliminate_blocks = 2;
CompressedRowBlockStructure* bs = new CompressedRowBlockStructure;
- scoped_array<double> values(new double[num_rows * num_cols]);
+ std::unique_ptr<double[]> values(new double[num_rows * num_cols]);
for (int c = 0; c < num_cols; ++c) {
bs->cols.push_back(Block());
@@ -431,7 +432,7 @@
problem->num_eliminate_blocks = 2;
CompressedRowBlockStructure* bs = new CompressedRowBlockStructure;
- scoped_array<double> values(new double[num_rows * num_cols]);
+ std::unique_ptr<double[]> values(new double[num_rows * num_cols]);
for (int c = 0; c < num_cols; ++c) {
bs->cols.push_back(Block());
@@ -538,7 +539,7 @@
problem->num_eliminate_blocks = 1;
CompressedRowBlockStructure* bs = new CompressedRowBlockStructure;
- scoped_array<double> values(new double[num_rows * num_cols]);
+ std::unique_ptr<double[]> values(new double[num_rows * num_cols]);
// Column block structure
bs->cols.push_back(Block());
diff --git a/internal/ceres/linear_least_squares_problems.h b/internal/ceres/linear_least_squares_problems.h
index 384efb5..5dfcd34 100644
--- a/internal/ceres/linear_least_squares_problems.h
+++ b/internal/ceres/linear_least_squares_problems.h
@@ -31,11 +31,11 @@
#ifndef CERES_INTERNAL_LINEAR_LEAST_SQUARES_PROBLEMS_H_
#define CERES_INTERNAL_LINEAR_LEAST_SQUARES_PROBLEMS_H_
+#include <memory>
#include <string>
#include <vector>
#include "ceres/sparse_matrix.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
namespace internal {
@@ -44,21 +44,20 @@
// ground truth solutions. To be used by various LinearSolver tests.
struct LinearLeastSquaresProblem {
LinearLeastSquaresProblem()
- : A(NULL), b(NULL), D(NULL), num_eliminate_blocks(0),
- x(NULL), x_D(NULL) {
+ : num_eliminate_blocks(0) {
}
- scoped_ptr<SparseMatrix> A;
- scoped_array<double> b;
- scoped_array<double> D;
+ std::unique_ptr<SparseMatrix> A;
+ std::unique_ptr<double[]> b;
+ std::unique_ptr<double[]> D;
// If using the schur eliminator then how many of the variable
// blocks are e_type blocks.
int num_eliminate_blocks;
// Solution to min_x |Ax - b|^2
- scoped_array<double> x;
+ std::unique_ptr<double[]> x;
// Solution to min_x |Ax - b|^2 + |Dx|^2
- scoped_array<double> x_D;
+ std::unique_ptr<double[]> x_D;
};
// Factories for linear least squares problem.
diff --git a/internal/ceres/local_parameterization_test.cc b/internal/ceres/local_parameterization_test.cc
index 15f0bb1..41c78cb 100644
--- a/internal/ceres/local_parameterization_test.cc
+++ b/internal/ceres/local_parameterization_test.cc
@@ -30,6 +30,8 @@
#include <cmath>
#include <limits>
+#include <memory>
+
#include "Eigen/Geometry"
#include "ceres/autodiff_local_parameterization.h"
#include "ceres/fpclassify.h"
@@ -611,10 +613,10 @@
constant_parameters4));
}
- scoped_ptr<LocalParameterization> param1_;
- scoped_ptr<LocalParameterization> param2_;
- scoped_ptr<LocalParameterization> param3_;
- scoped_ptr<LocalParameterization> param4_;
+ std::unique_ptr<LocalParameterization> param1_;
+ std::unique_ptr<LocalParameterization> param2_;
+ std::unique_ptr<LocalParameterization> param3_;
+ std::unique_ptr<LocalParameterization> param4_;
};
TEST_F(ProductParameterizationTest, LocalAndGlobalSize2) {
diff --git a/internal/ceres/normal_prior.cc b/internal/ceres/normal_prior.cc
index b3666cd..a3d5d8e 100644
--- a/internal/ceres/normal_prior.cc
+++ b/internal/ceres/normal_prior.cc
@@ -33,7 +33,6 @@
#include <cstddef>
#include <vector>
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
#include "glog/logging.h"
diff --git a/internal/ceres/numeric_diff_cost_function_test.cc b/internal/ceres/numeric_diff_cost_function_test.cc
index 983f11e..f006ff0 100644
--- a/internal/ceres/numeric_diff_cost_function_test.cc
+++ b/internal/ceres/numeric_diff_cost_function_test.cc
@@ -33,10 +33,11 @@
#include <algorithm>
#include <cmath>
+#include <memory>
#include <string>
#include <vector>
+
#include "ceres/internal/macros.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/array_utils.h"
#include "ceres/numeric_diff_test_utils.h"
#include "ceres/test_util.h"
@@ -48,7 +49,7 @@
namespace internal {
TEST(NumericDiffCostFunction, EasyCaseFunctorCentralDifferences) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<EasyFunctor,
CENTRAL,
@@ -61,7 +62,7 @@
}
TEST(NumericDiffCostFunction, EasyCaseFunctorForwardDifferences) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<EasyFunctor,
FORWARD,
@@ -74,7 +75,7 @@
}
TEST(NumericDiffCostFunction, EasyCaseFunctorRidders) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<EasyFunctor,
RIDDERS,
@@ -87,7 +88,7 @@
}
TEST(NumericDiffCostFunction, EasyCaseCostFunctionCentralDifferences) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<EasyCostFunction,
CENTRAL,
@@ -100,7 +101,7 @@
}
TEST(NumericDiffCostFunction, EasyCaseCostFunctionForwardDifferences) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<EasyCostFunction,
FORWARD,
@@ -113,7 +114,7 @@
}
TEST(NumericDiffCostFunction, EasyCaseCostFunctionRidders) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<EasyCostFunction,
RIDDERS,
@@ -127,7 +128,7 @@
TEST(NumericDiffCostFunction,
TranscendentalCaseFunctorCentralDifferences) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<TranscendentalFunctor,
CENTRAL,
@@ -141,7 +142,7 @@
TEST(NumericDiffCostFunction,
TranscendentalCaseFunctorForwardDifferences) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<TranscendentalFunctor,
FORWARD,
@@ -161,7 +162,7 @@
// behavior.
options.ridders_relative_initial_step_size = 1e-3;
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<TranscendentalFunctor,
RIDDERS,
@@ -175,7 +176,7 @@
TEST(NumericDiffCostFunction,
TranscendentalCaseCostFunctionCentralDifferences) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<TranscendentalCostFunction,
CENTRAL,
@@ -189,7 +190,7 @@
TEST(NumericDiffCostFunction,
TranscendentalCaseCostFunctionForwardDifferences) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<TranscendentalCostFunction,
FORWARD,
@@ -209,7 +210,7 @@
// behavior.
options.ridders_relative_initial_step_size = 1e-3;
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<TranscendentalCostFunction,
RIDDERS,
@@ -238,7 +239,7 @@
// templates are instantiated for various shapes of the Jacobian
// matrix.
TEST(NumericDiffCostFunction, EigenRowMajorColMajorTest) {
- scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<SizeTestingCostFunction<1,1>, CENTRAL, 1, 1>(
new SizeTestingCostFunction<1,1>, ceres::TAKE_OWNERSHIP));
@@ -282,7 +283,7 @@
TEST(NumericDiffCostFunction,
EasyCaseFunctorCentralDifferencesAndDynamicNumResiduals) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<EasyFunctor,
CENTRAL,
@@ -295,7 +296,7 @@
}
TEST(NumericDiffCostFunction, ExponentialFunctorRidders) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<ExponentialFunctor,
RIDDERS,
@@ -307,7 +308,7 @@
}
TEST(NumericDiffCostFunction, ExponentialCostFunctionRidders) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
cost_function.reset(
new NumericDiffCostFunction<ExponentialCostFunction,
RIDDERS,
@@ -319,7 +320,7 @@
}
TEST(NumericDiffCostFunction, RandomizedFunctorRidders) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
NumericDiffOptions options;
// Larger initial step size is chosen to produce robust results in the
// presence of random noise.
@@ -337,7 +338,7 @@
}
TEST(NumericDiffCostFunction, RandomizedCostFunctionRidders) {
- internal::scoped_ptr<CostFunction> cost_function;
+ std::unique_ptr<CostFunction> cost_function;
NumericDiffOptions options;
// Larger initial step size is chosen to produce robust results in the
// presence of random noise.
@@ -368,7 +369,7 @@
double* parameters[] = {¶meter};
double* jacobians[] = {jacobian};
- scoped_ptr<CostFunction> cost_function(
+ std::unique_ptr<CostFunction> cost_function(
new NumericDiffCostFunction<OnlyFillsOneOutputFunctor, CENTRAL, 2, 1>(
new OnlyFillsOneOutputFunctor));
InvalidateArray(2, jacobian);
diff --git a/internal/ceres/parameter_block.h b/internal/ceres/parameter_block.h
index a41d9d1..9149a54 100644
--- a/internal/ceres/parameter_block.h
+++ b/internal/ceres/parameter_block.h
@@ -33,6 +33,7 @@
#include <algorithm>
#include <cstdlib>
+#include <memory>
#include <limits>
#include <string>
#include <unordered_set>
@@ -40,7 +41,6 @@
#include "ceres/integral_types.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/local_parameterization.h"
#include "ceres/stringprintf.h"
#include "glog/logging.h"
@@ -368,7 +368,7 @@
// ends up simplifying the internals of Ceres enough to justify the potential
// pitfalls of using "mutable."
mutable const double* state_;
- mutable scoped_array<double> local_parameterization_jacobian_;
+ mutable std::unique_ptr<double[]> local_parameterization_jacobian_;
// The index of the parameter. This is used by various other parts of Ceres to
// permit switching from a ParameterBlock* to an index in another array.
@@ -381,7 +381,7 @@
int32 delta_offset_;
// If non-null, contains the residual blocks this parameter block is in.
- scoped_ptr<ResidualBlockSet> residual_blocks_;
+ std::unique_ptr<ResidualBlockSet> residual_blocks_;
// Upper and lower bounds for the parameter block. SetUpperBound
// and SetLowerBound lazily initialize the upper_bounds_ and
@@ -394,8 +394,8 @@
// std::numeric_limits<double>::max() and
// -std::numeric_limits<double>::max() respectively which correspond
// to the parameter block being unconstrained.
- scoped_array<double> upper_bounds_;
- scoped_array<double> lower_bounds_;
+ std::unique_ptr<double[]> upper_bounds_;
+ std::unique_ptr<double[]> lower_bounds_;
// Necessary so ProblemImpl can clean up the parameterizations.
friend class ProblemImpl;
diff --git a/internal/ceres/parameter_block_ordering.cc b/internal/ceres/parameter_block_ordering.cc
index 649ce14..a71c019 100644
--- a/internal/ceres/parameter_block_ordering.cc
+++ b/internal/ceres/parameter_block_ordering.cc
@@ -30,10 +30,11 @@
#include "ceres/parameter_block_ordering.h"
+#include <memory>
#include <unordered_set>
+
#include "ceres/graph.h"
#include "ceres/graph_algorithms.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/map_util.h"
#include "ceres/parameter_block.h"
#include "ceres/program.h"
@@ -52,7 +53,7 @@
vector<ParameterBlock*>* ordering) {
CHECK_NOTNULL(ordering)->clear();
EventLogger event_logger("ComputeStableSchurOrdering");
- scoped_ptr<Graph< ParameterBlock*> > graph(CreateHessianGraph(program));
+ std::unique_ptr<Graph< ParameterBlock*> > graph(CreateHessianGraph(program));
event_logger.AddEvent("CreateHessianGraph");
const vector<ParameterBlock*>& parameter_blocks = program.parameter_blocks();
@@ -83,7 +84,7 @@
vector<ParameterBlock*>* ordering) {
CHECK_NOTNULL(ordering)->clear();
- scoped_ptr<Graph< ParameterBlock*> > graph(CreateHessianGraph(program));
+ std::unique_ptr<Graph< ParameterBlock*> > graph(CreateHessianGraph(program));
int independent_set_size = IndependentSetOrdering(*graph, ordering);
const vector<ParameterBlock*>& parameter_blocks = program.parameter_blocks();
@@ -102,7 +103,7 @@
ParameterBlockOrdering* ordering) {
CHECK_NOTNULL(ordering)->Clear();
const vector<ParameterBlock*> parameter_blocks = program.parameter_blocks();
- scoped_ptr<Graph< ParameterBlock*> > graph(CreateHessianGraph(program));
+ std::unique_ptr<Graph< ParameterBlock*> > graph(CreateHessianGraph(program));
int num_covered = 0;
int round = 0;
diff --git a/internal/ceres/parameter_block_ordering_test.cc b/internal/ceres/parameter_block_ordering_test.cc
index 41babff..339e73b 100644
--- a/internal/ceres/parameter_block_ordering_test.cc
+++ b/internal/ceres/parameter_block_ordering_test.cc
@@ -31,16 +31,17 @@
#include "ceres/parameter_block_ordering.h"
#include <cstddef>
+#include <memory>
#include <unordered_set>
#include <vector>
-#include "gtest/gtest.h"
+
+#include "ceres/cost_function.h"
#include "ceres/graph.h"
#include "ceres/problem_impl.h"
#include "ceres/program.h"
-#include "ceres/stl_util.h"
-#include "ceres/cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/sized_cost_function.h"
+#include "ceres/stl_util.h"
+#include "gtest/gtest.h"
namespace ceres {
namespace internal {
@@ -85,7 +86,7 @@
TEST_F(SchurOrderingTest, NoFixed) {
const Program& program = problem_.program();
const vector<ParameterBlock*>& parameter_blocks = program.parameter_blocks();
- scoped_ptr<HessianGraph> graph(CreateHessianGraph(program));
+ std::unique_ptr<HessianGraph> graph(CreateHessianGraph(program));
const VertexSet& vertices = graph->vertices();
EXPECT_EQ(vertices.size(), 4);
@@ -130,7 +131,7 @@
problem_.SetParameterBlockConstant(w_);
const Program& program = problem_.program();
- scoped_ptr<HessianGraph> graph(CreateHessianGraph(program));
+ std::unique_ptr<HessianGraph> graph(CreateHessianGraph(program));
EXPECT_EQ(graph->vertices().size(), 0);
}
@@ -139,7 +140,7 @@
const Program& program = problem_.program();
const vector<ParameterBlock*>& parameter_blocks = program.parameter_blocks();
- scoped_ptr<HessianGraph> graph(CreateHessianGraph(program));
+ std::unique_ptr<HessianGraph> graph(CreateHessianGraph(program));
const VertexSet& vertices = graph->vertices();
diff --git a/internal/ceres/partitioned_matrix_view_test.cc b/internal/ceres/partitioned_matrix_view_test.cc
index 1e48892..7eafff4 100644
--- a/internal/ceres/partitioned_matrix_view_test.cc
+++ b/internal/ceres/partitioned_matrix_view_test.cc
@@ -30,11 +30,11 @@
#include "ceres/partitioned_matrix_view.h"
+#include <memory>
#include <vector>
#include "ceres/block_structure.h"
#include "ceres/casts.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/random.h"
#include "ceres/sparse_matrix.h"
@@ -50,7 +50,7 @@
protected :
virtual void SetUp() {
srand(5);
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(2));
CHECK_NOTNULL(problem.get());
A_.reset(problem->A.release());
@@ -68,8 +68,8 @@
int num_rows_;
int num_cols_;
int num_eliminate_blocks_;
- scoped_ptr<SparseMatrix> A_;
- scoped_ptr<PartitionedMatrixViewBase> pmv_;
+ std::unique_ptr<SparseMatrix> A_;
+ std::unique_ptr<PartitionedMatrixViewBase> pmv_;
};
TEST_F(PartitionedMatrixViewTest, DimensionsTest) {
@@ -143,7 +143,7 @@
}
TEST_F(PartitionedMatrixViewTest, BlockDiagonalEtE) {
- scoped_ptr<BlockSparseMatrix>
+ std::unique_ptr<BlockSparseMatrix>
block_diagonal_ee(pmv_->CreateBlockDiagonalEtE());
const CompressedRowBlockStructure* bs = block_diagonal_ee->block_structure();
@@ -157,7 +157,7 @@
}
TEST_F(PartitionedMatrixViewTest, BlockDiagonalFtF) {
- scoped_ptr<BlockSparseMatrix>
+ std::unique_ptr<BlockSparseMatrix>
block_diagonal_ff(pmv_->CreateBlockDiagonalFtF());
const CompressedRowBlockStructure* bs = block_diagonal_ff->block_structure();
diff --git a/internal/ceres/preprocessor.h b/internal/ceres/preprocessor.h
index ce2eec5..37e4204 100644
--- a/internal/ceres/preprocessor.h
+++ b/internal/ceres/preprocessor.h
@@ -39,7 +39,6 @@
#include "ceres/evaluator.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/iteration_callback.h"
#include "ceres/linear_solver.h"
#include "ceres/minimizer.h"
@@ -92,11 +91,11 @@
Minimizer::Options minimizer_options;
ProblemImpl* problem;
- scoped_ptr<ProblemImpl> gradient_checking_problem;
- scoped_ptr<Program> reduced_program;
- scoped_ptr<LinearSolver> linear_solver;
- scoped_ptr<IterationCallback> logging_callback;
- scoped_ptr<IterationCallback> state_updating_callback;
+ std::unique_ptr<ProblemImpl> gradient_checking_problem;
+ std::unique_ptr<Program> reduced_program;
+ std::unique_ptr<LinearSolver> linear_solver;
+ std::unique_ptr<IterationCallback> logging_callback;
+ std::unique_ptr<IterationCallback> state_updating_callback;
std::shared_ptr<Evaluator> evaluator;
std::shared_ptr<CoordinateDescentMinimizer> inner_iteration_minimizer;
diff --git a/internal/ceres/problem_impl.cc b/internal/ceres/problem_impl.cc
index 1f3c55b..94af8ad 100644
--- a/internal/ceres/problem_impl.cc
+++ b/internal/ceres/problem_impl.cc
@@ -34,10 +34,12 @@
#include <algorithm>
#include <cstddef>
#include <iterator>
+#include <memory>
#include <set>
#include <string>
#include <utility>
#include <vector>
+
#include "ceres/casts.h"
#include "ceres/compressed_row_jacobian_writer.h"
#include "ceres/compressed_row_sparse_matrix.h"
@@ -822,7 +824,7 @@
context_impl_->EnsureMinimumThreads(evaluator_options.num_threads - 1);
evaluator_options.context = context_impl_;
- scoped_ptr<Evaluator> evaluator(
+ std::unique_ptr<Evaluator> evaluator(
new ProgramEvaluator<ScratchEvaluatePreparer,
CompressedRowJacobianWriter>(evaluator_options,
&program));
@@ -835,7 +837,7 @@
gradient->resize(evaluator->NumEffectiveParameters());
}
- scoped_ptr<CompressedRowSparseMatrix> tmp_jacobian;
+ std::unique_ptr<CompressedRowSparseMatrix> tmp_jacobian;
if (jacobian != NULL) {
tmp_jacobian.reset(
down_cast<CompressedRowSparseMatrix*>(evaluator->CreateJacobian()));
diff --git a/internal/ceres/problem_impl.h b/internal/ceres/problem_impl.h
index 4c24e3b..44d6e89 100644
--- a/internal/ceres/problem_impl.h
+++ b/internal/ceres/problem_impl.h
@@ -40,13 +40,13 @@
#define CERES_PUBLIC_PROBLEM_IMPL_H_
#include <map>
+#include <memory>
#include <unordered_set>
#include <vector>
#include "ceres/context_impl.h"
#include "ceres/internal/macros.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/problem.h"
#include "ceres/types.h"
@@ -209,7 +209,7 @@
ResidualBlockSet residual_block_set_;
// The actual parameter and residual blocks.
- internal::scoped_ptr<internal::Program> program_;
+ std::unique_ptr<internal::Program> program_;
// When removing parameter blocks, parameterizations have ambiguous
// ownership. Instead of scanning the entire problem to see if the
diff --git a/internal/ceres/problem_test.cc b/internal/ceres/problem_test.cc
index 826e2c2..3473c59 100644
--- a/internal/ceres/problem_test.cc
+++ b/internal/ceres/problem_test.cc
@@ -32,12 +32,12 @@
#include "ceres/problem.h"
#include "ceres/problem_impl.h"
+#include <memory>
#include "ceres/casts.h"
#include "ceres/cost_function.h"
#include "ceres/crs_matrix.h"
#include "ceres/evaluator_test_utils.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/local_parameterization.h"
#include "ceres/loss_function.h"
#include "ceres/map_util.h"
@@ -496,7 +496,7 @@
ExpectParameterBlockContainsResidualBlock(values, r4);
}
- scoped_ptr<ProblemImpl> problem;
+ std::unique_ptr<ProblemImpl> problem;
double y[4], z[5], w[3];
};
diff --git a/internal/ceres/program.cc b/internal/ceres/program.cc
index f6cd138..31b5d1a 100644
--- a/internal/ceres/program.cc
+++ b/internal/ceres/program.cc
@@ -31,7 +31,9 @@
#include "ceres/program.h"
#include <map>
+#include <memory>
#include <vector>
+
#include "ceres/array_utils.h"
#include "ceres/casts.h"
#include "ceres/compressed_row_sparse_matrix.h"
@@ -274,7 +276,7 @@
CHECK_NOTNULL(fixed_cost);
CHECK_NOTNULL(error);
- scoped_ptr<Program> reduced_program(new Program(*this));
+ std::unique_ptr<Program> reduced_program(new Program(*this));
if (!reduced_program->RemoveFixedBlocks(removed_parameter_blocks,
fixed_cost,
error)) {
@@ -292,7 +294,7 @@
CHECK_NOTNULL(fixed_cost);
CHECK_NOTNULL(error);
- scoped_array<double> residual_block_evaluate_scratch;
+ std::unique_ptr<double[]> residual_block_evaluate_scratch;
residual_block_evaluate_scratch.reset(
new double[MaxScratchDoublesNeededForEvaluate()]);
*fixed_cost = 0.0;
diff --git a/internal/ceres/program_evaluator.h b/internal/ceres/program_evaluator.h
index 10dcc06..17175a6 100644
--- a/internal/ceres/program_evaluator.h
+++ b/internal/ceres/program_evaluator.h
@@ -83,12 +83,12 @@
#include "ceres/internal/port.h"
#include <map>
+#include <memory>
#include <string>
#include <vector>
#include "ceres/evaluation_callback.h"
#include "ceres/execution_summary.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/parameter_block.h"
#include "ceres/program.h"
#include "ceres/residual_block.h"
@@ -373,12 +373,12 @@
}
double cost;
- scoped_array<double> residual_block_evaluate_scratch;
+ std::unique_ptr<double[]> residual_block_evaluate_scratch;
// The gradient in the local parameterization.
- scoped_array<double> gradient;
+ std::unique_ptr<double[]> gradient;
// Enough space to store the residual for the largest residual block.
- scoped_array<double> residual_block_residuals;
- scoped_array<double*> jacobian_block_ptrs;
+ std::unique_ptr<double[]> residual_block_residuals;
+ std::unique_ptr<double*[]> jacobian_block_ptrs;
};
static void BuildResidualLayout(const Program& program,
@@ -418,8 +418,8 @@
Evaluator::Options options_;
Program* program_;
JacobianWriter jacobian_writer_;
- scoped_array<EvaluatePreparer> evaluate_preparers_;
- scoped_array<EvaluateScratch> evaluate_scratch_;
+ std::unique_ptr<EvaluatePreparer[]> evaluate_preparers_;
+ std::unique_ptr<EvaluateScratch[]> evaluate_scratch_;
std::vector<int> residual_layout_;
::ceres::internal::ExecutionSummary execution_summary_;
};
diff --git a/internal/ceres/program_test.cc b/internal/ceres/program_test.cc
index 7bf512f..6778484 100644
--- a/internal/ceres/program_test.cc
+++ b/internal/ceres/program_test.cc
@@ -30,9 +30,11 @@
#include "ceres/program.h"
-#include <limits>
#include <cmath>
+#include <limits>
+#include <memory>
#include <vector>
+
#include "ceres/sized_cost_function.h"
#include "ceres/problem_impl.h"
#include "ceres/residual_block.h"
@@ -94,7 +96,7 @@
vector<double*> removed_parameter_blocks;
double fixed_cost = 0.0;
string message;
- scoped_ptr<Program> reduced_program(
+ std::unique_ptr<Program> reduced_program(
CHECK_NOTNULL(problem
.program()
.CreateReducedProgram(&removed_parameter_blocks,
@@ -118,7 +120,7 @@
vector<double*> removed_parameter_blocks;
double fixed_cost = 0.0;
string message;
- scoped_ptr<Program> reduced_program(
+ std::unique_ptr<Program> reduced_program(
CHECK_NOTNULL(problem
.program()
.CreateReducedProgram(&removed_parameter_blocks,
@@ -145,7 +147,7 @@
vector<double*> removed_parameter_blocks;
double fixed_cost = 0.0;
string message;
- scoped_ptr<Program> reduced_program(
+ std::unique_ptr<Program> reduced_program(
CHECK_NOTNULL(problem
.program()
.CreateReducedProgram(&removed_parameter_blocks,
@@ -174,7 +176,7 @@
vector<double*> removed_parameter_blocks;
double fixed_cost = 0.0;
string message;
- scoped_ptr<Program> reduced_program(
+ std::unique_ptr<Program> reduced_program(
CHECK_NOTNULL(problem
.program()
.CreateReducedProgram(&removed_parameter_blocks,
@@ -201,7 +203,7 @@
vector<double*> removed_parameter_blocks;
double fixed_cost = 0.0;
string message;
- scoped_ptr<Program> reduced_program(
+ std::unique_ptr<Program> reduced_program(
CHECK_NOTNULL(problem
.program()
.CreateReducedProgram(&removed_parameter_blocks,
@@ -227,7 +229,7 @@
ResidualBlock *expected_removed_block =
problem.program().residual_blocks()[0];
- scoped_array<double> scratch(
+ std::unique_ptr<double[]> scratch(
new double[expected_removed_block->NumScratchDoublesForEvaluate()]);
double expected_fixed_cost;
expected_removed_block->Evaluate(true,
@@ -240,7 +242,7 @@
vector<double*> removed_parameter_blocks;
double fixed_cost = 0.0;
string message;
- scoped_ptr<Program> reduced_program(
+ std::unique_ptr<Program> reduced_program(
CHECK_NOTNULL(problem
.program()
.CreateReducedProgram(&removed_parameter_blocks,
@@ -318,7 +320,7 @@
Program* program = problem.mutable_program();
program->SetParameterOffsetsAndIndex();
- scoped_ptr<TripletSparseMatrix> actual_block_sparse_jacobian(
+ std::unique_ptr<TripletSparseMatrix> actual_block_sparse_jacobian(
program->CreateJacobianBlockSparsityTranspose());
Matrix expected_dense_jacobian;
@@ -385,7 +387,7 @@
Program* program = problem.mutable_program();
program->SetParameterOffsetsAndIndex();
- scoped_ptr<TripletSparseMatrix> actual_block_sparse_jacobian(
+ std::unique_ptr<TripletSparseMatrix> actual_block_sparse_jacobian(
program->CreateJacobianBlockSparsityTranspose());
Matrix expected_dense_jacobian;
diff --git a/internal/ceres/reorder_program.cc b/internal/ceres/reorder_program.cc
index 94a35bd..f3480a3 100644
--- a/internal/ceres/reorder_program.cc
+++ b/internal/ceres/reorder_program.cc
@@ -31,6 +31,7 @@
#include "ceres/reorder_program.h"
#include <algorithm>
+#include <memory>
#include <numeric>
#include <vector>
@@ -359,7 +360,7 @@
MapValuesToContiguousRange(constraints.size(), &constraints[0]);
// Compute a block sparse presentation of J'.
- scoped_ptr<TripletSparseMatrix> tsm_block_jacobian_transpose(
+ std::unique_ptr<TripletSparseMatrix> tsm_block_jacobian_transpose(
program->CreateJacobianBlockSparsityTranspose());
cholmod_sparse* block_jacobian_transpose =
@@ -388,7 +389,7 @@
return;
#else
- scoped_ptr<TripletSparseMatrix> tsm_block_jacobian_transpose(
+ std::unique_ptr<TripletSparseMatrix> tsm_block_jacobian_transpose(
program->CreateJacobianBlockSparsityTranspose());
typedef Eigen::SparseMatrix<int> SparseMatrix;
@@ -550,7 +551,7 @@
}
// Compute a block sparse presentation of J'.
- scoped_ptr<TripletSparseMatrix> tsm_block_jacobian_transpose(
+ std::unique_ptr<TripletSparseMatrix> tsm_block_jacobian_transpose(
program->CreateJacobianBlockSparsityTranspose());
vector<int> ordering(program->NumParameterBlocks(), 0);
diff --git a/internal/ceres/residual_block.h b/internal/ceres/residual_block.h
index a32f1c3..815a7a1 100644
--- a/internal/ceres/residual_block.h
+++ b/internal/ceres/residual_block.h
@@ -34,12 +34,12 @@
#ifndef CERES_INTERNAL_RESIDUAL_BLOCK_H_
#define CERES_INTERNAL_RESIDUAL_BLOCK_H_
+#include <memory>
#include <string>
#include <vector>
#include "ceres/cost_function.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/stringprintf.h"
#include "ceres/types.h"
@@ -134,7 +134,7 @@
private:
const CostFunction* cost_function_;
const LossFunction* loss_function_;
- scoped_array<ParameterBlock*> parameter_blocks_;
+ std::unique_ptr<ParameterBlock*[]> parameter_blocks_;
// The index of the residual, typically in a Program. This is only to permit
// switching from a ResidualBlock* to an index in the Program's array, needed
diff --git a/internal/ceres/residual_block_utils_test.cc b/internal/ceres/residual_block_utils_test.cc
index 3a7e9c3..3beaa10 100644
--- a/internal/ceres/residual_block_utils_test.cc
+++ b/internal/ceres/residual_block_utils_test.cc
@@ -30,12 +30,12 @@
#include <cmath>
#include <limits>
+#include <memory>
#include "gtest/gtest.h"
#include "ceres/parameter_block.h"
#include "ceres/residual_block.h"
#include "ceres/residual_block_utils.h"
#include "ceres/cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/sized_cost_function.h"
namespace ceres {
@@ -54,7 +54,7 @@
parameter_blocks,
-1);
- scoped_array<double> scratch(
+ std::unique_ptr<double[]> scratch(
new double[residual_block.NumScratchDoublesForEvaluate()]);
double cost;
diff --git a/internal/ceres/schur_complement_solver.cc b/internal/ceres/schur_complement_solver.cc
index 16470fd..0fb9c30 100644
--- a/internal/ceres/schur_complement_solver.cc
+++ b/internal/ceres/schur_complement_solver.cc
@@ -32,6 +32,7 @@
#include <algorithm>
#include <ctime>
+#include <memory>
#include <set>
#include <vector>
@@ -45,7 +46,6 @@
#include "ceres/conjugate_gradients_solver.h"
#include "ceres/detect_structure.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/lapack.h"
#include "ceres/linear_solver.h"
#include "ceres/sparse_cholesky.h"
@@ -325,7 +325,7 @@
return summary;
}
- scoped_ptr<CompressedRowSparseMatrix> lhs;
+ std::unique_ptr<CompressedRowSparseMatrix> lhs;
const CompressedRowSparseMatrix::StorageType storage_type =
sparse_cholesky_->StorageType();
if (storage_type == CompressedRowSparseMatrix::UPPER_TRIANGULAR) {
@@ -399,9 +399,9 @@
VectorRef(solution, num_rows).setZero();
- scoped_ptr<LinearOperator> lhs_adapter(
+ std::unique_ptr<LinearOperator> lhs_adapter(
new BlockRandomAccessSparseMatrixAdapter(*sc));
- scoped_ptr<LinearOperator> preconditioner_adapter(
+ std::unique_ptr<LinearOperator> preconditioner_adapter(
new BlockRandomAccessDiagonalMatrixAdapter(*preconditioner_));
diff --git a/internal/ceres/schur_complement_solver.h b/internal/ceres/schur_complement_solver.h
index e83a715..5f15c86 100644
--- a/internal/ceres/schur_complement_solver.h
+++ b/internal/ceres/schur_complement_solver.h
@@ -31,6 +31,7 @@
#ifndef CERES_INTERNAL_SCHUR_COMPLEMENT_SOLVER_H_
#define CERES_INTERNAL_SCHUR_COMPLEMENT_SOLVER_H_
+#include <memory>
#include <set>
#include <utility>
#include <vector>
@@ -40,7 +41,6 @@
#include "ceres/block_sparse_matrix.h"
#include "ceres/block_structure.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/schur_eliminator.h"
#include "ceres/types.h"
@@ -140,9 +140,9 @@
LinearSolver::Options options_;
- scoped_ptr<SchurEliminatorBase> eliminator_;
- scoped_ptr<BlockRandomAccessMatrix> lhs_;
- scoped_array<double> rhs_;
+ std::unique_ptr<SchurEliminatorBase> eliminator_;
+ std::unique_ptr<BlockRandomAccessMatrix> lhs_;
+ std::unique_ptr<double[]> rhs_;
CERES_DISALLOW_COPY_AND_ASSIGN(SchurComplementSolver);
};
@@ -180,8 +180,8 @@
// Size of the blocks in the Schur complement.
std::vector<int> blocks_;
- scoped_ptr<SparseCholesky> sparse_cholesky_;
- scoped_ptr<BlockRandomAccessDiagonalMatrix> preconditioner_;
+ std::unique_ptr<SparseCholesky> sparse_cholesky_;
+ std::unique_ptr<BlockRandomAccessDiagonalMatrix> preconditioner_;
CERES_DISALLOW_COPY_AND_ASSIGN(SparseSchurComplementSolver);
};
diff --git a/internal/ceres/schur_complement_solver_test.cc b/internal/ceres/schur_complement_solver_test.cc
index 3f70300..2350858 100644
--- a/internal/ceres/schur_complement_solver_test.cc
+++ b/internal/ceres/schur_complement_solver_test.cc
@@ -31,13 +31,13 @@
#include "ceres/schur_complement_solver.h"
#include <cstddef>
+#include <memory>
#include "ceres/block_sparse_matrix.h"
#include "ceres/block_structure.h"
#include "ceres/casts.h"
#include "ceres/context_impl.h"
#include "ceres/detect_structure.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/linear_solver.h"
#include "ceres/triplet_sparse_matrix.h"
@@ -51,7 +51,7 @@
class SchurComplementSolverTest : public ::testing::Test {
protected:
void SetUpFromProblemId(int problem_id) {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(problem_id));
CHECK_NOTNULL(problem.get());
@@ -72,7 +72,7 @@
ContextImpl context;
options.context = &context;
- scoped_ptr<LinearSolver> qr(LinearSolver::Create(options));
+ std::unique_ptr<LinearSolver> qr(LinearSolver::Create(options));
TripletSparseMatrix triplet_A(A->num_rows(),
A->num_cols(),
@@ -115,7 +115,7 @@
&options.e_block_size,
&options.f_block_size);
- scoped_ptr<LinearSolver> solver(LinearSolver::Create(options));
+ std::unique_ptr<LinearSolver> solver(LinearSolver::Create(options));
LinearSolver::PerSolveOptions per_solve_options;
LinearSolver::Summary summary;
@@ -142,9 +142,9 @@
int num_cols;
int num_eliminate_blocks;
- scoped_ptr<BlockSparseMatrix> A;
- scoped_array<double> b;
- scoped_array<double> D;
+ std::unique_ptr<BlockSparseMatrix> A;
+ std::unique_ptr<double[]> b;
+ std::unique_ptr<double[]> D;
Vector x;
Vector sol;
Vector sol_d;
diff --git a/internal/ceres/schur_eliminator.h b/internal/ceres/schur_eliminator.h
index df0d22d..d93bcb0 100644
--- a/internal/ceres/schur_eliminator.h
+++ b/internal/ceres/schur_eliminator.h
@@ -32,13 +32,14 @@
#define CERES_INTERNAL_SCHUR_ELIMINATOR_H_
#include <map>
+#include <memory>
#include <mutex>
#include <vector>
+
#include "ceres/block_random_access_matrix.h"
#include "ceres/block_sparse_matrix.h"
#include "ceres/block_structure.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
namespace ceres {
@@ -343,7 +344,7 @@
//
// [thread_id * buffer_size_ , (thread_id + 1) * buffer_size_]
//
- scoped_array<double> buffer_;
+ std::unique_ptr<double[]> buffer_;
// Buffer to store per thread matrix matrix products used by
// ChunkOuterProduct. Like buffer_ it is of size num_threads *
@@ -351,7 +352,7 @@
//
// [thread_id * buffer_size_ , (thread_id + 1) * buffer_size_ -1]
//
- scoped_array<double> chunk_outer_product_buffer_;
+ std::unique_ptr<double[]> chunk_outer_product_buffer_;
int buffer_size_;
int uneliminated_row_begins_;
diff --git a/internal/ceres/schur_eliminator_impl.h b/internal/ceres/schur_eliminator_impl.h
index 628d998..da5d922 100644
--- a/internal/ceres/schur_eliminator_impl.h
+++ b/internal/ceres/schur_eliminator_impl.h
@@ -50,12 +50,12 @@
#include <algorithm>
#include <map>
+
#include "ceres/block_random_access_matrix.h"
#include "ceres/block_sparse_matrix.h"
#include "ceres/block_structure.h"
#include "ceres/internal/eigen.h"
#include "ceres/internal/fixed_array.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/invert_psd_matrix.h"
#include "ceres/map_util.h"
#include "ceres/schur_eliminator.h"
diff --git a/internal/ceres/schur_eliminator_test.cc b/internal/ceres/schur_eliminator_test.cc
index 9826d87..6197bfc 100644
--- a/internal/ceres/schur_eliminator_test.cc
+++ b/internal/ceres/schur_eliminator_test.cc
@@ -30,6 +30,7 @@
#include "ceres/schur_eliminator.h"
+#include <memory>
#include "Eigen/Dense"
#include "ceres/block_random_access_dense_matrix.h"
#include "ceres/block_sparse_matrix.h"
@@ -37,7 +38,6 @@
#include "ceres/context_impl.h"
#include "ceres/detect_structure.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/test_util.h"
#include "ceres/triplet_sparse_matrix.h"
@@ -54,7 +54,7 @@
class SchurEliminatorTest : public ::testing::Test {
protected:
void SetUpFromId(int id) {
- scoped_ptr<LinearLeastSquaresProblem>
+ std::unique_ptr<LinearLeastSquaresProblem>
problem(CreateLinearLeastSquaresProblemFromId(id));
CHECK_NOTNULL(problem.get());
SetupHelper(problem.get());
@@ -154,7 +154,7 @@
&options.f_block_size);
}
- scoped_ptr<SchurEliminatorBase> eliminator;
+ std::unique_ptr<SchurEliminatorBase> eliminator;
eliminator.reset(SchurEliminatorBase::Create(options));
const bool kFullRankETE = true;
eliminator->Init(num_eliminate_blocks, kFullRankETE, A->block_structure());
@@ -186,9 +186,9 @@
relative_tolerance);
}
- scoped_ptr<BlockSparseMatrix> A;
- scoped_array<double> b;
- scoped_array<double> D;
+ std::unique_ptr<BlockSparseMatrix> A;
+ std::unique_ptr<double[]> b;
+ std::unique_ptr<double[]> D;
int num_eliminate_blocks;
int num_eliminate_cols;
diff --git a/internal/ceres/schur_jacobi_preconditioner.cc b/internal/ceres/schur_jacobi_preconditioner.cc
index 13e6463..3ad5dd7 100644
--- a/internal/ceres/schur_jacobi_preconditioner.cc
+++ b/internal/ceres/schur_jacobi_preconditioner.cc
@@ -32,9 +32,9 @@
#include <utility>
#include <vector>
+
#include "ceres/block_random_access_diagonal_matrix.h"
#include "ceres/block_sparse_matrix.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/schur_eliminator.h"
#include "glog/logging.h"
diff --git a/internal/ceres/schur_jacobi_preconditioner.h b/internal/ceres/schur_jacobi_preconditioner.h
index fb7753b..2a61d6f 100644
--- a/internal/ceres/schur_jacobi_preconditioner.h
+++ b/internal/ceres/schur_jacobi_preconditioner.h
@@ -38,11 +38,12 @@
#ifndef CERES_INTERNAL_SCHUR_JACOBI_PRECONDITIONER_H_
#define CERES_INTERNAL_SCHUR_JACOBI_PRECONDITIONER_H_
+#include <memory>
#include <set>
-#include <vector>
#include <utility>
+#include <vector>
+
#include "ceres/internal/macros.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/preconditioner.h"
namespace ceres {
@@ -93,9 +94,9 @@
virtual bool UpdateImpl(const BlockSparseMatrix& A, const double* D);
Preconditioner::Options options_;
- scoped_ptr<SchurEliminatorBase> eliminator_;
+ std::unique_ptr<SchurEliminatorBase> eliminator_;
// Preconditioner matrix.
- scoped_ptr<BlockRandomAccessDiagonalMatrix> m_;
+ std::unique_ptr<BlockRandomAccessDiagonalMatrix> m_;
CERES_DISALLOW_COPY_AND_ASSIGN(SchurJacobiPreconditioner);
};
diff --git a/internal/ceres/scratch_evaluate_preparer.h b/internal/ceres/scratch_evaluate_preparer.h
index fa9ebd0..c8d9b93 100644
--- a/internal/ceres/scratch_evaluate_preparer.h
+++ b/internal/ceres/scratch_evaluate_preparer.h
@@ -35,7 +35,7 @@
#ifndef CERES_INTERNAL_SCRATCH_EVALUATE_PREPARER_H_
#define CERES_INTERNAL_SCRATCH_EVALUATE_PREPARER_H_
-#include "ceres/internal/scoped_ptr.h"
+#include <memory>
namespace ceres {
namespace internal {
@@ -60,7 +60,7 @@
private:
// Scratch space for the jacobians; each jacobian is packed one after another.
// There is enough scratch to hold all the jacobians for the largest residual.
- scoped_array<double> jacobian_scratch_;
+ std::unique_ptr<double[]> jacobian_scratch_;
};
} // namespace internal
diff --git a/internal/ceres/solver.cc b/internal/ceres/solver.cc
index 4083c59..de3329e 100644
--- a/internal/ceres/solver.cc
+++ b/internal/ceres/solver.cc
@@ -32,8 +32,10 @@
#include "ceres/solver.h"
#include <algorithm>
+#include <memory>
#include <sstream> // NOLINT
#include <vector>
+
#include "ceres/casts.h"
#include "ceres/context.h"
#include "ceres/context_impl.h"
@@ -444,7 +446,6 @@
void Minimize(internal::PreprocessedProblem* pp,
Solver::Summary* summary) {
using internal::Program;
- using internal::scoped_ptr;
using internal::Minimizer;
Program* program = pp->reduced_program.get();
@@ -459,7 +460,7 @@
}
const Vector original_reduced_parameters = pp->reduced_parameters;
- scoped_ptr<Minimizer> minimizer(
+ std::unique_ptr<Minimizer> minimizer(
Minimizer::Create(pp->options.minimizer_type));
minimizer->Minimize(pp->minimizer_options,
pp->reduced_parameters.data(),
@@ -519,7 +520,6 @@
using internal::Preprocessor;
using internal::ProblemImpl;
using internal::Program;
- using internal::scoped_ptr;
using internal::WallTimeInSeconds;
CHECK_NOTNULL(problem);
@@ -546,7 +546,7 @@
// If gradient_checking is enabled, wrap all cost functions in a
// gradient checker and install a callback that terminates if any gradient
// error is detected.
- scoped_ptr<internal::ProblemImpl> gradient_checking_problem;
+ std::unique_ptr<internal::ProblemImpl> gradient_checking_problem;
internal::GradientCheckingIterationCallback gradient_checking_callback;
Solver::Options modified_options = options;
if (options.check_gradients) {
@@ -561,7 +561,7 @@
program = problem_impl->mutable_program();
}
- scoped_ptr<Preprocessor> preprocessor(
+ std::unique_ptr<Preprocessor> preprocessor(
Preprocessor::Create(modified_options.minimizer_type));
PreprocessedProblem pp;
diff --git a/internal/ceres/solver_test.cc b/internal/ceres/solver_test.cc
index 80f12e4..8f68fec 100644
--- a/internal/ceres/solver_test.cc
+++ b/internal/ceres/solver_test.cc
@@ -31,11 +31,11 @@
#include "ceres/solver.h"
#include <limits>
+#include <memory>
#include <cmath>
#include <vector>
#include "gtest/gtest.h"
#include "ceres/evaluation_callback.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/autodiff_cost_function.h"
#include "ceres/sized_cost_function.h"
#include "ceres/problem.h"
@@ -98,7 +98,7 @@
double x = 50.0;
const double original_x = x;
- scoped_ptr<CostFunction> cost_function(QuadraticCostFunctor::Create());
+ std::unique_ptr<CostFunction> cost_function(QuadraticCostFunctor::Create());
Problem::Options problem_options;
problem_options.cost_function_ownership = DO_NOT_TAKE_OWNERSHIP;
Problem problem(problem_options);
diff --git a/internal/ceres/sparse_cholesky.h b/internal/ceres/sparse_cholesky.h
index d77cccd..85487bf 100644
--- a/internal/ceres/sparse_cholesky.h
+++ b/internal/ceres/sparse_cholesky.h
@@ -52,7 +52,7 @@
//
// Example usage:
//
-// scoped_ptr<SparseCholesky>
+// std::unique_ptr<SparseCholesky>
// sparse_cholesky(SparseCholesky::Create(SUITE_SPARSE, AMD));
//
// CompressedRowSparseMatrix lhs = ...;
diff --git a/internal/ceres/sparse_cholesky_test.cc b/internal/ceres/sparse_cholesky_test.cc
index c94beea..79db689 100644
--- a/internal/ceres/sparse_cholesky_test.cc
+++ b/internal/ceres/sparse_cholesky_test.cc
@@ -30,6 +30,7 @@
#include "ceres/sparse_cholesky.h"
+#include <memory>
#include <numeric>
#include <vector>
@@ -39,7 +40,6 @@
#include "ceres/compressed_row_sparse_matrix.h"
#include "ceres/inner_product_computer.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/random.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
@@ -61,12 +61,12 @@
options.min_row_block_size = 1;
options.max_row_block_size = max_col_block_size;
options.block_density = block_density;
- scoped_ptr<BlockSparseMatrix> random_matrix(
+ std::unique_ptr<BlockSparseMatrix> random_matrix(
BlockSparseMatrix::CreateRandomMatrix(options));
// Add a diagonal block sparse matrix to make it full rank.
Vector diagonal = Vector::Ones(random_matrix->num_cols());
- scoped_ptr<BlockSparseMatrix> block_diagonal(
+ std::unique_ptr<BlockSparseMatrix> block_diagonal(
BlockSparseMatrix::CreateDiagonalMatrix(
diagonal.data(), random_matrix->block_structure()->cols));
random_matrix->AppendRows(*block_diagonal);
@@ -107,14 +107,14 @@
const int min_block_size,
const int max_block_size,
const double block_density) {
- scoped_ptr<SparseCholesky> sparse_cholesky(SparseCholesky::Create(
+ std::unique_ptr<SparseCholesky> sparse_cholesky(SparseCholesky::Create(
sparse_linear_algebra_library_type, ordering_type));
const CompressedRowSparseMatrix::StorageType storage_type =
sparse_cholesky->StorageType();
- scoped_ptr<BlockSparseMatrix> m(CreateRandomFullRankMatrix(
+ std::unique_ptr<BlockSparseMatrix> m(CreateRandomFullRankMatrix(
num_blocks, min_block_size, max_block_size, block_density));
- scoped_ptr<InnerProductComputer> inner_product_computer(
+ std::unique_ptr<InnerProductComputer> inner_product_computer(
InnerProductComputer::Create(*m, storage_type));
inner_product_computer->Compute();
CompressedRowSparseMatrix* lhs = inner_product_computer->mutable_result();
diff --git a/internal/ceres/sparse_normal_cholesky_solver.cc b/internal/ceres/sparse_normal_cholesky_solver.cc
index 37f5a8e..0572870 100644
--- a/internal/ceres/sparse_normal_cholesky_solver.cc
+++ b/internal/ceres/sparse_normal_cholesky_solver.cc
@@ -33,11 +33,11 @@
#include <algorithm>
#include <cstring>
#include <ctime>
+#include <memory>
#include "ceres/block_sparse_matrix.h"
#include "ceres/inner_product_computer.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/sparse_cholesky.h"
#include "ceres/triplet_sparse_matrix.h"
@@ -76,7 +76,7 @@
if (per_solve_options.D != NULL) {
// Temporarily append a diagonal block to the A matrix, but undo
// it before returning the matrix to the user.
- scoped_ptr<BlockSparseMatrix> regularizer;
+ std::unique_ptr<BlockSparseMatrix> regularizer;
regularizer.reset(BlockSparseMatrix::CreateDiagonalMatrix(
per_solve_options.D, A->block_structure()->cols));
event_logger.AddEvent("Diagonal");
diff --git a/internal/ceres/sparse_normal_cholesky_solver.h b/internal/ceres/sparse_normal_cholesky_solver.h
index e24799d..537a2c9 100644
--- a/internal/ceres/sparse_normal_cholesky_solver.h
+++ b/internal/ceres/sparse_normal_cholesky_solver.h
@@ -63,8 +63,8 @@
double* x);
const LinearSolver::Options options_;
- scoped_ptr<SparseCholesky> sparse_cholesky_;
- scoped_ptr<InnerProductComputer> inner_product_computer_;
+ std::unique_ptr<SparseCholesky> sparse_cholesky_;
+ std::unique_ptr<InnerProductComputer> inner_product_computer_;
CERES_DISALLOW_COPY_AND_ASSIGN(SparseNormalCholeskySolver);
};
diff --git a/internal/ceres/sparse_normal_cholesky_solver_test.cc b/internal/ceres/sparse_normal_cholesky_solver_test.cc
index f991298..1b836a5 100644
--- a/internal/ceres/sparse_normal_cholesky_solver_test.cc
+++ b/internal/ceres/sparse_normal_cholesky_solver_test.cc
@@ -28,10 +28,10 @@
//
// Author: sameeragarwal@google.com (Sameer Agarwal)
+#include <memory>
#include "ceres/block_sparse_matrix.h"
#include "ceres/casts.h"
#include "ceres/context_impl.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/linear_solver.h"
#include "ceres/triplet_sparse_matrix.h"
@@ -54,7 +54,7 @@
class SparseNormalCholeskySolverTest : public ::testing::Test {
protected:
virtual void SetUp() {
- scoped_ptr<LinearLeastSquaresProblem> problem(
+ std::unique_ptr<LinearLeastSquaresProblem> problem(
CreateLinearLeastSquaresProblemFromId(2));
CHECK_NOTNULL(problem.get());
@@ -79,7 +79,7 @@
A_->LeftMultiply(b_.get(), rhs.data());
Vector expected_solution = lhs.llt().solve(rhs);
- scoped_ptr<LinearSolver> solver(LinearSolver::Create(options));
+ std::unique_ptr<LinearSolver> solver(LinearSolver::Create(options));
LinearSolver::PerSolveOptions per_solve_options;
per_solve_options.D = D;
Vector actual_solution(A_->num_cols());
@@ -101,9 +101,9 @@
TestSolver(options, D_.get());
}
- scoped_ptr<BlockSparseMatrix> A_;
- scoped_array<double> b_;
- scoped_array<double> D_;
+ std::unique_ptr<BlockSparseMatrix> A_;
+ std::unique_ptr<double[]> b_;
+ std::unique_ptr<double[]> D_;
};
#ifndef CERES_NO_SUITESPARSE
diff --git a/internal/ceres/subset_preconditioner.cc b/internal/ceres/subset_preconditioner.cc
index e970b91..c7f5ef6 100644
--- a/internal/ceres/subset_preconditioner.cc
+++ b/internal/ceres/subset_preconditioner.cc
@@ -30,10 +30,10 @@
#include "ceres/subset_preconditioner.h"
+#include <memory>
#include <string>
#include "ceres/compressed_row_sparse_matrix.h"
#include "ceres/inner_product_computer.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/sparse_cholesky.h"
#include "ceres/types.h"
@@ -72,7 +72,7 @@
// A = [P]
// [Q]
// [D]
- scoped_ptr<BlockSparseMatrix> regularizer(
+ std::unique_ptr<BlockSparseMatrix> regularizer(
BlockSparseMatrix::CreateDiagonalMatrix(D, bs->cols));
m->AppendRows(*regularizer);
}
diff --git a/internal/ceres/subset_preconditioner.h b/internal/ceres/subset_preconditioner.h
index 062253b..77c3d91 100644
--- a/internal/ceres/subset_preconditioner.h
+++ b/internal/ceres/subset_preconditioner.h
@@ -31,7 +31,7 @@
#ifndef CERES_INTERNAL_SUBSET_PRECONDITIONER_H_
#define CERES_INTERNAL_SUBSET_PRECONDITIONER_H_
-#include "ceres/internal/scoped_ptr.h"
+#include <memory>
#include "ceres/preconditioner.h"
namespace ceres {
@@ -81,8 +81,8 @@
const Preconditioner::Options options_;
const int num_cols_;
- scoped_ptr<SparseCholesky> sparse_cholesky_;
- scoped_ptr<InnerProductComputer> inner_product_computer_;
+ std::unique_ptr<SparseCholesky> sparse_cholesky_;
+ std::unique_ptr<InnerProductComputer> inner_product_computer_;
};
} // namespace internal
diff --git a/internal/ceres/subset_preconditioner_test.cc b/internal/ceres/subset_preconditioner_test.cc
index 147ecf8..b159e0f 100644
--- a/internal/ceres/subset_preconditioner_test.cc
+++ b/internal/ceres/subset_preconditioner_test.cc
@@ -28,6 +28,7 @@
//
// Author: sameeragarwal@google.com (Sameer Agarwal)
+#include <memory>
#include "ceres/subset_preconditioner.h"
#include "Eigen/Dense"
#include "Eigen/SparseCore"
@@ -35,7 +36,6 @@
#include "ceres/compressed_row_sparse_matrix.h"
#include "ceres/inner_product_computer.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
@@ -118,11 +118,11 @@
inner_product_computer_->Compute();
}
- scoped_ptr<BlockSparseMatrix> m_;
- scoped_ptr<BlockSparseMatrix> b_;
- scoped_ptr<BlockSparseMatrix> block_diagonal_;
- scoped_ptr<InnerProductComputer> inner_product_computer_;
- scoped_ptr<Preconditioner> preconditioner_;
+ std::unique_ptr<BlockSparseMatrix> m_;
+ std::unique_ptr<BlockSparseMatrix> b_;
+ std::unique_ptr<BlockSparseMatrix> block_diagonal_;
+ std::unique_ptr<InnerProductComputer> inner_product_computer_;
+ std::unique_ptr<Preconditioner> preconditioner_;
Vector diagonal_;
int start_row_block_;
};
diff --git a/internal/ceres/tiny_solver_cost_function_adapter_test.cc b/internal/ceres/tiny_solver_cost_function_adapter_test.cc
index 364fea9..620df41 100644
--- a/internal/ceres/tiny_solver_cost_function_adapter_test.cc
+++ b/internal/ceres/tiny_solver_cost_function_adapter_test.cc
@@ -32,9 +32,9 @@
#include <algorithm>
#include <cmath>
+#include <memory>
#include "ceres/cost_function.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/sized_cost_function.h"
#include "gtest/gtest.h"
@@ -67,7 +67,7 @@
template<int kNumResiduals, int kNumParameters>
void TestHelper() {
- internal::scoped_ptr<CostFunction> cost_function(new CostFunction2x3);
+ std::unique_ptr<CostFunction> cost_function(new CostFunction2x3);
typedef TinySolverCostFunctionAdapter<kNumResiduals, kNumParameters> CostFunctionAdapter;
CostFunctionAdapter cfa(*cost_function);
EXPECT_EQ(CostFunctionAdapter::NUM_RESIDUALS, kNumResiduals);
diff --git a/internal/ceres/triplet_sparse_matrix.cc b/internal/ceres/triplet_sparse_matrix.cc
index cd19444..8920747 100644
--- a/internal/ceres/triplet_sparse_matrix.cc
+++ b/internal/ceres/triplet_sparse_matrix.cc
@@ -32,9 +32,9 @@
#include <algorithm>
#include <cstddef>
+
#include "ceres/internal/eigen.h"
#include "ceres/internal/port.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/random.h"
#include "ceres/types.h"
#include "glog/logging.h"
diff --git a/internal/ceres/triplet_sparse_matrix.h b/internal/ceres/triplet_sparse_matrix.h
index 1d82e14..606f8e8 100644
--- a/internal/ceres/triplet_sparse_matrix.h
+++ b/internal/ceres/triplet_sparse_matrix.h
@@ -31,10 +31,10 @@
#ifndef CERES_INTERNAL_TRIPLET_SPARSE_MATRIX_H_
#define CERES_INTERNAL_TRIPLET_SPARSE_MATRIX_H_
+#include <memory>
#include <vector>
#include "ceres/sparse_matrix.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
namespace ceres {
@@ -144,9 +144,9 @@
// stored at the location (rows_[i], cols_[i]). If the there are
// multiple entries with the same (rows_[i], cols_[i]), the values_
// entries corresponding to them are summed up.
- scoped_array<int> rows_;
- scoped_array<int> cols_;
- scoped_array<double> values_;
+ std::unique_ptr<int[]> rows_;
+ std::unique_ptr<int[]> cols_;
+ std::unique_ptr<double[]> values_;
};
} // namespace internal
diff --git a/internal/ceres/triplet_sparse_matrix_test.cc b/internal/ceres/triplet_sparse_matrix_test.cc
index 730272e..d71df7b 100644
--- a/internal/ceres/triplet_sparse_matrix_test.cc
+++ b/internal/ceres/triplet_sparse_matrix_test.cc
@@ -30,8 +30,8 @@
#include "ceres/triplet_sparse_matrix.h"
+#include <memory>
#include "gtest/gtest.h"
-#include "ceres/internal/scoped_ptr.h"
namespace ceres {
namespace internal {
@@ -279,11 +279,11 @@
}
TEST(TripletSparseMatrix, CreateDiagonalMatrix) {
- scoped_array<double> values(new double[10]);
+ std::unique_ptr<double[]> values(new double[10]);
for (int i = 0; i < 10; ++i)
values[i] = i;
- scoped_ptr<TripletSparseMatrix> m(
+ std::unique_ptr<TripletSparseMatrix> m(
TripletSparseMatrix::CreateSparseDiagonalMatrix(values.get(), 10));
EXPECT_EQ(m->num_rows(), 10);
EXPECT_EQ(m->num_cols(), 10);
diff --git a/internal/ceres/trust_region_minimizer.cc b/internal/ceres/trust_region_minimizer.cc
index a863e63..cd57abf 100644
--- a/internal/ceres/trust_region_minimizer.cc
+++ b/internal/ceres/trust_region_minimizer.cc
@@ -34,6 +34,7 @@
#include <cmath>
#include <cstdlib>
#include <cstring>
+#include <memory>
#include <limits>
#include <string>
#include <vector>
@@ -573,7 +574,7 @@
line_search_options.function = &line_search_function;
std::string message;
- scoped_ptr<LineSearch> line_search(CHECK_NOTNULL(
+ std::unique_ptr<LineSearch> line_search(CHECK_NOTNULL(
LineSearch::Create(ceres::ARMIJO, line_search_options, &message)));
LineSearch::Summary line_search_summary;
line_search_function.Init(x, *delta);
diff --git a/internal/ceres/trust_region_minimizer.h b/internal/ceres/trust_region_minimizer.h
index 9c5274d..8ddd77e 100644
--- a/internal/ceres/trust_region_minimizer.h
+++ b/internal/ceres/trust_region_minimizer.h
@@ -31,8 +31,8 @@
#ifndef CERES_INTERNAL_TRUST_REGION_MINIMIZER_H_
#define CERES_INTERNAL_TRUST_REGION_MINIMIZER_H_
+#include <memory>
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/minimizer.h"
#include "ceres/solver.h"
#include "ceres/sparse_matrix.h"
@@ -94,7 +94,7 @@
SparseMatrix* jacobian_;
TrustRegionStrategy* strategy_;
- scoped_ptr<TrustRegionStepEvaluator> step_evaluator_;
+ std::unique_ptr<TrustRegionStepEvaluator> step_evaluator_;
bool is_not_silent_;
bool inner_iterations_are_enabled_;
diff --git a/internal/ceres/visibility_based_preconditioner.cc b/internal/ceres/visibility_based_preconditioner.cc
index 31d2cc3..b13c529 100644
--- a/internal/ceres/visibility_based_preconditioner.cc
+++ b/internal/ceres/visibility_based_preconditioner.cc
@@ -33,16 +33,17 @@
#include <algorithm>
#include <functional>
#include <iterator>
+#include <memory>
#include <set>
#include <utility>
#include <vector>
+
#include "Eigen/Dense"
#include "ceres/block_random_access_sparse_matrix.h"
#include "ceres/block_sparse_matrix.h"
#include "ceres/canonical_views_clustering.h"
#include "ceres/graph.h"
#include "ceres/graph_algorithms.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/schur_eliminator.h"
#include "ceres/single_linkage_clustering.h"
@@ -151,9 +152,9 @@
// maximum spanning forest of this graph.
vector<set<int> > cluster_visibility;
ComputeClusterVisibility(visibility, &cluster_visibility);
- scoped_ptr<WeightedGraph<int> > cluster_graph(
+ std::unique_ptr<WeightedGraph<int> > cluster_graph(
CHECK_NOTNULL(CreateClusterGraph(cluster_visibility)));
- scoped_ptr<WeightedGraph<int> > forest(
+ std::unique_ptr<WeightedGraph<int> > forest(
CHECK_NOTNULL(Degree2MaximumSpanningForest(*cluster_graph)));
ForestToClusterPairs(*forest, &cluster_pairs_);
}
@@ -173,7 +174,7 @@
// memberships for each camera block.
void VisibilityBasedPreconditioner::ClusterCameras(
const vector<set<int> >& visibility) {
- scoped_ptr<WeightedGraph<int> > schur_complement_graph(
+ std::unique_ptr<WeightedGraph<int> > schur_complement_graph(
CHECK_NOTNULL(CreateSchurComplementGraph(visibility)));
std::unordered_map<int, int> membership;
@@ -412,7 +413,7 @@
const TripletSparseMatrix* tsm =
down_cast<BlockRandomAccessSparseMatrix*>(m_.get())->mutable_matrix();
- scoped_ptr<CompressedRowSparseMatrix> lhs;
+ std::unique_ptr<CompressedRowSparseMatrix> lhs;
const CompressedRowSparseMatrix::StorageType storage_type =
sparse_cholesky_->StorageType();
if (storage_type == CompressedRowSparseMatrix::UPPER_TRIANGULAR) {
diff --git a/internal/ceres/visibility_based_preconditioner.h b/internal/ceres/visibility_based_preconditioner.h
index 1c831d0..b47bb68 100644
--- a/internal/ceres/visibility_based_preconditioner.h
+++ b/internal/ceres/visibility_based_preconditioner.h
@@ -48,14 +48,15 @@
#ifndef CERES_INTERNAL_VISIBILITY_BASED_PRECONDITIONER_H_
#define CERES_INTERNAL_VISIBILITY_BASED_PRECONDITIONER_H_
+#include <memory>
#include <set>
#include <unordered_map>
#include <unordered_set>
#include <utility>
#include <vector>
+
#include "ceres/graph.h"
#include "ceres/internal/macros.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_solver.h"
#include "ceres/pair_hash.h"
#include "ceres/preconditioner.h"
@@ -185,11 +186,11 @@
// Set of cluster pairs (including self pairs (i,i)) in the
// preconditioner.
std::unordered_set<std::pair<int, int>, pair_hash> cluster_pairs_;
- scoped_ptr<SchurEliminatorBase> eliminator_;
+ std::unique_ptr<SchurEliminatorBase> eliminator_;
// Preconditioner matrix.
- scoped_ptr<BlockRandomAccessSparseMatrix> m_;
- scoped_ptr<SparseCholesky> sparse_cholesky_;
+ std::unique_ptr<BlockRandomAccessSparseMatrix> m_;
+ std::unique_ptr<SparseCholesky> sparse_cholesky_;
CERES_DISALLOW_COPY_AND_ASSIGN(VisibilityBasedPreconditioner);
};
diff --git a/internal/ceres/visibility_based_preconditioner_test.cc b/internal/ceres/visibility_based_preconditioner_test.cc
index 2227116..437b5d4 100644
--- a/internal/ceres/visibility_based_preconditioner_test.cc
+++ b/internal/ceres/visibility_based_preconditioner_test.cc
@@ -30,6 +30,7 @@
#include "ceres/visibility_based_preconditioner.h"
+#include <memory>
#include "Eigen/Dense"
#include "ceres/block_random_access_dense_matrix.h"
#include "ceres/block_random_access_sparse_matrix.h"
@@ -37,7 +38,6 @@
#include "ceres/casts.h"
#include "ceres/file.h"
#include "ceres/internal/eigen.h"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/linear_least_squares_problems.h"
#include "ceres/schur_eliminator.h"
#include "ceres/stringprintf.h"
@@ -66,7 +66,7 @@
// void SetUp() {
// string input_file = TestFileAbsolutePath("problem-6-1384-000.lsqp");
-// scoped_ptr<LinearLeastSquaresProblem> problem(
+// std::unique_ptr<LinearLeastSquaresProblem> problem(
// CHECK_NOTNULL(CreateLinearLeastSquaresProblemFromFile(input_file)));
// A_.reset(down_cast<BlockSparseMatrix*>(problem->A.release()));
// b_.reset(problem->b.release());
@@ -98,7 +98,7 @@
// schur_complement_.reset(new BlockRandomAccessDenseMatrix(blocks));
// Vector rhs(schur_complement_->num_rows());
-// scoped_ptr<SchurEliminatorBase> eliminator;
+// std::unique_ptr<SchurEliminatorBase> eliminator;
// LinearSolver::Options eliminator_options;
// eliminator_options.elimination_groups = options_.elimination_groups;
// eliminator_options.num_threads = options_.num_threads;
@@ -230,13 +230,13 @@
// int num_eliminate_blocks_;
// int num_camera_blocks_;
-// scoped_ptr<BlockSparseMatrix> A_;
-// scoped_array<double> b_;
-// scoped_array<double> D_;
+// std::unique_ptr<BlockSparseMatrix> A_;
+// std::unique_ptr<double[]> b_;
+// std::unique_ptr<double[]> D_;
// Preconditioner::Options options_;
-// scoped_ptr<VisibilityBasedPreconditioner> preconditioner_;
-// scoped_ptr<BlockRandomAccessDenseMatrix> schur_complement_;
+// std::unique_ptr<VisibilityBasedPreconditioner> preconditioner_;
+// std::unique_ptr<BlockRandomAccessDenseMatrix> schur_complement_;
// };
// TEST_F(VisibilityBasedPreconditionerTest, OneClusterClusterJacobi) {
diff --git a/internal/ceres/visibility_test.cc b/internal/ceres/visibility_test.cc
index 73517da..81ad99f 100644
--- a/internal/ceres/visibility_test.cc
+++ b/internal/ceres/visibility_test.cc
@@ -31,11 +31,12 @@
#include "ceres/visibility.h"
+#include <memory>
#include <set>
#include <vector>
+
#include "ceres/block_structure.h"
#include "ceres/graph.h"
-#include "ceres/internal/scoped_ptr.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
@@ -106,7 +107,7 @@
ASSERT_EQ(visibility[i].size(), 1);
}
- scoped_ptr<WeightedGraph<int> > graph(CreateSchurComplementGraph(visibility));
+ std::unique_ptr<WeightedGraph<int> > graph(CreateSchurComplementGraph(visibility));
EXPECT_EQ(graph->vertices().size(), visibility.size());
for (int i = 0; i < visibility.size(); ++i) {
EXPECT_EQ(graph->VertexWeight(i), 1.0);
@@ -182,7 +183,7 @@
ASSERT_EQ(visibility[i].size(), 0);
}
- scoped_ptr<WeightedGraph<int> > graph(CreateSchurComplementGraph(visibility));
+ std::unique_ptr<WeightedGraph<int> > graph(CreateSchurComplementGraph(visibility));
EXPECT_EQ(graph->vertices().size(), visibility.size());
for (int i = 0; i < visibility.size(); ++i) {
EXPECT_EQ(graph->VertexWeight(i), 1.0);