diff --git a/src/boards/RIGv2/Actuators/Actuators.cpp b/src/boards/RIGv2/Actuators/Actuators.cpp
index 3464c7aa2d94082280efd49c9732dc0d6728c602..626c60ca49368d17487082a2fd58f0f10f991a79 100644
--- a/src/boards/RIGv2/Actuators/Actuators.cpp
+++ b/src/boards/RIGv2/Actuators/Actuators.cpp
@@ -65,14 +65,13 @@ void Actuators::ServoInfo::unsafeSetServoPosition(float position)
         return;
     }
 
+    position *= limit;
     if (flipped)
     {
-        servo->setPosition(1.0f - position);
-    }
-    else
-    {
-        servo->setPosition(position);
+        position = 1.0f - position;
     }
+
+    servo->setPosition(position);
 }
 
 float Actuators::ServoInfo::getServoPosition()
@@ -83,14 +82,14 @@ float Actuators::ServoInfo::getServoPosition()
         return 0.0f;
     }
 
+    float position = servo->getPosition();
     if (flipped)
     {
-        return 1.0f - servo->getPosition();
-    }
-    else
-    {
-        return servo->getPosition();
+        position = 1.0f - position;
     }
+
+    position /= limit;
+    return position;
 }
 
 Actuators::Actuators(TaskScheduler &scheduler) : scheduler{scheduler}
@@ -131,31 +130,35 @@ Actuators::Actuators(TaskScheduler &scheduler) : scheduler{scheduler}
 
     ServoInfo *info;
     info               = getServo(ServosList::FILLING_VALVE);
-    info->maxAperture  = Config::Servos::DEFAULT_FILLING_MAXIMUM_APERTURE;
+    info->maxAperture  = Config::Servos::DEFAULT_FILLING_MAX_APERTURE;
     info->openingTime  = Config::Servos::DEFAULT_FILLING_OPENING_TIME;
+    info->limit        = Config::Servos::FILLING_LIMIT;
     info->flipped      = Config::Servos::FILLING_FLIPPED;
     info->openingEvent = Common::Events::MOTOR_OPEN_FILLING_VALVE;
     info->closingEvent = Common::Events::MOTOR_CLOSE_FILLING_VALVE;
     info->unsafeSetServoPosition(0.0f);
 
     info               = getServo(ServosList::RELEASE_VALVE);
-    info->maxAperture  = Config::Servos::DEFAULT_RELEASE_MAXIMUM_APERTURE;
+    info->maxAperture  = Config::Servos::DEFAULT_RELEASE_MAX_APERTURE;
     info->openingTime  = Config::Servos::DEFAULT_RELEASE_OPENING_TIME;
+    info->limit        = Config::Servos::RELEASE_LIMIT;
     info->flipped      = Config::Servos::RELEASE_FLIPPED;
     info->openingEvent = Common::Events::MOTOR_OPEN_RELEASE_VALVE;
     info->closingEvent = Common::Events::MOTOR_CLOSE_RELEASE_VALVE;
     info->unsafeSetServoPosition(0.0f);
 
     info               = getServo(ServosList::DISCONNECT_SERVO);
-    info->maxAperture  = Config::Servos::DEFAULT_DISCONNECT_MAXIMUM_APERTURE;
+    info->maxAperture  = Config::Servos::DEFAULT_DISCONNECT_MAX_APERTURE;
     info->openingTime  = Config::Servos::DEFAULT_DISCONNECT_OPENING_TIME;
+    info->limit        = 1.0;
     info->flipped      = Config::Servos::DISCONNECT_FLIPPED;
     info->openingEvent = Common::Events::MOTOR_DISCONNECT;
     info->unsafeSetServoPosition(0.0f);
 
     info               = getServo(ServosList::MAIN_VALVE);
-    info->maxAperture  = Config::Servos::DEFAULT_MAIN_MAXIMUM_APERTURE;
+    info->maxAperture  = Config::Servos::DEFAULT_MAIN_MAX_APERTURE;
     info->openingTime  = Config::Servos::DEFAULT_MAIN_OPENING_TIME;
+    info->limit        = Config::Servos::MAIN_LIMIT;
     info->flipped      = Config::Servos::MAIN_FLIPPED;
     info->openingEvent = Common::Events::MOTOR_OPEN_FEED_VALVE;
     info->closingEvent = Common::Events::MOTOR_CLOSE_FEED_VALVE;
