diff --git a/skyward-boardcore b/skyward-boardcore
index 9969c2790fc2bab95462750c2f761a0f40139e9f..390eb97c2e750be2c3bbad6b959d0dbf86f3470c 160000
--- a/skyward-boardcore
+++ b/skyward-boardcore
@@ -1 +1 @@
-Subproject commit 9969c2790fc2bab95462750c2f761a0f40139e9f
+Subproject commit 390eb97c2e750be2c3bbad6b959d0dbf86f3470c
diff --git a/src/boards/RIGv2/Configs/ActuatorsConfig.h b/src/boards/RIGv2/Configs/ActuatorsConfig.h
index c425cb54e24b991fe37749b8760d805f0ceb3e12..1f831c6d6e72e8ba581320377d866004d6611bad 100644
--- a/src/boards/RIGv2/Configs/ActuatorsConfig.h
+++ b/src/boards/RIGv2/Configs/ActuatorsConfig.h
@@ -54,8 +54,8 @@ 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    = 0.70f;
+static constexpr float VENTING_LIMIT = 0.50f;
+static constexpr float MAIN_LIMIT    = 1.00f;
 
 static constexpr bool FILLING_FLIPPED    = true;
 static constexpr bool VENTING_FLIPPED    = false;
diff --git a/src/boards/RIGv2/Radio/Radio.cpp b/src/boards/RIGv2/Radio/Radio.cpp
index ae216506ec4cf97ff8c3c85ca78965684b539f19..60e7704f3a1386a3e1fd665e8476d6b2ccfe05c2 100644
--- a/src/boards/RIGv2/Radio/Radio.cpp
+++ b/src/boards/RIGv2/Radio/Radio.cpp
@@ -29,6 +29,7 @@
 #include <RIGv2/StateMachines/TARS1/TARS1.h>
 #include <common/Events.h>
 #include <common/Radio.h>
+#include <diagnostic/CpuMeter/CpuMeter.h>
 #include <events/EventBroker.h>
 #include <radio/SX1278/SX1278Frontends.h>
 // TODO(davide.mor): Remove TimestampTimer
