diff --git a/include/core/ceres_wrapper/ceres_manager.h b/include/core/ceres_wrapper/ceres_manager.h
index dd88e5db6bf3b7ac38a925a64ba66c089dbb09ec..9408ab7ad594b73e5ec75aa689a646fe68a24380 100644
--- a/include/core/ceres_wrapper/ceres_manager.h
+++ b/include/core/ceres_wrapper/ceres_manager.h
@@ -20,17 +20,48 @@ typedef std::shared_ptr<CostFunction>  CostFunctionPtr;
 namespace wolf {
 
 WOLF_PTR_TYPEDEFS(CeresManager);
+WOLF_PTR_TYPEDEFS(ParamsCeres);
 
-struct CeresParams : public SolverParams
+struct ParamsCeres : public ParamsSolver
 {
-    CeresParams() = default;
+    bool update_immediately;
+    ceres::Solver::Options solver_options;
+    ceres::Problem::Options problem_options;
+    ceres::Covariance::Options covariance_options;
+
+    ParamsCeres() :
+        update_immediately(false),
+        solver_options(),
+        problem_options(),
+        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;
+
+        #if CERES_VERSION_MINOR >= 13
+            covariance_options.algorithm_type = ceres::SPARSE_QR;//ceres::DENSE_SVD;
+            covariance_options.sparse_linear_algebra_library_type = ceres::SUITE_SPARSE;
+        #elif CERES_VERSION_MINOR >= 10
+            covariance_options.algorithm_type = ceres::SUITE_SPARSE_QR;//ceres::DENSE_SVD;
+        #else
+            covariance_options.algorithm_type = ceres::SPARSE_QR;//ceres::DENSE_SVD;
+        #endif
+        covariance_options.num_threads = 1;
+        covariance_options.apply_loss_function = false;
+
+    }
 
-    CeresParams(std::string _unique_name, CeresParams& params)
+    ParamsCeres(std::string _unique_name, const ParamsServer& _server) :
+        ParamsCeres()
     {
-        //
+        update_immediately                    = _server.getParam<bool>(prefix + "update_immediately");
+
+        // ceres solver options
+        solver_options.max_num_iterations      = _server.getParam<int>(prefix + "max_num_iterations");
     }
 
-    ~CeresParams() override = default;
+    ~ParamsCeres() override = default;
 };
 /** \brief Ceres manager for WOLF
  *
@@ -45,20 +76,25 @@ class CeresManager : public SolverManager
 
         std::map<StateBlockPtr, LocalParametrizationWrapperPtr> state_blocks_local_param_;
 
-        ceres::Solver::Options ceres_options_;
         ceres::Solver::Summary summary_;
         std::unique_ptr<ceres::Problem> ceres_problem_;
         std::unique_ptr<ceres::Covariance> covariance_;
 
+        ParamsCeresPtr params_ceres_;
+
     public:
 
+//        CeresManager(const ProblemPtr& _wolf_problem,
+//                     const ceres::Solver::Options& _ceres_options
+//                     = ceres::Solver::Options());
+        CeresManager(const ProblemPtr& _wolf_problem);
+
         CeresManager(const ProblemPtr& _wolf_problem,
-                     const ceres::Solver::Options& _ceres_options
-                     = ceres::Solver::Options());
+                     const ParamsCeresPtr& _params);
 
-        ~CeresManager() override;
+        WOLF_SOLVER_CREATE(CeresManager, ParamsCeres);
 
-        static SolverManagerPtr create(const ProblemPtr& _wolf_problem, const ParamsServer& _server);
+        ~CeresManager() override;
 
         ceres::Solver::Summary getSummary();
 
@@ -119,7 +155,7 @@ inline std::unique_ptr<ceres::Problem>& CeresManager::getCeresProblem()
 
 inline ceres::Solver::Options& CeresManager::getSolverOptions()
 {
-    return ceres_options_;
+    return params_ceres_->solver_options;
 }
 
 inline bool CeresManager::isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const
diff --git a/include/core/solver/solver_manager.h b/include/core/solver/solver_manager.h
index 9b2a665facbd1cf2590a81cb311075789b33f575..bbd21e22ea38d1bfe66954e541af28766001f4a9 100644
--- a/include/core/solver/solver_manager.h
+++ b/include/core/solver/solver_manager.h
@@ -10,6 +10,7 @@
 namespace wolf {
 
 WOLF_PTR_TYPEDEFS(SolverManager)
+WOLF_PTR_TYPEDEFS(ParamsSolver)
 
 /*
  * Macro for defining Autoconf solver creator for WOLF's high level API.
@@ -20,42 +21,37 @@ WOLF_PTR_TYPEDEFS(SolverManager)
  * In order to use this macro, the derived solver manager class, SolverManagerClass,
  * must have a constructor available with the API:
  *
- *   SolverManagerClass(const SolverParamsClassPtr _params);
+ *   SolverManagerClass(const ProblemPtr& wolf_problem,
+ *                      const ParamsSolverClassPtr _params);
  */
