diff --git a/CMakeLists.txt b/CMakeLists.txt
index 124b25d122f653a93147595d9b28d20f7ca1f29d..cdfe8fc38ffb106eeb966de8c630f26b9a0dc5fd 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -377,8 +377,11 @@ sbs_target(test-max31855 stm32f429zi_stm32f4discovery)
 add_executable(test-mpu9250 src/tests/sensors/test-mpu9250.cpp)
 sbs_target(test-mpu9250 stm32f429zi_skyward_parafoil)
 
-add_executable(test-ms5803 src/tests/sensors/test-ms5803.cpp)
-sbs_target(test-ms5803 stm32f429zi_skyward_death_stack_x)
+add_executable(test-ms5803-spi src/tests/sensors/test-ms5803-spi.cpp)
+sbs_target(test-ms5803-spi stm32f429zi_skyward_death_stack_x)
+
+add_executable(test-ms5803-i2c src/tests/sensors/test-ms5803-i2c.cpp)
+sbs_target(test-ms5803-i2c stm32f429zi_stm32f4discovery)
 
 add_executable(test-ubxgps-serial src/tests/sensors/test-ubxgps-serial.cpp)
 sbs_target(test-ubxgps-serial stm32f429zi_skyward_death_stack_x)
diff --git a/cmake/boardcore.cmake b/cmake/boardcore.cmake
index e9578c1be5dc6f02995299aaa5c88aa90bd03ffb..777fad422c136021d0b1f3d5255bc3867c72ab0a 100644
--- a/cmake/boardcore.cmake
+++ b/cmake/boardcore.cmake
@@ -93,6 +93,7 @@ foreach(OPT_BOARD ${BOARDS})
         ${SBS_BASE}/src/shared/sensors/MBLoadCell/MBLoadCell.cpp
         ${SBS_BASE}/src/shared/sensors/MPU9250/MPU9250.cpp
         ${SBS_BASE}/src/shared/sensors/MS5803/MS5803.cpp
+        ${SBS_BASE}/src/shared/sensors/MS5803/MS5803I2C.cpp
         ${SBS_BASE}/src/shared/sensors/SensorManager.cpp
         ${SBS_BASE}/src/shared/sensors/SensorSampler.cpp
         ${SBS_BASE}/src/shared/sensors/UBXGPS/UBXGPSSerial.cpp
diff --git a/src/shared/sensors/MS5803/MS5803.cpp b/src/shared/sensors/MS5803/MS5803.cpp
index b01661807d7f3aec58adaa36bb2c14d6c24f4409..681d662ee32cc18616093a1d5c7f83e6481acbf1 100644
--- a/src/shared/sensors/MS5803/MS5803.cpp
+++ b/src/shared/sensors/MS5803/MS5803.cpp
@@ -41,12 +41,13 @@ bool MS5803::init()
     SPITransaction transaction{spiSlave};
 
     // Read calibration data
