Use compiler attributes instead of [[deprecated]]

This change is needed because compiler attributes and c++
annotations like [[deprecated]] do not mix well and we need that
for our public API.

https://github.com/ceres-solver/ceres-solver/issues/749

Change-Id: I79eda795f2912f9af9ab36ee24b8428b47104743
diff --git a/include/ceres/autodiff_local_parameterization.h b/include/ceres/autodiff_local_parameterization.h
index 8ec91e0..ac2b5e3 100644
--- a/include/ceres/autodiff_local_parameterization.h
+++ b/include/ceres/autodiff_local_parameterization.h
@@ -110,18 +110,18 @@
 // seen where instead of using k_ directly, k_ is wrapped with T(k_).
 
 template <typename Functor, int kGlobalSize, int kLocalSize>
-class [[deprecated(
-    "Use AutoDiffManifold instead.")]] AutoDiffLocalParameterization
-    : public LocalParameterization {
+class CERES_DEPRECATED_WITH_MSG("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);
   }
 
diff --git a/include/ceres/gradient_checker.h b/include/ceres/gradient_checker.h
index 4e63141..b92a29d 100644
--- a/include/ceres/gradient_checker.h
+++ b/include/ceres/gradient_checker.h
@@ -80,14 +80,13 @@
   // 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.
-  [[deprecated(
+  CERES_DEPRECATED_WITH_MSG(
       "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);
+      "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 8984cba..08a58d0 100644
--- a/include/ceres/gradient_problem.h
+++ b/include/ceres/gradient_problem.h
@@ -105,11 +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.
-  [[deprecated(
+  CERES_DEPRECATED_WITH_MSG(
       "LocalParameterizations are deprecated. Please use the constructor that "
-      "uses Manifold instead.")]] GradientProblem(FirstOrderFunction* function,
-                                                  LocalParameterization*
-                                                      parameterization);
+      "uses Manifold instead.")
+  GradientProblem(FirstOrderFunction* function,
+                  LocalParameterization* parameterization);
 
   // Takes ownership of the function and the manifold.
   GradientProblem(FirstOrderFunction* function, Manifold* manifold);
@@ -154,8 +154,8 @@
   //
   // NOTE: This method is deprecated and will be removed in the next public
   // release of Ceres Solver.
-  [[deprecated("Use Manifolds instead.")]] const LocalParameterization*
-  parameterization() const {
+  CERES_DEPRECATED_WITH_MSG("Use Manifolds instead.")
+  const LocalParameterization* parameterization() const {
     return parameterization_.get();
   }
 
@@ -164,14 +164,15 @@
   //
   // NOTE: This method is deprecated and will be removed in the next public
   // release of Ceres Solver.
-  [[deprecated("Use Manifolds instead.")]] LocalParameterization*
-  mutable_parameterization() {
+  CERES_DEPRECATED_WITH_MSG("Use Manifolds instead.")
+  LocalParameterization* mutable_parameterization() {
     return parameterization_.get();
   }
 
  private:
   std::unique_ptr<FirstOrderFunction> function_;
-  [[deprecated]] std::unique_ptr<LocalParameterization> parameterization_;
+  CERES_DEPRECATED_WITH_MSG("")
+  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 042d611..322f1f3 100644
--- a/include/ceres/gradient_problem_solver.h
+++ b/include/ceres/gradient_problem_solver.h
@@ -305,7 +305,8 @@
     int num_parameters = -1;
 
     // Dimension of the tangent space of the problem.
-    [[deprecated("Use num_tangent_parameters.")]] int num_local_parameters = -1;
+    CERES_DEPRECATED_WITH_MSG("Use num_tangent_parameters.")
+    int num_local_parameters = -1;
 
     // Dimension of the tangent space of the problem.
     int num_tangent_parameters = -1;
diff --git a/include/ceres/internal/port.h b/include/ceres/internal/port.h
index 7c72bb5..a8a7409 100644
--- a/include/ceres/internal/port.h
+++ b/include/ceres/internal/port.h
@@ -68,6 +68,18 @@
 #endif
 #endif
 
+// A macro to mark a function/variable/class as deprecated.
+// We use compiler specific attributes rather than the c++
+// attribute because they do not mix well with each other.
+#if defined(_MSC_VER)
+#define CERES_DEPRECATED_WITH_MSG(message) __declspec(deprecated(message))
+#elif defined(__GNUC__)
+#define CERES_DEPRECATED_WITH_MSG(message) __attribute__((deprecated(message)))
+#else
+// In the worst case fall back to c++ attribute.
+#define CERES_DEPRECATED(message) [[deprecated(message)]]
+#endif
+
 // A macro to signal which functions and classes are exported when
 // building a shared library.
 #if defined(_MSC_VER)
diff --git a/include/ceres/jet.h b/include/ceres/jet.h
index 3a5b554..dee27e4 100644
--- a/include/ceres/jet.h
+++ b/include/ceres/jet.h
@@ -472,13 +472,13 @@
 
 // Legacy names from pre-C++11 days.
 // clang-format off
-[[deprecated("ceres::IsFinite will be removed in a future Ceres Solver release. Please use ceres::isfinite.")]]
+CERES_DEPRECATED_WITH_MSG("ceres::IsFinite will be removed in a future Ceres Solver release. Please use ceres::isfinite.")
 inline bool IsFinite(double x)   { return std::isfinite(x); }
-[[deprecated("ceres::IsInfinite will be removed in a future Ceres Solver release. Please use ceres::isinf.")]]
+CERES_DEPRECATED_WITH_MSG("ceres::IsInfinite will be removed in a future Ceres Solver release. Please use ceres::isinf.")
 inline bool IsInfinite(double x) { return std::isinf(x);    }
-[[deprecated("ceres::IsNaN will be removed in a future Ceres Solver release. Please use ceres::isnan.")]]
+CERES_DEPRECATED_WITH_MSG("ceres::IsNaN will be removed in a future Ceres Solver release. Please use ceres::isnan.")
 inline bool IsNaN(double x)      { return std::isnan(x);    }
-[[deprecated("ceres::IsNormal will be removed in a future Ceres Solver release. Please use ceres::isnormal.")]]
+CERES_DEPRECATED_WITH_MSG("ceres::IsNormal will be removed in a future Ceres Solver release. Please use ceres::isnormal.")
 inline bool IsNormal(double x)   { return std::isnormal(x); }
 // clang-format on
 
@@ -971,35 +971,35 @@
 
 // Legacy functions from the pre-C++11 days.
 template <typename T, int N>
-[[deprecated(
+CERES_DEPRECATED_WITH_MSG(
     "ceres::IsFinite will be removed in a future Ceres Solver release. Please "
-    "use ceres::isfinite.")]] inline bool
-IsFinite(const Jet<T, N>& f) {
+    "use ceres::isfinite.")
+inline bool IsFinite(const Jet<T, N>& f) {
   return isfinite(f);
 }
 
 template <typename T, int N>
-[[deprecated(
+CERES_DEPRECATED_WITH_MSG(
     "ceres::IsNaN will be removed in a future Ceres Solver release. Please use "
-    "ceres::isnan.")]] inline bool
-IsNaN(const Jet<T, N>& f) {
+    "ceres::isnan.")
+inline bool IsNaN(const Jet<T, N>& f) {
   return isnan(f);
 }
 
 template <typename T, int N>
-[[deprecated(
+CERES_DEPRECATED_WITH_MSG(
     "ceres::IsNormal will be removed in a future Ceres Solver release. Please "
-    "use ceres::isnormal.")]] inline bool
-IsNormal(const Jet<T, N>& f) {
+    "use ceres::isnormal.")
+inline bool IsNormal(const Jet<T, N>& f) {
   return isnormal(f);
 }
 
 // The jet is infinite if any part of the jet is infinite.
 template <typename T, int N>
-[[deprecated(
+CERES_DEPRECATED_WITH_MSG(
     "ceres::IsInfinite will be removed in a future Ceres Solver release. "
-    "Please use ceres::isinf.")]] inline bool
-IsInfinite(const Jet<T, N>& f) {
+    "Please use ceres::isinf.")
+inline bool IsInfinite(const Jet<T, N>& f) {
   return isinf(f);
 }
 
diff --git a/include/ceres/local_parameterization.h b/include/ceres/local_parameterization.h
index d4a590f..b18d6c6 100644
--- a/include/ceres/local_parameterization.h
+++ b/include/ceres/local_parameterization.h
@@ -114,10 +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 [[deprecated(
+class CERES_DEPRECATED_WITH_MSG(
     "LocalParameterizations will be removed from the Ceres Solver API in "
-    "version 2.2.0. Use Manifolds instead.")]] CERES_EXPORT
-    LocalParameterization {
+    "version 2.2.0. Use Manifolds instead.")
+    CERES_EXPORT LocalParameterization {
  public:
   virtual ~LocalParameterization();
 
@@ -127,8 +127,9 @@
   //
   // 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.
   //
@@ -158,13 +159,13 @@
 // Some basic parameterizations
 
 // Identity Parameterization: Plus(x, delta) = x + delta
-class [[deprecated(
-    "Use EuclideanManifold instead.")]] CERES_EXPORT IdentityParameterization
-    : public LocalParameterization {
+class CERES_DEPRECATED_WITH_MSG("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,
@@ -178,14 +179,14 @@
 };
 
 // Hold a subset of the parameters inside a parameter block constant.
-class [[deprecated(
-    "Use SubsetManifold instead.")]] CERES_EXPORT SubsetParameterization
-    : public LocalParameterization {
+class CERES_DEPRECATED_WITH_MSG("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,
@@ -205,12 +206,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 [[deprecated(
-    "Use QuaternionManifold instead.")]] CERES_EXPORT QuaternionParameterization
-    : public LocalParameterization {
+class CERES_DEPRECATED_WITH_MSG("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; }
@@ -227,11 +228,13 @@
 //
 // Plus(x, delta) = [sin(|delta|) delta / |delta|, cos(|delta|)] * x
 // with * being the quaternion multiplication operator.
-class [[deprecated("Use EigenQuaternionManifold instead.")]] CERES_EXPORT
-    EigenQuaternionParameterization : public ceres::LocalParameterization {
+class CERES_DEPRECATED_WITH_MSG("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; }
@@ -251,12 +254,13 @@
 // 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 [[deprecated("Use SphereManifold instead.")]] CERES_EXPORT
+class CERES_DEPRECATED_WITH_MSG("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; }
@@ -279,14 +283,15 @@
 // manifold (see https://en.wikipedia.org/wiki/Affine_Grassmannian_(manifold))
 // for the case Graff_1(R^n).
 template <int AmbientSpaceDimension>
-class [[deprecated("Use LineManifold instead.")]] LineParameterization
-    : public LocalParameterization {
+class CERES_DEPRECATED_WITH_MSG("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); }
@@ -306,9 +311,8 @@
 // is the local parameterization for a rigid transformation, where the
 // rotation is represented using a quaternion.
 //
-class [[deprecated(
-    "Use ProductManifold instead.")]] CERES_EXPORT ProductParameterization
-    : public LocalParameterization {
+class CERES_DEPRECATED_WITH_MSG("Use ProductManifold instead.")
+    CERES_EXPORT ProductParameterization : public LocalParameterization {
  public:
   ProductParameterization(const ProductParameterization&) = delete;
   ProductParameterization& operator=(const ProductParameterization&) = delete;
@@ -317,7 +321,7 @@
   // parameterizations.
   //
   template <typename... LocalParams>
-  ProductParameterization(LocalParams * ... local_params)
+  ProductParameterization(LocalParams*... local_params)
       : local_params_(sizeof...(LocalParams)),
         local_size_{0},
         global_size_{0},
@@ -344,8 +348,9 @@
     }
   }
 
-  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 global_size_; }
   int LocalSize() const override { return local_size_; }
diff --git a/include/ceres/problem.h b/include/ceres/problem.h
index dba29dc..1bec60a 100644
--- a/include/ceres/problem.h
+++ b/include/ceres/problem.h
@@ -136,10 +136,10 @@
     // the pointers only once, since sharing objects is allowed.
     Ownership cost_function_ownership = TAKE_OWNERSHIP;
     Ownership loss_function_ownership = TAKE_OWNERSHIP;
-    [[deprecated(
+    CERES_DEPRECATED_WITH_MSG(
         "Local Parameterizations are deprecated. Use Manifold and "
-        "manifold_ownership instead.")]] Ownership
-        local_parameterization_ownership = TAKE_OWNERSHIP;
+        "manifold_ownership instead.")
+    Ownership local_parameterization_ownership = TAKE_OWNERSHIP;
     Ownership manifold_ownership = TAKE_OWNERSHIP;
 
     // If true, trades memory for faster RemoveResidualBlock() and
@@ -295,12 +295,12 @@
   // ManifoldAdapter object. So HasManifold() will return true, GetManifold()
   // will return the wrapped object and ParameterBlockTangentSize() will return
   // the LocalSize of the LocalParameterization.
-  [[deprecated(
+  CERES_DEPRECATED_WITH_MSG(
       "LocalParameterizations are deprecated. Use the version with Manifolds "
-      "instead.")]] void
-  AddParameterBlock(double* values,
-                    int size,
-                    LocalParameterization* local_parameterization);
+      "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.
@@ -389,10 +389,10 @@
   // ManifoldAdapter object. So HasManifold() will return true, GetManifold()
   // 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);
+  CERES_DEPRECATED_WITH_MSG(
+      "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.
@@ -407,10 +407,10 @@
   // 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.
-  [[deprecated(
+  CERES_DEPRECATED_WITH_MSG(
       "LocalParameterizations are deprecated. Use GetManifold "
-      "instead.")]] const LocalParameterization*
-  GetParameterization(const double* values) const;
+      "instead.")
+  const LocalParameterization* GetParameterization(const double* values) const;
 
   // Returns true if a LocalParameterization is associated with this parameter
   // block, false otherwise.
@@ -420,9 +420,9 @@
   //
   // 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;
+  CERES_DEPRECATED_WITH_MSG(
+      "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
@@ -487,10 +487,10 @@
   // for the parameter block. If there is no LocalParameterization or Manifold
   // associated with this parameter block, then ParameterBlockLocalSize =
   // ParameterBlockSize.
-  [[deprecated(
+  CERES_DEPRECATED_WITH_MSG(
       "LocalParameterizations are deprecated. Use ParameterBlockTangentSize "
-      "instead.")]] int
-  ParameterBlockLocalSize(const double* values) const;
+      "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