Deprecate LocalParameterizations

Add [[deprecate]] notices to everything LocalParameterization
related.

Make sure that Ceres can be compiled without triggering
deprecation warnings.

Update the documentation:

a. Add deprecation notices.
b. Document interaction between LocalParameterization and Manifold
   coexisting in the Problem.
c. Add documentation for Manifold(s)

Change-Id: Ie4ad48963c83fded86e533c8c60561af402fbaff
diff --git a/BUILD b/BUILD
index 8853aea..20f1d0a 100644
--- a/BUILD
+++ b/BUILD
@@ -167,6 +167,10 @@
     # but in the future disable these warnings only for rotation_test.
     # TODO(keir): When the tests are macro-ified, apply these selectively.
     "-Wno-address",
+
+    # Disable warnings about deprecated interfraces while we are
+    # transitioning from LocalParameterization to Manifolds.
+    "-Wno-deprecated-declarations",
 ]
 
 TEST_DEPS = [
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 5254b73..65a6f94 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,5 +1,5 @@
 # Ceres Solver - A fast non-linear least squares minimizer
-# Copyright 2015 Google Inc. All rights reserved.
+# Copyright 2022 Google Inc. All rights reserved.
 # http://ceres-solver.org/
 #
 # Redistribution and use in source and binary forms, with or without
diff --git a/bazel/ceres.bzl b/bazel/ceres.bzl
index 03f8ee7..c70341a 100644
--- a/bazel/ceres.bzl
+++ b/bazel/ceres.bzl
@@ -183,6 +183,10 @@
         copts = [
             "-I" + internal,
             "-Wno-sign-compare",
+
+            # Disable warnings about deprecated interfraces while we are
+            # transitioning from LocalParameterization to Manifolds.
+            "-Wno-deprecated-declarations",
         ] + schur_eliminator_copts,
 
         # These include directories and defines are propagated to other targets
diff --git a/docs/source/conf.py b/docs/source/conf.py
index cc55b8a..eaa4947 100644
--- a/docs/source/conf.py
+++ b/docs/source/conf.py
@@ -41,16 +41,16 @@
 
 # General information about the project.
 project = u'Ceres Solver'
-copyright = u'2020 Google Inc'
+copyright = u'2022 Google Inc'
 
 # The version info for the project you're documenting, acts as replacement for
 # |version| and |release|, also used in various other places throughout the
 # built documents.
 #
 # The short X.Y version.
-version = '2.0'
+version = '2.1'
 # The full version, including alpha/beta/rc tags.
-release = '2.0.0'
+release = '2.1.0'
 
 # The language for content autogenerated by Sphinx. Refer to documentation
 # for a list of supported languages.
diff --git a/docs/source/features.rst b/docs/source/features.rst
index 724d6dc..634be9d 100644
--- a/docs/source/features.rst
+++ b/docs/source/features.rst
@@ -1,3 +1,7 @@
+.. default-domain:: cpp
+
+.. cpp:namespace:: ceres
+
 ====
 Why?
 ====
diff --git a/docs/source/gradient_solver.rst b/docs/source/gradient_solver.rst
index dde9d7e..dfe1822 100644
--- a/docs/source/gradient_solver.rst
+++ b/docs/source/gradient_solver.rst
@@ -1,6 +1,8 @@
+.. default-domain:: cpp
+
 .. highlight:: c++
 
-.. default-domain:: cpp
+.. cpp:namespace:: ceres
 
 .. _chapter-gradient_problem_solver:
 
@@ -46,6 +48,12 @@
 :class:`GradientProblem`
 ------------------------
 
+.. NOTE::
+
+   The :class:`LocalParameterization` interface and associated classes
+   are deprecated. They will be removed in the version 2.2.0. Please use
+   :class:`Manifold` based constructor instead.
+
 .. class:: GradientProblem
 
 .. code-block:: c++
@@ -55,8 +63,11 @@
     explicit GradientProblem(FirstOrderFunction* function);
     GradientProblem(FirstOrderFunction* function,
                     LocalParameterization* parameterization);
+    GradientProblem(FirstOrderFunction* function,
+                    Manifold* manifold);
     int NumParameters() const;
-    int NumLocalParameters() const;
+    int NumLocalParameters() const { return NumTangentParameters(); }
+    int NumTangentParameters() const;
     bool Evaluate(const double* parameters, double* cost, double* gradient) const;
     bool Plus(const double* x, const double* delta, double* x_plus_delta) const;
   };
@@ -70,19 +81,21 @@
 
 Structurally :class:`GradientProblem` is a composition of a
 :class:`FirstOrderFunction` and optionally a
-:class:`LocalParameterization`.
+:class:`LocalParameterization` or a :class:`Manifold`.
 
 The :class:`FirstOrderFunction` is responsible for evaluating the cost
 and gradient of the objective function.
 
-The :class:`LocalParameterization` is responsible for going back and
-forth between the ambient space and the local tangent space. When a
-:class:`LocalParameterization` is not provided, then the tangent space
-is assumed to coincide with the ambient Euclidean space that the
-gradient vector lives in.
+The :class:`LocalParameterization`/:class:`Manifold` is responsible
+for going back and forth between the ambient space and the local
+tangent space. When a :class:`LocalParameterization` or a
+:class:`Manifold` is not provided, then the tangent space is assumed
+to coincide with the ambient Euclidean space that the gradient vector
+lives in.
 
 The constructor takes ownership of the :class:`FirstOrderFunction` and
-:class:`LocalParamterization` objects passed to it.
+:class:`LocalParameterization` or :class:`Manifold` objects passed to
+it.
 
 
 .. function:: void Solve(const GradientProblemSolver::Options& options, const GradientProblem& problem, double* parameters, GradientProblemSolver::Summary* summary)
@@ -342,8 +355,8 @@
 
    where :math:`\|\cdot\|_\infty` refers to the max norm, :math:`\Pi`
    is projection onto the bounds constraints and :math:`\boxplus` is
-   Plus operation for the overall local parameterization associated
-   with the parameter vector.
+   Plus operation for the manifold associated with the parameter
+   vector.
 
 .. member:: double GradientProblemSolver::Options::parameter_tolerance
 
@@ -490,7 +503,19 @@
 
    Dimension of the tangent space of the problem. This is different
    from :member:`GradientProblemSolver::Summary::num_parameters` if a
-   :class:`LocalParameterization` object is used.
+   :class:`LocalParameterization`/:class:`Manifold` object is used.
+
+   .. NOTE::
+
+      ``num_local_parameters`` is deprecated and will be removed in
+      Ceres Solver version 2.2.0. Please use ``num_tangent_parameters``
+      instead.
+
+.. member:: int GradientProblemSolver::Summary::num_tangent_parameters
+
+   Dimension of the tangent space of the problem. This is different
+   from :member:`GradientProblemSolver::Summary::num_parameters` if a
+   :class:`LocalParameterization`/:class:`Manifold` object is used.
 
 .. member:: LineSearchDirectionType GradientProblemSolver::Summary::line_search_direction_type
 
diff --git a/docs/source/gradient_tutorial.rst b/docs/source/gradient_tutorial.rst
index 1264847..0e4f8e8 100644
--- a/docs/source/gradient_tutorial.rst
+++ b/docs/source/gradient_tutorial.rst
@@ -160,7 +160,7 @@
                                                       kNumParameters>(
           new Rosenbrock);
     }
-};
+  };
 
 And finally, if you would rather compute the derivatives by hand (say
 because the size of the parameter vector is too large to be
diff --git a/docs/source/nnls_modeling.rst b/docs/source/nnls_modeling.rst
index cac3d1c..9503774 100644
--- a/docs/source/nnls_modeling.rst
+++ b/docs/source/nnls_modeling.rst
@@ -1,5 +1,7 @@
 .. default-domain:: cpp
 
+.. highlight:: c++
+
 .. cpp:namespace:: ceres
 
 .. _`chapter-nnls_modeling`:
@@ -50,7 +52,7 @@
 
 As a special case, when :math:`\rho_i(x) = x`, i.e., the identity
 function, and :math:`l_j = -\infty` and :math:`u_j = \infty` we get
-the more familiar unconstrained `non-linear least squares problem
+the usual unconstrained `non-linear least squares problem
 <http://en.wikipedia.org/wiki/Non-linear_least_squares>`_.
 
 .. math:: :label: ceresproblemunconstrained
@@ -512,8 +514,8 @@
   parameters.
 
 
-Numeric Differentiation & LocalParameterization
------------------------------------------------
+Numeric Differentiation & Manifolds
+-----------------------------------
 
    If your cost function depends on a parameter block that must lie on
    a manifold and the functor cannot be evaluated for values of that
@@ -522,11 +524,10 @@
 
    This is because numeric differentiation in Ceres is performed by
    perturbing the individual coordinates of the parameter blocks that
-   a cost functor depends on. In doing so, we assume that the
-   parameter blocks live in an Euclidean space and ignore the
-   structure of manifold that they live As a result some of the
-   perturbations may not lie on the manifold corresponding to the
-   parameter block.
+   a cost functor depends on. This perturbation assumes that the
+   parameter block lives on a Euclidean Manifold rather than the
+   actual manifold associated with the parameter block. As a result
+   some of the perturbed points may not lie on the manifold anymore.
 
    For example consider a four dimensional parameter block that is
    interpreted as a unit Quaternion. Perturbing the coordinates of
@@ -534,7 +535,7 @@
    parameter block.
 
    Fixing this problem requires that :class:`NumericDiffCostFunction`
-   be aware of the :class:`LocalParameterization` associated with each
+   be aware of the :class:`Manifold` associated with each
    parameter block and only generate perturbations in the local
    tangent space of each parameter block.
 
@@ -620,8 +621,8 @@
    As a rule of thumb, try using :class:`NumericDiffCostFunction` before
    you use :class:`DynamicNumericDiffCostFunction`.
 
-   **WARNING** The same caution about mixing local parameterizations
-   with numeric differentiation applies as is the case with
+   **WARNING** The same caution about mixing manifolds with numeric
+   differentiation applies as is the case with
    :class:`NumericDiffCostFunction`.
 
 :class:`CostFunctionToFunctor`
@@ -864,38 +865,39 @@
 
 
 :class:`GradientChecker`
-================================
+========================
 
 .. class:: GradientChecker
 
-    This class compares the Jacobians returned by a cost function against
-    derivatives estimated using finite differencing. It is meant as a tool for
-    unit testing, giving you more fine-grained control than the check_gradients
-    option in the solver options.
+    This class compares the Jacobians returned by a cost function
+    against derivatives estimated using finite differencing. It is
+    meant as a tool for unit testing, giving you more fine-grained
+    control than the check_gradients option in the solver options.
 
     The condition enforced is that
 
     .. math:: \forall{i,j}: \frac{J_{ij} - J'_{ij}}{max_{ij}(J_{ij} - J'_{ij})} < r
 
-    where :math:`J_{ij}` is the jacobian as computed by the supplied cost
-    function (by the user) multiplied by the local parameterization Jacobian,
+    where :math:`J_{ij}` is the jacobian as computed by the supplied
+    cost function multiplied by the `Manifold::PlusJacobian`,
     :math:`J'_{ij}` is the jacobian as computed by finite differences,