@@ -150,9 +151,12 @@ void Radio::sendNack(const mavlink_message_t& msg)
 
 Boardcore::MavlinkStatus Radio::getMavStatus()
 {
-    if(mavDriver) {
+    if (mavDriver)
+    {
         return mavDriver->getStatus();
-    } else {
+    }
+    else
+    {
         return {};
     }
 }
@@ -476,7 +480,7 @@ bool Radio::packSystemTm(uint8_t tmId, mavlink_message_t& msg)
             tm.floating_level       = 69.0f;  // Lol
             // TODO(davide.mor): Add the rest of these
 
-            tm.battery_voltage     = 0.0f;
+            tm.battery_voltage     = CpuMeter::getCpuStats().mean;
             tm.current_consumption = sensors->getUmbilicalCurrent().current;
 
             mavlink_msg_motor_tm_encode(Config::Radio::MAV_SYSTEM_ID,
diff --git a/src/boards/RIGv2/Sensors/Sensors.cpp b/src/boards/RIGv2/Sensors/Sensors.cpp
index e4cd96281898c2b6f86b6eaf5748c35fd6a4d47c..99569c3beca18cfb65334f23a863c9d33114b0ea 100644
--- a/src/boards/RIGv2/Sensors/Sensors.cpp
+++ b/src/boards/RIGv2/Sensors/Sensors.cpp
@@ -60,7 +60,6 @@ bool Sensors::start()
 
 InternalADCData Sensors::getInternalADCLastSample()
 {
-    PauseKernelLock l;
     if (!internalAdc)
     {
         return {};
@@ -70,7 +69,6 @@ InternalADCData Sensors::getInternalADCLastSample()
 
 ADS131M08Data Sensors::getADC1LastSample()
 {
-    PauseKernelLock l;
     if (!adc1)
     {
         return {};
@@ -80,7 +78,6 @@ ADS131M08Data Sensors::getADC1LastSample()
 
 MAX31856Data Sensors::getTc1LastSample()
 {
-    PauseKernelLock l;
     if (!tc1)
     {
         return {};
@@ -91,7 +88,6 @@ MAX31856Data Sensors::getTc1LastSample()
 
 PressureData Sensors::getVesselPress()
 {
-    PauseKernelLock l;
     if (!vesselPressure)
     {
         return {};
@@ -101,7 +97,6 @@ PressureData Sensors::getVesselPress()
 
 PressureData Sensors::getFillingPress()
 {
-    PauseKernelLock l;
     if (!fillingPressure)
     {
         return {};
@@ -111,7 +106,6 @@ PressureData Sensors::getFillingPress()
 
 PressureData Sensors::getTopTankPress()
 {
-    PauseKernelLock l;
     if (!topTankPressure)
     {
         return {};
@@ -121,7 +115,6 @@ PressureData Sensors::getTopTankPress()
 
 PressureData Sensors::getBottomTankPress()
 {
-    PauseKernelLock l;
     if (!bottomTankPressure)
     {
         return {};
@@ -131,7 +124,6 @@ PressureData Sensors::getBottomTankPress()
 
 LoadCellData Sensors::getVesselWeight()
 {
-    PauseKernelLock l;
     if (!vesselWeight)
     {
         return {};
@@ -141,7 +133,6 @@ LoadCellData Sensors::getVesselWeight()
 
 LoadCellData Sensors::getTankWeight()
 {
-    PauseKernelLock l;
     if (!tankWeight)
     {
         return {};
@@ -315,6 +306,12 @@ void Sensors::adc1Callback()
                   sample.voltage[4], sample.voltage[5],
                   sample.voltage[6], sample.voltage[7]};
 
+    LOG_INFO(logger, "{:.4}\t{:.4}\t{:.4}\t{:.4}",
+             (sample.voltage[0] / Config::Sensors::ADC1_CH1_SHUNT_RESISTANCE) * 1000.0f,
+             (sample.voltage[1] / Config::Sensors::ADC1_CH2_SHUNT_RESISTANCE) * 1000.0f,
+             (sample.voltage[2] / Config::Sensors::ADC1_CH3_SHUNT_RESISTANCE) * 1000.0f,
+             (sample.voltage[3] / Config::Sensors::ADC1_CH4_SHUNT_RESISTANCE) * 1000.0f);
+
     /*printf("%.4f\t%.4f\t%.4f\t%.4f\t%.4f\t%.4f\t%.4f\t%.4f\n",
              sample.voltage[0], sample.voltage[1], sample.voltage[2],
              sample.voltage[3], sample.voltage[4], sample.voltage[5],
@@ -405,7 +402,7 @@ void Sensors::topTankPressureInit(Boardcore::SensorManager::SensorMap_t &map)
             auto sample = adc1->getLastSample();
             return sample.getVoltage(Config::Sensors::ADC1_TOP_PT_CHANNEL);
         },
-        Config::Sensors::ADC1_CH3_SHUNT_RESISTANCE,
+        Config::Sensors::ADC1_CH4_SHUNT_RESISTANCE,
         Config::Sensors::TANK_TOP_MAX_PRESSURE, Config::Sensors::PT_MIN_CURRENT,
         Config::Sensors::PT_MAX_CURRENT);
 
@@ -417,7 +414,7 @@ void Sensors::topTankPressureInit(Boardcore::SensorManager::SensorMap_t &map)
 void Sensors::topTankPressureCallback()
 {
     PressureData sample = topTankPressure->getLastSample();
-    PTsData data{sample.pressureTimestamp, 3, sample.pressure};
+    PTsData data{sample.pressureTimestamp, 3,  sample.pressure};
     sdLogger.log(data);
 }
 
@@ -429,7 +426,7 @@ void Sensors::bottomTankPressureInit(Boardcore::SensorManager::SensorMap_t &map)
             auto sample = adc1->getLastSample();
             return sample.getVoltage(Config::Sensors::ADC1_BOTTOM_PT_CHANNEL);
         },
-        Config::Sensors::ADC1_CH4_SHUNT_RESISTANCE,
+        Config::Sensors::ADC1_CH3_SHUNT_RESISTANCE,
         Config::Sensors::TANK_BOTTOM_MAX_PRESSURE,
         Config::Sensors::PT_MIN_CURRENT, Config::Sensors::PT_MAX_CURRENT);
 
diff --git a/src/boards/RIGv2/Sensors/Sensors.h b/src/boards/RIGv2/Sensors/Sensors.h
index 70069e3c60e544123651083dbc2ee2a71575cc47..9efdb1a974e363cfc8807ec2564c22351d80906d 100644
--- a/src/boards/RIGv2/Sensors/Sensors.h
+++ b/src/boards/RIGv2/Sensors/Sensors.h
@@ -64,7 +64,7 @@ public:
     Boardcore::LoadCellData getTankWeight();
     Boardcore::CurrentData getUmbilicalCurrent();
     Boardcore::CurrentData getServoCurrent();
-    VoltageData getBatteryVoltage();
+    Boardcore::VoltageData getBatteryVoltage();
 
     void calibrate();
 
diff --git a/src/boards/RIGv2/Sensors/SensorsData.h b/src/boards/RIGv2/Sensors/SensorsData.h
index d2d97acf293b5eae435f7bd26bf0d11256f05cc4..7f3239c6c84eca00ecb237490d4613cf1d45106e 100644
--- a/src/boards/RIGv2/Sensors/SensorsData.h
+++ b/src/boards/RIGv2/Sensors/SensorsData.h
@@ -112,24 +112,4 @@ struct PTsData : Boardcore::PressureData
            << "\n";
     }
 };
-
-struct VoltageData
-{
-    uint64_t voltageTimestamp;
-    float voltage;
-
-    VoltageData() : voltageTimestamp{0}, voltage{0} {}
-
-    VoltageData(uint64_t time, float voltage)
-        : voltageTimestamp{time}, voltage{voltage}
-    {
-    }
-
-    static std::string header() { return "timestamp,voltage\n"; }
-
-    void print(std::ostream& os) const
-    {
-        os << voltageTimestamp << "," << voltage << "\n";
-    }
-};
 }  // namespace RIGv2
\ No newline at end of file