Fix missing declaration warnings in Ceres code

This commit includes the following:

- Changes to CMake to make it safer to see which compiler flags are supported,
  so this way we do not need to worry about version checks in CMake.

- Unix platforms (which includes both Linux and Apple as far as i can tell)
  will now enable -Wmissing-declarations warning for the whole Ceres.

- Changes in all sources to solve missing declaration warning. In most cases
  it was either matter of using static qualifier or moving functions to an
  anonymous namespace.

  In one case the function got removed, since it seems to be unused.

  Additionally, in slam examples there was a non-inlined function implementation
  in a header, which is a direct way to cause linking errors if other .cc file
  will include that helper header.

- All third party sources (which is currently only gmock) has this extra
  paranoid warning disabled.

This warning is important in the following cases:

- Detect helper functions which are not needed anymore.
- Avoid unnoticed pollution of namespace.
- Avoid bad level calls.
- Avoid missing updates in header files after changes in implementation file.
- Helps integrating Ceres into software where paranoid warnings are important.

Change-Id: I9b1044aced3910d8c6b2356cfe2bf57f3c8c58db
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 4ce361d..dc01b7d 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -77,6 +77,7 @@
 # append rather than set in case the user has passed their own
 # additional paths via -D.
 list(APPEND CMAKE_MODULE_PATH "${Ceres_SOURCE_DIR}/cmake")
+include(AddCompileFlagsIfSupported)
 include(UpdateCacheVariable)
 
 # Set up the git hook to make Gerrit Change-Id: lines in commit messages.
@@ -570,9 +571,20 @@
 endif (MSVC)
 
 if (UNIX)
-  # GCC is not strict enough by default, so enable most of the warnings.
-  set(CMAKE_CXX_FLAGS
-    "${CMAKE_CXX_FLAGS} -Wno-unknown-pragmas -Wno-sign-compare -Wno-unused-parameter -Wno-missing-field-initializers")
+  # Flags which we add to GCC to make it more picky about stuff
+  # we do care about,
+  add_cxx_compiler_flag_if_supported(CERES_STRICT_CXX_FLAGS
+                                     -Wmissing-declarations)
+  # Flags which we add to GCC to silence lots of annoying false-positives.
+  add_cxx_compiler_flag_if_supported(CERES_STRICT_CXX_FLAGS
+                                     -Wno-unknown-pragmas)
+  add_cxx_compiler_flag_if_supported(CERES_STRICT_CXX_FLAGS
+                                     -Wno-sign-compare)
+  add_cxx_compiler_flag_if_supported(CERES_STRICT_CXX_FLAGS
+                                     -Wno-unused-parameter)
+  add_cxx_compiler_flag_if_supported(CERES_STRICT_CXX_FLAGS
+                                     -Wno-missing-field-initializers)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${CERES_STRICT_CXX_FLAGS}")
 endif (UNIX)
 
 # Use a larger inlining threshold for Clang, since it hobbles Eigen,