@@ -163,8 +166,9 @@ Actuators::Actuators(TaskScheduler &scheduler) : scheduler{scheduler}
 
     // This servo is not yet enabled
     info               = getServo(ServosList::VENTING_VALVE);
-    info->maxAperture  = Config::Servos::DEFAULT_VENTING_MAXIMUM_APERTURE;
+    info->maxAperture  = Config::Servos::DEFAULT_VENTING_MAX_APERTURE;
     info->openingTime  = Config::Servos::DEFAULT_VENTING_OPENING_TIME;
+    info->limit        = Config::Servos::VENTING_LIMIT;
     info->flipped      = Config::Servos::VENTING_FLIPPED;
     info->openingEvent = Common::Events::MOTOR_OPEN_VENTING_VALVE;
     info->closingEvent = Common::Events::MOTOR_CLOSE_VENTING_VALVE;
@@ -312,10 +316,11 @@ bool Actuators::isServoOpen(ServosList servo)
     return info->getServoPosition() > Config::Servos::SERVO_OPEN_THRESHOLD;
 }
 
-uint64_t Actuators::getServoOpeningTime(ServosList servo) {
+uint64_t Actuators::getServoOpeningTime(ServosList servo)
+{
     Lock<FastMutex> lock(infosMutex);
     ServoInfo *info = getServo(servo);
-    if(info == nullptr)
+    if (info == nullptr)
     {
         return 0;
     }
@@ -323,10 +328,11 @@ uint64_t Actuators::getServoOpeningTime(ServosList servo) {
     return info->openingTime;
 }
 
-float Actuators::getServoMaxAperture(ServosList servo) {
+float Actuators::getServoMaxAperture(ServosList servo)
+{
     Lock<FastMutex> lock(infosMutex);
     ServoInfo *info = getServo(servo);
-    if(info == nullptr)
+    if (info == nullptr)
     {
         return 0;
     }
diff --git a/src/boards/RIGv2/Actuators/Actuators.h b/src/boards/RIGv2/Actuators/Actuators.h
index f824329a29b7e66c62dd5773e68d28e1e69b4581..438f505d305cfaceadb8cd8751411f9786ae098d 100644
--- a/src/boards/RIGv2/Actuators/Actuators.h
+++ b/src/boards/RIGv2/Actuators/Actuators.h
@@ -43,6 +43,8 @@ private:
         uint64_t openingTime = 100000;  // Default 100s [ms]
         // What angle is the maximum
         float maxAperture = 1.0;
+        // Hard limit of the aperture
+        float limit = 1.0;
         // Should this servo be reversed?
         bool flipped = false;
 
diff --git a/src/boards/RIGv2/Configs/ActuatorsConfig.h b/src/boards/RIGv2/Configs/ActuatorsConfig.h
index 1db325bee962ed0c7a4b49f9855852ad4c5a6f25..afe032ba23c55bd0f952fd6239008591e27c0868 100644
--- a/src/boards/RIGv2/Configs/ActuatorsConfig.h
+++ b/src/boards/RIGv2/Configs/ActuatorsConfig.h
@@ -47,17 +47,22 @@ static constexpr uint32_t DEFAULT_MAIN_OPENING_TIME       = 6000;   // 6s
 static constexpr uint32_t DEFAULT_RELEASE_OPENING_TIME    = 10000;  // 10s
 static constexpr uint32_t DEFAULT_DISCONNECT_OPENING_TIME = 10000;  // 10s
 
-static constexpr float DEFAULT_FILLING_MAXIMUM_APERTURE    = 1.00f;
-static constexpr float DEFAULT_VENTING_MAXIMUM_APERTURE    = 1.00f;
-static constexpr float DEFAULT_MAIN_MAXIMUM_APERTURE       = 1.00f;
-static constexpr float DEFAULT_RELEASE_MAXIMUM_APERTURE    = 1.00f;
-static constexpr float DEFAULT_DISCONNECT_MAXIMUM_APERTURE = 1.00f;
+static constexpr float DEFAULT_FILLING_MAX_APERTURE    = 1.00f;
+static constexpr float DEFAULT_VENTING_MAX_APERTURE    = 1.00f;
+static constexpr float DEFAULT_MAIN_MAX_APERTURE       = 1.00f;
+static constexpr float DEFAULT_RELEASE_MAX_APERTURE    = 1.00f;
+static constexpr float DEFAULT_DISCONNECT_MAX_APERTURE = 1.00f;
+
+static constexpr float FILLING_LIMIT = 0.65f;
+static constexpr float RELEASE_LIMIT = 0.45f;
+static constexpr float VENTING_LIMIT = 0.5f;
+static constexpr float MAIN_LIMIT    = 1.0f;
 
 static constexpr bool FILLING_FLIPPED    = true;
-static constexpr bool VENTING_FLIPPED    = true;
-static constexpr bool MAIN_FLIPPED       = true;
-static constexpr bool RELEASE_FLIPPED    = false;
-static constexpr bool DISCONNECT_FLIPPED = true;
+static constexpr bool VENTING_FLIPPED    = false;
+static constexpr bool MAIN_FLIPPED       = false;
+static constexpr bool RELEASE_FLIPPED    = true;
+static constexpr bool DISCONNECT_FLIPPED = false;
 
 }  // namespace Servos
 }  // namespace Config
diff --git a/src/boards/RIGv2/Configs/SensorsConfig.h b/src/boards/RIGv2/Configs/SensorsConfig.h
index e573dc4ce50c5a5f0265360e609a99c8173b36f8..0bfeca7f4c34c77d3b83ae012ab4ca0a3749cda9 100644
--- a/src/boards/RIGv2/Configs/SensorsConfig.h
+++ b/src/boards/RIGv2/Configs/SensorsConfig.h
@@ -34,20 +34,21 @@ namespace Sensors
 {
 
 static constexpr uint32_t ADC_SAMPLE_PERIOD = 10;
-static constexpr uint32_t TC_SAMPLE_PERIOD = 100;
+static constexpr uint32_t TC_SAMPLE_PERIOD  = 100;
 
-static constexpr float ADC1_CH1_SHUNT_RESISTANCE = 30;
-static constexpr float ADC1_CH2_SHUNT_RESISTANCE = 30;
-static constexpr float ADC1_CH3_SHUNT_RESISTANCE = 30;
-static constexpr float ADC1_CH4_SHUNT_RESISTANCE = 30;
+static constexpr float ADC1_CH1_SHUNT_RESISTANCE = 30.3;
+static constexpr float ADC1_CH2_SHUNT_RESISTANCE = 30.4;
+static constexpr float ADC1_CH3_SHUNT_RESISTANCE = 30.5;
+static constexpr float ADC1_CH4_SHUNT_RESISTANCE = 30.8;
 
 // ADC channels definitions for various sensors
-static constexpr int ADC1_VESSEL_PT_CHANNEL = 0;
-static constexpr int ADC1_FILLING_PT_CHANNEL = 1;
-static constexpr int ADC1_BOTTOM_PT_CHANNEL = 2;
-static constexpr int ADC1_TOP_PT_CHANNEL = 3;
-static constexpr int ADC1_VESSEL_LC_CHANNEL = 6;
-static constexpr int ADC1_TANK_LC_CHANNEL = 7;
+static constexpr int ADC1_VESSEL_PT_CHANNEL     = 0;
+static constexpr int ADC1_FILLING_PT_CHANNEL    = 1;
+static constexpr int ADC1_BOTTOM_PT_CHANNEL     = 2;
+static constexpr int ADC1_TOP_PT_CHANNEL        = 3;
+static constexpr int ADC1_SERVO_CURRENT_CHANNEL = 4;
+static constexpr int ADC1_VESSEL_LC_CHANNEL     = 5;
+static constexpr int ADC1_TANK_LC_CHANNEL       = 6;
 
 static constexpr float PT_MIN_CURRENT = 4;
 static constexpr float PT_MAX_CURRENT = 20;
@@ -57,10 +58,21 @@ static constexpr float TANK_TOP_MAX_PRESSURE    = 100;  // bar
 static constexpr float TANK_BOTTOM_MAX_PRESSURE = 100;  // bar
 static constexpr float VESSEL_MAX_PRESSURE      = 400;  // bar
 
-static constexpr unsigned int LC_CALIBRATE_SAMPLE_COUNT = 10;
+static constexpr unsigned int LC_CALIBRATE_SAMPLE_COUNT  = 10;
 static constexpr unsigned int LC_CALIBRATE_SAMPLE_PERIOD = 40;
 
-}
+// Servo current sensor calibration data
+// - A: 0.0 V: 2.520
+// - A: 0.5 V: 2.513
+// - A: 1.0 V: 2.505
+// - A: 1.5 V: 2.498
+// - A: 2.0 V: 2.490
+// - A: 2.5 V: 2.484
+// - A: 5.2 V: 2.441
+static constexpr float SERVO_CURRENT_SCALE   = 4.5466;
+static constexpr float SERVO_CURRENT_ZERO    = 2.520 / SERVO_CURRENT_SCALE;
+static constexpr float BATTERY_VOLTAGE_SCALE = 4.7917;
+}  // namespace Sensors
 
 }  // namespace Config
 
