Use int32 for parameter block sizes.

CostFunction now uses int32 instead of int16
to store the size of its parameter blocks.

This is an API breaking change.

Change-Id: I032ea583bc7ea4b3009be25d23a3be143749c73e
diff --git a/include/ceres/cost_function.h b/include/ceres/cost_function.h
index 8013e96..722ac77 100644
--- a/include/ceres/cost_function.h
+++ b/include/ceres/cost_function.h
@@ -115,7 +115,7 @@
                         double* residuals,
                         double** jacobians) const = 0;
 
-  const vector<int16>& parameter_block_sizes() const {
+  const vector<int32>& parameter_block_sizes() const {
     return parameter_block_sizes_;
   }
 
@@ -124,7 +124,7 @@
   }
 
  protected:
-  vector<int16>* mutable_parameter_block_sizes() {
+  vector<int32>* mutable_parameter_block_sizes() {
     return &parameter_block_sizes_;
   }
 
@@ -135,7 +135,7 @@
  private:
   // Cost function signature metadata: number of inputs & their sizes,
   // number of outputs (residuals).
-  vector<int16> parameter_block_sizes_;
+  vector<int32> parameter_block_sizes_;
   int num_residuals_;
   CERES_DISALLOW_COPY_AND_ASSIGN(CostFunction);
 };
diff --git a/include/ceres/cost_function_to_functor.h b/include/ceres/cost_function_to_functor.h
index fa1012d..0d01f77 100644
--- a/include/ceres/cost_function_to_functor.h
+++ b/include/ceres/cost_function_to_functor.h
@@ -127,7 +127,7 @@
         << N3 << ", " << N4 << ", " << N5 << ", " << N6 << ", " << N7 << ", "
         << N8 << ", " << N9;
 
-    const vector<int16>& parameter_block_sizes =
+    const vector<int32>& parameter_block_sizes =
         cost_function->parameter_block_sizes();
     const int num_parameter_blocks =
         (N0 > 0) + (N1 > 0) + (N2 > 0) + (N3 > 0) + (N4 > 0) +
@@ -679,7 +679,7 @@
   template <typename JetT>
   bool EvaluateWithJets(const JetT** inputs, JetT* output) const {
     const int kNumParameters =  N0 + N1 + N2 + N3 + N4 + N5 + N6 + N7 + N8 + N9;
-    const vector<int16>& parameter_block_sizes =
+    const vector<int32>& parameter_block_sizes =
         cost_function_->parameter_block_sizes();
     const int num_parameter_blocks = parameter_block_sizes.size();
     const int num_residuals = cost_function_->num_residuals();
@@ -732,7 +732,7 @@
       output[i].v.setZero();
 
       for (int j = 0; j < num_parameter_blocks; ++j) {
-        const int16 block_size = parameter_block_sizes[j];
+        const int32 block_size = parameter_block_sizes[j];
         for (int k = 0; k < parameter_block_sizes[j]; ++k) {
           output[i].v +=
               jacobian_blocks[j][i * block_size + k] * inputs[j][k].v;
diff --git a/include/ceres/dynamic_numeric_diff_cost_function.h b/include/ceres/dynamic_numeric_diff_cost_function.h
index c2bfb32..2b6e826 100644
--- a/include/ceres/dynamic_numeric_diff_cost_function.h
+++ b/include/ceres/dynamic_numeric_diff_cost_function.h
@@ -104,7 +104,7 @@
         << "You must call DynamicNumericDiffCostFunction::SetNumResiduals() "
         << "before DynamicNumericDiffCostFunction::Evaluate().";
 
-    const vector<int16>& block_sizes = parameter_block_sizes();
+    const vector<int32>& block_sizes = parameter_block_sizes();
     CHECK(!block_sizes.empty())
         << "You must call DynamicNumericDiffCostFunction::AddParameterBlock() "
         << "before DynamicNumericDiffCostFunction::Evaluate().";
diff --git a/include/ceres/gradient_checker.h b/include/ceres/gradient_checker.h
index 3ec8056..79ebae5 100644
--- a/include/ceres/gradient_checker.h
+++ b/include/ceres/gradient_checker.h
@@ -119,7 +119,7 @@
     // Do a consistency check between the term and the template parameters.
     CHECK_EQ(M, term->num_residuals());
     const int num_residuals = M;
-    const vector<int16>& block_sizes = term->parameter_block_sizes();
+    const vector<int32>& block_sizes = term->parameter_block_sizes();
     const int num_blocks = block_sizes.size();
 
     CHECK_LE(num_blocks, 5) << "Unable to test functions that take more "