diff --git a/cmake/AddCompileFlagsIfSupported.cmake b/cmake/AddCompileFlagsIfSupported.cmake
new file mode 100644
index 0000000..1af9ee8
--- /dev/null
+++ b/cmake/AddCompileFlagsIfSupported.cmake
@@ -0,0 +1,51 @@
+# Ceres Solver - A fast non-linear least squares minimizer
+# Copyright 2017 Google Inc. All rights reserved.
+# http://ceres-solver.org/
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# * Redistributions of source code must retain the above copyright notice,
+#   this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above copyright notice,
+#   this list of conditions and the following disclaimer in the documentation
+#   and/or other materials provided with the distribution.
+# * Neither the name of Google Inc. nor the names of its contributors may be
+#   used to endorse or promote products derived from this software without
+#   specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+# Author: sergey.vfx@gmail.com (Sergey Sharybin)
+
+function(add_cxx_compiler_flag_if_supported
+    AGGREGATED_CXX_FLAGS_VAR
+    FLAG_TO_ADD_IF_SUPPORTED)
+  include(CheckCXXCompilerFlag)
+  # Use of whitespace or '-' in variable names (used by CheckCXXSourceCompiles
+  # as #defines) will trigger errors.
+  string(STRIP "${FLAG_TO_ADD_IF_SUPPORTED}" FLAG_TO_ADD_IF_SUPPORTED)
+  # Build an informatively named test result variable so that it will be evident
+  # which tests were performed/succeeded in the CMake output, e.g for -Wall:
+  #
+  # -- Performing Test CHECK_CXX_FLAG_Wall - Success
+  #
+  # NOTE: This variable is also used to cache test result.
+  string(REPLACE "-" "_" CHECK_CXX_FLAG
+    "CHECK_CXX_FLAG${FLAG_TO_ADD_IF_SUPPORTED}")
+  check_cxx_compiler_flag(${FLAG_TO_ADD_IF_SUPPORTED} ${CHECK_CXX_FLAG})
+  if (${CHECK_CXX_FLAG})
+    set(${AGGREGATED_CXX_FLAGS_VAR}
+      "${${AGGREGATED_CXX_FLAGS_VAR}} ${FLAG_TO_ADD_IF_SUPPORTED}" PARENT_SCOPE)
+  endif()
+endfunction()
diff --git a/examples/bundle_adjuster.cc b/examples/bundle_adjuster.cc
index 5619c52..d075d07 100644
--- a/examples/bundle_adjuster.cc
+++ b/examples/bundle_adjuster.cc
@@ -128,6 +128,7 @@
 
 namespace ceres {
 namespace examples {
+namespace {
 
 void SetLinearSolver(Solver::Options* options) {
   CHECK(StringToLinearSolverType(FLAGS_linear_solver,
@@ -327,6 +328,7 @@
   }
 }
 
+}  // namespace
 }  // namespace examples
 }  // namespace ceres
 
diff --git a/examples/curve_fitting.c b/examples/curve_fitting.c
index 0027aa8..fef5581 100644
--- a/examples/curve_fitting.c
+++ b/examples/curve_fitting.c
@@ -123,10 +123,10 @@
 /* This is the equivalent of a use-defined CostFunction in the C++ Ceres API.
  * This is passed as a callback to the Ceres C API, which internally converts
  * the callback into a CostFunction. */
-int exponential_residual(void* user_data,
-                         double** parameters,
-                         double* residuals,
-                         double** jacobians) {
+static int exponential_residual(void* user_data,
+                                double** parameters,
+                                double* residuals,
+                                double** jacobians) {
   double* measurement = (double*) user_data;
   double x = measurement[0];
   double y = measurement[1];
diff --git a/examples/denoising.cc b/examples/denoising.cc
index a8bdd7c..e64d70f 100644
--- a/examples/denoising.cc
+++ b/examples/denoising.cc
@@ -62,6 +62,7 @@
 
 namespace ceres {
 namespace examples {
+namespace {
 
 // This cost function is used to build the data term.
 //
@@ -167,6 +168,8 @@
     }
   }
 }
+
+}  // namespace
 }  // namespace examples
 }  // namespace ceres
 
diff --git a/examples/ellipse_approximation.cc b/examples/ellipse_approximation.cc
index f519f0c..59894a2 100644
--- a/examples/ellipse_approximation.cc
+++ b/examples/ellipse_approximation.cc
@@ -357,9 +357,9 @@
   const double sqrt_weight_;
 };
 
-bool SolveWithFullReport(ceres::Solver::Options options,
-                         ceres::Problem* problem,
-                         bool dynamic_sparsity) {
+static bool SolveWithFullReport(ceres::Solver::Options options,
+                                ceres::Problem* problem,
+                                bool dynamic_sparsity) {
   options.dynamic_sparsity = dynamic_sparsity;
 
   ceres::Solver::Summary summary;
diff --git a/examples/nist.cc b/examples/nist.cc
index 8ce7291..017ae82 100644
--- a/examples/nist.cc
+++ b/examples/nist.cc
@@ -132,6 +132,7 @@
 
 namespace ceres {
 namespace examples {
+namespace {
 
 using Eigen::Dynamic;
 using Eigen::RowMajor;
@@ -678,6 +679,7 @@
        << "/54\n";
 }
 
+}  // namespace
 }  // namespace examples
 }  // namespace ceres
 
diff --git a/examples/robot_pose_mle.cc b/examples/robot_pose_mle.cc
index 1f5058a..87def11 100644
--- a/examples/robot_pose_mle.cc
+++ b/examples/robot_pose_mle.cc
@@ -231,6 +231,8 @@
   const double corridor_length;
 };
 