diff --git a/src/boards/RIGv2/Configs/TARS1Config.h b/src/boards/RIGv2/Configs/TARS1Config.h
index f9d372f67f8f9d2a6b8f5fa72dac993d1f87d71b..d36a0359cfaa4d1a05854556179a5e6178a0f760 100644
--- a/src/boards/RIGv2/Configs/TARS1Config.h
+++ b/src/boards/RIGv2/Configs/TARS1Config.h
@@ -31,6 +31,7 @@ namespace Config
 namespace TARS1
 {
 static constexpr uint32_t SAMPLE_PERIOD = 10;
+static constexpr size_t MEDIAN_SAMPLE_NUMBER = 10;
 
 static constexpr uint32_t WASHING_OPENING_TIME         = 5000;
 static constexpr uint32_t WASHING_TIME_DELAY           = 1000;
diff --git a/src/boards/RIGv2/Radio/Radio.cpp b/src/boards/RIGv2/Radio/Radio.cpp
index 2041adfea67e05236b27a1c6ee247f6df6e593b0..63c3d5e93911f82519ae8dff8114a550ec8796a1 100644
--- a/src/boards/RIGv2/Radio/Radio.cpp
+++ b/src/boards/RIGv2/Radio/Radio.cpp
@@ -293,7 +293,7 @@ void Radio::handleMessage(const mavlink_message_t& msg)
 
 void Radio::handleCommand(const mavlink_message_t& msg)
 {
-    uint8_t cmd            = mavlink_msg_command_tc_get_command_id(&msg);
+    uint8_t cmd = mavlink_msg_command_tc_get_command_id(&msg);
     switch (cmd)
     {
         case MAV_CMD_START_LOGGING:
@@ -330,6 +330,13 @@ void Radio::handleCommand(const mavlink_message_t& msg)
             break;
         }
 
+        case MAV_CMD_FORCE_REBOOT:
+        {
+            EventBroker::getInstance().post(TMTC_RESET_BOARD, TOPIC_MOTOR);
+            sendAck(msg);
+            break;
+        }
+
         default:
         {
             // Unrecognized command
diff --git a/src/boards/RIGv2/Sensors/Sensors.cpp b/src/boards/RIGv2/Sensors/Sensors.cpp
index 85d607cbf9ba4b1b9d363d4534be8ddfddee5ba2..7f2b7f96013fbc211c510f0d5839d6b39d971fbc 100644
--- a/src/boards/RIGv2/Sensors/Sensors.cpp
+++ b/src/boards/RIGv2/Sensors/Sensors.cpp
@@ -25,6 +25,8 @@
 #include <RIGv2/Buses.h>
 #include <RIGv2/Configs/SensorsConfig.h>
 #include <interfaces-impl/hwmapping.h>
+// TODO(davide.mor): Remove TimestampTimer
+#include <drivers/timer/TimestampTimer.h>
 
 using namespace Boardcore;
 using namespace miosix;
@@ -43,16 +45,6 @@ float pressureFromVoltage(float voltage, float shuntResistance,
     return value * maxPressure;
 }
 
-float loadFromVoltage(float voltage, float excitationVoltage, float ratedOutput,
-                      float ratedCapacity)
-{
-    // Convert to a value between [0, 1] based on 0 and maximum output voltage
-    float value = (voltage * 1000.0f) / (ratedOutput * excitationVoltage);
-
-    // Finally remap to the range [0, ratedCapacity]
-    return value * ratedCapacity;
-}
-
 bool Sensors::isStarted() { return started; }
 
 bool Sensors::start()
@@ -146,9 +138,7 @@ LoadCellData Sensors::getVesselWeight()
         sample.voltage[Config::Sensors::ADC1_VESSEL_LC_CHANNEL] -
         vesselLcOffset;
 
-    float load = loadFromVoltage(calibratedVoltage, 8.0f, 2.0f, 500.0f);
-
-    return {sample.timestamp, load};
+    return {sample.timestamp, calibratedVoltage};
 }
 
 LoadCellData Sensors::getTankWeight()
@@ -157,30 +147,30 @@ LoadCellData Sensors::getTankWeight()
     float calibratedVoltage =
         sample.voltage[Config::Sensors::ADC1_TANK_LC_CHANNEL] - tankLcOffset;
 
-    float load = loadFromVoltage(calibratedVoltage, 8.0f, 2.0f, 500.0f);
-
-    return {sample.timestamp, load};
+    return {sample.timestamp, calibratedVoltage};
 }
 
 CurrentData Sensors::getUmbilicalCurrent()
 {
-    auto sample = getInternalADCLastSample();
-
-    return {sample.timestamp, sample.voltage[11]};
+    return {TimestampTimer::getTimestamp(), 0.0};
 }
 
 CurrentData Sensors::getServoCurrent()
 {
-    auto sample = getInternalADCLastSample();
+    auto sample = getADC1LastSample();
 
-    return {sample.timestamp, sample.voltage[9]};
+    float current = (sample.voltage[Config::Sensors::ADC1_SERVO_CURRENT_CHANNEL] - Config::Sensors::SERVO_CURRENT_ZERO) *
+                    Config::Sensors::SERVO_CURRENT_SCALE;
+    // Current reading are flipped
+    return {sample.timestamp, -current / 5.0f * 50.0f};
 }
 
 VoltageData Sensors::getBatteryVoltage()
 {
     auto sample = getInternalADCLastSample();
 
-    return {sample.timestamp, sample.voltage[14]};
+    float voltage = sample.voltage[14] * Config::Sensors::BATTERY_VOLTAGE_SCALE;
+    return {sample.timestamp, voltage};
 }
 
 void Sensors::calibrate()
diff --git a/src/boards/RIGv2/StateMachines/GroundModeManager/GroundModeManager.cpp b/src/boards/RIGv2/StateMachines/GroundModeManager/GroundModeManager.cpp
index b7ae89aff0b4ea8b40bc146ac35a059fa87c899e..c876bb0d56ce2540f94e5b43b8f6f20c5ef73b13 100644
--- a/src/boards/RIGv2/StateMachines/GroundModeManager/GroundModeManager.cpp
+++ b/src/boards/RIGv2/StateMachines/GroundModeManager/GroundModeManager.cpp
@@ -73,6 +73,12 @@ void GroundModeManager::state_idle(const Boardcore::Event &event)
             break;
         }
 
