diff --git a/include/core/ceres_wrapper/iteration_update_callback.h b/include/core/ceres_wrapper/iteration_update_callback.h
index 0496c336e9b04b364696b2b5de38e26498e57b70..7875cb7c1d28d9775e05a4af7c1b99757fbf0baf 100644
--- a/include/core/ceres_wrapper/iteration_update_callback.h
+++ b/include/core/ceres_wrapper/iteration_update_callback.h
@@ -16,8 +16,10 @@ namespace wolf {
 class IterationUpdateCallback : public ceres::IterationCallback
 {
     public:
-        explicit IterationUpdateCallback(ProblemPtr _problem)
-        : problem_(_problem) {}
+        explicit IterationUpdateCallback(ProblemPtr _problem, bool verbose = false)
+        : problem_(_problem)
+        , verbose_(verbose)
+        {}
 
         ~IterationUpdateCallback() {}
 
@@ -26,7 +28,9 @@ class IterationUpdateCallback : public ceres::IterationCallback
             if (problem_->getStateBlockNotificationMapSize() != 0 or
                 problem_->getFactorNotificationMapSize() != 0)
             {
-                WOLF_INFO("Stopping solver to update the problem!");
+                if (verbose_)
+                    std::cout << "Stopping solver to update the problem!\n";
+                WOLF_INFO_COND(verbose_, "Stopping solver to update the problem!");
                 return ceres::SOLVER_TERMINATE_SUCCESSFULLY;
             }
             return ceres::SOLVER_CONTINUE;
@@ -34,6 +38,7 @@ class IterationUpdateCallback : public ceres::IterationCallback
 
     private:
         ProblemPtr problem_;
+        bool verbose_;
 };
 
 }
diff --git a/src/ceres_wrapper/solver_ceres.cpp b/src/ceres_wrapper/solver_ceres.cpp
index b3413b2c7760f7f29966427c8f2b4cce50a2953c..1b6d5893f4e8b61f07702459ad95d4ce1d6df021 100644
--- a/src/ceres_wrapper/solver_ceres.cpp
+++ b/src/ceres_wrapper/solver_ceres.cpp
@@ -14,6 +14,7 @@ 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,
@@ -21,11 +22,12 @@ SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem,
      : SolverManager(_wolf_problem, _params)
      , params_ceres_(_params)
 {
+    WOLF_INFO("GIVEN PARAMS constructor");
     covariance_ = wolf::make_unique<ceres::Covariance>(params_ceres_->covariance_options);
     ceres_problem_ = wolf::make_unique<ceres::Problem>(params_ceres_->problem_options);
 
     if (params_ceres_->update_immediately)
-        getSolverOptions().callbacks.push_back(new IterationUpdateCallback(wolf_problem_));
+        getSolverOptions().callbacks.push_back(new IterationUpdateCallback(wolf_problem_, params_ceres_->verbose != SolverManager::ReportVerbosity::QUIET));
 }
 
 SolverCeres::~SolverCeres()
@@ -49,7 +51,7 @@ SolverCeres::~SolverCeres()
 std::string SolverCeres::solveDerived(const ReportVerbosity report_level)
 {
     // run Ceres Solver
-    ceres::Solve(params_ceres_->solver_options, ceres_problem_.get(), &summary_);
+    ceres::Solve(getSolverOptions(), ceres_problem_.get(), &summary_);
 
     std::string report;
 
diff --git a/src/solver/solver_manager.cpp b/src/solver/solver_manager.cpp
index a0b6f028ce349227ad94a979c16e788c51a09915..6aa6371d1a4d3c1072771ce4150841cfa85823c8 100644
--- a/src/solver/solver_manager.cpp
+++ b/src/solver/solver_manager.cpp
@@ -109,6 +109,8 @@ std::string SolverManager::solve()
 
 std::string SolverManager::solve(const ReportVerbosity report_level)
 {
+    WOLF_INFO_COND(report_level != SolverManager::ReportVerbosity::QUIET, "SOLVING...");
+
     // update problem
     update();