-    multiplied by the local parameterization Jacobian as well, and :math:`r`
+    multiplied by the `Manifold::PlusJacobian` as well, and :math:`r`
     is the relative precision.
 
    Usage:
 
    .. code-block:: c++
 
-       //  my_cost_function takes two parameter blocks. The first has a local
-       //  parameterization associated with it.
+       // my_cost_function takes two parameter blocks. The first has a
+       // manifold associated with it.
+
        CostFunction* my_cost_function = ...
-       LocalParameterization* my_parameterization = ...
+       Manifold* my_manifold = ...
        NumericDiffOptions numeric_diff_options;
 
-       std::vector<LocalParameterization*> local_parameterizations;
-       local_parameterizations.push_back(my_parameterization);
-       local_parameterizations.push_back(nullptr);
+       std::vector<Manifold*> manifolds;
+       manifolds.push_back(my_manifold);
+       manifolds.push_back(nullptr);
 
        std::vector parameter1;
        std::vector parameter2;
@@ -906,7 +908,8 @@
        parameter_blocks.push_back(parameter2.data());
 
        GradientChecker gradient_checker(my_cost_function,
-           local_parameterizations, numeric_diff_options);
+                                        manifolds,
+                                        numeric_diff_options);
        GradientCheckResults results;
        if (!gradient_checker.Probe(parameter_blocks.data(), 1e-9, &results) {
          LOG(ERROR) << "An error has occurred:\n" << results.error_log;
@@ -1182,9 +1185,617 @@
 performance, so we upper bound it by zero. For more details see
 `corrector.cc <https://github.com/ceres-solver/ceres-solver/blob/master/internal/ceres/corrector.cc#L51>`_
 
+
+:class:`Manifolds`
+==================
+
+.. class:: Manifold
+
+In sensor fusion problems, we often have to model quantities that live
+in spaces known as `Manifolds
+<https://en.wikipedia.org/wiki/Manifold>`_, for example the
+rotation/orientation of a sensor that is represented by a `Quaternion
+<https://en.wikipedia.org/wiki/Quaternion>`_.
+
+Manifolds are spaces which locally look like Euclidean spaces. More
+precisely, at each point on the manifold there is a linear space that
+is tangent to the manifold. It has dimension equal to the intrinsic
+dimension of the manifold itself, which is less than or equal to the
+ambient space in which the manifold is embedded.
+
+For example, the tangent space to a point on a sphere in three
+dimensions is the two dimensional plane that is tangent to the sphere
+at that point. There are two reasons tangent spaces are interesting:
+
+1. They are Eucliean spaces so the usual vector space operations apply
+   there, which makes numerical operations easy.
+
+2. Movements in the tangent space translate into movements along the
+   manifold.  Movements perpendicular to the tangent space do not
+   translate into movements on the manifold.
+
+However, moving along the 2 dimensional plane tangent to the sphere
+and projecting back onto the sphere will move you away from the point
+you started from but moving along the normal at the same point and the
+projecting back onto the sphere brings you back to the point.
+
+Besides the mathematical niceness, modeling manifold valued
+quantities correctly and paying attention to their geometry has
+practical benefits too:
+
+1. It naturally constrains the quantity to the manifold throughout the
+   optimization, freeing the user from hacks like *quaternion
+   normalization*.
+
+2. It reduces the dimension of the optimization problem to its
+   *natural* size. For example, a quantity restricted to a line is a
+   one dimensional object regardless of the dimension of the ambient
+   space in which this line lives.
+
+   Working in the tangent space reduces not just the computational
+   complexity of the optimization algorithm, but also improves the
+   numerical behaviour of the algorithm.
+
+A basic operation one can perform on a manifold is the
+:math:`\boxplus` operation that computes the result of moving along
+:math:`\delta` in the tangent space at :math:`x`, and then projecting
+back onto the manifold that :math:`x` belongs to. Also known as a
+*Retraction*, :math:`\boxplus` is a generalization of vector addition
+in Euclidean spaces.
+
+The inverse of :math:`\boxplus` is :math:`\boxminus`, which given two
+points :math:`y` and :math:`x` on the manifold computes the tangent
+vector :math:`\Delta` at :math:`x` s.t. :math:`\boxplus(x, \Delta) =
+y`.
+
+Let us now consider two examples.
+
+The `Euclidean space <https://en.wikipedia.org/wiki/Euclidean_space>`_
+:math:`\mathbb{R}^n` is the simplest example of a manifold. It has
+dimension :math:`n` (and so does its tangent space) and
+:math:`\boxplus` and :math:`\boxminus` are the familiar vector sum and
+difference operations.
+
+.. math::
+   \begin{align*}
+   \boxplus(x, \Delta) &= x + \Delta = y\\
+   \boxminus(y, x) &= y - x = \Delta.
+   \end{align*}
+
+A more interesting case is the case :math:`SO(3)`, the `special
+orthogonal group <https://en.wikipedia.org/wiki/3D_rotation_group>`_
+in three dimensions - the space of 3x3 rotation
+matrices. :math:`SO(3)` is a three dimensional manifold embedded in
+:math:`R^9` or :math:`R^{3\times 3}`.  So points on :math:`SO(3)` are
+represented using 9 dimensional vectors or :math:`3\times 3` matrices,
+and points in its tangent spaces are represented by 3 dimensional
+vectors.
+
+For :math:`SO(3)`, :math:`\boxplus` and :math:`\boxminus` are defined
+in terms of the matrix :math:`\exp` and :math:`\log` operations as
+follows:
+
+Given a 3-vector :math:`\Delta = [\begin{matrix}p,&q,&r\end{matrix}]`, we have
+
+.. math::
+
+   \exp(\Delta) & = \left [ \begin{matrix}
+   \cos \theta + cp^2 & -sr + cpq        &  sq + cpr \\
+   sr + cpq         & \cos \theta + cq^2& -sp + cqr \\
+   -sq + cpr        & sp + cqr         & \cos \theta + cr^2
+   \end{matrix} \right ]
+
+where,
+
+.. math::
+     \begin{align}
+     \theta &= \sqrt{p^2 + q^2 + r^2},\\
+     s &= \frac{\sin \theta}{\theta},\\
+     c &= \frac{1 - \cos \theta}{\theta^2}.
+     \end{align}
+
+Given :math:`x \in SO(3)`, we have
+
+.. math::
+
+   \log(x) = 1/(2 \sin(\theta)/\theta)\left[\begin{matrix} x_{32} - x_{23},& x_{13} - x_{31},& x_{21} - x_{12}\end{matrix} \right]
+
+
+where,
+
+.. math:: \theta = cos^{-1}((\operatorname{Trace}(x) - 1)/2)
+
+Then,
+
+.. math::
+   \begin{align*}
+   \boxplus(x, \Delta) &= x \exp(\Delta)
+   \boxminus(y, x) &= \log(x^T y)
+   \end{align*}
+
+For :math:`\boxplus` and :math:`\boxplus` to be mathematically
+consistent, the following identities must be satisfied at all points
+:math:`x` on the manifold:
+
+1. :math:`\boxplus(x, 0) = x`. This ensures that the tangent space is
+   *centered* at :math:`x`, and the zero vector is the identity
+   element.
+2. For all :math:`y` on the manifold, :math:`\boxplus(x,
+   \boxminus(y,x)) = y`. This ensures that any :math:`y` can be
+   reached from math:`x`.
+3. For all :math:`\Delta`, :math:`\boxminus(\boxplus(x, \Delta), x) =
+   \Delta`. This ensures that :math:`\boxplus` is an injective
+   (one-to-one) map.
+4. For all :math:`\Delta_1, \Delta_2\ |\boxminus(\boxplus(x, \Delta_1),
+   \boxplus(x, \Delta_2)) <= |\Delta_1 - \Delta_2|`. Allows us to define
+   a metric on the manifold.
+
+Additionally we require that :math:`\boxplus` and :math:`\boxminus` be
+sufficiently smooth. In particular they need to be differentiable
+everywhere on the manifold.
+
+For more details, please see `Integrating Generic Sensor Fusion
+Algorithms with Sound State Representations through Encapsulation of
+Manifolds <https://arxiv.org/pdf/1107.1119.pdf>`_
+By C. Hertzberg, R. Wagner, U. Frese and L. Schroder
+
+The :class:`Manifold` interface allows the user to define a manifold
+for the purposes optimization by implementing ``Plus`` and ``Minus``
+operations and their derivatives (corresponding naturally to
+:math:`\boxplus` and :math:`boxminus`).
+
+..code-block c++::
+
+  class Manifold {
+   public:
+    virtual ~Manifold();
+    virtual int AmbientSize() const = 0;
+    virtual int TangentSize() const = 0;
+    virtual bool Plus(const double* x,
+                      const double* delta,
+                      double* x_plus_delta) const = 0;
+    virtual bool PlusJacobian(const double* x, double* jacobian) const = 0;
+    virtual bool RightMultiplyByPlusJacobian(const double* x,
+                                             const int num_rows,
+                                             const double* ambient_matrix,
+                                             double* tangent_matrix) const;
+    virtual bool Minus(const double* y,
+                       const double* x,
+                       double* y_minus_x) const = 0;
+    virtual bool MinusJacobian(const double* x, double* jacobian) const = 0;
+  };
+
+
+.. function:: int Manifold::AmbientSize() const;
+
+   Dimension of the ambient space in which the manifold is embedded.
+
+.. function:: int Manifold::TangentSize() const;
+
+   Dimension of the manifold/tangent space.
+
+.. function:: bool Plus(const double* x, const double* delta, double* x_plus_delta) const;
+
+   Implements the :math:`\boxplus(x,\Delta)` operation for the manifold.
+
+   A generalization of vector addition in Euclidean space, ``Plus``
+   computes the result of moving along ``delta`` in the tangent space
+   at ``x``, and then projecting back onto the manifold that ``x``
+   belongs to.
+
+   ``x`` and ``x_plus_delta`` are :func:`Manifold::AmbientSize` vectors.
+   ``delta`` is a :func:`Manifold::TangentSize` vector.
+
+   Return value indicates if the operation was successful or not.
+
+.. function:: bool PlusJacobian(const double* x, double* jacobian) const;
+
+   Compute the derivative of :math:`\boxplus(x, \Delta)` w.r.t
+   :math:`\Delta` at :\math:`\Delta = 0`, i.e. :math:`(D_2
+   \boxplus)(x, 0)`.
+
+   ``jacobian`` is a row-major :func:`Manifold::AmbientSize`
+   :math:`\times` :func:`Manifold::TangentSize` matrix.
+
+   Return value indicates whether the operation was successful or not.
+
+.. function:: bool RightMultiplyByPlusJacobian(const double* x, const int num_rows, const double* ambient_matrix, double* tangent_matrix) const;
+
+   ``tangent_matrix`` = ``ambient_matrix`` :math:`\times` plus_jacobian.
+
+
+   ``ambient_matrix`` is a row-major ``num_rows`` :math:`\times`
+   :func:`Manifold::AmbientSize` matrix.
+
+   ``tangent_matrix`` is a row-major ``num_rows`` :math:`\times`
+   :func:`Manifold::TangentSize` matrix.
+
+   Return value indicates whether the operation was successful or not.
+
+   This function is only used by the :class:`GradientProblemSolver`,
+   where the dimension of the parameter block can be large and it may
+   be more efficient to compute this product directly rather than
+   first evaluating the Jacobian into a matrix and then doing a matrix
+   vector product.
+
+   Because this is not an often used function, we provide a default
+   implementation for convenience. If performance becomes an issue
+   then the user should consider implementing a specialization.
+
+.. function:: bool Minus(const double* y, const double* x, double* y_minus_x) const;
+
+   Implements :math:`\boxminus(y,x)` operation for the manifold.
+
+   A generalization of vector subtraction in Euclidean spaces, given
+   two points ``x`` and ``y`` on the manifold, ``Minus`` computes the
+   change to ``x`` in the tangent space at ``x``, that will take it to
+   ``y``.
+
+   ``x`` and ``y`` are :func:`Manifold::AmbientSize` vectors.
+   ``y_minus_x`` is a ::func:`Manifold::TangentSize` vector.
+
+   Return value indicates if the operation was successful or not.
+
+.. function:: bool MinusJacobian(const double* x, double* jacobian) const = 0;
+
+   Compute the derivative of :math:`\boxminus(y, x)` w.r.t :math:`y`
+   at :math:`y = x`, i.e :math:`(D_1 \boxminus) (x, x)`.
+
+   ``jacobian`` is a row-major :func:`Manifold::TangentSize`
+   :math:`\times` :func:`Manifold::AmbientSize` matrix.
+
+   Return value indicates whether the operation was successful or not.
+
+Ceres Solver ships with a number of commonly used instances of
+:class:`Manifold`.
+
+For `Lie Groups <https://en.wikipedia.org/wiki/Lie_group>`_, a great
+place to find high quality implementations is the `Sophus
+<https://github.com/strasdat/Sophus>`_ library developed by Hauke
+Strasdat and his collaborators.
+
+:class:`EuclideanManifold`
+--------------------------
+
+.. class:: EuclideanManifold
+
+:class:`EuclideanManifold` as the name implies represents a Euclidean
+space, where the :math:`\boxplus` and :math:`\boxminus` operations are
+the usual vector addition and subtraction.
+
+.. math::
+
+   \begin{align*}
+     \boxplus(x, \Delta) &= x + \Delta\\
+      \boxminus(y,x) &= y - x
+   \end{align*}
+
+By default parameter blocks are assumed to be Euclidean, so there is
+no need to use this manifold on its own. It is provided for the
+purpose of testing and for use in combination with other manifolds
+using :class:`ProductManifold`.
+
+:class:`SubsetManifold`
+-----------------------
+
+.. class:: SubsetManifold
+
+Suppose :math:`x` is a two dimensional vector, and the user wishes to
+hold the first coordinate constant. Then, :math:`\Delta` is a scalar
+and :math:`\boxplus` is defined as
+
+.. math::
+   \boxplus(x, \Delta) = x + \left[ \begin{array}{c} 0 \\ 1 \end{array} \right] \Delta
+
+and given two, two-dimensional vectors :math:`x` and :math:`y` with
+the same first coordinate, :math:`\boxminus` is defined as:
+
+.. math::
+   \boxminus(y, x) = y[1] - x[1]
+
+:class:`SubsetManifold` generalizes this construction to hold
+any part of a parameter block constant by specifying the set of
+coordinates that are held constant.
+
+.. NOTE::
+
+   It is legal to hold *all* coordinates of a parameter block to
+   constant using a :class:`SubsetManifold`. It is the same as calling
+   :func:`Problem::SetParameterBlockConstant` on that parameter block.
+
+
+:class:`ProductManifold`
+------------------------
+
+.. class:: ProductManifold
+
+In cases, where a parameter block is the Cartesian product of a number
+of manifolds and you have the manifold of the individual
+parameter blocks available, :class:`ProductManifold` can be used to
+construct a :class:`Manifold` of the cartesian product.
+
+For the case of the rigid transformation, where say you have a
+parameter block of size 7, where the first four entries represent the
+rotation as a quaternion, and the next three the translation, a
+manifold can be constructed as:
+
+.. code-block:: c++
+
+   ProductManifold se3(new QuaternionManifold(), new EuclideanManifold(3));
+
+
+:class:`QuaternionManifold`
+---------------------------
+
+.. class:: QuaternionManifold
+
+.. NOTE::
+
+   If you are using ``Eigen`` quaternions, then you should use
+   :class:`EigenQuaternionManifold` instead because ``Eigen`` uses a
+   different memory layout for its Quaternions.
+
+Manifold for a Hamilton `Quaternion
+<https://en.wikipedia.org/wiki/Quaternion>`_. Quaternions are a three
+dimensional manifold represented as unit norm 4-vectors, i.e.
+
+.. math:: q = \left [\begin{matrix}q_0,& q_1,& q_2,& q_3\end{matrix}\right], \|q\| = 1
+
+is the ambient space representation. Here :math:`q_0` is the scalar
+part. :math:`q_1` is the coefficient of :math:`i`, :math:`q_2` is the
+coefficient of :math:`j`, and :math:`q_3` is the coeffcient of
+:math:`k`. Where:
+
+.. math::
+
+   \begin{align*}
+   i\times j &= k,\\
+   j\times k &= i,\\
+   k\times i &= j,\\
+   i\times i &= -1,\\
+   j\times j &= -1,\\
+   k\times k &= -1.
+   \end{align*}
+
+The tangent space is three dimensional and the :math:`\boxplus` and
+:math:`\boxminus` operators are defined in term of :math:`\exp` and
+:math:`\log` operations.
+
+.. math::
+
+   \boxplus(x, \Delta) = \exp\left(\Delta\right) \otimes  x \\
+   \boxminus(y,x) = \log\left(y \otimes x^{-1}\right)
+
+Where :math:`\otimes` is the `Quaternion product
+<https://en.wikipedia.org/wiki/Quaternion#Hamilton_product>`_ and
+since :math:`x` is a unit quaternion, :math:`x^{-1} = [\begin{matrix}
+q_0,& -q_1,& -q_2,& -q_3\end{matrix}]`. Given a vector :math:`\Delta
+\in \mathbb{R}^3`,
+
+.. math::
+   \exp(\Delta) = \left[ \begin{matrix}
+                         \cos\left(\|\Delta\|\right)\\
+			 \frac{\displaystyle \sin\left(|\Delta\|\right)}{\displaystyle \|\Delta\|} \Delta
+    	                 \end{matrix} \right]
+
+and given a unit quaternion :math:`q = \left [\begin{matrix}q_0,& q_1,& q_2,& q_3\end{matrix}\right]`
+
+.. math::
+
+   \log(q) =  \frac{\operatorname{atan2}\left(\sqrt{1-q_0^2},q_0\right)}{\sqrt{1-q_0^2}} \left [\begin{matrix}q_1,& q_2,& q_3\end{matrix}\right]
+
+
+:class:`EigenQuaternionManifold`
+--------------------------------
+
+.. class:: EigenQuaternionManifold
+
+Implements the quaternion manifold for `Eigen's
+<http://eigen.tuxfamily.org/index.php?title=Main_Page>`_
+representation of the Hamilton quaternion. Geometrically it is exactly
+the same as the :class:`QuaternionManifold` defined above. However,
+Eigen uses a different internal memory layout for the elements of the
+quaternion than what is commonly used. It stores the quaternion in
+memory as :math:`[q_1, q_2, q_3, q_0]` or :math:`[x, y, z, w]` where
+the real (scalar) part is last.
+
+Since Ceres operates on parameter blocks which are raw double pointers
+this difference is important and requires a different manifold.
+
+:class:`SphereManifold`
+-----------------------
+
+.. class:: SphereManifold
+
+This provides a manifold on a sphere meaning that the norm of the
+vector stays the same. Such cases often arises in Structure for Motion
+problems. One example where they are used is in representing points
+whose triangulation is ill-conditioned. Here it is advantageous to use
+an over-parameterization since homogeneous vectors can represent
+points at infinity.
+
+The ambient space dimension is required to be greater than 1.
+
+The class works with dynamic and static ambient space dimensions. If
+the ambient space dimensions is know at compile time use
+
+.. code-block:: c++
+
+   SphereManifold<3> manifold;
+
+If the ambient space dimensions is not known at compile time the
+template parameter needs to be set to `ceres::DYNAMIC` and the actual
+dimension needs to be provided as a constructor argument:
+
+.. code-block:: c++
+
+   SphereManifold<ceres::DYNAMIC> manifold(ambient_dim);
+
+For more details, please see Section B.2 (p.25) in `Integrating
+Generic Sensor Fusion Algorithms with Sound State Representations
+through Encapsulation of Manifolds
+<https://arxiv.org/pdf/1107.1119.pdf>`_
+By C. Hertzberg, R. Wagner, U. Frese and L. Schroder
+
+
+:class:`LineManifold`
+---------------------
+
+.. class:: LineManifold
+
+This class provides a manifold for lines, where the line is defined
+using an origin point and a direction vector. So the ambient size
+needs to be two times the dimension of the space in which the line
+lives.  The first half of the parameter block is interpreted as the
+origin point and the second half as the direction. This manifold is a
+special case of the `Affine Grassmannian manifold
+<https://en.wikipedia.org/wiki/Affine_Grassmannian_(manifold))>`_ for
+the case :math:`\operatorname{Graff}_1(R^n)`.
+
+Note that this is a manifold for a line, rather than a point
+constrained to lie on a line. It is useful when one wants to optimize
+over the space of lines. For example, given :math:`n` distinct points
+in 3D (measurements) we want to find the line that minimizes the sum
+of squared distances to all the points.
+
+:class:`AutoDiffManifold`
+=========================
+
+.. class:: AutoDiffManifold
+
+Create a :math:`Manifold` with Jacobians computed via automatic
+differentiation.
+
+To get an auto differentiated manifold, you must define a Functor with
+templated ``Plus`` and ``Minus`` functions that compute:
+
+.. code-block:: c++
+
+  x_plus_delta = Plus(x, delta);
+  y_minus_x    = Minus(y, x);
+
+Where, ``x``, ``y`` and ``x_plus_y`` are vectors on the manifold in
+the ambient space (so they are ``kAmbientSize`` vectors) and
+``delta``, ``y_minus_x`` are vectors in the tangent space (so they are
+``kTangentSize`` vectors).
+
+The Functor should have the signature:
+
+.. code-block:: c++
+
+   struct Functor {
+    template <typename T>
+    bool Plus(const T* x, const T* delta, T* x_plus_delta) const;
+
+    template <typename T>
+    bool Minus(const T* y, const T* x, T* y_minus_x) const;
+   };
+
+
+Observe that  the ``Plus`` and  ``Minus`` operations are  templated on
+the parameter  ``T``.  The autodiff framework  substitutes appropriate
+``Jet``  objects for  ``T`` in  order to  compute the  derivative when
+necessary.  This  is  the  same  mechanism that  is  used  to  compute
+derivatives when using :class:`AutoDiffCostFunction`.
+
+``Plus`` and ``Minus`` should return true if the computation is
+successful and false otherwise, in which case the result will not be
+used.
+
+Given this Functor, the corresponding :class:`Manifold` can be constructed as:
+
+.. code-block:: c++
+
+   AutoDiffManifold<Functor, kAmbientSize, kTangentSize> manifold;
+
+.. NOTE::
+
+   The following is only used for illustration purposes. Ceres Solver
+   ships with an optimized, production grade :math:`QuaternionManifold`
+   implementation.
+
+As a concrete example consider the case of `Quaternions
+<https://en.wikipedia.org/wiki/Quaternion>`_. Quaternions form a three
+dimensional manifold embedded in :math:`\mathbb{R}^4`, i.e. they have
+an ambient dimension of 4 and their tangent space has dimension 3. The
+following Functor defines the ``Plus`` and ``Minus`` operations on the
+Quaternion manifold. It assumes that the quaternions are laid out as
+``[w,x,y,z]`` in memory, i.e. the real or scalar part is the first
+coordinate.
+
+.. code-block:: c++
+
+   struct QuaternionFunctor {
+     template <typename T>
+     bool Plus(const T* x, const T* delta, T* x_plus_delta) const {
+       const T squared_norm_delta =
+           delta[0] * delta[0] + delta[1] * delta[1] + delta[2] * delta[2];
+
+       T q_delta[4];
+       if (squared_norm_delta > T(0.0)) {
+         T norm_delta = sqrt(squared_norm_delta);
+         const T sin_delta_by_delta = sin(norm_delta) / norm_delta;
+         q_delta[0] = cos(norm_delta);
+         q_delta[1] = sin_delta_by_delta * delta[0];
+         q_delta[2] = sin_delta_by_delta * delta[1];
+         q_delta[3] = sin_delta_by_delta * delta[2];
+       } else {
+         // We do not just use q_delta = [1,0,0,0] here because that is a
+         // constant and when used for automatic differentiation will
+         // lead to a zero derivative. Instead we take a first order
+         // approximation and evaluate it at zero.
+         q_delta[0] = T(1.0);
+         q_delta[1] = delta[0];
+         q_delta[2] = delta[1];
+         q_delta[3] = delta[2];
+       }
+
+       QuaternionProduct(q_delta, x, x_plus_delta);
+       return true;
+     }
+
+     template <typename T>
+     bool Minus(const T* y, const T* x, T* y_minus_x) const {
+       T minus_x[4] = {x[0], -x[1], -x[2], -x[3]};
+       T ambient_y_minus_x[4];
+       QuaternionProduct(y, minus_x, ambient_y_minus_x);
+       T u_norm = sqrt(ambient_y_minus_x[1] * ambient_y_minus_x[1] +
+		       ambient_y_minus_x[2] * ambient_y_minus_x[2] +
+		       ambient_y_minus_x[3] * ambient_y_minus_x[3]);
+       if (u_norm > 0.0) {
+	 T theta = atan2(u_norm, ambient_y_minus_x[0]);
+	 y_minus_x[0] = theta * ambient_y_minus_x[1] / u_norm;
+	 y_minus_x[1] = theta * ambient_y_minus_x[2] / u_norm;
+	 y_minus_x[2] = theta * ambient_y_minus_x[3] / u_norm;
+       } else {
+	 We do not use [0,0,0] here because even though the value part is
+	 a constant, the derivative part is not.
+	 y_minus_x[0] = ambient_y_minus_x[1];
+	 y_minus_x[1] = ambient_y_minus_x[2];
+	 y_minus_x[2] = ambient_y_minus_x[3];
+       }
+       return true;
+     }
+   };
+
+
+Then given this struct, the auto differentiated Quaternion Manifold can now
+be constructed as
+
+.. code-block:: c++
+
+   Manifold* manifold = new AutoDiffManifold<QuaternionFunctor, 4, 3>;
+
+
 :class:`LocalParameterization`
 ==============================
 
+.. NOTE::
+
+   The :class:`LocalParameterization` interface and associated classes
+   are deprecated. They will be removed in the version 2.2.0. Please use
+   :class:`Manifold` instead.
+
 .. class:: LocalParameterization
 
   In many optimization problems, especially sensor fusion problems,
@@ -1212,18 +1823,17 @@
      manifold.  Movements perpendicular to the tangent space do not
      translate into movements on the manifold.
 
-     Returning to our sphere example, moving in the 2 dimensional
-     plane tangent to the sphere and projecting back onto the sphere
-     will move you away from the point you started from but moving
-     along the normal at the same point and the projecting back onto
-     the sphere brings you back to the point.
+  Moving along the 2 dimensional plane tangent to the sphere and
+  projecting back onto the sphere will move you away from the point
+  you started from but moving along the normal at the same point and
+  the projecting back onto the sphere brings you back to the point.
 
   Besides the mathematical niceness, modeling manifold valued
   quantities correctly and paying attention to their geometry has
   practical benefits too:
 
-  1. It naturally constrains the quantity to the manifold through out
-     the optimization. Freeing the user from hacks like *quaternion
+  1. It naturally constrains the quantity to the manifold throughout
+     the optimization, freeing the user from hacks like *quaternion
      normalization*.
 
   2. It reduces the dimension of the optimization problem to its
@@ -1232,7 +1842,7 @@
      space in which this line lives.
 
      Working in the tangent space reduces not just the computational
-     complexity of the optimization algorithm, but also improves the
+     complexity of the optimization algorithm, but also improves its
      numerical behaviour of the algorithm.
 
   A basic operation one can perform on a manifold is the
@@ -1353,6 +1963,14 @@
 :class:`IdentityParameterization`
 ---------------------------------
 
+.. NOTE::
+
+   :class:`IdentityParameterization` is deprecated. It will be removed
+   in version 2.2.0 of Ceres Solver. Please use
+   :class:`EuclideanManifold` instead.
+
+.. class:: IdentityParameterization
+
 A trivial version of :math:`\boxplus` is when :math:`\Delta` is of the
 same size as :math:`x` and
 
@@ -1363,6 +1981,14 @@
 :class:`QuaternionParameterization`
 -----------------------------------
 
+.. NOTE::
+
+   :class:`QuaternionParameterization` is deprecated. It will be
+   removed in version 2.2.0 of Ceres Solver. Please use
+   :class:`QuaternionManifold` instead.
+
+.. class:: QuaternionParameterization
+
 Another example that occurs commonly in Structure from Motion problems
 is when camera rotations are parameterized using a quaternion. This is
 a 3-dimensional manifold that lives in 4-dimensional space.
@@ -1375,6 +2001,14 @@
 :class:`EigenQuaternionParameterization`
 ----------------------------------------
 
+.. NOTE::
+
+   :class:`EigenQuaternionParameterization` is deprecated. It will be
+   removed in version 2.2.0 of Ceres Solver. Please use
+   :class:`EigenQuaternionManifold` instead.
+
+.. class:: EigenQuaternionParameterization
+
 `Eigen <http://eigen.tuxfamily.org/index.php?title=Main_Page>`_ uses a
 different internal memory layout for the elements of the quaternion
 than what is commonly used. Specifically, Eigen stores the elements in
@@ -1392,6 +2026,14 @@
 :class:`SubsetParameterization`
 -------------------------------
 
+.. NOTE::
+
+   :class:`SubsetParameterization` is deprecated. It will be removed
+   in version 2.2.0 of Ceres Solver. Please use
+   :class:`SubsetManifold` instead.
+
+.. class:: SubsetParameterization
+
 Suppose :math:`x` is a two dimensional vector, and the user wishes to
 hold the first coordinate constant. Then, :math:`\Delta` is a scalar
 and :math:`\boxplus` is defined as
@@ -1410,6 +2052,14 @@
 :class:`HomogeneousVectorParameterization`
 ------------------------------------------
 
+.. NOTE::
+
+   :class:`HomogeneousVectorParameterization` is deprecated. It will
+   be removed in version 2.2.0 of Ceres Solver. Please use
+   :class:`SphereManifold` instead.
+
+.. class:: HomogeneousVectorParameterization
+
 In computer vision, homogeneous vectors are commonly used to represent
 objects in projective geometry such as points in projective space. One
 example where it is useful to use this over-parameterization is in
@@ -1432,6 +2082,14 @@
 :class:`LineParameterization`
 -----------------------------
 
+.. NOTE::
+
+   :class:`LineParameterization` is deprecated. It will be removed in
+   version 2.2.0 of Ceres Solver. Please use :class:`LineManifold`
+   instead.
+
+.. class:: LineParameterization
+
 This class provides a parameterization for lines, where the line is
 defined using an origin point and a direction vector. So the
 parameter vector size needs to be two times the ambient space
@@ -1450,6 +2108,14 @@
 :class:`ProductParameterization`
 --------------------------------
 
+.. NOTE::
+
+   :class:`ProductParameterization` is deprecated. It will be removed
+   in version 2.2.0 of Ceres Solver. Please use
+   :class:`ProductManifold` instead.
+
+.. class:: ProductParameterization
+
 Consider an optimization problem over the space of rigid
 transformations :math:`SE(3)`, which is the Cartesian product of
 :math:`SO(3)` and :math:`\mathbb{R}^3`. Suppose you are using
@@ -1476,6 +2142,12 @@
 :class:`AutoDiffLocalParameterization`
 ======================================
 
+.. NOTE::
+
+   :class:`AutoDiffParameterization` is deprecated. It will be removed
+   in version 2.2.0 of Ceres Solver. Please use
+   :class:`AutoDiffManifold` instead.
+
 .. class:: AutoDiffLocalParameterization
 
   :class:`AutoDiffLocalParameterization` does for
@@ -1540,11 +2212,22 @@
                                 Local Size -------------------+
 
 
+
 :class:`Problem`
 ================
 
 .. class:: Problem
 
+   .. NOTE:: We are currently in the process of transitioning from
+      :class:`LocalParameterization` to :class:`Manifolds` in the
+      Ceres Solver API. During this period, :class:`Problem` will
+      support using both :class:`Manifold` and
+      :class:`LocalParameterization` objects interchangably. In
+      particular, adding a :class:`LocalParameterization` to a
+      parameter block is the same as adding a :class:`Manifold` to
+      that parameter block. For methods in the API affected by this
+      change, see their documentation below.
+
    :class:`Problem` holds the robustified bounds constrained
    non-linear least squares problem :eq:`ceresproblem_modeling`. To
    create a least squares problem, use the
@@ -1585,10 +2268,10 @@
 
    :func:`Problem::AddParameterBlock` explicitly adds a parameter
    block to the :class:`Problem`. Optionally it allows the user to
-   associate a :class:`LocalParameterization` object with the
-   parameter block too. Repeated calls with the same arguments are
-   ignored. Repeated calls with the same double pointer but a
-   different size results in undefined behavior.
+   associate a :class:`Manifold` object with the parameter block
+   too. Repeated calls with the same arguments are ignored. Repeated
+   calls with the same double pointer but a different size results in
+   undefined behavior.
 
    You can set any parameter block to be constant using
    :func:`Problem::SetParameterBlockConstant` and undo this using
@@ -1608,17 +2291,18 @@
    **Ownership**
 
    :class:`Problem` by default takes ownership of the
-   ``cost_function``, ``loss_function`` and ``local_parameterization``
-   pointers. These objects remain live for the life of the
-   :class:`Problem`. If the user wishes to keep control over the
-   destruction of these objects, then they can do this by setting the
-   corresponding enums in the :class:`Problem::Options` struct.
+   ``cost_function``, ``loss_function``, ``local_parameterization``,
+   and ``manifold`` pointers. These objects remain live for the life
+   of the :class:`Problem`. If the user wishes to keep control over
+   the destruction of these objects, then they can do this by setting
+   the corresponding enums in the :class:`Problem::Options` struct.
 
-   Note that even though the Problem takes ownership of ``cost_function``
-   and ``loss_function``, it does not preclude the user from re-using
-   them in another residual block. The destructor takes care to call
-   delete on each ``cost_function`` or ``loss_function`` pointer only
-   once, regardless of how many residual blocks refer to them.
+   Note that even though the Problem takes ownership of objects,
+   ``cost_function`` and ``loss_function``, it does not preclude the
+   user from re-using them in another residual block. Similarly the
+   same ``local_parameterization`` or ``manifold`` object can be used
+   with multiple parameter blocks. The destructor takes care to call
+   delete on each owned object exactly once.
 
 .. class:: Problem::Options
 
@@ -1648,6 +2332,13 @@
 
 .. member:: Ownership Problem::Options::local_parameterization_ownership
 
+   .. NOTE::
+
+      `Problem::Options::local_parameterization_ownership` is
+      deprecated. It will be removed in Ceres Solver version
+      2.2.0. Please move to using Manifolds and use
+      `Problem::Options::manifold_ownership` instead.
+
    Default: ``TAKE_OWNERSHIP``
 
    This option controls whether the Problem object owns the local
@@ -1658,6 +2349,16 @@
    to delete the pointers only once, since sharing local
    parameterizations is allowed.
 
+.. member:: Ownership Problem::Options::manifold_ownership
+
+   Default: ``TAKE_OWNERSHIP``
+
+   This option controls whether the Problem object owns the manifolds.
+
+   If set to TAKE_OWNERSHIP, then the problem object will delete the
+   manifolds on destruction. The destructor is careful to delete the
+   pointers only once, since sharing manifolds is allowed.
+
 .. member:: bool Problem::Options::enable_fast_removal
 
     Default: ``false``
@@ -1788,10 +2489,58 @@
 
 .. function:: void Problem::AddParameterBlock(double* values, int size, LocalParameterization* local_parameterization)
 
-   Add a parameter block with appropriate size to the problem.
+   .. NOTE::
+
+       This method is deprecated and will be removed in Ceres Solver
+       version 2.2.0. Please move to using the :class:`Manifold` based version
+       of `AddParameterBlock`.
+
+       During the transition from :class:`LocalParameterization` to
+       :class:`Manifold`, internally the
+       :class:`LocalParameterization` is treated as a
+       :class:`Manifold` by wrapping it using a `ManifoldAdapter`
+       object. So :func:`Problem::HasManifold` will return true,
+       :func:`Problem::GetManifold` will return the wrapped object and
+       :func:`Problem::ParameterBlockTangentSize` will return the value of
+       :func:`LocalParameterization::LocalSize`.
+
+   Add a parameter block with appropriate size and parameterization to the
+   problem. It is okay for `local_parameterization` to be `nullptr`.
+
    Repeated calls with the same arguments are ignored. Repeated calls
-   with the same double pointer but a different size results in
-   undefined behavior.
+   with the same double pointer but a different size results in a crash
+   (unless `Solver::Options::diable_all_safety_checks` is set to true).
+
+   Repeated calls with the same double pointer and size but different
+   :class:`LocalParameterization` is equivalent to calling
+   `SetParameterization(local_parameterization)`, i.e., any previously
+   associated :class:`LocalParameterization` or :class:`Manifold`
+   object will be replaced with the `local_parameterization`.
+
+
+.. function:: void Problem::AddParameterBlock(double* values, int size, Manifold* manifold)
+
+   .. NOTE::
+
+      During the transition from :class:`LocalParameterization` to
+      :class:`Manifold`, calling `AddParameterBlock` with a
+      :class:`Manifold` when a :class:`LocalParameterization` is
+      already associated with the parameter block is okay. It is
+      equivalent to calling `SetManifold(manifold)`, i.e., any
+      previously associated :class:`LocalParameterization` or
+      :class:`Manifold` object will be replaced with the manifold.
+
+   Add a parameter block with appropriate size and Manifold to the
+   problem. It is okay for `manifold` to be `nullptr`.
+
+   Repeated calls with the same arguments are ignored. Repeated calls
+   with the same double pointer but a different size results in a crash
+   (unless `Solver::Options::diable_all_safety_checks` is set to true).
+
+   Repeated calls with the same double pointer and size but different
+   :class:`Manifold` is equivalent to calling `SetManifold(manifold)`,
+   i.e., any previously associated :class:`LocalParameterization` or
+   :class:`Manifold` object will be replaced with the `manifold`.
 
 .. function:: void Problem::AddParameterBlock(double* values, int size)
 
@@ -1854,17 +2603,40 @@
    Returns ``true`` if a parameter block is set constant, and false
    otherwise. A parameter block may be set constant in two ways:
    either by calling ``SetParameterBlockConstant`` or by associating a
-   ``LocalParameterization`` with a zero dimensional tangent space
-   with it.
+   :class:`LocalParameterization` or :class:`Manifold` with a zero
+   dimensional tangent space with it.
 
 .. function:: void Problem::SetParameterization(double* values, LocalParameterization* local_parameterization)
 
-   Set the local parameterization for one of the parameter blocks.
-   The local_parameterization is owned by the Problem by default. It
-   is acceptable to set the same parameterization for multiple
-   parameters; the destructor is careful to delete local
-   parameterizations only once. Calling `SetParameterization` with
-   `nullptr` will clear any previously set parameterization.
+   .. NOTE::
+
+      This method is deprecated and will be removed in Ceres Solver
+      version 2.2.0. Please move to using the SetManifold instead.
+
+      During the transition from :class:`LocalParameterization` to
+      :class:`Manifold`, calling `AddParameterBlock` with a
+      :class:`Manifold` when a :class:`LocalParameterization` is
+      already associated with the parameter block is okay. It is
+      equivalent to calling `SetManifold(manifold)`, i.e., any
+      previously associated :class:`LocalParameterization` or
+      :class:`Manifold` object will be replaced with the manifold.
+
+   Set the :class:`LocalParameterization` for the parameter
+   block. Calling :func:`Problem::SetParameterization` with
+   ``nullptr`` will clear any previously set
+   :class:`LocalParameterization` or :class:`Manifold` for the
+   parameter block.
+
+   Repeated calls will cause any previously associated
+   :class:`LocalParameterization` or :class:`Manifold` object to be
+   replaced with the ``local_parameterization``.
+
+   The ``local_parameterization`` is owned by the :class:`Problem` by
+   default (See :class:`Problem::Options` to override this behaviour).
+
+   It is acceptable to set the same :class:`LocalParameterization` for
+   multiple parameter blocks; the Problem destructor is careful to
+   delete :class:`LocalParamaterizations` only once.
 
 .. function:: LocalParameterization* Problem::GetParameterization(const double* values) const
 
@@ -1872,6 +2644,76 @@
    parameter block. If there is no parameterization object associated
    then `nullptr` is returned
 
+   .. NOTE::
+
+       This method is deprecated and will be removed in Ceres Solver
+       version 2.2.0. Please move to using the
+       :func:`Problem::GetParameterization` instead.
+
+       Note also that if a :class:`LocalParameterization` is
+       associated with a parameter block, :func:`Problem::HasManifold`
+       will return true and :func:`Problem::GetManifold` will return
+       the :class:`LocalParameterization` wrapped in a
+       ``ManifoldAdapter``.
+
+       The converse is NOT true, i.e., if a :class:`Manifold` is
+       associated with a parameter block,
+       :func:`Problem::HasParameterization` will return ``false`` and
+       :func:`Problem::GetParameterization` will return a
+       ``nullptr``.
+
+.. function:: bool HasParameterization(const double* values) const;
+
+   Returns ``true`` if a :class:`LocalParameterization` is associated
+   with this parameter block, ``false`` otherwise.
+
+   .. NOTE::
+
+      This method is deprecated and will be removed in the next public
+      release of Ceres Solver. Use :func:`Problem::HasManifold` instead.
+
+      Note also that if a ::class::`Manifold` is associated with the
+      parameter block, this method will return ``false``.
+
+.. function:: void SetManifold(double* values, Manifold* manifold);
+
+   Set the :class:`Manifold` for the parameter block. Calling
+   :func:`Problem::SetManifold` with ``nullptr`` will clear any
+   previously set :class:`LocalParameterization` or :class:`Manifold`
+   for the parameter block.
+
+   Repeated calls will result in any previously associated
+   :class:`LocalParameterization` or :class:`Manifold` object to be
+   replaced with ``manifold``.
+
+   ``manifold`` is owned by :class:`Problem` by default (See
+   :class:`Problem::Options` to override this behaviour).
+
+   It is acceptable to set the same :class:`Manifold` for multiple
+   parameter blocks.
+
+.. function:: const Manifold* GetManifold(const double* values) const;
+
+   Get the :class:`Manifold` object associated with this parameter block.
+
+   If there is no :class:`Manifold` Or :class:`LocalParameterization`
+   object associated then ``nullptr`` is returned.
+
+   .. NOTE::
+
+      During the transition from :class:`LocalParameterization` to
+      :class:`Manifold`, internally the :class:`LocalParameterization` is
+      treated as a :class:`Manifold` by wrapping it using a ``ManifoldAdapter``
+      object. So calling :func:`Problem::GetManifold` on a parameter block with a
+      :class:`LocalParameterization` associated with it will return the
+      :class:`LocalParameterization` wrapped in a ManifoldAdapter.
+
+.. function:: bool HasManifold(const double* values) const;
+
+   Returns ``true`` if a :class:`Manifold` or a
+   :class:`LocalParameterization` is associated with this parameter
+   block, ``false`` otherwise.
+
 .. function:: void Problem::SetParameterLowerBound(double* values, int index, double lower_bound)
 
    Set the lower bound for the parameter at position `index` in the
@@ -1924,9 +2766,25 @@
 
 .. function:: int Problem::ParameterBlockLocalSize(const double* values) const
 
-   The size of local parameterization for the parameter block. If
-   there is no local parameterization associated with this parameter
-   block, then ``ParameterBlockLocalSize`` = ``ParameterBlockSize``.
+   The dimension of the tangent space of the
+   :class:`LocalParameterization` or :class:`Manifold` for the
+   parameter block. If there is no :class:`LocalParameterization` or
+   :class:`Manifold` associated with this parameter block, then
+   ``ParameterBlockLocalSize = ParameterBlockSize``.
+
+   .. NOTE::
+
+      This method is deprecated and will be removed in Ceres Solver
+      Version 2.2.0. Use :func:`Problem::ParameterBlockTangentSize`
+      instead.
+
+.. function:: int Problem::ParameterBlockTangentSize(const double* values) const
+
+   The dimension of the tangent space of the
+   :class:`LocalParameterization` or :class:`Manifold` for the
+   parameter block. If there is no :class:`LocalParameterization` or
+   :class:`Manifold` associated with this parameter block, then
+   ``ParameterBlockLocalSize = ParameterBlockSize``.
 
 .. function:: bool Problem::HasParameterBlock(const double* values) const
 
@@ -1986,10 +2844,10 @@
    function returns false, the caller should expect the output
    memory locations to have been modified.
 
-   The returned cost and jacobians have had robustification and local
-   parameterizations applied already; for example, the jacobian for a
-   4-dimensional quaternion parameter using the
-   :class:`QuaternionParameterization` is ``num_residuals x 3``
+   The returned cost and jacobians have had robustification and
+   :class:`LocalParameterization`/:class:`Manifold` applied already;
+   for example, the jacobian for a 4-dimensional quaternion parameter
+   using the :class:`QuaternionManifold` is ``num_residuals x 3``
    instead of ``num_residuals x 4``.
 
    ``apply_loss_function`` as the name implies allows the user to
@@ -2060,10 +2918,11 @@
 
    .. NOTE::
 
-      If no local parameterizations are used, then the size of
-      the gradient vector is the sum of the sizes of all the parameter
-      blocks. If a parameter block has a local parameterization, then
-      it contributes "LocalSize" entries to the gradient vector.
+      If no :class:`LocalParameterization`/:class:`Manifold` are used,
+      then the size of the gradient vector is the sum of the sizes of
+      all the parameter blocks. If a parameter block has a local
+      parameterization, then it contributes "LocalSize" entries to the
+      gradient vector.
 
    .. NOTE::
 
@@ -2117,7 +2976,7 @@
 
 .. member:: int Problem::EvaluateOptions::num_threads
 
-   Number of threads to use. (Requires OpenMP).
+   Number of threads to use.
 
 
 :class:`EvaluationCallback`
@@ -2143,7 +3002,7 @@
    every time, and once before it computes the residuals and/or the
    Jacobians.
 
-   User parameters (the double* values provided by the us) are fixed
+   User parameters (the double* values provided by the user) are fixed
    until the next call to
    :func:`EvaluationCallback::PrepareForEvaluation`. If
    ``new_evaluation_point == true``, then this is a new point that is
diff --git a/docs/source/nnls_solving.rst b/docs/source/nnls_solving.rst
index 3c8ecbb..9946645 100644
--- a/docs/source/nnls_solving.rst
+++ b/docs/source/nnls_solving.rst
@@ -1,6 +1,7 @@
-
 .. default-domain:: cpp
 
+.. highlight:: c++
+
 .. cpp:namespace:: ceres
 
 .. _chapter-nnls_solving:
@@ -1239,8 +1240,8 @@
 
    where :math:`\|\cdot\|_\infty` refers to the max norm, :math:`\Pi`
    is projection onto the bounds constraints and :math:`\boxplus` is
-   Plus operation for the overall local parameterization associated
-   with the parameter vector.
+   Plus operation for the overall manifold associated with the
+   parameter vector.
 
 .. member:: double Solver::Options::parameter_tolerance
 
@@ -2212,7 +2213,7 @@
    Dimension of the tangent space of the problem (or the number of
    columns in the Jacobian for the problem). This is different from
    :member:`Solver::Summary::num_parameters` if a parameter block is
-   associated with a :class:`LocalParameterization`.
+   associated with a :class:`Manifold`.
 
 .. member:: int Solver::Summary::num_residual_blocks
 
@@ -2238,7 +2239,7 @@
    number of columns in the Jacobian for the reduced problem). This is
    different from :member:`Solver::Summary::num_parameters_reduced` if
    a parameter block in the reduced problem is associated with a
-   :class:`LocalParameterization`.
+   :class:`Manifold`.
 
 .. member:: int Solver::Summary::num_residual_blocks_reduced
 
diff --git a/docs/source/nnls_tutorial.rst b/docs/source/nnls_tutorial.rst
index 7f7e810..b5f2710 100644
--- a/docs/source/nnls_tutorial.rst
+++ b/docs/source/nnls_tutorial.rst
@@ -728,7 +728,7 @@
 
 For a more sophisticated bundle adjustment example which demonstrates
 the use of Ceres' more advanced features including its various linear
-solvers, robust loss functions and local parameterizations see
+solvers, robust loss functions and manifolds see
 `examples/bundle_adjuster.cc
 <https://ceres-solver.googlesource.com/ceres-solver/+/master/examples/bundle_adjuster.cc>`_
 
@@ -886,10 +886,12 @@
    i.e. :math:`\Sigma_{ab}^{-\frac{1}{2}} r_{ab}` where :math:`\Sigma_{ab}` is
    the covariance.
 
-   Lastly, we use a local parameterization to normalize the orientation in the
-   range which is normalized between :math:`[-\pi,\pi)`.  Specially, we define
-   the :member:`AngleLocalParameterization::operator()` function to be:
-   :math:`\mathrm{Normalize}(\psi + \delta \psi)`.
+   Lastly, we use a manifold to normalize the orientation in the range
+   :math:`[-\pi,\pi)`.  Specially, we define the
+   :member:`AngleManifold::Plus()` function to be:
+   :math:`\mathrm{Normalize}(\psi + \Delta)` and
+   ::member::`AngleManifold::Minus()` function to be
+   :math:`\mathrm{Normalize}(y) - \mathrm{Normalize}(x)`.
 
    This package includes an executable :member:`pose_graph_2d` that will read a
    problem definition file. This executable can work with any 2D problem
@@ -980,17 +982,18 @@
    i.e. :math:`\Sigma_{ab}^{-\frac{1}{2}} r_{ab}` where :math:`\Sigma_{ab}` is
    the covariance.
 
-   Given that we are using a quaternion to represent the orientation, we need to
-   use a local parameterization (:class:`EigenQuaternionParameterization`) to
+   Given that we are using a quaternion to represent the orientation,
+   we need to use a manifold (:class:`EigenQuaternionManifold`) to
    only apply updates orthogonal to the 4-vector defining the
-   quaternion. Eigen's quaternion uses a different internal memory layout for
-   the elements of the quaternion than what is commonly used. Specifically,
-   Eigen stores the elements in memory as :math:`[x, y, z, w]` where the real
-   part is last whereas it is typically stored first. Note, when creating an
-   Eigen quaternion through the constructor the elements are accepted in
-   :math:`w`, :math:`x`, :math:`y`, :math:`z` order. Since Ceres operates on
-   parameter blocks which are raw double pointers this difference is important
-   and requires a different parameterization.
+   quaternion. Eigen's quaternion uses a different internal memory
+   layout for the elements of the quaternion than what is commonly
+   used. Specifically, Eigen stores the elements in memory as
+   :math:`[x, y, z, w]` where the real part is last whereas it is
+   typically stored first. Note, when creating an Eigen quaternion
+   through the constructor the elements are accepted in :math:`w`,
+   :math:`x`, :math:`y`, :math:`z` order. Since Ceres operates on
+   parameter blocks which are raw double pointers this difference is
+   important and requires a different parameterization.
 
    This package includes an executable :member:`pose_graph_3d` that will read a
    problem definition file. This executable can work with any 3D problem
diff --git a/include/ceres/autodiff_local_parameterization.h b/include/ceres/autodiff_local_parameterization.h
index 76e22ed..8ec91e0 100644
--- a/include/ceres/autodiff_local_parameterization.h
+++ b/include/ceres/autodiff_local_parameterization.h
@@ -40,6 +40,10 @@
 
 namespace ceres {
 
+// WARNING: LocalParameterizations are deprecated, so is
+// AutoDiffLocalParameterization. They will be removed from Ceres Solver in
+// version 2.2.0. Please use Manifolds and AutoDiffManifold instead.
+
 // Create local parameterization with Jacobians computed via automatic
 // differentiation. For more information on local parameterizations,
 // see include/ceres/local_parameterization.h
@@ -106,17 +110,18 @@
 // seen where instead of using k_ directly, k_ is wrapped with T(k_).
 
 template <typename Functor, int kGlobalSize, int kLocalSize>
-class AutoDiffLocalParameterization : public LocalParameterization {
+class [[deprecated(
+    "Use AutoDiffManifold instead.")]] AutoDiffLocalParameterization
+    : public LocalParameterization {
  public:
   AutoDiffLocalParameterization() : functor_(new Functor()) {}
 
   // Takes ownership of functor.
-  explicit AutoDiffLocalParameterization(Functor* functor)
+  explicit AutoDiffLocalParameterization(Functor * functor)
       : functor_(functor) {}
 
-  bool Plus(const double* x,
-            const double* delta,
-            double* x_plus_delta) const override {
+  bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const override {
     return (*functor_)(x, delta, x_plus_delta);
   }
 
@@ -142,7 +147,7 @@
   int GlobalSize() const override { return kGlobalSize; }
   int LocalSize() const override { return kLocalSize; }
 
-  const Functor & functor() const { return *functor_; }
+  const Functor& functor() const { return *functor_; }
 
  private:
   std::unique_ptr<Functor> functor_;
diff --git a/include/ceres/autodiff_manifold.h b/include/ceres/autodiff_manifold.h
index 462fcde..7b5f639 100644
--- a/include/ceres/autodiff_manifold.h
+++ b/include/ceres/autodiff_manifold.h
@@ -42,16 +42,16 @@
 // more information on manifolds, see include/ceres/manifold.h
 //
 // To get an auto differentiated manifold, you must define a class/struct with
-// templated Plus and Minus functions that computes
+// templated Plus and Minus functions that compute
 //
 //   x_plus_delta = Plus(x, delta);
 //   y_minus_x    = Minus(y, x);
 //
 // Where, x, y and x_plus_y are vectors on the manifold in the ambient space (so
-// they are kAmbientSize vectors) and and delta, y_minus_x are vectors in the
+// they are kAmbientSize vectors) and delta, y_minus_x are vectors in the
 // tangent space (so they are kTangentSize vectors).
 //
-// The Functor should have the signatures:
+// The Functor should have the signature:
 //
 // struct Functor {
 //   template <typename T>
diff --git a/include/ceres/covariance.h b/include/ceres/covariance.h
index 2fe025d..eba61a1 100644
--- a/include/ceres/covariance.h
+++ b/include/ceres/covariance.h
@@ -145,7 +145,7 @@
 //   a. The rank deficiency arises from overparameterization. e.g., a
 //   four dimensional quaternion used to parameterize SO(3), which is
 //   a three dimensional manifold. In cases like this, the user should
-//   use an appropriate LocalParameterization. Not only will this lead
+//   use an appropriate LocalParameterization/Manifold. Not only will this lead
 //   to better numerical behaviour of the Solver, it will also expose
 //   the rank deficiency to the Covariance object so that it can
 //   handle it correctly.
diff --git a/include/ceres/gradient_checker.h b/include/ceres/gradient_checker.h
index f2ea0fc..4e63141 100644
--- a/include/ceres/gradient_checker.h
+++ b/include/ceres/gradient_checker.h
@@ -80,10 +80,14 @@
   // NOTE: This constructor is deprecated and will be removed in the next public
   // release of Ceres Solver. Please transition to using the Manifold based
   // version.
-  GradientChecker(
-      const CostFunction* function,
-      const std::vector<const LocalParameterization*>* local_parameterizations,
-      const NumericDiffOptions& options);
+  [[deprecated(
+      "Local Parameterizations are deprecated. Use the constructor that uses "
+      "Manifolds instead.")]] GradientChecker(const CostFunction* function,
+                                              const std::vector<
+                                                  const LocalParameterization*>*
+                                                  local_parameterizations,
+                                              const NumericDiffOptions&
+                                                  options);
 
   // This will not take ownership of the cost function or manifolds.
   //
diff --git a/include/ceres/gradient_problem.h b/include/ceres/gradient_problem.h
index d9d40e2..8984cba 100644
--- a/include/ceres/gradient_problem.h
+++ b/include/ceres/gradient_problem.h
@@ -105,8 +105,11 @@
   // NOTE: This constructor is deprecated and will be removed in the next public
   // release of Ceres Solver. Please move to using the Manifold based
   // constructor.
-  GradientProblem(FirstOrderFunction* function,
-                  LocalParameterization* parameterization);
+  [[deprecated(
+      "LocalParameterizations are deprecated. Please use the constructor that "
+      "uses Manifold instead.")]] GradientProblem(FirstOrderFunction* function,
+                                                  LocalParameterization*
+                                                      parameterization);
 
   // Takes ownership of the function and the manifold.
   GradientProblem(FirstOrderFunction* function, Manifold* manifold);
@@ -151,7 +154,8 @@
   //
   // NOTE: This method is deprecated and will be removed in the next public
   // release of Ceres Solver.
-  const LocalParameterization* parameterization() const {
+  [[deprecated("Use Manifolds instead.")]] const LocalParameterization*
+  parameterization() const {
     return parameterization_.get();
   }
 
@@ -160,13 +164,14 @@
   //
   // NOTE: This method is deprecated and will be removed in the next public
   // release of Ceres Solver.
-  LocalParameterization* mutable_parameterization() {
+  [[deprecated("Use Manifolds instead.")]] LocalParameterization*
+  mutable_parameterization() {
     return parameterization_.get();
   }
 
  private:
   std::unique_ptr<FirstOrderFunction> function_;
-  std::unique_ptr<LocalParameterization> parameterization_;
+  [[deprecated]] std::unique_ptr<LocalParameterization> parameterization_;
   std::unique_ptr<Manifold> manifold_;
   std::unique_ptr<double[]> scratch_;
 };
diff --git a/include/ceres/gradient_problem_solver.h b/include/ceres/gradient_problem_solver.h
index 9fab62e..042d611 100644
--- a/include/ceres/gradient_problem_solver.h
+++ b/include/ceres/gradient_problem_solver.h
@@ -305,7 +305,10 @@
     int num_parameters = -1;
 
     // Dimension of the tangent space of the problem.
-    int num_local_parameters = -1;
+    [[deprecated("Use num_tangent_parameters.")]] int num_local_parameters = -1;
+
+    // Dimension of the tangent space of the problem.
+    int num_tangent_parameters = -1;
 
     // Type of line search direction used.
     LineSearchDirectionType line_search_direction_type = LBFGS;
diff --git a/include/ceres/local_parameterization.h b/include/ceres/local_parameterization.h
index b16c893..d4a590f 100644
--- a/include/ceres/local_parameterization.h
+++ b/include/ceres/local_parameterization.h
@@ -41,6 +41,9 @@
 
 namespace ceres {
 
+// WARNING: LocalParameterizations are deprecated. They will be removed from
+// Ceres Solver in version 2.2.0. Please use Manifolds instead.
+
 // Purpose: Sometimes parameter blocks x can overparameterize a problem
 //
 //   min f(x)
@@ -111,7 +114,10 @@
 //
 // The class LocalParameterization defines the function Plus and its
 // Jacobian which is needed to compute the Jacobian of f w.r.t delta.
-class CERES_EXPORT LocalParameterization {
+class [[deprecated(
+    "LocalParameterizations will be removed from the Ceres Solver API in "
+    "version 2.2.0. Use Manifolds instead.")]] CERES_EXPORT
+    LocalParameterization {
  public:
   virtual ~LocalParameterization();
 
@@ -120,9 +126,9 @@
   //   x_plus_delta = Plus(x, delta)
   //
   // with the condition that Plus(x, 0) = x.
-  virtual bool Plus(const double* x,
-                    const double* delta,
-                    double* x_plus_delta) const = 0;
+  //
+  virtual bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const = 0;
 
   // The jacobian of Plus(x, delta) w.r.t delta at delta = 0.
   //
@@ -152,12 +158,13 @@
 // Some basic parameterizations
 
 // Identity Parameterization: Plus(x, delta) = x + delta
-class CERES_EXPORT IdentityParameterization : public LocalParameterization {
+class [[deprecated(
+    "Use EuclideanManifold instead.")]] CERES_EXPORT IdentityParameterization
+    : public LocalParameterization {
  public:
   explicit IdentityParameterization(int size);
-  bool Plus(const double* x,
-            const double* delta,
-            double* x_plus_delta) const override;
+  bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const override;
   bool ComputeJacobian(const double* x, double* jacobian) const override;
   bool MultiplyByJacobian(const double* x,
                           const int num_cols,
@@ -171,13 +178,14 @@
 };
 
 // Hold a subset of the parameters inside a parameter block constant.
-class CERES_EXPORT SubsetParameterization : public LocalParameterization {
+class [[deprecated(
+    "Use SubsetManifold instead.")]] CERES_EXPORT SubsetParameterization
+    : public LocalParameterization {
  public:
   explicit SubsetParameterization(int size,
                                   const std::vector<int>& constant_parameters);
-  bool Plus(const double* x,
-            const double* delta,
-            double* x_plus_delta) const override;
+  bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const override;
   bool ComputeJacobian(const double* x, double* jacobian) const override;
   bool MultiplyByJacobian(const double* x,
                           const int num_cols,
@@ -197,11 +205,12 @@
 // with * being the quaternion multiplication operator. Here we assume
 // that the first element of the quaternion vector is the real (cos
 // theta) part.
-class CERES_EXPORT QuaternionParameterization : public LocalParameterization {
+class [[deprecated(
+    "Use QuaternionManifold instead.")]] CERES_EXPORT QuaternionParameterization
+    : public LocalParameterization {
  public:
-  bool Plus(const double* x,
-            const double* delta,
-            double* x_plus_delta) const override;
+  bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const override;
   bool ComputeJacobian(const double* x, double* jacobian) const override;
   int GlobalSize() const override { return 4; }
   int LocalSize() const override { return 3; }
@@ -218,37 +227,36 @@
 //
 // Plus(x, delta) = [sin(|delta|) delta / |delta|, cos(|delta|)] * x
 // with * being the quaternion multiplication operator.
-class CERES_EXPORT EigenQuaternionParameterization
-    : public ceres::LocalParameterization {
+class [[deprecated("Use EigenQuaternionManifold instead.")]] CERES_EXPORT
+    EigenQuaternionParameterization : public ceres::LocalParameterization {
  public:
-  bool Plus(const double* x,
-            const double* delta,
-            double* x_plus_delta) const override;
+  bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const override;
   bool ComputeJacobian(const double* x, double* jacobian) const override;
   int GlobalSize() const override { return 4; }
   int LocalSize() const override { return 3; }
 };
 
 // This provides a parameterization for homogeneous vectors which are commonly
-// used in Structure for Motion problems.  One example where they are used is
-// in representing points whose triangulation is ill-conditioned. Here
-// it is advantageous to use an over-parameterization since homogeneous vectors
-// can represent points at infinity.
+// used in Structure from Motion problems.  One example where they are used is
+// in representing points whose triangulation is ill-conditioned. Here it is
+// advantageous to use an over-parameterization since homogeneous vectors can
+// represent points at infinity.
 //
 // The plus operator is defined as
 // Plus(x, delta) =
 //    [sin(0.5 * |delta|) * delta / |delta|, cos(0.5 * |delta|)] * x
+//
 // with * defined as an operator which applies the update orthogonal to x to
 // remain on the sphere. We assume that the last element of x is the scalar
 // component. The size of the homogeneous vector is required to be greater than
 // 1.
-class CERES_EXPORT HomogeneousVectorParameterization
-    : public LocalParameterization {
+class [[deprecated("Use SphereManifold instead.")]] CERES_EXPORT
+    HomogeneousVectorParameterization : public LocalParameterization {
  public:
   explicit HomogeneousVectorParameterization(int size);
-  bool Plus(const double* x,
-            const double* delta,
-            double* x_plus_delta) const override;
+  bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const override;
   bool ComputeJacobian(const double* x, double* jacobian) const override;
   int GlobalSize() const override { return size_; }
   int LocalSize() const override { return size_ - 1; }
@@ -271,14 +279,14 @@
 // manifold (see https://en.wikipedia.org/wiki/Affine_Grassmannian_(manifold))
 // for the case Graff_1(R^n).
 template <int AmbientSpaceDimension>
-class LineParameterization : public LocalParameterization {
+class [[deprecated("Use LineManifold instead.")]] LineParameterization
+    : public LocalParameterization {
  public:
   static_assert(AmbientSpaceDimension >= 2,
                 "The ambient space must be at least 2");
 
-  bool Plus(const double* x,
-            const double* delta,
-            double* x_plus_delta) const override;
+  bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const override;
   bool ComputeJacobian(const double* x, double* jacobian) const override;
   int GlobalSize() const override { return 2 * AmbientSpaceDimension; }
   int LocalSize() const override { return 2 * (AmbientSpaceDimension - 1); }
@@ -297,7 +305,10 @@
 //
 // is the local parameterization for a rigid transformation, where the
 // rotation is represented using a quaternion.
-class CERES_EXPORT ProductParameterization : public LocalParameterization {
+//
+class [[deprecated(
+    "Use ProductManifold instead.")]] CERES_EXPORT ProductParameterization
+    : public LocalParameterization {
  public:
   ProductParameterization(const ProductParameterization&) = delete;
   ProductParameterization& operator=(const ProductParameterization&) = delete;
@@ -306,7 +317,7 @@
   // parameterizations.
   //
   template <typename... LocalParams>
-  ProductParameterization(LocalParams*... local_params)
+  ProductParameterization(LocalParams * ... local_params)
       : local_params_(sizeof...(LocalParams)),
         local_size_{0},
         global_size_{0},
@@ -333,11 +344,9 @@
     }
   }
 
-  bool Plus(const double* x,
-            const double* delta,
-            double* x_plus_delta) const override;
-  bool ComputeJacobian(const double* x,
-                       double* jacobian) const override;
+  bool Plus(const double* x, const double* delta, double* x_plus_delta)
+      const override;
+  bool ComputeJacobian(const double* x, double* jacobian) const override;
   int GlobalSize() const override { return global_size_; }
   int LocalSize() const override { return local_size_; }
 
diff --git a/include/ceres/manifold.h b/include/ceres/manifold.h
index dcf9750..98e27c5 100644
--- a/include/ceres/manifold.h
+++ b/include/ceres/manifold.h
@@ -94,7 +94,7 @@
 // A more interesting case is SO(3), the special orthogonal group in three
 // dimensions - the space of 3x3 rotation matrices. SO(3) is a three dimensional
 // manifold embedded in R^9 or R^(3x3). So points on SO(3) are represented using
-// 9 dimensional vectors or 3x3 matrices, and point in its tangent spaces are
+// 9 dimensional vectors or 3x3 matrices, and points in its tangent spaces are
 // represented by 3 dimensional vectors.
 //
 // Defining Plus and Minus are defined in terms of the matrix Exp and Log
@@ -142,10 +142,6 @@
 // Representations through Encapsulation of Manifolds"
 // By C. Hertzberg, R. Wagner, U. Frese and L. Schroder
 // https://arxiv.org/pdf/1107.1119.pdf
-//
-// TODO(sameeragarwal): Add documentation about how this class replaces
-// LocalParameterization once the transition starts happening.
-
 class CERES_EXPORT Manifold {
  public:
   virtual ~Manifold();
@@ -158,10 +154,9 @@
 
   //   x_plus_delta = Plus(x, delta),
   //
-  // Plus computes the result of moving along delta in the tangent space at x,
-  // and then projecting back onto the manifold that x belongs to. In
-  // Differential Geometry this is known as a "Retraction". It is a
-  // generalization of vector addition in Euclidean spaces.
+  // A generalization of vector addition in Euclidean space, Plus computes the
+  // result of moving along delta in the tangent space at x, and then projecting
+  // back onto the manifold that x belongs to.
   //
   // x and x_plus_delta are AmbientSize() vectors.
   // delta is a TangentSize() vector.
@@ -282,11 +277,10 @@
 //
 // Example usage:
 //
-// ProductParameterization product_manifold(new Quaternion(),
-//                                          new EuclideanManifold(3));
+// ProductParameterization se3(new Quaternion(), new EuclideanManifold(3));
 //
-// is the manifold for a rigid transformation, where the
-// rotation is represented using a quaternion.
+// is the manifold for a rigid transformation, where the rotation is represented
+// using a quaternion.
 class CERES_EXPORT ProductManifold : public Manifold {
  public:
   ProductManifold(const ProductManifold&) = delete;
diff --git a/include/ceres/problem.h b/include/ceres/problem.h
index 4436e51..dba29dc 100644
--- a/include/ceres/problem.h
+++ b/include/ceres/problem.h
@@ -136,7 +136,10 @@
     // the pointers only once, since sharing objects is allowed.
     Ownership cost_function_ownership = TAKE_OWNERSHIP;
     Ownership loss_function_ownership = TAKE_OWNERSHIP;
-    Ownership local_parameterization_ownership = TAKE_OWNERSHIP;
+    [[deprecated(
+        "Local Parameterizations are deprecated. Use Manifold and "
+        "manifold_ownership instead.")]] Ownership
+        local_parameterization_ownership = TAKE_OWNERSHIP;
     Ownership manifold_ownership = TAKE_OWNERSHIP;
 
     // If true, trades memory for faster RemoveResidualBlock() and
@@ -292,9 +295,12 @@
   // ManifoldAdapter object. So HasManifold() will return true, GetManifold()
   // will return the wrapped object and ParameterBlockTangentSize() will return
   // the LocalSize of the LocalParameterization.
-  void AddParameterBlock(double* values,
-                         int size,
-                         LocalParameterization* local_parameterization);
+  [[deprecated(
+      "LocalParameterizations are deprecated. Use the version with Manifolds "
+      "instead.")]] void
+  AddParameterBlock(double* values,
+                    int size,
+                    LocalParameterization* local_parameterization);
 
   // Add a parameter block with appropriate size and Manifold to the
   // problem. It is okay for manifold to be nullptr.
@@ -381,9 +387,12 @@
   // During the transition from LocalParameterization to Manifold, internally
   // the LocalParameterization is treated as a Manifold by wrapping it using a
   // ManifoldAdapter object. So HasManifold() will return true, GetManifold()
-  // will return the wrapped object and ParameterBlockTangent.
-  void SetParameterization(double* values,
-                           LocalParameterization* local_parameterization);
+  // will return the wrapped object and ParameterBlockTangentSize will return
+  // the same value of ParameterBlockLocalSize.
+  [[deprecated(
+      "LocalParameterizations are deprecated. Use SetManifold instead.")]] void
+  SetParameterization(double* values,
+                      LocalParameterization* local_parameterization);
 
   // Get the LocalParameterization object associated with this parameter block.
   // If there is no LocalParameterization associated then nullptr is returned.
@@ -393,19 +402,27 @@
   //
   // Note also that if a LocalParameterization is associated with a parameter
   // block, HasManifold will return true and GetManifold will return the
-  // LocalParameterization wrapped in a ManifoldAdapeter.
+  // LocalParameterization wrapped in a ManifoldAdapter.
   //
-  // The converse is not true, i.e., if a Manifold is associated with a
+  // The converse is NOT true, i.e., if a Manifold is associated with a
   // parameter block, HasParameterization will return false and
   // GetParameterization will return a nullptr.
-  const LocalParameterization* GetParameterization(const double* values) const;
+  [[deprecated(
+      "LocalParameterizations are deprecated. Use GetManifold "
+      "instead.")]] const LocalParameterization*
+  GetParameterization(const double* values) const;
 
-  // Returns true if a LocalParameterization or a Manifold is associated with
-  // this parameter block, false otherwise.
+  // Returns true if a LocalParameterization is associated with this parameter
+  // block, false otherwise.
   //
   // NOTE: This method is deprecated and will be removed in the next public
   // release of Ceres Solver. Use HasManifold instead.
-  bool HasParameterization(const double* values) const;
+  //
+  // Note also that if a Manifold is associated with the parameter block, this
+  // method will return false.
+  [[deprecated(
+      "LocalParameterizations are deprecated. Use HasManifold instead.")]] bool
+  HasParameterization(const double* values) const;
 
   // Set the Manifold for the parameter block. Calling SetManifold with nullptr
   // will clear any previously set LocalParameterization or Manifold for the
@@ -417,11 +434,10 @@
   // The manifold is owned by the Problem by default (See Problem::Options to
   // override this behaviour).
   //
-  // It is acceptable to set the same Manifold for multiple parameter blocks;
-  // the destructor is careful to delete Manifolds only once.
+  // It is acceptable to set the same Manifold for multiple parameter blocks.
   void SetManifold(double* values, Manifold* manifold);
 
-  // Get the manifold object associated with this parameter block.
+  // Get the Manifold object associated with this parameter block.
   //
   // If there is no Manifold Or LocalParameterization object associated then
   // nullptr is returned.
@@ -430,7 +446,7 @@
   // internally the LocalParameterization is treated as a Manifold by wrapping
   // it using a ManifoldAdapter object. So calling GetManifold on a parameter
   // block with a LocalParameterization associated with it will return the
-  // LocalParameterization wrapped in a Manifold adapter.
+  // LocalParameterization wrapped in a ManifoldAdapter
   const Manifold* GetManifold(const double* values) const;
 
   // Returns true if a Manifold or a LocalParameterization is associated with
@@ -471,7 +487,10 @@
   // for the parameter block. If there is no LocalParameterization or Manifold
   // associated with this parameter block, then ParameterBlockLocalSize =
   // ParameterBlockSize.
-  int ParameterBlockLocalSize(const double* values) const;
+  [[deprecated(
+      "LocalParameterizations are deprecated. Use ParameterBlockTangentSize "
+      "instead.")]] int
+  ParameterBlockLocalSize(const double* values) const;
 
   // The dimenion of the tangent space of the LocalParameterization or Manifold
   // for the parameter block. If there is no LocalParameterization or Manifold
diff --git a/include/ceres/solver.h b/include/ceres/solver.h
index 74fb300..eac6134 100644
--- a/include/ceres/solver.h
+++ b/include/ceres/solver.h
@@ -883,7 +883,7 @@
     // Dimension of the tangent space of the problem (or the number of
     // columns in the Jacobian for the problem). This is different
     // from num_parameters if a parameter block is associated with a
-    // LocalParameterization
+    // LocalParameterization/Manifold.
     int num_effective_parameters = -1;
 
     // Number of residual blocks in the problem.
@@ -904,7 +904,7 @@
     // number of columns in the Jacobian for the reduced
     // problem). This is different from num_parameters_reduced if a
     // parameter block in the reduced problem is associated with a
-    // LocalParameterization.
+    // LocalParameterization/Manifold.
     int num_effective_parameters_reduced = -1;
 
     // Number of residual blocks in the reduced problem.
diff --git a/internal/ceres/CMakeLists.txt b/internal/ceres/CMakeLists.txt
index cfb1b90..d009ac2 100644
--- a/internal/ceres/CMakeLists.txt
+++ b/internal/ceres/CMakeLists.txt
@@ -261,6 +261,14 @@
 set_target_properties(ceres PROPERTIES
   VERSION ${CERES_VERSION}
   SOVERSION ${CERES_VERSION_MAJOR})
+
+# Disable warnings about deprecated interfaces while we are
+# transitioning from LocalParameterization to Manifolds.
+target_compile_options(ceres PRIVATE
+  $<$<OR:$<CXX_COMPILER_ID:Clang>,$<CXX_COMPILER_ID:AppleClang>,$<CXX_COMPILER_ID:GNU>>:
+  -Wno-deprecated-declarations>
+  $<$<CXX_COMPILER_ID:MSVC>: /wd4996>)
+
 if (BUILD_SHARED_LIBS)
   set_target_properties(ceres PROPERTIES
     # Set the default symbol visibility to hidden to unify the behavior among
@@ -434,6 +442,14 @@
              ${Ceres_SOURCE_DIR}/internal/ceres
              ${CERES_LIBRARY_PRIVATE_DEPENDENCIES_INCLUDE_DIRS})
 
+
+    # Disable warnings about deprecated interfaces while we are
+    # transitioning from LocalParameterization to Manifolds.
+    target_compile_options(${NAME}_test PRIVATE
+      $<$<OR:$<CXX_COMPILER_ID:Clang>,$<CXX_COMPILER_ID:AppleClang>,$<CXX_COMPILER_ID:GNU>>:
+      -Wno-deprecated-declarations>
+      $<$<CXX_COMPILER_ID:MSVC>: /wd4996>)
+
     target_link_libraries(${NAME}_test PUBLIC test_util Ceres::ceres gtest)
     if (BUILD_SHARED_LIBS)
       # Define gtest-specific shared library flags for linking.
diff --git a/scripts/make_docs.py b/scripts/make_docs.py
index 7d5c4cd..cb74a77 100644
--- a/scripts/make_docs.py
+++ b/scripts/make_docs.py
@@ -60,7 +60,7 @@
   sphinx_exe = sys.argv[3]
 
 # Run Sphinx to build the documentation.
-os.system('%s -b html -d %s %s %s' %(sphinx_exe, cache_dir, src_dir, html_dir))
+os.system('%s -n -b html -d %s %s %s' %(sphinx_exe, cache_dir, src_dir, html_dir))
 
 replacements = [
   # The title for the homepage is not ideal, so change it.