+namespace {
+
 void SimulateRobot(vector<double>* odometry_values,
                    vector<double>* range_readings) {
   const int num_steps = static_cast<int>(
@@ -269,6 +271,8 @@
   }
 }
 
+}  // namespace
+
 int main(int argc, char** argv) {
   google::InitGoogleLogging(argv[0]);
   CERES_GFLAGS_NAMESPACE::ParseCommandLineFlags(&argc, &argv, true);
diff --git a/examples/slam/pose_graph_2d/pose_graph_2d.cc b/examples/slam/pose_graph_2d/pose_graph_2d.cc
index b9374db..d53461b 100644
--- a/examples/slam/pose_graph_2d/pose_graph_2d.cc
+++ b/examples/slam/pose_graph_2d/pose_graph_2d.cc
@@ -51,6 +51,7 @@
 
 namespace ceres {
 namespace examples {
+namespace {
 
 // Constructs the nonlinear least squares optimization problem from the pose
 // graph constraints.
@@ -148,6 +149,7 @@
   return true;
 }
 
+}  // namespace
 }  // namespace examples
 }  // namespace ceres
 
diff --git a/examples/slam/pose_graph_2d/types.h b/examples/slam/pose_graph_2d/types.h
index a54d9bf..43e0ffe 100644
--- a/examples/slam/pose_graph_2d/types.h
+++ b/examples/slam/pose_graph_2d/types.h
@@ -55,7 +55,7 @@
   }
 };
 
-std::istream& operator>>(std::istream& input, Pose2d& pose) {
+inline std::istream& operator>>(std::istream& input, Pose2d& pose) {
   input >> pose.x >> pose.y >> pose.yaw_radians;
   // Normalize the angle between -pi to pi.
   pose.yaw_radians = NormalizeAngle(pose.yaw_radians);
@@ -82,7 +82,7 @@
   }
 };
 
-std::istream& operator>>(std::istream& input, Constraint2d& constraint) {
+inline std::istream& operator>>(std::istream& input, Constraint2d& constraint) {
   input >> constraint.id_begin >> constraint.id_end >> constraint.x >>
       constraint.y >> constraint.yaw_radians >>
       constraint.information(0, 0) >> constraint.information(0, 1) >>
diff --git a/examples/slam/pose_graph_3d/pose_graph_3d.cc b/examples/slam/pose_graph_3d/pose_graph_3d.cc
index dcc85af..dc35e5d 100644
--- a/examples/slam/pose_graph_3d/pose_graph_3d.cc
+++ b/examples/slam/pose_graph_3d/pose_graph_3d.cc
@@ -43,6 +43,7 @@
 
 namespace ceres {
 namespace examples {
+namespace {
 
 // Constructs the nonlinear least squares optimization problem from the pose
 // graph constraints.
@@ -140,6 +141,7 @@
   return true;
 }
 
+}  // namespace
 }  // namespace examples
 }  // namespace ceres
 
diff --git a/examples/slam/pose_graph_3d/types.h b/examples/slam/pose_graph_3d/types.h
index 2f12501..2142820 100644
--- a/examples/slam/pose_graph_3d/types.h
+++ b/examples/slam/pose_graph_3d/types.h
@@ -54,7 +54,7 @@
   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 };
 
