diff --git a/include/core/ceres_wrapper/solver_ceres.h b/include/core/ceres_wrapper/solver_ceres.h
index 424e858f1a6af27e75135649155424dcafc260aa..e4306aa8ca126185a6343435405c1bcb5940e650 100644
--- a/include/core/ceres_wrapper/solver_ceres.h
+++ b/include/core/ceres_wrapper/solver_ceres.h
@@ -28,19 +28,13 @@ struct ParamsCeres : public ParamsSolver
     ceres::Covariance::Options covariance_options;
 
     ParamsCeres() :
-        ParamsSolver(),
-        solver_options(),
-        problem_options(),
-        covariance_options()
+        ParamsSolver()
     {
         loadHardcodedValues();
     }
 
     ParamsCeres(std::string _unique_name, const ParamsServer& _server) :
-        ParamsSolver(_unique_name, _server),
-        solver_options(),
-        problem_options(),
-        covariance_options()
+        ParamsSolver(_unique_name, _server)
     {
         loadHardcodedValues();
 
@@ -53,6 +47,9 @@ struct ParamsCeres : public ParamsSolver
 
     void loadHardcodedValues()
     {
+        solver_options = ceres::Solver::Options();
+        problem_options = ceres::Problem::Options();
+        covariance_options = ceres::Covariance::Options();
         problem_options.cost_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
         problem_options.loss_function_ownership = ceres::TAKE_OWNERSHIP;
         problem_options.local_parameterization_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
diff --git a/src/ceres_wrapper/solver_ceres.cpp b/src/ceres_wrapper/solver_ceres.cpp
index c1b02b709874bce11ea89d5d7e335fe01860d7c7..e2ebc5e1f71c59599433158196870fe69b21de7f 100644
--- a/src/ceres_wrapper/solver_ceres.cpp
+++ b/src/ceres_wrapper/solver_ceres.cpp
@@ -14,7 +14,6 @@ namespace wolf
 SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem) :
         SolverCeres(_wolf_problem, std::make_shared<ParamsCeres>())
 {
-    WOLF_INFO("DEFAULT PARAMS constructor");
 }
 
 SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem,
@@ -22,7 +21,6 @@ SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem,
      : SolverManager(_wolf_problem, _params)
      , params_ceres_(_params)
 {
-    WOLF_INFO("GIVEN PARAMS constructor verbosity: ", (int)params_ceres_->verbose);
     covariance_ = wolf::make_unique<ceres::Covariance>(params_ceres_->covariance_options);
     ceres_problem_ = wolf::make_unique<ceres::Problem>(params_ceres_->problem_options);