diff --git a/CMakeLists.txt b/CMakeLists.txt
index 5dc146fa31ce8179c45cf0c50eea777f53258c93..022a89eec620212c6bc607a42951910a35e1bb9e 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -95,7 +95,7 @@ message("UPPER_NAME ${UPPER_NAME}")
 
 
 #find dependencies.
-FIND_PACKAGE(wolf REQUIRED)
+FIND_PACKAGE(wolfcore REQUIRED)
 FIND_PACKAGE(wolfimu REQUIRED)
 
 # Define the directory where will be the configured config.h
@@ -115,7 +115,7 @@ configure_file(${CMAKE_CURRENT_SOURCE_DIR}/internal/config.h.in "${WOLF_CONFIG_D
 include_directories("${PROJECT_BINARY_DIR}/conf")
 
 include_directories("include")
-include_directories(${wolf_INCLUDE_DIRS})
+include_directories(${wolfcore_INCLUDE_DIRS})
 INCLUDE_DIRECTORIES(${wolfimu_INCLUDE_DIRS})
 
 #HEADERS
@@ -200,7 +200,7 @@ endif()
 
 
 
-TARGET_LINK_LIBRARIES(${PLUGIN_NAME} ${wolf_LIBRARIES})
+TARGET_LINK_LIBRARIES(${PLUGIN_NAME} ${wolfcore_LIBRARIES})
 # Link the library with the required dependencies
 # TARGET_LINK_LIBRARIES(${PLUGIN_NAME} wolfimu_INCLUDE_DIRS)
 
diff --git a/cmake_modules/wolfConfig.cmake b/cmake_modules/wolfConfig.cmake
deleted file mode 100644
index 4ff944f2ffccea98faba230f382774a82f6ff2cc..0000000000000000000000000000000000000000
--- a/cmake_modules/wolfConfig.cmake
+++ /dev/null
@@ -1,89 +0,0 @@
-#edit the following line to add the librarie's header files
-FIND_PATH(
-    wolfbodydynamics_INCLUDE_DIRS
-    NAMES bodydynamics.found
-    PATHS /usr/local/include/iri-algorithms/wolf/plugin_bodydynamics)
-IF(wolfbodydynamics_INCLUDE_DIRS)
-  MESSAGE("Found bodydynamics include dirs: ${wolfbodydynamics_INCLUDE_DIRS}")
-ELSE(wolfbodydynamics_INCLUDE_DIRS)
-  MESSAGE("Couldn't find bodydynamics include dirs")
-ENDIF(wolfbodydynamics_INCLUDE_DIRS)
-
-FIND_LIBRARY(
-    wolfbodydynamics_LIBRARIES
-    NAMES libwolfbodydynamics.so libwolfbodydynamics.dylib
-    PATHS /usr/local/lib/iri-algorithms)
-IF(wolfbodydynamics_LIBRARIES)
-  MESSAGE("Found bodydynamics lib: ${wolfbodydynamics_LIBRARIES}")
-ELSE(wolfbodydynamics_LIBRARIES)
-  MESSAGE("Couldn't find wolf bodydynamics lib")
-ENDIF(wolfbodydynamics_LIBRARIES)
-
-IF (wolfbodydynamics_INCLUDE_DIRS AND wolfbodydynamics_LIBRARIES)
-   SET(wolfbodydynamics_FOUND TRUE)
- ELSE(wolfbodydynamics_INCLUDE_DIRS AND wolfbodydynamics_LIBRARIES)
-   set(wolfbodydynamics_FOUND FALSE)
-ENDIF (wolfbodydynamics_INCLUDE_DIRS AND wolfbodydynamics_LIBRARIES)
-
-IF (wolfbodydynamics_FOUND)
-   IF (NOT wolfbodydynamics_FIND_QUIETLY)
-      MESSAGE(STATUS "Found bodydynamics: ${wolfbodydynamics_LIBRARIES}")
-   ENDIF (NOT wolfbodydynamics_FIND_QUIETLY)
-ELSE (wolfbodydynamics_FOUND)
-   IF (wolfbodydynamics_FIND_REQUIRED)
-      MESSAGE(FATAL_ERROR "Could not find wolf bodydynamics")
-   ENDIF (wolfbodydynamics_FIND_REQUIRED)
-ENDIF (wolfbodydynamics_FOUND)
-
-
-macro(wolf_report_not_found REASON_MSG)
-  set(wolfbodydynamics_FOUND FALSE)
-  unset(wolfbodydynamics_INCLUDE_DIRS)
-  unset(wolfbodydynamics_LIBRARIES)
-
-  # Reset the CMake module path to its state when this script was called.
-  set(CMAKE_MODULE_PATH ${CALLERS_CMAKE_MODULE_PATH})
-
-  # Note <package>_FIND_[REQUIRED/QUIETLY] variables defined by
-  # FindPackage() use the camelcase library name, not uppercase.
-  if (wolfbodydynamics_FIND_QUIETLY)
-    message(STATUS "Failed to find wolfbodydynamics- " ${REASON_MSG} ${ARGN})
-  else (wolfbodydynamics_FIND_REQUIRED)
-    message(FATAL_ERROR "Failed to find wolfbodydynamics - " ${REASON_MSG} ${ARGN})
-  else()
-    # Neither QUIETLY nor REQUIRED, use SEND_ERROR which emits an error
-    # that prevents generation, but continues configuration.
-    message(SEND_ERROR "Failed to find wolfbodydynamics - " ${REASON_MSG} ${ARGN})
-  endif ()
-  return()
-endmacro(wolf_report_not_found)
-
-if(NOT wolfbodydynamics_FOUND)
-  wolf_report_not_found("Something went wrong while setting up wolf bodydynamics.")
-endif(NOT wolfbodydynamics_FOUND)
-# Set the include directories for wolf (itself).
-set(wolfbodydynamics_FOUND TRUE)
-
-# Suppose that our plugin requires openCV & vision_utils
-
-FIND_PACKAGE(vision_utils REQUIRED)
-list(APPEND wolfbodydynamics_INCLUDE_DIRS ${vision_utils_INCLUDE_DIR})
-list(APPEND wolfbodydynamics_LIBRARIES ${vision_utils_LIBRARY})
-
-FIND_PACKAGE(OpenCV REQUIRED)
-list(APPEND wolfbodydynamics_INCLUDE_DIRS ${OpenCV_INCLUDE_DIRS})
-list(APPEND wolfbodydynamics_LIBRARIES ${OpenCV_LIBS})
-
-#Making sure wolf is looked for
-if(NOT wolf_FOUND)
-  FIND_PACKAGE(wolf REQUIRED)
-
-  #We reverse in order to insert at the start
-  list(REVERSE wolfbodydynamics_INCLUDE_DIRS)
-  list(APPEND wolfbodydynamics_INCLUDE_DIRS ${wolf_INCLUDE_DIRS})
-  list(REVERSE wolfbodydynamics_INCLUDE_DIRS)
-
-  list(REVERSE wolfbodydynamics_LIBRARIES)
-  list(APPEND wolfbodydynamics_LIBRARIES ${wolf_LIBRARIES})
-  list(REVERSE wolfbodydynamics_LIBRARIES)
-endif()
\ No newline at end of file
diff --git a/cmake_modules/wolfbodydynamicsConfig.cmake b/cmake_modules/wolfbodydynamicsConfig.cmake
index 050a2367341c643d938f88c0ef7438ef7e34a0a9..b7892af3f5a97fde7ce130c0571d340a4929194f 100644
--- a/cmake_modules/wolfbodydynamicsConfig.cmake
+++ b/cmake_modules/wolfbodydynamicsConfig.cmake
@@ -73,14 +73,14 @@ set(wolfbodydynamics_FOUND TRUE)
 
 # Making sure that wolf is always looked for
 if(NOT wolf_FOUND)
-  FIND_PACKAGE(wolf REQUIRED)
+  FIND_PACKAGE(wolfcore REQUIRED)
 
   #We reverse in order to insert at the start
   list(REVERSE wolfbodydynamics_INCLUDE_DIRS)
-  list(APPEND wolfbodydynamics_INCLUDE_DIRS ${wolf_INCLUDE_DIRS})
+  list(APPEND wolfbodydynamics_INCLUDE_DIRS ${wolfcore_INCLUDE_DIRS})
   list(REVERSE wolfbodydynamics_INCLUDE_DIRS)
 
   list(REVERSE wolfbodydynamics_LIBRARIES)
-  list(APPEND wolfbodydynamics_LIBRARIES ${wolf_LIBRARIES})
+  list(APPEND wolfbodydynamics_LIBRARIES ${wolfcore_LIBRARIES})
   list(REVERSE wolfbodydynamics_LIBRARIES)
 endif()
\ No newline at end of file
diff --git a/demos/CMakeLists.txt b/demos/CMakeLists.txt
index 7108b33b0cb7581abcd72bb88231efb2eeb63881..2195b83987881c6e11b180b7b1cb575e30ab4755 100644
--- a/demos/CMakeLists.txt
+++ b/demos/CMakeLists.txt
@@ -25,7 +25,7 @@ target_compile_definitions(mcapi_povcdl_estimation PRIVATE ${PINOCCHIO_CFLAGS_OT
 
 
 target_link_libraries(mcapi_povcdl_estimation
-    ${wolf_LIBRARIES}
+    ${wolfcore_LIBRARIES}
     ${wolfimu_LIBRARIES}
     ${PLUGIN_NAME}
     ${MCAPI_LIBRARIES}
diff --git a/test/gtest_factor_force_torque.cpp b/test/gtest_factor_force_torque.cpp
index a36fb851d00ff1bd8654ed09e4583c34b7c5d260..d529469ae5a1801ff365149b7c53ce26d3bf13d5 100644
--- a/test/gtest_factor_force_torque.cpp
+++ b/test/gtest_factor_force_torque.cpp
@@ -151,7 +151,7 @@ void perturbateAllIfUnFixed(const FrameBasePtr& KF)
 FrameBasePtr createKFWithCDLI(const ProblemPtr& problem, const TimeStamp& t, VectorComposite x_origin,
                               Vector3d c, Vector3d cd, Vector3d Lc, Vector6d bias_imu)
 {
-    FrameBasePtr KF = FrameBase::emplace<FrameBase>(problem->getTrajectory(), wolf::KEY, t, "POV", x_origin);
+    FrameBasePtr KF = FrameBase::emplaceKeyFrame<FrameBase>(problem->getTrajectory(), t, "POV", x_origin);
     StateBlockPtr sbc = make_shared<StateBlock>(c);  KF->addStateBlock('C', sbc, problem);
     StateBlockPtr sbd = make_shared<StateBlock>(cd); KF->addStateBlock('D', sbd, problem);
     StateBlockPtr sbL = make_shared<StateBlock>(Lc); KF->addStateBlock('L', sbL, problem);
diff --git a/test/gtest_feature_force_torque_preint_WIP.cpp b/test/gtest_feature_force_torque_preint_WIP.cpp
index e196ee03554f378fd3e808f32e2e437da073be1e..0b7c24a0dbd989b9f003b03b58e769fe1ede3a50 100644
--- a/test/gtest_feature_force_torque_preint_WIP.cpp
+++ b/test/gtest_feature_force_torque_preint_WIP.cpp
@@ -111,7 +111,7 @@ class FeatureForceTorquePreint_test : public testing::Test
     //emplace Frame
         ts_ = problem_->getProcessorIsMotion()->getBuffer().back().ts_;
         state_vec_ = problem_->getProcessorIsMotion()->getCurrentState();
-        last_frame_ = problem_->emplaceFrame(KEY, state_vec_, ts_);
+        last_frame_ = problem_->emplaceKeyFrame( state_vec_, ts_);
 
     //emplace a feature
         delta_preint_ = problem_->getProcessorIsMotion()->getMotion().delta_integr_;
diff --git a/test/gtest_processor_force_torque_preint.cpp b/test/gtest_processor_force_torque_preint.cpp
index 58ee5df4de68ef9849f5bca65e84c7dafe60eec6..8925efb81dab1b9fe0f3818e0608293fe898abd2 100644
--- a/test/gtest_processor_force_torque_preint.cpp
+++ b/test/gtest_processor_force_torque_preint.cpp
@@ -203,7 +203,7 @@ public:
         // - call setOrigin on processors isMotion
         setOriginState();
         MatrixXd P_origin_ = pow(1e-3, 2) * MatrixXd::Identity(18,18);
-        KF1_ = problem_->emplaceFrame(KEY, t0_, x_origin_);
+        KF1_ = problem_->emplaceKeyFrame( t0_, x_origin_);
         // Prior pose factor
         CapturePosePtr pose_prior_capture = CaptureBase::emplace<CapturePose>(KF1_, t0_, nullptr, x_origin_.head(7), P_origin_.topLeftCorner(6, 6));
         pose_prior_capture->emplaceFeatureAndFactor();
@@ -269,7 +269,7 @@ public:
         setOdomData();
         Matrix6d rel_pose_cov = 1e-6 * Matrix6d::Identity();
 
-        KF2_ = problem_->getTrajectory()->getLastKeyFrame();
+        KF2_ = problem_->getTrajectory()->getLastFrame();
         CaptureBasePtr cap_pose_base = CaptureBase::emplace<CapturePose>(KF2_, KF2_->getTimeStamp(), nullptr, prev_pose_curr_, rel_pose_cov);
         FeatureBasePtr ftr_odom3d_base = FeatureBase::emplace<FeaturePose>(cap_pose_base, prev_pose_curr_, rel_pose_cov);
         FactorBase::emplace<FactorOdom3d>(ftr_odom3d_base, ftr_odom3d_base, KF1_, nullptr, false);
diff --git a/test/gtest_processor_inertial_kinematics.cpp b/test/gtest_processor_inertial_kinematics.cpp
index 8653902ac933e7abf7b8b01e94eeeb87b1e56fb9..ab377e4bebe2bea742a6691db4a77cbe54d0f1d6 100644
--- a/test/gtest_processor_inertial_kinematics.cpp
+++ b/test/gtest_processor_inertial_kinematics.cpp
@@ -101,7 +101,7 @@ class FactorInertialKinematics_2KF : public testing::Test
 
         // Set origin of the problem
         // KF0_ = problem_->setPriorFactor(x_origin_, P_origin_, t_, 0.005);
-        KF0_ = problem_->emplaceFrame(KEY, t_, x_origin_);
+        KF0_ = problem_->emplaceKeyFrame( t_, x_origin_);
 
         ///////////////////////////////////////////////////
         // Prior pose factor
@@ -197,7 +197,7 @@ TEST_F(FactorInertialKinematics_2KF, sensor_and_processors_registration)
     Vector3d pdiff; pdiff << 4.5, 0, 0;
     Vector3d vdiff; vdiff << 3, 0, 0;
 
-    FrameBasePtr KF1 = problem_->getTrajectory()->getLastKeyFrame();
+    FrameBasePtr KF1 = problem_->getTrajectory()->getLastFrame();
 
 
     ASSERT_MATRIX_APPROX(KF0_->getStateBlock('P')->getState(), ZERO3, 1e-6);