-std::istream& operator>>(std::istream& input, Pose3d& pose) {
+inline std::istream& operator>>(std::istream& input, Pose3d& pose) {
   input >> pose.p.x() >> pose.p.y() >> pose.p.z() >> pose.q.x() >>
       pose.q.y() >> pose.q.z() >> pose.q.w();
   // Normalize the quaternion to account for precision loss due to
@@ -90,7 +90,7 @@
   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 };
 
-std::istream& operator>>(std::istream& input, Constraint3d& constraint) {
+inline std::istream& operator>>(std::istream& input, Constraint3d& constraint) {
   Pose3d& t_be = constraint.t_be;
   input >> constraint.id_begin >> constraint.id_end >> t_be;
 
diff --git a/include/ceres/types.h b/include/ceres/types.h
index 4473ad5..fec3cea 100644
--- a/include/ceres/types.h
+++ b/include/ceres/types.h
@@ -502,6 +502,7 @@
 CERES_EXPORT bool StringtoLoggingType(std::string value, LoggingType* type);
 
 CERES_EXPORT const char* DumpFormatTypeToString(DumpFormatType type);
+CERES_EXPORT bool StringtoDumpFormatType(std::string value, DumpFormatType* type);
 CERES_EXPORT bool StringtoDumpFormatType(std::string value, LoggingType* type);
 
 CERES_EXPORT const char* TerminationTypeToString(TerminationType type);
diff --git a/internal/ceres/CMakeLists.txt b/internal/ceres/CMakeLists.txt
index 281eede..3670aa4 100644
--- a/internal/ceres/CMakeLists.txt
+++ b/internal/ceres/CMakeLists.txt
@@ -219,6 +219,16 @@
   list(APPEND CERES_LIBRARY_SOURCE miniglog/glog/logging.cc)
 endif (MINIGLOG)
 
+# Ceres C++ compiler flags can be too strict for an external library code
+# which we do not maintain.
+include(CheckCXXCompilerFlag)
+check_cxx_compiler_flag("-Wno-missing-declarations"
+                        CHECK_CXX_FLAG_Wno_missing_declarations)
+if (CHECK_CXX_FLAG_Wno_missing_declarations)
+  set_property(SOURCE gmock_gtest_all.cc
+               APPEND_STRING PROPERTY COMPILE_FLAGS "-Wno-missing-declarations")
+endif()
+
 add_library(ceres ${CERES_LIBRARY_SOURCE})
 set_target_properties(ceres PROPERTIES
   VERSION ${CERES_VERSION}
diff --git a/internal/ceres/autodiff_local_parameterization_test.cc b/internal/ceres/autodiff_local_parameterization_test.cc
index f2396dc..df7723d 100644
--- a/internal/ceres/autodiff_local_parameterization_test.cc
+++ b/internal/ceres/autodiff_local_parameterization_test.cc
@@ -141,8 +141,8 @@
   }
 };
 
-void QuaternionParameterizationTestHelper(const double* x,
-                                          const double* delta) {
+static void QuaternionParameterizationTestHelper(const double* x,
+                                                 const double* delta) {
   const double kTolerance = 1e-14;
   double x_plus_delta_ref[4] = {0.0, 0.0, 0.0, 0.0};
   double jacobian_ref[12];
diff --git a/internal/ceres/c_api_test.cc b/internal/ceres/c_api_test.cc
index 95b727a..fa11249 100644
--- a/internal/ceres/c_api_test.cc
+++ b/internal/ceres/c_api_test.cc
@@ -108,10 +108,10 @@
 };
 
 // A test cost function, similar to the one in curve_fitting.c.
-int exponential_residual(void* user_data,
-                         double** parameters,
-                         double* residuals,
-                         double** jacobians) {
+static int exponential_residual(void* user_data,
+                                double** parameters,
+                                double* residuals,
+                                double** jacobians) {
   double* measurement = (double*) user_data;
   double x = measurement[0];
   double y = measurement[1];
diff --git a/internal/ceres/compressed_col_sparse_matrix_utils_test.cc b/internal/ceres/compressed_col_sparse_matrix_utils_test.cc
index 2162b9f..ba422a4 100644
--- a/internal/ceres/compressed_col_sparse_matrix_utils_test.cc
+++ b/internal/ceres/compressed_col_sparse_matrix_utils_test.cc
@@ -87,11 +87,11 @@
   }
 }
 
-void FillBlock(const vector<int>& row_blocks,
-               const vector<int>& col_blocks,
-               const int row_block_id,
-               const int col_block_id,
-               vector<Eigen::Triplet<double>>* triplets) {
+static void FillBlock(const vector<int>& row_blocks,
+                      const vector<int>& col_blocks,
+                      const int row_block_id,
+                      const int col_block_id,
+                      vector<Eigen::Triplet<double>>* triplets) {
   const int row_offset = std::accumulate(&row_blocks[0], &row_blocks[row_block_id], 0);
   const int col_offset = std::accumulate(&col_blocks[0], &col_blocks[col_block_id], 0);
   for (int r = 0; r < row_blocks[row_block_id]; ++r) {
diff --git a/internal/ceres/compressed_row_sparse_matrix_test.cc b/internal/ceres/compressed_row_sparse_matrix_test.cc
index 50a7ecd..d6cda93 100644
--- a/internal/ceres/compressed_row_sparse_matrix_test.cc
+++ b/internal/ceres/compressed_row_sparse_matrix_test.cc
@@ -48,7 +48,7 @@
 
 using std::vector;
 
-void CompareMatrices(const SparseMatrix* a, const SparseMatrix* b) {
+static void CompareMatrices(const SparseMatrix* a, const SparseMatrix* b) {
   EXPECT_EQ(a->num_rows(), b->num_rows());
   EXPECT_EQ(a->num_cols(), b->num_cols());
 
@@ -380,7 +380,7 @@
 
 typedef ::testing::tuple<CompressedRowSparseMatrix::StorageType> Param;
 
-std::string ParamInfoToString(testing::TestParamInfo<Param> info) {
+static std::string ParamInfoToString(testing::TestParamInfo<Param> info) {
   if (::testing::get<0>(info.param) ==
       CompressedRowSparseMatrix::UPPER_TRIANGULAR) {
     return "UPPER";
diff --git a/internal/ceres/cost_function_to_functor_test.cc b/internal/ceres/cost_function_to_functor_test.cc
index 3c9a6fe..0a6d86c 100644
--- a/internal/ceres/cost_function_to_functor_test.cc
+++ b/internal/ceres/cost_function_to_functor_test.cc
@@ -43,8 +43,9 @@
 using std::vector;
 const double kTolerance = 1e-18;
 
-void ExpectCostFunctionsAreEqual(const CostFunction& cost_function,
-                                 const CostFunction& actual_cost_function) {
+static void ExpectCostFunctionsAreEqual(
+    const CostFunction& cost_function,
+    const CostFunction& actual_cost_function) {
   EXPECT_EQ(cost_function.num_residuals(),
             actual_cost_function.num_residuals());
   const int num_residuals = cost_function.num_residuals();
diff --git a/internal/ceres/dense_linear_solver_test.cc b/internal/ceres/dense_linear_solver_test.cc
index 2f3b863..4de745f 100644
--- a/internal/ceres/dense_linear_solver_test.cc
+++ b/internal/ceres/dense_linear_solver_test.cc
@@ -45,7 +45,7 @@
     tuple<LinearSolverType, DenseLinearAlgebraLibraryType, bool, int>
         Param;
 
-std::string ParamInfoToString(testing::TestParamInfo<Param> info) {
+static std::string ParamInfoToString(testing::TestParamInfo<Param> info) {
   Param param = info.param;
   std::stringstream ss;
   ss << LinearSolverTypeToString(::testing::get<0>(param)) << "_"
@@ -107,6 +107,8 @@
   EXPECT_NEAR(residual, 0.0, 10 * std::numeric_limits<double>::epsilon());
 }
 
+namespace {
+
 // TODO(sameeragarwal): Should we move away from hard coded linear
 // least squares problem to randomly generated ones?
 #ifndef CERES_NO_LAPACK
@@ -132,6 +134,6 @@
     ParamInfoToString);
 
 #endif
-
+}  // namespace
 }  // namespace internal
 }  // namespace ceres
diff --git a/internal/ceres/dense_sparse_matrix_test.cc b/internal/ceres/dense_sparse_matrix_test.cc
index 4d52e81..b8ac2ba 100644
--- a/internal/ceres/dense_sparse_matrix_test.cc
+++ b/internal/ceres/dense_sparse_matrix_test.cc
@@ -45,7 +45,7 @@
 namespace ceres {
 namespace internal {
 
-void CompareMatrices(const SparseMatrix* a, const SparseMatrix* b) {
+static void CompareMatrices(const SparseMatrix* a, const SparseMatrix* b) {
   EXPECT_EQ(a->num_rows(), b->num_rows());
   EXPECT_EQ(a->num_cols(), b->num_cols());
 
diff --git a/internal/ceres/evaluation_callback_test.cc b/internal/ceres/evaluation_callback_test.cc
index a28d5a8..9ca500f 100644
--- a/internal/ceres/evaluation_callback_test.cc
+++ b/internal/ceres/evaluation_callback_test.cc
@@ -231,7 +231,7 @@
   EXPECT_NE(Djb2Hash(parameters, 2), original_parameters_hash);
 }
 
-void WithLineSearchMinimizerImpl(
+static void WithLineSearchMinimizerImpl(
     LineSearchType line_search,
     LineSearchDirectionType line_search_direction,
     LineSearchInterpolationType line_search_interpolation) {
diff --git a/internal/ceres/evaluator_test.cc b/internal/ceres/evaluator_test.cc
index 4473fd8..ef76be2 100644
--- a/internal/ceres/evaluator_test.cc
+++ b/internal/ceres/evaluator_test.cc
@@ -216,7 +216,7 @@
   ProblemImpl problem;
 };
 
-void SetSparseMatrixConstant(SparseMatrix* sparse_matrix, double value) {
+static void SetSparseMatrixConstant(SparseMatrix* sparse_matrix, double value) {
   VectorRef(sparse_matrix->mutable_values(),
             sparse_matrix->num_nonzeros()).setConstant(value);
 }
diff --git a/internal/ceres/gradient_checker_test.cc b/internal/ceres/gradient_checker_test.cc
index 05648fd..a9d439f 100644
--- a/internal/ceres/gradient_checker_test.cc
+++ b/internal/ceres/gradient_checker_test.cc
@@ -170,10 +170,10 @@
 
 const double kTolerance = 1e-6;
 
-void CheckDimensions(const GradientChecker::ProbeResults& results,
-                     const std::vector<int>& parameter_sizes,
-                     const std::vector<int>& local_parameter_sizes,
-                     int residual_size) {
+static void CheckDimensions(const GradientChecker::ProbeResults& results,
+                            const std::vector<int>& parameter_sizes,
+                            const std::vector<int>& local_parameter_sizes,
+                            int residual_size) {
   CHECK_EQ(parameter_sizes.size(), local_parameter_sizes.size());
   int num_parameters = parameter_sizes.size();
   ASSERT_EQ(residual_size, results.residuals.size());
@@ -368,7 +368,7 @@
 };
 
 // Helper function to compare two Eigen matrices (used in the test below).
-void ExpectMatricesClose(Matrix p, Matrix q, double tolerance) {
+static void ExpectMatricesClose(Matrix p, Matrix q, double tolerance) {
   ASSERT_EQ(p.rows(), q.rows());
   ASSERT_EQ(p.cols(), q.cols());
   ExpectArraysClose(p.size(), p.data(), q.data(), tolerance);
diff --git a/internal/ceres/gradient_checking_cost_function_test.cc b/internal/ceres/gradient_checking_cost_function_test.cc
index f08bcd0..3747142 100644
--- a/internal/ceres/gradient_checking_cost_function_test.cc
+++ b/internal/ceres/gradient_checking_cost_function_test.cc
@@ -324,8 +324,8 @@
 
 // Verify that the two ParameterBlocks are formed from the same user
 // array and have the same LocalParameterization object.
-void ParameterBlocksAreEquivalent(const ParameterBlock*  left,
-                                  const ParameterBlock* right) {
+static void ParameterBlocksAreEquivalent(const ParameterBlock*  left,
+                                         const ParameterBlock* right) {
   CHECK(left != nullptr);
   CHECK(right != nullptr);
   EXPECT_EQ(left->user_state(), right->user_state());
diff --git a/internal/ceres/householder_vector_test.cc b/internal/ceres/householder_vector_test.cc
index fca0360..69a6d3c 100644
--- a/internal/ceres/householder_vector_test.cc
+++ b/internal/ceres/householder_vector_test.cc
@@ -36,7 +36,7 @@
 namespace ceres {
 namespace internal {
 
-void HouseholderTestHelper(const Vector& x) {
+static void HouseholderTestHelper(const Vector& x) {
   const double kTolerance = 1e-14;
 
   // Check to ensure that H * x = ||x|| * [0 ... 0 1]'.
diff --git a/internal/ceres/jet_test.cc b/internal/ceres/jet_test.cc
index 10fd8b8..3f2b7d3 100644
--- a/internal/ceres/jet_test.cc
+++ b/internal/ceres/jet_test.cc
@@ -44,6 +44,8 @@
 namespace ceres {
 namespace internal {
 
+namespace {
+
 const double kE = 2.71828182845904523536;
 
 typedef Jet<double, 2> J;
@@ -106,6 +108,8 @@
   ExpectClose(exact_dy, estimated_dy, kNumericalTolerance);
 }
 
+}  // namespace
+
 TEST(Jet, Jet) {
   // Pick arbitrary values for x and y.
   J x = MakeJet(2.3, -2.7, 1e-3);
diff --git a/internal/ceres/local_parameterization_test.cc b/internal/ceres/local_parameterization_test.cc
index 18b7e8c..a2eff2f 100644
--- a/internal/ceres/local_parameterization_test.cc
+++ b/internal/ceres/local_parameterization_test.cc
@@ -477,8 +477,8 @@
   }
 };
 
-void HomogeneousVectorParameterizationHelper(const double* x,
-                                             const double* delta) {
+static void HomogeneousVectorParameterizationHelper(const double* x,
+                                                    const double* delta) {
   const double kTolerance = 1e-14;
 
   HomogeneousVectorParameterization homogeneous_vector_parameterization(4);
diff --git a/internal/ceres/normal_prior_test.cc b/internal/ceres/normal_prior_test.cc
index 1a51cfd..9abbf7f 100644
--- a/internal/ceres/normal_prior_test.cc
+++ b/internal/ceres/normal_prior_test.cc
@@ -39,6 +39,8 @@
 namespace ceres {
 namespace internal {
 
+namespace {
+
 void RandomVector(Vector* v) {
   for (int r = 0; r < v->rows(); ++r)
     (*v)[r] = 2 * RandDouble() - 1;
@@ -52,6 +54,8 @@
   }
 }
 
+}  // namespace
+
 TEST(NormalPriorTest, ResidualAtRandomPosition) {
   srand(5);
 
diff --git a/internal/ceres/problem_test.cc b/internal/ceres/problem_test.cc
index 529fbe9..736e295 100644
--- a/internal/ceres/problem_test.cc
+++ b/internal/ceres/problem_test.cc
@@ -940,7 +940,7 @@
   }
 }
 
-void ExpectProblemHasResidualBlocks(
+static void ExpectProblemHasResidualBlocks(
     const ProblemImpl &problem,
     const ResidualBlockId *expected_residual_blocks) {
   vector<ResidualBlockId> residual_blocks;
@@ -1096,7 +1096,7 @@
 };
 
 // Convert a CRSMatrix to a dense Eigen matrix.
-void CRSToDenseMatrix(const CRSMatrix& input, Matrix* output) {
+static void CRSToDenseMatrix(const CRSMatrix& input, Matrix* output) {
   CHECK(output != nullptr);
   Matrix& m = *output;
   m.resize(input.num_rows, input.num_cols);
diff --git a/internal/ceres/reorder_program.cc b/internal/ceres/reorder_program.cc
index 5a3fbfd..3ad2a5f 100644
--- a/internal/ceres/reorder_program.cc
+++ b/internal/ceres/reorder_program.cc
@@ -335,7 +335,7 @@
 
 // Pre-order the columns corresponding to the schur complement if
 // possible.
-void MaybeReorderSchurComplementColumnsUsingSuiteSparse(
+static void MaybeReorderSchurComplementColumnsUsingSuiteSparse(
     const ParameterBlockOrdering& parameter_block_ordering,
     Program* program) {
 #ifndef CERES_NO_SUITESPARSE
@@ -381,7 +381,7 @@
 #endif
 }
 
-void MaybeReorderSchurComplementColumnsUsingEigen(
+static void MaybeReorderSchurComplementColumnsUsingEigen(
     const int size_of_first_elimination_group,
     const ProblemImpl::ParameterMap& parameter_map,
     Program* program) {
diff --git a/internal/ceres/residual_block_utils_test.cc b/internal/ceres/residual_block_utils_test.cc
index 3beaa10..deaa13a 100644
--- a/internal/ceres/residual_block_utils_test.cc
+++ b/internal/ceres/residual_block_utils_test.cc
@@ -43,7 +43,7 @@
 
 // Routine to check if ResidualBlock::Evaluate for unary CostFunction
 // with one residual succeeds with true or dies.
-void CheckEvaluation(const CostFunction& cost_function, bool is_good) {
+static void CheckEvaluation(const CostFunction& cost_function, bool is_good) {
   double x = 1.0;
   ParameterBlock parameter_block(&x, 1, -1);
   std::vector<ParameterBlock*> parameter_blocks;
diff --git a/internal/ceres/rotation_test.cc b/internal/ceres/rotation_test.cc
index d980ba2..197495f 100644
--- a/internal/ceres/rotation_test.cc
+++ b/internal/ceres/rotation_test.cc
@@ -54,7 +54,7 @@
 const double kPi = 3.14159265358979323846;
 const double kHalfSqrt2 = 0.707106781186547524401;
 
-double RandDouble() {
+static double RandDouble() {
   double r = rand();
   return r / RAND_MAX;
 }
@@ -680,6 +680,8 @@
 typedef Jet<double, 3> J3;
 typedef Jet<double, 4> J4;
 
+namespace {
+
 J3 MakeJ3(double a, double v0, double v1, double v2) {
   J3 j;
   j.a = a;
@@ -705,6 +707,8 @@
   return internal::IsClose(x, y, kTolerance, NULL, NULL);
 }
 
+}  // namespace
+
 template <int N>
 bool IsClose(const Jet<double, N> &x, const Jet<double, N> &y) {
   if (!IsClose(x.a, y.a)) {
@@ -1093,9 +1097,9 @@
   EXPECT_THAT(rotation_matrix, IsNear3x3Matrix(round_trip));
 }
 
-void CheckRotationMatrixToAngleAxisRoundTrip(const double theta,
-                                             const double phi,
-                                             const double angle) {
+static void CheckRotationMatrixToAngleAxisRoundTrip(const double theta,
+                                                    const double phi,
+                                                    const double angle) {
   double angle_axis[3];
   angle_axis[0] = angle * sin(phi) * cos(theta);
   angle_axis[1] = angle * sin(phi) * sin(theta);
diff --git a/internal/ceres/sparse_cholesky.cc b/internal/ceres/sparse_cholesky.cc
index 3275cc0..0639ea9 100644
--- a/internal/ceres/sparse_cholesky.cc
+++ b/internal/ceres/sparse_cholesky.cc
@@ -126,14 +126,6 @@
   return termination_type;
 }
 
-CompressedRowSparseMatrix::StorageType StorageTypeForSparseLinearAlgebraLibrary(
-    SparseLinearAlgebraLibraryType sparse_linear_algebra_library_type) {
-  if (sparse_linear_algebra_library_type == SUITE_SPARSE) {
-    return CompressedRowSparseMatrix::UPPER_TRIANGULAR;
-  }
-  return CompressedRowSparseMatrix::LOWER_TRIANGULAR;
-}
-
 RefinedSparseCholesky::RefinedSparseCholesky(
     std::unique_ptr<SparseCholesky> sparse_cholesky,
     std::unique_ptr<IterativeRefiner> iterative_refiner)
diff --git a/internal/ceres/sparse_cholesky_test.cc b/internal/ceres/sparse_cholesky_test.cc
index 75b5e20..2ef24e3 100644
--- a/internal/ceres/sparse_cholesky_test.cc
+++ b/internal/ceres/sparse_cholesky_test.cc
@@ -49,6 +49,8 @@
 namespace ceres {
 namespace internal {
 
+namespace {
+
 BlockSparseMatrix* CreateRandomFullRankMatrix(const int num_col_blocks,
                                               const int min_col_block_size,
                                               const int max_col_block_size,
@@ -75,9 +77,9 @@
   return random_matrix.release();
 }
 
-bool ComputeExpectedSolution(const CompressedRowSparseMatrix& lhs,
-                             const Vector& rhs,
-                             Vector* solution) {
+static bool ComputeExpectedSolution(const CompressedRowSparseMatrix& lhs,
+                                    const Vector& rhs,
+                                    Vector* solution) {
   Matrix eigen_lhs;
   lhs.ToDenseMatrix(&eigen_lhs);
   if (lhs.storage_type() == CompressedRowSparseMatrix::UPPER_TRIANGULAR) {
@@ -160,6 +162,8 @@
   return ss.str();
 }
 
+}  // namespace
+
 class SparseCholeskyTest : public ::testing::TestWithParam<Param> {};
 
 TEST_P(SparseCholeskyTest, FactorAndSolve) {
@@ -186,6 +190,8 @@
   }
 }
 
+namespace {
+
 #ifndef CERES_NO_SUITESPARSE
 INSTANTIATE_TEST_SUITE_P(SuiteSparseCholesky,
                          SparseCholeskyTest,
@@ -342,5 +348,7 @@
       LINEAR_SOLVER_SUCCESS);
 };
 
+}  // namespace
+
 }  // namespace internal
 }  // namespace ceres
diff --git a/internal/ceres/subset_preconditioner_test.cc b/internal/ceres/subset_preconditioner_test.cc
index 31ba70a..5466f1b 100644
--- a/internal/ceres/subset_preconditioner_test.cc
+++ b/internal/ceres/subset_preconditioner_test.cc
@@ -43,6 +43,8 @@
 namespace ceres {
 namespace internal {
 
+namespace {
+
 // TODO(sameeragarwal): Refactor the following two functions out of
 // here and sparse_cholesky_test.cc into a more suitable place.
 template <int UpLoType>
@@ -82,6 +84,8 @@
   return ss.str();
 }
 
+}  // namespace
+
 class SubsetPreconditionerTest : public ::testing::TestWithParam<Param> {
  protected:
   virtual void SetUp() {