diff --git a/skyward-boardcore b/skyward-boardcore
index a68a5319fdc78c8fbd45ee2e614cda19724c6a6c..f57081da20964030a07990dd985afe5c845241f4 160000
--- a/skyward-boardcore
+++ b/skyward-boardcore
@@ -1 +1 @@
-Subproject commit a68a5319fdc78c8fbd45ee2e614cda19724c6a6c
+Subproject commit f57081da20964030a07990dd985afe5c845241f4
diff --git a/src/boards/Parafoil/Configs/SensorsConfig.h b/src/boards/Parafoil/Configs/SensorsConfig.h
index cca2faaeee649ab3c38c7975eea69a0c9b665714..8b573793b7716a6af5733e4f697b3b5c5c455bdc 100644
--- a/src/boards/Parafoil/Configs/SensorsConfig.h
+++ b/src/boards/Parafoil/Configs/SensorsConfig.h
@@ -24,16 +24,19 @@
 #include <drivers/adc/InternalADC.h>
 #include <drivers/usart/USART.h>
 #include <interfaces-impl/hwmapping.h>
-#include <sensors/ADS1118/ADS1118.h>
+#include <sensors/ADS131M08/ADS131M08Defs.h>
 #include <sensors/BMX160/BMX160Config.h>
+#include <sensors/H3LIS331DL/H3LIS331DL.h>
+// TODO change with H3LIS331DLdef when merge request is merged
 #include <sensors/LIS3MDL/LIS3MDL.h>
