diff --git a/corelib/src/CMakeLists.txt b/corelib/src/CMakeLists.txt index c189d3df44..7e6cd99687 100644 --- a/corelib/src/CMakeLists.txt +++ b/corelib/src/CMakeLists.txt @@ -715,6 +715,13 @@ IF(GTSAM_FOUND) ${LIBRARIES} gtsam # Windows: Place static libs at the end ) + IF(WIN32) + #explicitly add metis target on windows (after gtsam target) + SET(LIBRARIES + ${LIBRARIES} + metis + ) + ENDIF(WIN32) ENDIF(GTSAM_FOUND) IF(WITH_MADGWICK) diff --git a/corelib/src/optimizer/OptimizerCeres.cpp b/corelib/src/optimizer/OptimizerCeres.cpp index fdb77272ce..5a62283a83 100644 --- a/corelib/src/optimizer/OptimizerCeres.cpp +++ b/corelib/src/optimizer/OptimizerCeres.cpp @@ -238,8 +238,9 @@ std::map OptimizerCeres::optimize( UINFO("Ceres optimizing begin (iterations=%d)", iterations()); ceres::Solver::Options options; + options.linear_solver_type = ceres::ITERATIVE_SCHUR; + options.sparse_linear_algebra_library_type = ceres::SUITE_SPARSE; options.max_num_iterations = iterations(); - options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY; options.function_tolerance = this->epsilon(); ceres::Solver::Summary summary; UTimer timer; @@ -457,7 +458,8 @@ std::map OptimizerCeres::optimizeBA( // standard solver, SPARSE_NORMAL_CHOLESKY, also works fine but it is slower // for standard bundle adjustment problems. ceres::Solver::Options options; - options.linear_solver_type = ceres::DENSE_SCHUR; + options.linear_solver_type = ceres::ITERATIVE_SCHUR; + options.sparse_linear_algebra_library_type = ceres::SUITE_SPARSE; options.max_num_iterations = iterations(); //options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY; options.function_tolerance = this->epsilon();