+        case TMTC_RESET_BOARD:
+        {
+            reboot();
+            break;
+        }
+
         case FMM_INIT_ERROR:
         {
             transition(&GroundModeManager::state_init_err);
@@ -97,6 +103,12 @@ void GroundModeManager::state_init_err(const Boardcore::Event &event)
             break;
         }
 
+        case TMTC_RESET_BOARD:
+        {
+            reboot();
+            break;
+        }
+
         case TMTC_FORCE_INIT:
         {
             transition(&GroundModeManager::state_disarmed);
@@ -117,6 +129,12 @@ void GroundModeManager::state_disarmed(const Boardcore::Event &event)
             break;
         }
 
+        case TMTC_RESET_BOARD:
+        {
+            reboot();
+            break;
+        }
+
         case TMTC_ARM:
         {
             transition(&GroundModeManager::state_armed);
diff --git a/src/boards/RIGv2/StateMachines/TARS1/MedianFilter.h b/src/boards/RIGv2/StateMachines/TARS1/MedianFilter.h
new file mode 100644
index 0000000000000000000000000000000000000000..0302d292532d156778f06e3530dad144930a72cb
--- /dev/null
+++ b/src/boards/RIGv2/StateMachines/TARS1/MedianFilter.h
@@ -0,0 +1,57 @@
+/* Copyright (c) 2024 Skyward Experimental Rocketry
+ * Authors: Davide Mor
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <algorithm>
+#include <memory>
+#include <array>
+
+namespace RIGv2
+{
+
+template<typename T, size_t Max>
+class MedianFilter
+{
+public:
+    MedianFilter() {}
+
+    void reset() {
+        idx = 0;
+    }
+    
+    void add(T value) {
+        values[idx] = value;
+        idx = (idx + 1) % Max;
+    }
+    
+    T calcMedian() {
+        std::sort(values.begin(), values.end());
+        return values[idx / 2];
+    }
+
+private:
+    size_t idx = 0;
+    std::array<T, Max> values = {0};
+};
+
+}
\ No newline at end of file
diff --git a/src/boards/RIGv2/StateMachines/TARS1/TARS1.cpp b/src/boards/RIGv2/StateMachines/TARS1/TARS1.cpp
index ccd34de6d598fdeb4cb7d0ea4bc2d4c3b4d98194..c3e1e473f4bac9377637c522981838ace1ad07b9 100644
--- a/src/boards/RIGv2/StateMachines/TARS1/TARS1.cpp
+++ b/src/boards/RIGv2/StateMachines/TARS1/TARS1.cpp
@@ -23,7 +23,6 @@
 #include "TARS1.h"
 
 #include <RIGv2/Actuators/Actuators.h>
-#include <RIGv2/Configs/TARS1Config.h>
 #include <RIGv2/Sensors/Sensors.h>
 #include <common/Events.h>
 #include <events/EventBroker.h>
@@ -62,10 +61,7 @@ bool TARS1::start()
     return true;
 }
 
-bool TARS1::isRefueling()
-{
-    return testState(&TARS1::state_refueling);
-}
+bool TARS1::isRefueling() { return testState(&TARS1::state_refueling); }
 
 void TARS1::state_ready(const Event& event)
 {
@@ -260,17 +256,23 @@ void TARS1::sample()
     ModuleManager& modules = ModuleManager::getInstance();
     Sensors* sensors       = modules.get<Sensors>();
 
-    float pressure = sensors->getTankBottomPress().pressure;
-    float mass     = sensors->getTankWeight().load;
+    pressureFilter.add(sensors->getTankBottomPress().pressure);
+    massFilter.add(sensors->getTankWeight().load);
+    medianSamples++;
 
-    // TODO(davide.mor): Perform filtering on input data
+    if (medianSamples == Config::TARS1::MEDIAN_SAMPLE_NUMBER)
+    {
+        float pressure = pressureFilter.calcMedian();
+        float mass     = massFilter.calcMedian();
+        medianSamples  = 0;
 
-    logSample(pressure, mass);
+        logSample(pressure, mass);
 
-    {
-        Lock<FastMutex> lock(sampleMutex);
-        pressureSample = pressure;
-        massSample     = mass;
+        {
+            Lock<FastMutex> lock(sampleMutex);
+            pressureSample = pressure;
+            massSample     = mass;
+        }
     }
 }
 
diff --git a/src/boards/RIGv2/StateMachines/TARS1/TARS1.h b/src/boards/RIGv2/StateMachines/TARS1/TARS1.h
index 7422ba1f856839fc55f179d2f5b65bca562a817f..9367d8e339b465ff543ba80f0d4b4c84a652845a 100644
--- a/src/boards/RIGv2/StateMachines/TARS1/TARS1.h
+++ b/src/boards/RIGv2/StateMachines/TARS1/TARS1.h
@@ -26,6 +26,8 @@
 #include <miosix.h>
 #include <scheduler/TaskScheduler.h>
 #include <RIGv2/StateMachines/TARS1/TARS1Data.h>
+#include <RIGv2/StateMachines/TARS1/MedianFilter.h>
+#include <RIGv2/Configs/TARS1Config.h>
 
 #include <utils/ModuleManager/ModuleManager.hpp>
 
@@ -61,6 +63,10 @@ private:
     float previousPressure = 0;
     float currentPressure  = 0;
 
+    int medianSamples = 0;
+    MedianFilter<float, Config::TARS1::MEDIAN_SAMPLE_NUMBER> massFilter;
+    MedianFilter<float, Config::TARS1::MEDIAN_SAMPLE_NUMBER> pressureFilter;
+
     miosix::FastMutex sampleMutex;
     float massSample     = 0;
     float pressureSample = 0;