+#include <sensors/LPS22DF/LPS22DF.h>
 #include <sensors/calibration/AxisOrientation.h>
 
 namespace Parafoil
 {
 namespace SensorsConfig
 {
-constexpr unsigned int NUMBER_OF_SENSORS  = 8;
+constexpr unsigned int NUMBER_OF_SENSORS  = 9;
 constexpr uint32_t MAG_CALIBRATION_PERIOD = 100;  // [ms]
 
 // BMX160
@@ -59,6 +62,32 @@ constexpr unsigned int BMX160_ACC_DATA_SIZE    = 6;
 constexpr unsigned int BMX160_GYRO_DATA_SIZE   = 6;
 constexpr unsigned int BMX160_MAG_DATA_SIZE    = 8;
 
+// H3LIS331DL
+constexpr Boardcore::H3LIS331DLDefs::OutputDataRate H3LIS331DL_ODR =
+    Boardcore::H3LIS331DLDefs::OutputDataRate::ODR_400;
+constexpr Boardcore::H3LIS331DLDefs::BlockDataUpdate H3LIS331DL_BDU =
+    Boardcore::H3LIS331DLDefs::BlockDataUpdate::BDU_CONTINUOS_UPDATE;
+constexpr Boardcore::H3LIS331DLDefs::FullScaleRange H3LIS331DL_FSR =
+    Boardcore::H3LIS331DLDefs::FullScaleRange::FS_100;
+constexpr uint32_t H3LIS331DL_PERIOD = 10;  // [ms] 100Hz
+
+// LPS22DF
+constexpr Boardcore::LPS22DF::AVG LPS22DF_AVG = Boardcore::LPS22DF::AVG_4;
+constexpr Boardcore::LPS22DF::ODR LPS22DF_ODR = Boardcore::LPS22DF::ODR_100;
+constexpr uint32_t LPS22DF_PERIOD             = 20;  // [ms] 50Hz
+
+// UBXGPS
+constexpr uint8_t UBXGPS_SAMPLE_RATE = 5;
+constexpr uint32_t UBXGPS_PERIOD     = 1000 / UBXGPS_SAMPLE_RATE;  // [ms]
+
+// ADS
+constexpr Boardcore::ADS131M08Defs::OversamplingRatio
+    ADS131M08_OVERSAMPLING_RATIO =
+        Boardcore::ADS131M08Defs::OversamplingRatio::OSR_8192;
+constexpr bool ADS131M08_GLOBAL_CHOP_MODE = true;
+constexpr uint32_t ADS131M08_PERIOD       = 10;  // [ms] 100Hz
+//
+
 // UNUSED - How many bytes go into the fifo each second
 constexpr unsigned int BMX160_FIFO_FILL_RATE =
     BMX160_ACC_GYRO_ODR * (BMX160_FIFO_HEADER_SIZE + BMX160_ACC_DATA_SIZE +
@@ -78,35 +107,6 @@ constexpr Boardcore::LIS3MDL::ODR MAG_LIS_ODR = Boardcore::LIS3MDL::ODR_80_HZ;
 constexpr Boardcore::LIS3MDL::FullScale MAG_LIS_FULLSCALE =
     Boardcore::LIS3MDL::FS_4_GAUSS;
 
-// ADS1118 and connected sensors
-constexpr Boardcore::ADS1118::ADS1118Mux ADS1118_CH_STATIC_PORT =
-    Boardcore::ADS1118::MUX_AIN0_GND;
-constexpr Boardcore::ADS1118::ADS1118DataRate ADS1118_DR_STATIC_PORT =
-    Boardcore::ADS1118::DR_860;
-constexpr Boardcore::ADS1118::ADS1118Pga ADS1118_PGA_STATIC_PORT =
-    Boardcore::ADS1118::FSR_6_144;
-
-constexpr Boardcore::ADS1118::ADS1118Mux ADS1118_CH_PITOT_PORT =
-    Boardcore::ADS1118::MUX_AIN1_GND;
-constexpr Boardcore::ADS1118::ADS1118DataRate ADS1118_DR_PITOT_PORT =
-    Boardcore::ADS1118::DR_860;
-constexpr Boardcore::ADS1118::ADS1118Pga ADS1118_PGA_PITOT_PORT =
-    Boardcore::ADS1118::FSR_6_144;
-
-constexpr Boardcore::ADS1118::ADS1118Mux ADS1118_CH_DPL_PORT =
-    Boardcore::ADS1118::MUX_AIN2_GND;
-constexpr Boardcore::ADS1118::ADS1118DataRate ADS1118_DR_DPL_PORT =
-    Boardcore::ADS1118::DR_860;
-constexpr Boardcore::ADS1118::ADS1118Pga ADS1118_PGA_DPL_PORT =
-    Boardcore::ADS1118::FSR_6_144;
-
-// MS5803 barometer
-constexpr unsigned int MS5803_TEMP_DIVIDER = 5;
-
-// GPS
-static constexpr int UBXGPS_BAUD_RATE            = 460800;
-static constexpr unsigned int UBXGPS_SAMPLE_RATE = 10;
-
 // Internal ADC & Battery Voltage
 constexpr Boardcore::InternalADC::Channel ADC_BATTERY_VOLTAGE =
     Boardcore::InternalADC::Channel::CH5;
@@ -119,11 +119,7 @@ constexpr float BATTERY_VOLTAGE_COEFF = 5.98;
 // imprecision, avoid clearing the fifo before the interrupt
 constexpr unsigned int BMX160_SAMPLE_PERIOD =
     BMX160_FIFO_FILL_TIME * (BMX160_FIFO_WATERMARK + 30) * 4 / 1024;  // [ms]
-constexpr unsigned int LIS3MDL_SAMPLE_PERIOD = 15;                    // [ms]
-constexpr unsigned int MS5803_SAMPLE_PERIOD  = 15;                    // [ms]
-constexpr unsigned int UBXGPS_SAMPLE_PERIOD =
-    1000 / UBXGPS_SAMPLE_RATE;                              // [ms]
-constexpr unsigned int ADS1118_SAMPLE_PERIOD       = 6;     // [ms]
+constexpr unsigned int LIS3MDL_SAMPLE_PERIOD       = 15;
 constexpr unsigned int INTERNAL_ADC_SAMPLE_PERIOD  = 1000;  // [ms]
 constexpr unsigned int INTERNAL_TEMP_SAMPLE_PERIOD = 2000;  // [ms]
 
diff --git a/src/boards/Parafoil/Sensors/Sensors.cpp b/src/boards/Parafoil/Sensors/Sensors.cpp
index 854abae1cf44aa44a5938e367e4ee431ebca34e7..ed9621a30772def2e5c5aeccdfc69100493a12ce 100644
--- a/src/boards/Parafoil/Sensors/Sensors.cpp
+++ b/src/boards/Parafoil/Sensors/Sensors.cpp
@@ -61,20 +61,26 @@ LIS3MDLData Sensors::getLIS3MDLLastSample()
     miosix::Lock<FastMutex> l(lis3mdlMutex);
     return lis3mdl != nullptr ? lis3mdl->getLastSample() : LIS3MDLData{};
 }
-MS5803Data Sensors::getMS5803LastSample()
+H3LIS331DLData Sensors::getH3LISLastSample()
 {
-    miosix::Lock<FastMutex> l(ms5803Mutex);
-    return ms5803 != nullptr ? ms5803->getLastSample() : MS5803Data{};
+    miosix::Lock<FastMutex> l(h3lisMutex);
+    return h3lis331dl != nullptr ? h3lis331dl->getLastSample()
+                                 : H3LIS331DLData{};
+}
+LPS22DFData Sensors::getLPS22LastSample()
+{
+    miosix::Lock<FastMutex> l(lps22Mutex);
+    return lps22df != nullptr ? lps22df->getLastSample() : LPS22DFData{};
 }
 UBXGPSData Sensors::getUbxGpsLastSample()
 {
     miosix::Lock<FastMutex> l(ubxGpsMutex);
     return ubxGps != nullptr ? ubxGps->getLastSample() : UBXGPSData{};
 }
-ADS1118Data Sensors::getADS1118LastSample()
+ADS131M08Data Sensors::getADS131LastSample()
 {
-    miosix::Lock<FastMutex> l(ads1118Mutex);
-    return ads1118 != nullptr ? ads1118->getLastSample() : ADS1118Data{};
+    miosix::Lock<FastMutex> l(ads131Mutex);
+    return ads131 != nullptr ? ads131->getLastSample() : ADS131M08Data{};
 }
 InternalADCData Sensors::getInternalADCLastSample()
 {
@@ -118,9 +124,10 @@ bool Sensors::start()
     bmx160Init();
     bmx160WithCorrectionInit();
     lis3mdlInit();
-    ms5803Init();
+    h3lisInit();
+    lps22Init();
     ubxGpsInit();
-    ads1118Init();
+    ads131Init();
     internalADCInit();
     batteryVoltageInit();
 
@@ -266,73 +273,109 @@ void Sensors::lis3mdlInit()
 
     LOG_INFO(logger, "LIS3MDL setup done!");
 }
-void Sensors::ms5803Init()
+void Sensors::h3lisInit()
 {
+
     ModuleManager& modules = ModuleManager::getInstance();
 
-    SPIBusConfig spiConfig{};
-    spiConfig.mode         = SPI::Mode::MODE_3;
-    spiConfig.clockDivider = SPI::ClockDivider::DIV_16;
+    // Get the correct SPI configuration
+    SPIBusConfig config = H3LIS331DL::getDefaultSPIConfig();
+    config.clockDivider = SPI::ClockDivider::DIV_16;
 
-    ms5803 = new MS5803(modules.get<Buses>()->spi1,
-                        miosix::sensors::ms5803::cs::getPin(), spiConfig,
-                        MS5803_TEMP_DIVIDER);
+    // Create sensor instance with configured parameters
+    h3lis331dl = new H3LIS331DL(
+        modules.get<Buses>()->spi1, miosix::sensors::h3lis331dl::cs::getPin(),
+        config, H3LIS331DL_ODR, H3LIS331DL_BDU, H3LIS331DL_FSR);
 
-    SensorInfo info("MS5803", MS5803_SAMPLE_PERIOD,
-                    bind(&Sensors::ms5803Callback, this));
-    sensorMap.emplace(make_pair(ms5803, info));
+    // Emplace the sensor inside the map
+    SensorInfo info("H3LIS331DL", H3LIS331DL_PERIOD,
+                    bind(&Sensors::h3lisCallback, this));
+    sensorMap.emplace(make_pair(h3lis331dl, info));
 
-    auto ms5803Status =
-        ([&]() -> SensorInfo { return manager->getSensorInfo(ms5803); });
-    sensorsInit[sensorsCounter++] = ms5803Status;
+    // used for the sensor state
+    auto h3lis331Status =
+        ([&]() -> SensorInfo { return manager->getSensorInfo(h3lis331dl); });
+    sensorsInit[sensorsCounter++] = h3lis331Status;
+}
+void Sensors::lps22Init()
 
-    LOG_INFO(logger, "MS5803 setup done!");
+{
+    ModuleManager& modules = ModuleManager::getInstance();
+
+    // Get the correct SPI configuration
+    SPIBusConfig config = LPS22DF::getDefaultSPIConfig();
+    config.clockDivider = SPI::ClockDivider::DIV_16;
+
+    // Configure the device
+    LPS22DF::Config sensorConfig;
+    sensorConfig.avg = LPS22DF_AVG;
+    sensorConfig.odr = LPS22DF_ODR;
+
+    // Create sensor instance with configured parameters
+    lps22df = new LPS22DF(modules.get<Buses>()->spi1,
+                          miosix::sensors::lps22df::cs::getPin(), config,
+                          sensorConfig);
+
+    // Emplace the sensor inside the map
+    SensorInfo info("LPS22DF", LPS22DF_PERIOD,
+                    bind(&Sensors::lps22Callback, this));
+    sensorMap.emplace(make_pair(lps22df, info));
+
+    // used for the sensor state
+    auto lps22Status =
+        ([&]() -> SensorInfo { return manager->getSensorInfo(lps22df); });
+    sensorsInit[sensorsCounter++] = lps22Status;
 }
+
 void Sensors::ubxGpsInit()
 {
-    ubxGps =
-        new UBXGPSSerial(UBXGPS_BAUD_RATE, UBXGPS_SAMPLE_RATE, USART2, 9600);
+    ModuleManager& modules = ModuleManager::getInstance();
+
+    // Get the correct SPI configuration
+    SPIBusConfig config = UBXGPSSpi::getDefaultSPIConfig();
+    config.clockDivider = SPI::ClockDivider::DIV_64;
+
+    // Create sensor instance with configured parameters
+    ubxGps = new UBXGPSSpi(modules.get<Buses>()->spi1,
+                           miosix::sensors::ubxgps::cs::getPin(), config, 5);
 
-    SensorInfo info("UBXGPS", UBXGPS_SAMPLE_PERIOD,
+    // Emplace the sensor inside the map
+    SensorInfo info("UBXGPS", UBXGPS_PERIOD,
                     bind(&Sensors::ubxGpsCallback, this));
     sensorMap.emplace(make_pair(ubxGps, info));
 
-    auto ubxGpsStatus =
+    // used for the sensor state
+    auto ubxStatus =
         ([&]() -> SensorInfo { return manager->getSensorInfo(ubxGps); });
-    sensorsInit[sensorsCounter++] = ubxGpsStatus;
-
-    LOG_INFO(logger, "UbloxGPS setup done!");
+    sensorsInit[sensorsCounter++] = ubxStatus;
 }
-void Sensors::ads1118Init()
+void Sensors::ads131Init()
 {
     ModuleManager& modules = ModuleManager::getInstance();
 
-    SPIBusConfig spiConfig = ADS1118::getDefaultSPIConfig();
-    spiConfig.clockDivider = SPI::ClockDivider::DIV_64;
-
-    ADS1118::ADS1118Config config = ADS1118::ADS1118_DEFAULT_CONFIG;
-    config.bits.mode              = ADS1118::ADS1118Mode::CONTINUOUS_CONV_MODE;
-
-    ads1118 =
-        new ADS1118(modules.get<Buses>()->spi1,
-                    miosix::sensors::ads1118::cs::getPin(), config, spiConfig);
-
-    ads1118->enableInput(ADS1118_CH_STATIC_PORT, ADS1118_DR_STATIC_PORT,
-                         ADS1118_PGA_STATIC_PORT);
-    ads1118->enableInput(ADS1118_CH_PITOT_PORT, ADS1118_DR_PITOT_PORT,
-                         ADS1118_PGA_PITOT_PORT);
-    ads1118->enableInput(ADS1118_CH_DPL_PORT, ADS1118_DR_DPL_PORT,
-                         ADS1118_PGA_DPL_PORT);
-
-    SensorInfo info("ADS1118", ADS1118_SAMPLE_PERIOD,
-                    bind(&Sensors::ads1118Callback, this));
-    sensorMap.emplace(make_pair(ads1118, info));
-
-    auto ads1118Status =
-        ([&]() -> SensorInfo { return manager->getSensorInfo(ads1118); });
-    sensorsInit[sensorsCounter++] = ads1118Status;
-
-    LOG_INFO(logger, "ADS1118 adc setup done!");
+    // Configure the SPI
+    SPIBusConfig config;
+    config.clockDivider = SPI::ClockDivider::DIV_32;
+
+    // Configure the device
+    ADS131M08::Config sensorConfig;
+    sensorConfig.oversamplingRatio     = ADS131M08_OVERSAMPLING_RATIO;
+    sensorConfig.globalChopModeEnabled = ADS131M08_GLOBAL_CHOP_MODE;
+
+    // Create the sensor instance with configured parameters
+    ads131 = new ADS131M08(modules.get<Buses>()->spi1,
+                           miosix::sensors::ads131m08::cs::getPin(), config,
+                           sensorConfig);
+
+    // Emplace the sensor inside the map
+    SensorInfo info("ADS131M08", ADS131M08_PERIOD,
+                    bind(&Sensors::ads131Callback, this));
+    sensorMap.emplace(make_pair(ads131, info));
+
+    // used for the sensor state
+    auto ads131m08Status =
+        ([&]() -> SensorInfo { return manager->getSensorInfo(ads131); });
+    sensorsInit[sensorsCounter++] = ads131m08Status;
 }
 void Sensors::internalADCInit()
 {
@@ -409,9 +452,14 @@ void Sensors::lis3mdlCallback()
     LIS3MDLData lastSample = lis3mdl->getLastSample();
     Logger::getInstance().log(lastSample);
 }
-void Sensors::ms5803Callback()
+void Sensors::h3lisCallback()
+{
+    H3LIS331DLData lastSample = h3lis331dl->getLastSample();
+    Logger::getInstance().log(lastSample);
+}
+void Sensors::lps22Callback()
 {
-    MS5803Data lastSample = ms5803->getLastSample();
+    LPS22DFData lastSample = lps22df->getLastSample();
     Logger::getInstance().log(lastSample);
 }
 void Sensors::ubxGpsCallback()
@@ -419,9 +467,9 @@ void Sensors::ubxGpsCallback()
     UBXGPSData lastSample = ubxGps->getLastSample();
     Logger::getInstance().log(lastSample);
 }
-void Sensors::ads1118Callback()
+void Sensors::ads131Callback()
 {
-    ADS1118Data lastSample = ads1118->getLastSample();
+    ADS131M08Data lastSample = ads131->getLastSample();
     Logger::getInstance().log(lastSample);
 }
 void Sensors::internalADCCallback()
diff --git a/src/boards/Parafoil/Sensors/Sensors.h b/src/boards/Parafoil/Sensors/Sensors.h
index 0b13052c5b04df1889a577c6d1330bff01f77e27..2455fc52b9be707ac04bdd6d2fc99784b5892c76 100644
--- a/src/boards/Parafoil/Sensors/Sensors.h
+++ b/src/boards/Parafoil/Sensors/Sensors.h
@@ -23,14 +23,15 @@
 
 #include <Parafoil/Configs/SensorsConfig.h>
 #include <drivers/adc/InternalADC.h>
-#include <sensors/ADS1118/ADS1118.h>
+#include <sensors/ADS131M08/ADS131M08.h>
 #include <sensors/BMX160/BMX160.h>
 #include <sensors/BMX160/BMX160WithCorrection.h>
+#include <sensors/H3LIS331DL/H3LIS331DL.h>
 #include <sensors/LIS3MDL/LIS3MDL.h>
-#include <sensors/MS5803/MS5803.h>
+#include <sensors/LPS22DF/LPS22DF.h>
 #include <sensors/SensorData.h>
 #include <sensors/SensorManager.h>
-#include <sensors/UBXGPS/UBXGPSSerial.h>
+#include <sensors/UBXGPS/UBXGPSSpi.h>
 #include <sensors/analog/BatteryVoltageSensor.h>
 #include <sensors/calibration/SoftAndHardIronCalibration/SoftAndHardIronCalibration.h>
 
@@ -72,10 +73,11 @@ public:
 
     Boardcore::BMX160Data getBMX160LastSample();
     Boardcore::BMX160WithCorrectionData getBMX160WithCorrectionLastSample();
+    Boardcore::H3LIS331DLData getH3LISLastSample();
     Boardcore::LIS3MDLData getLIS3MDLLastSample();
-    Boardcore::MS5803Data getMS5803LastSample();
+    Boardcore::LPS22DFData getLPS22LastSample();
     Boardcore::UBXGPSData getUbxGpsLastSample();
-    Boardcore::ADS1118Data getADS1118LastSample();
+    Boardcore::ADS131M08Data getADS131LastSample();
     Boardcore::InternalADCData getInternalADCLastSample();
     Boardcore::BatteryVoltageSensorData getBatteryVoltageLastSample();
 
@@ -91,17 +93,20 @@ private:
     void bmx160WithCorrectionInit();
     void bmx160WithCorrectionCallback();
 
+    void h3lisInit();
+    void h3lisCallback();
+
     void lis3mdlInit();
     void lis3mdlCallback();
 
-    void ms5803Init();
-    void ms5803Callback();
+    void lps22Init();
+    void lps22Callback();
 
     void ubxGpsInit();
     void ubxGpsCallback();
 
-    void ads1118Init();
-    void ads1118Callback();
+    void ads131Init();
+    void ads131Callback();
 
     void internalADCInit();
     void internalADCCallback();
@@ -111,9 +116,10 @@ private:
 
     // Sensors instances
     Boardcore::LIS3MDL* lis3mdl         = nullptr;
-    Boardcore::MS5803* ms5803           = nullptr;
-    Boardcore::UBXGPSSerial* ubxGps     = nullptr;
-    Boardcore::ADS1118* ads1118         = nullptr;
+    Boardcore::H3LIS331DL* h3lis331dl   = nullptr;
+    Boardcore::LPS22DF* lps22df         = nullptr;
+    Boardcore::UBXGPSSpi* ubxGps        = nullptr;
+    Boardcore::ADS131M08* ads131        = nullptr;
     Boardcore::InternalADC* internalADC = nullptr;
 
     // Fake processed sensors
@@ -122,11 +128,12 @@ private:
 
     // Mutexes for sampling
     miosix::FastMutex lis3mdlMutex;
-    miosix::FastMutex ms5803Mutex;
+    miosix::FastMutex lps22Mutex;
+    miosix::FastMutex h3lisMutex;
     miosix::FastMutex bmx160Mutex;
     miosix::FastMutex bmx160WithCorrectionMutex;
     miosix::FastMutex ubxGpsMutex;
-    miosix::FastMutex ads1118Mutex;
+    miosix::FastMutex ads131Mutex;
     miosix::FastMutex internalADCMutex;
     miosix::FastMutex batteryVoltageMutex;
 
diff --git a/src/boards/Parafoil/StateMachines/NASController/NASController.cpp b/src/boards/Parafoil/StateMachines/NASController/NASController.cpp
index e523b404514abf3c79d3de864412af8a82047221..76e42ebf811efa81aa4dfbeb1e124dc7f0cf0a6b 100644
--- a/src/boards/Parafoil/StateMachines/NASController/NASController.cpp
+++ b/src/boards/Parafoil/StateMachines/NASController/NASController.cpp
@@ -83,8 +83,8 @@ void NASController::update()
             modules.get<Sensors>()->getBMX160WithCorrectionLastSample();
         UBXGPSData gpsData = modules.get<Sensors>()->getUbxGpsLastSample();
 
-        MS5803Data baroData = modules.get<Sensors>()->getMS5803LastSample();
-
+        LPS22DFData barometerData =
+            modules.get<Sensors>()->getLPS22LastSample();
         // NAS prediction
         nas.predictGyro(imuData);
         nas.predictAcc(imuData);
@@ -92,7 +92,7 @@ void NASController::update()
         // NAS correction
         nas.correctMag(imuData);
         nas.correctGPS(gpsData);
-        nas.correctBaro(baroData.pressure);
+        nas.correctBaro(barometerData.pressure);
         // Correct with accelerometer if the acceleration is in specs
         Vector3f acceleration  = static_cast<AccelerometerData>(imuData);
         float accelerationNorm = acceleration.norm();
@@ -146,8 +146,8 @@ void NASController::calibrate()
                      imuData.magneticFieldZ);
 
         // Static pressure barometer
-        MS5803Data barometerData =
-            modules.get<Sensors>()->getMS5803LastSample();
+        LPS22DFData barometerData =
+            modules.get<Sensors>()->getLPS22LastSample();
         pressure.add(barometerData.pressure);
 
         miosix::Thread::sleep(NASConfig::CALIBRATION_SLEEP_TIME);
diff --git a/src/boards/Parafoil/TMRepository/TMRepository.cpp b/src/boards/Parafoil/TMRepository/TMRepository.cpp
index 3828b44d1262c3ea9935706368436aaca552ab98..d0d0666db2875661af3d118fba4468b5d0e14321 100644
--- a/src/boards/Parafoil/TMRepository/TMRepository.cpp
+++ b/src/boards/Parafoil/TMRepository/TMRepository.cpp
@@ -159,7 +159,7 @@ mavlink_message_t TMRepository::packSystemTm(SystemTMList tmId, uint8_t msgId,
             tm.timestamp = TimestampTimer::getTimestamp();
 
             // Last samples
-            MS5803Data ms5803 = modules.get<Sensors>()->getMS5803LastSample();
+            auto lps22df = modules.get<Sensors>()->getLPS22LastSample();
             BMX160Data imu =
                 modules.get<Sensors>()->getBMX160WithCorrectionLastSample();
             UBXGPSData gps = modules.get<Sensors>()->getUbxGpsLastSample();
@@ -179,7 +179,7 @@ mavlink_message_t TMRepository::packSystemTm(SystemTMList tmId, uint8_t msgId,
             tm.wes_n = wind[0];
             tm.wes_e = wind[1];
 
-            tm.pressure_digi = ms5803.pressure;
+            tm.pressure_digi = lps22df.pressure;
 
             // Altitude agl
             tm.altitude_agl = -nasState.d;
@@ -233,7 +233,7 @@ mavlink_message_t TMRepository::packSystemTm(SystemTMList tmId, uint8_t msgId,
                                      .batVoltage;
             // tm.current_consumption =
             //     modules.get<Sensors>()->getCurrentLastSample().current;
-            tm.temperature  = ms5803.temperature;
+            tm.temperature  = lps22df.temperature;
             tm.logger_error = Logger::getInstance().getStats().lastWriteError;
 
             tm.battery_voltage = modules.get<Sensors>()
@@ -379,7 +379,7 @@ mavlink_message_t TMRepository::packSensorsTm(SensorsTMList sensorId,
         {
             mavlink_pressure_tm_t tm;
 
-            auto pressureData = modules.get<Sensors>()->getMS5803LastSample();
+            auto pressureData = modules.get<Sensors>()->getLPS22LastSample();
 
             tm.timestamp = pressureData.pressureTimestamp;
             strcpy(tm.sensor_name, "MS5803");
diff --git a/src/entrypoints/Parafoil/parafoil-entry.cpp b/src/entrypoints/Parafoil/parafoil-entry.cpp
index dbccf1c946c451120aa2258ac4e75234c6a3de43..e515c772b66e8ab74d919bfeeba3f861a2b7b196 100644
--- a/src/entrypoints/Parafoil/parafoil-entry.cpp
+++ b/src/entrypoints/Parafoil/parafoil-entry.cpp
@@ -162,10 +162,14 @@ int main()
     }
 
     // Start modules
-    if (!Logger::getInstance().testSDCard())
+    if (!Logger::getInstance().start())
     {
         initResult = false;
-        LOG_ERR(logger, "Error testing the Logger module");
+        LOG_ERR(logger, "Error starting the Logger module");
+    }
+    else
+    {
+        LOG_DEBUG(logger, "Logger started");
     }
 
     if (!EventBroker::getInstance().start())