Merge commit 'cfb09d18272bb3c30585042533cbe7d876ef7ce0'

Upgrade ceres to the latest.

Change-Id: I2d8fb7d506a98f704e4e2f30e60030a0d6763b43
Signed-off-by: Austin Schuh <austin.linux@gmail.com>
diff --git a/frc971/vision/target_mapper.cc b/frc971/vision/target_mapper.cc
index b9b3712..57ab6e4 100644
--- a/frc971/vision/target_mapper.cc
+++ b/frc971/vision/target_mapper.cc
@@ -313,8 +313,8 @@
   }
 
   ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
-  ceres::LocalParameterization *quaternion_local_parameterization =
-      new ceres::EigenQuaternionParameterization;
+  ceres::Manifold *quaternion_local_parameterization =
+      new ceres::EigenQuaternionManifold();
 
   int min_constraint_id = std::numeric_limits<int>::max();
   int max_constraint_id = std::numeric_limits<int>::min();
@@ -368,10 +368,10 @@
                               pose_end_iter->second.p.data(),
                               pose_end_iter->second.q.coeffs().data());
 
-    problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(),
-                                 quaternion_local_parameterization);
-    problem->SetParameterization(pose_end_iter->second.q.coeffs().data(),
-                                 quaternion_local_parameterization);
+    problem->SetManifold(pose_begin_iter->second.q.coeffs().data(),
+                         quaternion_local_parameterization);
+    problem->SetManifold(pose_end_iter->second.q.coeffs().data(),
+                         quaternion_local_parameterization);
   }
 
   // The pose graph optimization problem has six DOFs that are not fully
@@ -411,14 +411,14 @@
       this, num_residuals, ceres::DO_NOT_TAKE_OWNERSHIP);
 
   ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
-  ceres::LocalParameterization *quaternion_local_parameterization =
-      new ceres::EigenQuaternionParameterization;
+  ceres::Manifold *quaternion_local_parameterization =
+      new ceres::EigenQuaternionManifold();
 
   problem->AddResidualBlock(cost_function.get(), loss_function,
                             T_frozen_actual_.vector().data(),
                             R_frozen_actual_.coeffs().data());
-  problem->SetParameterization(R_frozen_actual_.coeffs().data(),
-                               quaternion_local_parameterization);
+  problem->SetManifold(R_frozen_actual_.coeffs().data(),
+                       quaternion_local_parameterization);
   return cost_function;
 }