diff --git a/CMakeLists.txt b/CMakeLists.txt
index c06b7b5bc67092269865f24febc07432f1e3a7a2..3d5f3117a78320322fa060da9d1fb63aa0d72219 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -103,7 +103,7 @@ include/${PROJECT_NAME}/math/force_torque_delta_tools.h
 include/${PROJECT_NAME}/math/force_torque_inertial_delta_tools.h
   )
 SET(HDRS_CAPTURE
-include/${PROJECT_NAME}/capture/capture_force_torque_preint.h
+include/${PROJECT_NAME}/capture/capture_force_torque.h
 include/${PROJECT_NAME}/capture/capture_force_torque_inertial.h
 include/${PROJECT_NAME}/capture/capture_inertial_kinematics.h
 include/${PROJECT_NAME}/capture/capture_leg_odom.h
@@ -137,7 +137,7 @@ include/${PROJECT_NAME}/sensor/sensor_point_feet_nomove.h
 
 # ============ SOURCES ============ 
 SET(SRCS_CAPTURE
-src/capture/capture_force_torque_preint.cpp
+src/capture/capture_force_torque.cpp
 src/capture/capture_force_torque_inertial.cpp
 src/capture/capture_inertial_kinematics.cpp
 src/capture/capture_leg_odom.cpp
diff --git a/demos/solo_real_povcdl_estimation.cpp b/demos/solo_real_povcdl_estimation.cpp
index 9953db41444d0d1b1da732f5460c3bd398cd3a63..7b60949d554264ebb5ed946f9ff19db4e3c09bdb 100644
--- a/demos/solo_real_povcdl_estimation.cpp
+++ b/demos/solo_real_povcdl_estimation.cpp
@@ -557,7 +557,7 @@ int main (int argc, char **argv) {
         CImu->process();
         auto CIKin = std::make_shared<CaptureInertialKinematics>(ts, sen_ikin, meas_ikin, i_Iw, i_Lc_gesti);
         CIKin->process();
-        auto CFTpreint = std::make_shared<CaptureForceTorquePreint>(ts, sen_ft, CIKin, CImu, cap_ftp_data, Qftp);
+        auto CFTpreint = std::make_shared<CaptureForceTorque>(ts, sen_ft, CIKin, CImu, cap_ftp_data, Qftp);
         CFTpreint->process();
 
 
diff --git a/include/bodydynamics/capture/capture_force_torque_preint.h b/include/bodydynamics/capture/capture_force_torque.h
similarity index 94%
rename from include/bodydynamics/capture/capture_force_torque_preint.h
rename to include/bodydynamics/capture/capture_force_torque.h
index 81db7bf05f90fc9048a907253b477b73f8c748a5..fab1ca4951a7ec09fef965b2176a5d8a848aee66 100644
--- a/include/bodydynamics/capture/capture_force_torque_preint.h
+++ b/include/bodydynamics/capture/capture_force_torque.h
@@ -32,9 +32,9 @@
 
 namespace wolf {
     
-WOLF_PTR_TYPEDEFS(CaptureForceTorquePreint);
+WOLF_PTR_TYPEDEFS(CaptureForceTorque);
 
-class CaptureForceTorquePreint : public CaptureMotion
+class CaptureForceTorque : public CaptureMotion
 {
     public:
         /* 
@@ -51,7 +51,7 @@ class CaptureForceTorquePreint : public CaptureMotion
         qbl1, 4 : orientation of foot 1 in base frame
         qbl2, 4 : orientation of foot 2 in base frame
         */
-        CaptureForceTorquePreint(
+        CaptureForceTorque(
                     const TimeStamp& _init_ts,
                     SensorBasePtr _sensor_ptr,
                     CaptureInertialKinematicsPtr _capture_IK_ptr,  // to get the pbc bias
@@ -60,7 +60,7 @@ class CaptureForceTorquePreint : public CaptureMotion
                     const Eigen::MatrixXd& _data_cov,
                     CaptureBasePtr _capture_origin_ptr = nullptr);
     
-        ~CaptureForceTorquePreint() override;
+        ~CaptureForceTorque() override;
 
         CaptureBaseConstPtr getIkinCaptureOther() const { return cap_ikin_other_;}
         CaptureBasePtr getIkinCaptureOther(){ return cap_ikin_other_;}
diff --git a/include/bodydynamics/factor/factor_force_torque_preint.h b/include/bodydynamics/factor/factor_force_torque_preint.h
index 841bb63d6f94ffa9dc4ec115e5f4a3c3dd06d20a..5e2397e9b2c58837e225bd74a2a18fcfc625fca0 100644
--- a/include/bodydynamics/factor/factor_force_torque_preint.h
+++ b/include/bodydynamics/factor/factor_force_torque_preint.h
@@ -40,7 +40,7 @@ class FactorForceTorquePreint : public FactorAutodiff<FactorForceTorquePreint, 1
 {
     public:
         FactorForceTorquePreint(const FeatureForceTorquePreintPtr& _ftr_ptr,
-                                const CaptureForceTorquePreintPtr& _cap_origin_ptr, // gets to bp1, bw1
+                                const CaptureForceTorquePtr& _cap_origin_ptr, // gets to bp1, bw1
                                 const ProcessorBasePtr&            _processor_ptr,
                                 const CaptureBasePtr&               _cap_ikin_other,
                                 const CaptureBasePtr&               _cap_gyro_other,
@@ -130,7 +130,7 @@ class FactorForceTorquePreint : public FactorAutodiff<FactorForceTorquePreint, 1
 
 inline FactorForceTorquePreint::FactorForceTorquePreint(
                             const FeatureForceTorquePreintPtr& _ftr_ptr,
-                            const CaptureForceTorquePreintPtr& _cap_origin_ptr,
+                            const CaptureForceTorquePtr& _cap_origin_ptr,
                             const ProcessorBasePtr&            _processor_ptr,
                             const CaptureBasePtr&              _cap_ikin_other,
                             const CaptureBasePtr&              _cap_gyro_other,
diff --git a/include/bodydynamics/feature/feature_force_torque_preint.h b/include/bodydynamics/feature/feature_force_torque_preint.h
index 9a03d2a73e668123b29dd948c7988795ea45f9cf..fc04fa4731027bd0a48e5473ca996742d0df91cd 100644
--- a/include/bodydynamics/feature/feature_force_torque_preint.h
+++ b/include/bodydynamics/feature/feature_force_torque_preint.h
@@ -44,7 +44,7 @@ class FeatureForceTorquePreint : public FeatureBase
          * \param _J_delta_bias Jacobians of preintegrated delta wrt [pbc,gyro] biases
          * \param _pbc_bias COM position relative to bias bias of origin frame time
          * \param _gyro_bias gyroscope bias of origin frame time
-         * \param _cap_ftpreint_ptr pointer to parent CaptureMotion (CaptureForceTorquePreint)
+         * \param _cap_ftpreint_ptr pointer to parent CaptureMotion (CaptureForceTorque)
          */
         FeatureForceTorquePreint(const Eigen::VectorXd& _delta_preintegrated,
                                  const Eigen::MatrixXd& _delta_preintegrated_covariance,
diff --git a/src/capture/capture_force_torque_preint.cpp b/src/capture/capture_force_torque.cpp
similarity index 90%
rename from src/capture/capture_force_torque_preint.cpp
rename to src/capture/capture_force_torque.cpp
index 83e145e4b85a4895a81dce2251fcddd10681460d..0211ef89153eae87cd19ca7c6d44295f88af959b 100644
--- a/src/capture/capture_force_torque_preint.cpp
+++ b/src/capture/capture_force_torque.cpp
@@ -26,7 +26,7 @@
 
 namespace wolf {
 
-CaptureForceTorquePreint::CaptureForceTorquePreint(
+CaptureForceTorque::CaptureForceTorque(
                     const TimeStamp& _init_ts,
                     SensorBasePtr _sensor_ptr,
                     CaptureInertialKinematicsPtr _capture_IK_ptr,  // to get the pbc bias
@@ -34,14 +34,14 @@ CaptureForceTorquePreint::CaptureForceTorquePreint(
                     const Eigen::VectorXd& _data,
                     const Eigen::MatrixXd& _data_cov,  // TODO: no uncertainty from kinematics
                     CaptureBasePtr _capture_origin_ptr) :
-                CaptureMotion("CaptureForceTorquePreint", _init_ts, _sensor_ptr, _data, _data_cov,
+                CaptureMotion("CaptureForceTorque", _init_ts, _sensor_ptr, _data, _data_cov,
                               _capture_origin_ptr, nullptr, nullptr, nullptr),
                 cap_ikin_other_(_capture_IK_ptr),
                 cap_gyro_other_(_capture_motion_ptr)
 {
 }
 
-CaptureForceTorquePreint::~CaptureForceTorquePreint()
+CaptureForceTorque::~CaptureForceTorque()
 {
 
 }
diff --git a/src/processor/processor_force_torque_preint.cpp b/src/processor/processor_force_torque_preint.cpp
index 1b84f786077a0f65ee3cc944bf8ebe4f54511499..09348f2c3ce419d367f4877381f13cdc91215f18 100644
--- a/src/processor/processor_force_torque_preint.cpp
+++ b/src/processor/processor_force_torque_preint.cpp
@@ -98,7 +98,7 @@ CaptureMotionPtr ProcessorForceTorquePreint::emplaceCapture(const FrameBasePtr&
         capture_ikin = origin_ptr_->getFrame()->getCaptureOf(sensor_ikin_);
         capture_angvel = origin_ptr_->getFrame()->getCaptureOf(sensor_angvel_); 
     }
-    auto cap = CaptureBase::emplace<CaptureForceTorquePreint>(
+    auto cap = CaptureBase::emplace<CaptureForceTorque>(
                     _frame_own,
                     _ts,
                     _sensor,
@@ -111,7 +111,7 @@ CaptureMotionPtr ProcessorForceTorquePreint::emplaceCapture(const FrameBasePtr&
     // Cannot be recovered from the _calib and _calib_preint which are initialized using calib_size_
     // which is zero in our case since the calibration stateblocks are not actually in the FTPreint sensor/captures
 
-    auto cap_ftpreint = std::static_pointer_cast<CaptureForceTorquePreint>(cap);
+    auto cap_ftpreint = std::static_pointer_cast<CaptureForceTorque>(cap);
     Vector6d calib = getCalibration(cap_ftpreint);
     setCalibration(cap_ftpreint, calib);
     cap_ftpreint->setCalibrationPreint(calib);
@@ -143,7 +143,7 @@ VectorXd ProcessorForceTorquePreint::getCalibration (const CaptureBaseConstPtr _
 
     if (_capture) // access from capture is quicker
     {
-        auto cap_ft(std::static_pointer_cast<const CaptureForceTorquePreint>(_capture));
+        auto cap_ft(std::static_pointer_cast<const CaptureForceTorque>(_capture));
 
         // get calib part from Ikin capture
         bias_vec.segment<3>(0) = cap_ft->getIkinCaptureOther()->getSensorIntrinsic()->getState();
@@ -164,7 +164,7 @@ VectorXd ProcessorForceTorquePreint::getCalibration (const CaptureBaseConstPtr _
 
 void ProcessorForceTorquePreint::setCalibration (const CaptureBasePtr _capture, const VectorXd& _calibration)
 {
-    CaptureForceTorquePreintPtr cap_ft(std::static_pointer_cast<CaptureForceTorquePreint>(_capture));
+    CaptureForceTorquePtr cap_ft(std::static_pointer_cast<CaptureForceTorque>(_capture));
 
     // set calib part in Ikin capture
     cap_ft->getIkinCaptureOther()->getSensorIntrinsic()->setState(_calibration.head<3>());
@@ -178,9 +178,9 @@ void ProcessorForceTorquePreint::setCalibration (const CaptureBasePtr _capture,
 
 FactorBasePtr ProcessorForceTorquePreint::emplaceFactor(FeatureBasePtr _feature_motion, CaptureBasePtr _capture_origin)
 {
-    CaptureForceTorquePreintPtr cap_ftpreint_origin = std::static_pointer_cast<CaptureForceTorquePreint>(_capture_origin);
+    CaptureForceTorquePtr cap_ftpreint_origin = std::static_pointer_cast<CaptureForceTorque>(_capture_origin);
     FeatureForceTorquePreintPtr ftr_ftpreint = std::static_pointer_cast<FeatureForceTorquePreint>(_feature_motion);
-    CaptureForceTorquePreintPtr cap_ftpreint_new = std::static_pointer_cast<CaptureForceTorquePreint>(ftr_ftpreint->getCapture());
+    CaptureForceTorquePtr cap_ftpreint_new = std::static_pointer_cast<CaptureForceTorque>(ftr_ftpreint->getCapture());
 
     auto fac_ftpreint = FactorBase::emplace<FactorForceTorquePreint>(
             ftr_ftpreint,
diff --git a/test/gtest_processor_force_torque_preint.cpp b/test/gtest_processor_force_torque_preint.cpp
index 3465ea6187358cffe667af6a2dd326d279e31e47..bc5ce81200e5f5ec1e303665dea973364c448b15 100644
--- a/test/gtest_processor_force_torque_preint.cpp
+++ b/test/gtest_processor_force_torque_preint.cpp
@@ -253,7 +253,7 @@ public:
         CImu1->process();
         auto CIKin1 = std::make_shared<CaptureInertialKinematics>(t1, sen_ikin_, meas_ikin_, Iq_, Lq_);
         CIKin1->process();
-        auto CFTpreint1 = std::make_shared<CaptureForceTorquePreint>(t1, sen_ft_, CIKin1, CImu1, cap_ftp_data_, Qftp_);
+        auto CFTpreint1 = std::make_shared<CaptureForceTorque>(t1, sen_ft_, CIKin1, CImu1, cap_ftp_data_, Qftp_);
         CFTpreint1->process();
 
 
@@ -265,7 +265,7 @@ public:
         CImu2->process();
         auto CIKin2 = std::make_shared<CaptureInertialKinematics>(t2, sen_ikin_, meas_ikin_, Iq_, Lq_);
         CIKin2->process();
-        auto CFTpreint2 = std::make_shared<CaptureForceTorquePreint>(t2, sen_ft_, CIKin2, CImu2, cap_ftp_data_, Qftp_);
+        auto CFTpreint2 = std::make_shared<CaptureForceTorque>(t2, sen_ft_, CIKin2, CImu2, cap_ftp_data_, Qftp_);
         CFTpreint2->process();
 
         changeForData3();
@@ -275,7 +275,7 @@ public:
         CImu3->process();
         CaptureInertialKinematicsPtr CIKin3 = std::make_shared<CaptureInertialKinematics>(t3, sen_ikin_, meas_ikin_, Iq_, Lq_);
         CIKin3->process();
-        auto CFTpreint3 = std::make_shared<CaptureForceTorquePreint>(t3, sen_ft_, CIKin3, CImu3, cap_ftp_data_, Qftp_);
+        auto CFTpreint3 = std::make_shared<CaptureForceTorque>(t3, sen_ft_, CIKin3, CImu3, cap_ftp_data_, Qftp_);
         CFTpreint3->process();
 
         // T4, just here to make sure the KF at t3 is created
@@ -283,7 +283,7 @@ public:
         CImu4->process();
         CaptureInertialKinematicsPtr CIKin4 = std::make_shared<CaptureInertialKinematics>(t4, sen_ikin_, meas_ikin_, Iq_, Lq_);
         CIKin4->process();
-        auto CFTpreint4 = std::make_shared<CaptureForceTorquePreint>(t4, sen_ft_, CIKin3, CImu3, cap_ftp_data_, Qftp_);
+        auto CFTpreint4 = std::make_shared<CaptureForceTorque>(t4, sen_ft_, CIKin3, CImu3, cap_ftp_data_, Qftp_);
         CFTpreint4->process();
 
         /////////////////////////////////////////////