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/extrinsics_calibration.cc b/frc971/vision/extrinsics_calibration.cc
index 619ea89..2bbba9a 100644
--- a/frc971/vision/extrinsics_calibration.cc
+++ b/frc971/vision/extrinsics_calibration.cc
@@ -836,8 +836,8 @@
     CalibrationParameters *calibration_parameters) {
   ceres::Problem problem;
 
-  ceres::EigenQuaternionParameterization *quaternion_local_parameterization =
-      new ceres::EigenQuaternionParameterization();
+  ceres::EigenQuaternionManifold *quaternion_local_parameterization =
+      new ceres::EigenQuaternionManifold();
   // Set up the only cost function (also known as residual). This uses
   // auto-differentiation to obtain the derivative (jacobian).
 
@@ -874,9 +874,8 @@
   if (calibration_parameters->has_pivot) {
     // Constrain Z since it's along the rotation axis and therefore
     // redundant.
-    problem.SetParameterization(
-        calibration_parameters->pivot_to_imu_translation.data(),
-        new ceres::SubsetParameterization(3, {2}));
+    problem.SetManifold(calibration_parameters->pivot_to_imu_translation.data(),
+                        new ceres::SubsetManifold(3, {2}));
   } else {
     problem.SetParameterBlockConstant(
         calibration_parameters->pivot_to_imu.coeffs().data());
@@ -895,18 +894,15 @@
         calibration_parameters->board_to_world.coeffs().data());
   }
 
-  problem.SetParameterization(
+  problem.SetManifold(
       calibration_parameters->initial_orientation.coeffs().data(),
       quaternion_local_parameterization);
-  problem.SetParameterization(
-      calibration_parameters->pivot_to_camera.coeffs().data(),
-      quaternion_local_parameterization);
-  problem.SetParameterization(
-      calibration_parameters->pivot_to_imu.coeffs().data(),
-      quaternion_local_parameterization);
-  problem.SetParameterization(
-      calibration_parameters->board_to_world.coeffs().data(),
-      quaternion_local_parameterization);
+  problem.SetManifold(calibration_parameters->pivot_to_camera.coeffs().data(),
+                      quaternion_local_parameterization);
+  problem.SetManifold(calibration_parameters->pivot_to_imu.coeffs().data(),
+                      quaternion_local_parameterization);
+  problem.SetManifold(calibration_parameters->board_to_world.coeffs().data(),
+                      quaternion_local_parameterization);
   for (int i = 0; i < 3; ++i) {
     problem.SetParameterLowerBound(calibration_parameters->gyro_bias.data(), i,
                                    -0.05);