-#define WOLF_SOLVER_CREATE(SolverClass, SolverParamClass)                                      \
-static SolverManagerPtr create(const std::string& _unique_name,                                \
-                               const ParamsServer& _server)                                    \
-{                                                                                              \
-    auto params = std::make_shared<SolverParamClass>(_unique_name, _server);                   \
-                                                                                               \
-    auto solver = std::make_shared<SolverClass>(params);                                       \
-                                                                                               \
-    solver->setName(_unique_name);                                                             \
-                                                                                               \
-    return solver;                                                                             \
-}                                                                                              \
-static SolverManagerPtr create(const std::string& _unique_name, const SolverParamsPtr _params) \
-{                                                                                              \
-    auto params = std::static_pointer_cast<SolverParamClass>(_params);                         \
-                                                                                               \
-    auto solver = std::make_shared<SolverClass>(params);                                       \
-                                                                                               \
-    solver->setName(_unique_name);                                                             \
-                                                                                               \
-    return solver;                                                                             \
-}                                                                                              \
-
-struct SolverParams: public ParamsBase
+#define WOLF_SOLVER_CREATE(SolverClass, ParamsSolverClass)                      \
+static SolverManagerPtr create(const ProblemPtr& _problem,                      \
+                               const ParamsServer& _server)                     \
+{                                                                               \
+    auto params = std::make_shared<ParamsSolverClass>(#SolverClass, _server);   \
+    return std::make_shared<SolverClass>(_problem, params);                     \
+}                                                                               \
+static SolverManagerPtr create(const ProblemPtr& _problem,                      \
+                               const ParamsSolverPtr _params)                   \
+{                                                                               \
+    auto params = std::static_pointer_cast<ParamsSolverClass>(_params);         \
+    return std::make_shared<SolverClass>(_problem, params);                     \
+}                                                                               \
+
+struct ParamsSolver: public ParamsBase
 {
-  SolverParams() = default;
-  SolverParams(std::string _unique_name, const ParamsServer& _server):
-    ParamsBase(_unique_name, _server)
-  {
-    //
-  }
+    std::string prefix = "solver/";
+
+    ParamsSolver() = default;
+    ParamsSolver(std::string _unique_name, const ParamsServer& _server):
+        ParamsBase(_unique_name, _server)
+    {
+        //
+    }
 
-    ~SolverParams() override = default;
+    ~ParamsSolver() override = default;
 };
+
 /**
  * \brief Solver manager for WOLF
  */
diff --git a/src/ceres_wrapper/ceres_manager.cpp b/src/ceres_wrapper/ceres_manager.cpp
index b5bcfa4b7b6dc09e990adbecb93685c0294dbef5..d78128ae960e7be8b9c957cd36f9812d53f14249 100644
--- a/src/ceres_wrapper/ceres_manager.cpp
+++ b/src/ceres_wrapper/ceres_manager.cpp
@@ -5,35 +5,40 @@
 #include "core/landmark/landmark_base.h"
 #include "core/utils/make_unique.h"
 
-namespace wolf {
+namespace wolf
+{
+
+CeresManager::CeresManager(const ProblemPtr& _wolf_problem) :
+        CeresManager(_wolf_problem, std::make_shared<ParamsCeres>())
+{
+
+}
 
 CeresManager::CeresManager(const ProblemPtr& _wolf_problem,
-                           const ceres::Solver::Options& _ceres_options) :
-    SolverManager(_wolf_problem),
-    ceres_options_(_ceres_options)
+                           const ParamsCeresPtr& _params) :
+     SolverManager(_wolf_problem),
+     params_ceres_(_params)
 {
-    ceres::Covariance::Options covariance_options;
-#if CERES_VERSION_MINOR >= 13
-    covariance_options.algorithm_type = ceres::SPARSE_QR;//ceres::DENSE_SVD;
-    covariance_options.sparse_linear_algebra_library_type = ceres::SUITE_SPARSE;
-#elif CERES_VERSION_MINOR >= 10
-    covariance_options.algorithm_type = ceres::SUITE_SPARSE_QR;//ceres::DENSE_SVD;
-#else
-    covariance_options.algorithm_type = ceres::SPARSE_QR;//ceres::DENSE_SVD;
-#endif
-    covariance_options.num_threads = 1;
-    covariance_options.apply_loss_function = false;
-    //covariance_options.null_space_rank = -1;
-    covariance_ = wolf::make_unique<ceres::Covariance>(covariance_options);
-
-    ceres::Problem::Options problem_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;
-
-    ceres_problem_ = wolf::make_unique<ceres::Problem>(problem_options);
+    covariance_ = wolf::make_unique<ceres::Covariance>(params_ceres_->covariance_options);
+    ceres_problem_ = wolf::make_unique<ceres::Problem>(params_ceres_->problem_options);
 }
 
+//CeresManager::CeresManager(const ProblemPtr& _wolf_problem,
+//                           const ceres::Solver::Options& _ceres_options) :
+//    SolverManager(_wolf_problem),
+//    params_ceres_->solver_options(_ceres_options)
+//{
+//
+//    covariance_ = wolf::make_unique<ceres::Covariance>(covariance_options);
+//
+//    ceres::Problem::Options problem_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;
+//
+//    ceres_problem_ = wolf::make_unique<ceres::Problem>(problem_options);
+//}
+
 CeresManager::~CeresManager()
 {
     while (!fac_2_residual_idx_.empty())
@@ -46,18 +51,10 @@ CeresManager::~CeresManager()
     }
 }
 
-    SolverManagerPtr CeresManager::create(const ProblemPtr &_wolf_problem, const ParamsServer& _server)
-{
-    ceres::Solver::Options opt;
-    opt.max_num_iterations = _server.getParam<int>("solver/max_num_iterations");
-    // CeresManager m = CeresManager(wolf_problem, opt);
-    return std::make_shared<CeresManager>(_wolf_problem, opt);
-}
-
 std::string CeresManager::solveDerived(const ReportVerbosity report_level)
 {
     // run Ceres Solver
-    ceres::Solve(ceres_options_, ceres_problem_.get(), &summary_);
+    ceres::Solve(params_ceres_->solver_options, ceres_problem_.get(), &summary_);
 
     std::string report;
 
diff --git a/src/problem/problem.cpp b/src/problem/problem.cpp
index 813077742ceca8ee0b7b60913fab479145c4298b..4f1b16ee54140a055a27e5abdeb1599f631cd1a5 100644
--- a/src/problem/problem.cpp
+++ b/src/problem/problem.cpp
@@ -436,8 +436,7 @@ TimeStamp Problem::getTimeStamp ( ) const
 
     }
 
-    if (not ts.ok())
-        WOLF_WARN( "Problem has nowhere to find a valid timestamp!");
+    WOLF_DEBUG_COND(not ts.ok(), "Problem has nowhere to find a valid timestamp!");
 
     return ts;
 }
diff --git a/test/gtest_factor_block_difference.cpp b/test/gtest_factor_block_difference.cpp
index 9c739965701b6236dcff93fbafba1bd12f90eddb..738ec794e1d1d7ffc1ed96588207d66488933ffb 100644
--- a/test/gtest_factor_block_difference.cpp
+++ b/test/gtest_factor_block_difference.cpp
@@ -43,8 +43,7 @@ class FixtureFactorBlockDifference : public testing::Test
         {
             // Problem and solver
             problem_ = Problem::create("POV", 3);
-            ceres::Solver::Options ceres_options;
-            ceres_manager_ = std::make_shared<CeresManager>(problem_, ceres_options);
+            ceres_manager_ = std::make_shared<CeresManager>(problem_);
 
             TimeStamp t0(0);
             TimeStamp t1(1);