-    calibrationData.sens     = readReg(transaction, REG_PROM_SENS_MASK);
-    calibrationData.off      = readReg(transaction, REG_PROM_OFF_MASK);
-    calibrationData.tcs      = readReg(transaction, REG_PROM_TCS_MASK);
-    calibrationData.tco      = readReg(transaction, REG_PROM_TCO_MASK);
-    calibrationData.tref     = readReg(transaction, REG_PROM_TREF_MASK);
-    calibrationData.tempsens = readReg(transaction, REG_PROM_TEMPSENS_MASK);
+    calibrationData.sens = transaction.readRegister16(REG_PROM_SENS_MASK);
+    calibrationData.off  = transaction.readRegister16(REG_PROM_OFF_MASK);
+    calibrationData.tcs  = transaction.readRegister16(REG_PROM_TCS_MASK);
+    calibrationData.tco  = transaction.readRegister16(REG_PROM_TCO_MASK);
+    calibrationData.tref = transaction.readRegister16(REG_PROM_TREF_MASK);
+    calibrationData.tempsens =
+        transaction.readRegister16(REG_PROM_TEMPSENS_MASK);
 
     LOG_INFO(
         logger,
@@ -63,8 +64,6 @@ MS5803Data MS5803::sampleImpl()
 {
     SPITransaction transaction{spiSlave};
 
-    uint8_t buffer[3];
-
     switch (deviceState)
     {
         case STATE_INIT:
@@ -77,11 +76,8 @@ MS5803Data MS5803::sampleImpl()
         case STATE_SAMPLED_TEMP:
         {
             // Read back the sampled temperature
-            transaction.readRegisters(REG_ADC_READ, buffer, 3);
-
-            uint32_t tmpRawTemperature = (uint32_t)buffer[2] |
-                                         ((uint32_t)buffer[1] << 8) |
-                                         ((uint32_t)buffer[0] << 16);
+            uint32_t tmpRawTemperature =
+                transaction.readRegister24(REG_ADC_READ);
             lastTemperatureTimestamp = TimestampTimer::getTimestamp();
 
             // Check if the value is valid
@@ -98,11 +94,7 @@ MS5803Data MS5803::sampleImpl()
         case STATE_SAMPLED_PRESS:
         {
             // Read back the sampled pressure
-            transaction.readRegisters(REG_ADC_READ, buffer, 3);
-
-            uint32_t tmpRawPressure = (uint32_t)buffer[2] |
-                                      ((uint32_t)buffer[1] << 8) |
-                                      ((uint32_t)buffer[0] << 16);
+            uint32_t tmpRawPressure = transaction.readRegister24(REG_ADC_READ);
 
             // Check if the value is valid
             if (tmpRawPressure != 0)
@@ -169,18 +161,10 @@ MS5803Data MS5803::updateData()
         (((((int64_t)rawPressure) * sens) / 2097152.0) - offs) / 32786.0;
 
     // Pressure in Pascal
-    float temp_ = temp / 100.0f;
+    temp /= 100.0f;
 
     return MS5803Data(TimestampTimer::getTimestamp(), pressure,
-                      lastTemperatureTimestamp, temp_);
-}
-
-uint16_t MS5803::readReg(SPITransaction& transaction, uint8_t reg)
-{
-    uint8_t rcv[2];
-    transaction.readRegisters(reg, rcv, 2);
-    uint16_t data = (rcv[0] << 8) | rcv[1];
-    return data;
+                      lastTemperatureTimestamp, temp);
 }
 
 }  // namespace Boardcore
diff --git a/src/shared/sensors/MS5803/MS5803.h b/src/shared/sensors/MS5803/MS5803.h
index c7dc06bc07aa73c6479353555427ca44e89b7c50..7147d7ffeeeedb61484c1ea8e9feb133256da5c1 100644
--- a/src/shared/sensors/MS5803/MS5803.h
+++ b/src/shared/sensors/MS5803/MS5803.h
@@ -96,8 +96,6 @@ private:
 
     MS5803Data updateData();
 
-    uint16_t readReg(SPITransaction& spi, uint8_t reg);
-
     SPISlave spiSlave;
 
     MS5803CalibrationData calibrationData;
diff --git a/src/shared/sensors/MS5803/MS5803I2C.cpp b/src/shared/sensors/MS5803/MS5803I2C.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..edb63bf951cba60e75321cc96a74f74c458971ed
--- /dev/null
+++ b/src/shared/sensors/MS5803/MS5803I2C.cpp
@@ -0,0 +1,213 @@
+
+/* Copyright (c) 2021 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
+ *
+ * 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.
+ */
+
+#include "MS5803I2C.h"
+
+#include <drivers/timer/TimestampTimer.h>
+
+namespace Boardcore
+{
+
+MS5803I2C::MS5803I2C(I2C& bus, uint16_t temperatureDivider)
+    : bus(bus), temperatureDivider(temperatureDivider)
+{
+}
+
+bool MS5803I2C::init()
+{
+    // Read calibration data
+    calibrationData.sens     = readReg(REG_PROM_SENS_MASK);
+    calibrationData.off      = readReg(REG_PROM_OFF_MASK);
+    calibrationData.tcs      = readReg(REG_PROM_TCS_MASK);
+    calibrationData.tco      = readReg(REG_PROM_TCO_MASK);
+    calibrationData.tref     = readReg(REG_PROM_TREF_MASK);
+    calibrationData.tempsens = readReg(REG_PROM_TEMPSENS_MASK);
+
+    LOG_INFO(
+        logger,
+        "sens={:X}, off={:X}, tcs={:X}, tco={:X}, tref={:X}, tempsens={:X}",
+        calibrationData.sens, calibrationData.off, calibrationData.tcs,
+        calibrationData.tco, calibrationData.tref, calibrationData.tempsens);
+
+    return true;
+}
+
+bool MS5803I2C::selfTest() { return true; }
+
+MS5803Data MS5803I2C::sampleImpl()
+{
+    uint8_t buffer[3];
+
+    switch (deviceState)
+    {
+        case STATE_INIT:
+        {
+            // Begin temperature sampling
+            uint8_t val = static_cast<uint8_t>(REG_CONVERT_D2_4096);
+            if (!bus.write(slaveConfig, &val, 1))
+            {
+                lastError = SensorErrors::BUS_FAULT;
+                return lastSample;
+            }
+            deviceState = STATE_SAMPLED_TEMP;
+            break;
+        }
+        case STATE_SAMPLED_TEMP:
+        {
+            // Read back the sampled temperature
+            if (!bus.readFromRegister(slaveConfig, REG_ADC_READ, buffer, 3))
+            {
+                lastError = SensorErrors::BUS_FAULT;
+                return lastSample;
+            }
+
+            uint32_t tmpRawTemperature = (uint32_t)buffer[2] |
+                                         ((uint32_t)buffer[1] << 8) |
+                                         ((uint32_t)buffer[0] << 16);
+            lastTemperatureTimestamp = TimestampTimer::getTimestamp();
+
+            // Check if the value is valid
+            if (tmpRawTemperature != 0)
+                rawTemperature = tmpRawTemperature;
+            else
+                LOG_ERR(logger, "The read raw temperature isn't valid");
+
+            // Begin pressure sampling
+            uint8_t val = static_cast<uint8_t>(REG_CONVERT_D1_4096);
+            if (!bus.write(slaveConfig, &val, 1))
+            {
+                lastError = SensorErrors::BUS_FAULT;
+                return lastSample;
+            }
+            deviceState = STATE_SAMPLED_PRESS;
+            break;
+        }
+        case STATE_SAMPLED_PRESS:
+        {
+            // Read back the sampled pressure
+            if (!bus.readFromRegister(slaveConfig, REG_ADC_READ, buffer, 3))
+            {
+                lastError = SensorErrors::BUS_FAULT;
+                return lastSample;
+            }
+
+            uint32_t tmpRawPressure = (uint32_t)buffer[2] |
+                                      ((uint32_t)buffer[1] << 8) |
+                                      ((uint32_t)buffer[0] << 16);
+
+            // Check if the value is valid
+            if (tmpRawPressure != 0)
+                rawPressure = tmpRawPressure;
+            else
+                LOG_ERR(logger, "The read raw pressure isn't valid");
+
+            lastSample = updateData();
+            // Check whether to read the pressure or the temperature
+            tempCounter++;
+            if (tempCounter % temperatureDivider == 0)
+            {
+                // Begin temperature sampling
+                uint8_t val = static_cast<uint8_t>(REG_CONVERT_D2_4096);
+                if (!bus.write(slaveConfig, &val, 1))
+                {
+                    lastError = SensorErrors::BUS_FAULT;
+                    return lastSample;
+                }
+                deviceState = STATE_SAMPLED_TEMP;
+            }
+            else
+            {
+                // Begin pressure sampling again
+                uint8_t val = static_cast<uint8_t>(REG_CONVERT_D1_4096);
+                if (!bus.write(slaveConfig, &val, 1))
+                {
+                    lastError = SensorErrors::BUS_FAULT;
+                    return lastSample;
+                }
+            }
+            break;
+        }
+        default:
+            break;
+    }
+
+    return lastSample;
+}
+
+MS5803Data MS5803I2C::updateData()
+{
+    // First order compensation
+    int32_t dt   = rawTemperature - (((uint32_t)calibrationData.tref) << 8);
+    int32_t temp = 2000 + (((uint64_t)dt * calibrationData.tempsens) >> 23);
+
+    int64_t offs = ((int64_t)calibrationData.off << 16) +
+                   (((int64_t)calibrationData.tco * dt) >> 7);
+    int64_t sens = ((int64_t)calibrationData.sens << 15) +
+                   (((int64_t)calibrationData.tcs * dt) >> 8);
+
+    int64_t t2 = 0, off2 = 0, sens2 = 0;
+
+    // Second order temperature compensation
+    if (temp < 2000)
+    {
+        t2    = (((int64_t)dt) * dt) >> 31;
+        off2  = 3 * (temp - 2000) * (temp - 2000);
+        sens2 = (7 * (temp - 2000) * (temp - 2000)) >> 3;
+
+        if (temp < -1500)
+            sens2 = sens2 + 2 * (temp + 1500) * (temp + 1500);
+    }
+    else if (temp >= 4500)
+    {
+        sens2 = sens2 - (((temp - 4500) * (temp - 4500)) >> 3);
+    }
+
+    temp = temp - t2;
+    offs = offs - off2;
+    sens = sens - sens2;
+
+    float pressure =
+        (((((int64_t)rawPressure) * sens) / 2097152.0) - offs) / 32786.0;
+
+    // Pressure in Pascal
+    temp /= 100.0f;
+
+    return MS5803Data(TimestampTimer::getTimestamp(), pressure,
+                      lastTemperatureTimestamp, temp);
+}
+
+uint16_t MS5803I2C::readReg(uint8_t reg)
+{
+    uint8_t rcv[2];
+
+    if (!bus.readFromRegister(slaveConfig, reg, rcv, 2))
+    {
+        lastError = SensorErrors::BUS_FAULT;
+        return 0;
+    }
+
+    uint16_t data = (rcv[0] << 8) | rcv[1];
+    return data;
+}
+
+}  // namespace Boardcore
diff --git a/src/shared/sensors/MS5803/MS5803I2C.h b/src/shared/sensors/MS5803/MS5803I2C.h
new file mode 100644
index 0000000000000000000000000000000000000000..96db302d636c1e11143b1faf5e6758df4e23b087
--- /dev/null
+++ b/src/shared/sensors/MS5803/MS5803I2C.h
@@ -0,0 +1,116 @@
+/* Copyright (c) 2015-2021 Skyward Experimental Rocketry
+ * Authors: Davide Benini, Matteo Piazzolla, Alain Carlucci, Alberto Nidasio
+ *
+ * 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 <diagnostic/PrintLogger.h>
+#include <drivers/i2c/I2C.h>
+#include <sensors/Sensor.h>
+
+#include "MS5803Data.h"
+
+namespace Boardcore
+{
+
+class MS5803I2C : public Sensor<MS5803Data>
+{
+public:
+    enum FSMStates
+    {
+        STATE_INIT = 0,
+        STATE_SAMPLED_TEMP,
+        STATE_SAMPLED_PRESS
+    };
+
+    enum MS5803Registers : uint8_t
+    {
+        REG_RESET = 0x1E,
+
+        // Conversion commands for pressure and output data resolution
+        REG_CONVERT_D1_256  = 0x40,  // Conversion time: 0.48-0.54-0.60ms
+        REG_CONVERT_D1_512  = 0x42,  // Conversion time: 0.95-1.06-1.17ms
+        REG_CONVERT_D1_1024 = 0x44,  // Conversion time: 1.88-2.08-2.28ms
+        REG_CONVERT_D1_2048 = 0x46,  // Conversion time: 3.72-4.13-4-54ms
+        REG_CONVERT_D1_4096 = 0x48,  // Conversion time: 7.40-8.22-9.04ms
+
+        // Conversion commands for temperature and output data resolution
+        REG_CONVERT_D2_256  = 0x50,  // Conversion time: 0.48-0.54-0.60ms
+        REG_CONVERT_D2_512  = 0x52,  // Conversion time: 0.95-1.06-1.17ms
+        REG_CONVERT_D2_1024 = 0x54,  // Conversion time: 1.88-2.08-2.28ms
+        REG_CONVERT_D2_2048 = 0x56,  // Conversion time: 3.72-4.13-4-54ms
+        REG_CONVERT_D2_4096 = 0x58,  // Conversion time: 7.40-8.22-9.04ms
+
+        // Read command for adc output
+        REG_ADC_READ = 0x00,
+
+        REG_PROM_SENS_MASK     = 0xA2,
+        REG_PROM_OFF_MASK      = 0xA4,
+        REG_PROM_TCS_MASK      = 0xA6,
+        REG_PROM_TCO_MASK      = 0xA8,
+        REG_PROM_TREF_MASK     = 0xAA,
+        REG_PROM_TEMPSENS_MASK = 0xAC,
+    };
+
+    static constexpr uint8_t TIMEOUT = 5;
+
+    explicit MS5803I2C(I2C& bus, uint16_t temperatureDivider = 1);
+
+    bool init() override;
+
+    bool selfTest() override;
+
+private:
+    /**
+     * Implements a state machines composed of 3 states:
+     * 1. Command pressure sample
+     * 2. Read Pressure sample & command temperature sample
+     * 3. Read temperature sample & command pressure sample
+     *
+     * After the first call to sample() (state 1), the machine
+     * transitions between states 2 and 3: The effective sampling rate is half
+     * the rate at which this function is called.
+     * Example: call sample() at 100 Hz -> Pressure & Temperature sample
+     * Rate = 50 Hz
+     */
+    MS5803Data sampleImpl() override;
+
+    MS5803Data updateData();
+
+    uint16_t readReg(uint8_t reg);
+
+    I2C& bus;
+    I2CDriver::I2CSlaveConfig slaveConfig{0x77, I2CDriver::Addressing::BIT7,
+                                          I2CDriver::Speed::STANDARD};
+
+    MS5803CalibrationData calibrationData;
+    uint16_t temperatureDivider;
+
+    uint8_t deviceState               = STATE_INIT;
+    uint32_t rawTemperature           = 0;
+    uint32_t rawPressure              = 0;
+    uint64_t lastTemperatureTimestamp = 0;
+    uint16_t tempCounter              = 0;
+
+    PrintLogger logger = Logging::getLogger("ms5803");
+};
+
+}  // namespace Boardcore
diff --git a/src/tests/sensors/test-ms5803-i2c.cpp b/src/tests/sensors/test-ms5803-i2c.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..d8d90cc7628a9b9880ba604f1d0b5bc6bf85d1a9
--- /dev/null
+++ b/src/tests/sensors/test-ms5803-i2c.cpp
@@ -0,0 +1,73 @@
+/* Copyright (c) 2018 Skyward Experimental Rocketry
+ * Author: Nuno Barcellos
+ *
+ * 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.
+ */
+
+#include <sensors/MS5803/MS5803I2C.h>
+
+using namespace Boardcore;
+using namespace miosix;
+
+GpioPin scl(GPIOA_BASE, 8);
+GpioPin sda(GPIOC_BASE, 9);
+/**
+ * This test is intended to be run on the Death Stack X
+ */
+
+int main()
+{
+    printf("Starting...\n");
+
+    I2C bus(I2C3, scl, sda);
+    I2CDriver::I2CSlaveConfig slaveConfig{0x76, I2CDriver::Addressing::BIT7,
+                                          I2CDriver::Speed::STANDARD};
+
+    while (true)
+    {
+        uint8_t reg = 0xD0;
+        uint8_t data;
+        if (bus.readRegister(slaveConfig, reg, data))
+            printf("data: 0x%02x\n", data);
+
+        delayMs(100);
+    }
+    // printf("2...\n");
+    // MS5803I2C sensor(bus, 10);
+
+    // printf("3...\n");
+
+    // if (!sensor.init())
+    // {
+    //     printf("MS5803 Init failed\n");
+    // }
+
+    // printf("pressureTimestamp,press,temperatureTimestamp,temp\n");
+
+    // while (true)
+    // {
+    //     sensor.sample();
+
+    //     MS5803Data data = sensor.getLastSample();
+    //     printf("%llu,%f,%llu,%f\n", data.pressureTimestamp, data.pressure,
+    //            data.temperatureTimestamp, data.temperature);
+
+    //     Thread::sleep(20);
+    // }
+}
diff --git a/src/tests/sensors/test-ms5803.cpp b/src/tests/sensors/test-ms5803-spi.cpp
similarity index 100%
rename from src/tests/sensors/test-ms5803.cpp
rename to src/tests/sensors/test-ms5803-spi.cpp