From 16edb2c7d0ea42a05e91333e8ada95c5a5045e47 Mon Sep 17 00:00:00 2001
From: Alberto Nidasio <alberto.nidasio@skywarder.eu>
Date: Fri, 30 Jun 2023 16:00:40 +0000
Subject: [PATCH] [LPS22DF] Created driver of digital pressure sensor

---
 CMakeLists.txt                           |   3 +
 cmake/boardcore.cmake                    |   1 +
 src/shared/sensors/LPS22DF/LPS22DF.cpp   | 203 +++++++++++++++++++++++
 src/shared/sensors/LPS22DF/LPS22DF.h     | 152 +++++++++++++++++
 src/shared/sensors/LPS22DF/LPS22DFData.h |  52 ++++++
 src/shared/sensors/LPS22DF/LPS22DFDefs.h | 124 ++++++++++++++
 src/tests/sensors/test-lps22df.cpp       |  91 ++++++++++
 7 files changed, 626 insertions(+)
 create mode 100644 src/shared/sensors/LPS22DF/LPS22DF.cpp
 create mode 100644 src/shared/sensors/LPS22DF/LPS22DF.h
 create mode 100644 src/shared/sensors/LPS22DF/LPS22DFData.h
 create mode 100644 src/shared/sensors/LPS22DF/LPS22DFDefs.h
 create mode 100644 src/tests/sensors/test-lps22df.cpp

diff --git a/CMakeLists.txt b/CMakeLists.txt
index b449783ff..723e2f947 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -419,6 +419,9 @@ sbs_target(test-h3lis331dl stm32f407vg_stm32f4discovery)
 add_executable(test-lps28dfw src/tests/sensors/test-lps28dfw.cpp)
 sbs_target(test-lps28dfw stm32f767zi_nucleo)
 
+add_executable(test-lps22df src/tests/sensors/test-lps22df.cpp)
+sbs_target(test-lps22df stm32f767zi_nucleo)
+
 #-----------------------------------------------------------------------------#
 #                                Tests - Utils                                #
 #-----------------------------------------------------------------------------#
diff --git a/cmake/boardcore.cmake b/cmake/boardcore.cmake
index e88d029b7..85fa903a8 100644
--- a/cmake/boardcore.cmake
+++ b/cmake/boardcore.cmake
@@ -109,6 +109,7 @@ foreach(OPT_BOARD ${BOARDS})
         ${SBS_BASE}/src/shared/sensors/VN100/VN100.cpp
         ${SBS_BASE}/src/shared/sensors/LIS2MDL/LIS2MDL.cpp
         ${SBS_BASE}/src/shared/sensors/LPS28DFW/LPS28DFW.cpp
+        ${SBS_BASE}/src/shared/sensors/LPS22DF/LPS22DF.cpp
 
         # Calibration
         ${SBS_BASE}/src/shared/sensors/calibration/BiasCalibration/BiasCalibration.cpp
diff --git a/src/shared/sensors/LPS22DF/LPS22DF.cpp b/src/shared/sensors/LPS22DF/LPS22DF.cpp
new file mode 100644
index 000000000..41fe74fc2
--- /dev/null
+++ b/src/shared/sensors/LPS22DF/LPS22DF.cpp
@@ -0,0 +1,203 @@
+/* Copyright (c) 2023 Skyward Experimental Rocketry
+ * Author: Giulia Ghirardini
+ *
+ * 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 "LPS22DF.h"
+
+#include <drivers/timer/TimestampTimer.h>
+
+#include "LPS22DFDefs.h"
+
+using namespace Boardcore::LPS22DFDefs;
+
+namespace Boardcore
+{
+
+LPS22DF::LPS22DF(SPIBusInterface& bus, miosix::GpioPin cs)
+    : slave(bus, cs, getDefaultSPIConfig())
+{
+}
+
+LPS22DF::LPS22DF(SPIBusInterface& bus, miosix::GpioPin cs,
+                 SPIBusConfig spiConfig, Config config)
+    : slave(bus, cs, spiConfig), config(config)
+{
+}
+
+SPIBusConfig LPS22DF::getDefaultSPIConfig()
+{
+    SPIBusConfig spiConfig;
+    spiConfig.clockDivider = SPI::ClockDivider::DIV_256;
+    spiConfig.mode         = SPI::Mode::MODE_3;
+    spiConfig.byteOrder    = SPI::Order::LSB_FIRST;
+    return spiConfig;
+}
+
+bool LPS22DF::init()
+{
+    SPITransaction spi(slave);
+
+    if (isInitialized)
+    {
+        LOG_ERR(logger, "Attempted to initialized sensor twice");
+        lastError = ALREADY_INIT;
+        return false;
+    }
+
+    // Disable I2C and I3C interfaces
+    spi.writeRegister(IF_CTRL, IF_CTRL::I2C_I3C_DIS);
+
+    // Setting the actual sensor configurations (Mode, ODR, AVG)
+    setConfig(config);
+
+    lastError     = SensorErrors::NO_ERRORS;
+    isInitialized = true;
+    return true;
+}
+
+bool LPS22DF::selfTest()
+{
+    // Since the sensor doesn't provide any self-test feature we just try to
+    // probe the sensor and read his whoami register.
+    if (!isInitialized)
+    {
+        LOG_ERR(logger, "Invoked selfTest() but sensor was uninitialized");
+        lastError = NOT_INIT;
+        return false;
+    }
+
+    // Reading the whoami value to assure communication
+    SPITransaction spi(slave);
+    uint8_t whoamiValue = spi.readRegister(WHO_AM_I);
+
+    // Checking the whoami value to assure correct communication
+    if (whoamiValue != WHO_AM_I_VALUE)
+    {
+        LOG_ERR(logger, "WHO_AM_I: read 0x{:x} but expected 0x{:x}",
+                whoamiValue, WHO_AM_I_VALUE);
+        lastError = INVALID_WHOAMI;
+        return false;
+    }
+
+    return true;
+}
+
+void LPS22DF::setConfig(const Config& config)
+{
+    setAverage(config.avg);
+    setOutputDataRate(config.odr);
+}
+
+void LPS22DF::setAverage(AVG avg)
+{
+    SPITransaction spi(slave);
+
+    /**
+     * Since the CTRL_REG1 contains only the AVG and ODR settings, we use the
+     * internal driver state to set the register with the wanted ODR and AVG
+     * without previously reading it. This allows to avoid a useless
+     * transaction.
+     */
+    spi.writeRegister(CTRL_REG1, config.odr | avg);
+
+    config.avg = avg;
+}
+
+void LPS22DF::setOutputDataRate(ODR odr)
+{
+    SPITransaction spi(slave);
+
+    /**
+     * Since the CTRL_REG1 contains only the AVG and ODR settings, we use the
+     * internal driver state to set the register with the wanted ODR and AVG
+     * without previously reading it. This allows to avoid a useless
+     * transaction.
+     */
+    spi.writeRegister(CTRL_REG1, odr | config.avg);
+
+    config.odr = odr;
+}
+
+LPS22DFData LPS22DF::sampleImpl()
+{
+    SPITransaction spi(slave);
+
+    if (!isInitialized)
+    {
+        LOG_ERR(logger, "Invoked sampleImpl() but sensor was not initialized");
+        lastError = NOT_INIT;
+        return lastSample;
+    }
+
+    LPS22DFData data;
+    uint8_t statusValue = 0;
+
+    if (config.odr == ODR::ONE_SHOT)
+    {
+        // Reading previous value of Control Register 2
+        uint8_t ctrl_reg2_val = spi.readRegister(CTRL_REG2);
+
+        // Trigger sample
+        spi.writeRegister(CTRL_REG2, ctrl_reg2_val | CTRL_REG2::ONE_SHOT_START);
+
+        // Pull status register until the sample is ready
+        do
+        {
+            statusValue = spi.readRegister(STATUS);
+        } while (!(statusValue & (STATUS::P_DA | STATUS::T_DA)));
+    }
+    else
+    {
+        // Read status register value
+        statusValue = spi.readRegister(STATUS);
+    }
+
+    auto ts = TimestampTimer::getTimestamp();
+
+    // Sample pressure if data is available, return last sample otherwise
+    if (statusValue & STATUS::P_DA)
+    {
+        data.pressureTimestamp = ts;
+        data.pressure          = spi.readRegister24(PRESS_OUT_XL) / PRES_SENS;
+    }
+    else
+    {
+        lastError              = NO_NEW_DATA;
+        data.pressureTimestamp = lastSample.pressureTimestamp;
+        data.pressure          = lastSample.pressure;
+    }
+
+    // Sample temperature if data is available, return last sample otherwise
+    if (statusValue & STATUS::T_DA)
+    {
+        data.temperatureTimestamp = ts;
+        data.temperature          = spi.readRegister16(TEMP_OUT_L) / TEMP_SENS;
+    }
+    else
+    {
+        data.temperatureTimestamp = lastSample.temperatureTimestamp;
+        data.temperature          = lastSample.temperature;
+    }
+
+    return data;
+}
+
+}  // namespace Boardcore
diff --git a/src/shared/sensors/LPS22DF/LPS22DF.h b/src/shared/sensors/LPS22DF/LPS22DF.h
new file mode 100644
index 000000000..876c5fc49
--- /dev/null
+++ b/src/shared/sensors/LPS22DF/LPS22DF.h
@@ -0,0 +1,152 @@
+/* Copyright (c) 2023 Skyward Experimental Rocketry
+ * Author: Giulia Ghirardini
+ *
+ * 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/spi/SPIDriver.h>
+#include <sensors/Sensor.h>
+
+#include "LPS22DFData.h"
+
+namespace Boardcore
+{
+
+/**
+ * @brief Driver for LPS22DF, Low-power and high-precision MEMS pressure sensor.
+ */
+class LPS22DF : public Sensor<LPS22DFData>
+{
+public:
+    /**
+     * @brief Enumeration for Output Data Rate Configuration.
+     *
+     * Available are One shot (only one sample calculated when signal sent), 1
+     * Hz to 200 Hz. ODR configuration is valid for both pressure and
+     * temperature.
+     */
+    enum ODR : uint8_t
+    {
+        ONE_SHOT = 0b0000 << 3,
+        ODR_1    = 0b0001 << 3,
+        ODR_4    = 0b0010 << 3,
+        ODR_10   = 0b0011 << 3,
+        ODR_25   = 0b0100 << 3,
+        ODR_50   = 0b0101 << 3,
+        ODR_75   = 0b0110 << 3,
+        ODR_100  = 0b0111 << 3,
+        ODR_200  = 0b1000 << 3
+    };
+
+    /**
+     * @brief Oversampling average values.
+     *
+     * The value read from the sensor will actually be the average of multiple
+     * samples. Available are from 4 to 512 averaged samples.
+     *
+     * @warning For an AGV value of 512, 128, 64 the maximum ODR values are
+     * respectively of 25, 75 and 100 Hz. For any other AVG value all ODR
+     * configurations are possible.
+     */
+    enum AVG : uint8_t
+    {
+        AVG_4   = 0b000,
+        AVG_8   = 0b001,
+        AVG_16  = 0b010,
+        AVG_32  = 0b011,
+        AVG_64  = 0b100,
+        AVG_128 = 0b101,
+        AVG_512 = 0b111
+    };
+
+    /**
+     * @brief Struct that sums up all the settings of the sensor.
+     */
+    struct Config
+    {
+        ODR odr = ODR::ODR_25;
+        AVG avg = AVG::AVG_512;
+    };
+
+    /**
+     * @brief Constructor that stores the initial default settings (without
+     * applying them to the sensor).
+     * @param bus SPI bus.
+     * @param cs SPI Chip Select pin.
+     */
+    LPS22DF(SPIBusInterface& bus, miosix::GpioPin cs);
+
+    /**
+     * @brief Constructor that stores the initial settings (without applying
+     * them to the sensor).
+     * @param bus SPI bus.
+     * @param cs SPI Chip Select pin.
+     * @param config Sensor configuration.
+     */
+    LPS22DF(SPIBusInterface& bus, miosix::GpioPin cs, SPIBusConfig spiConfig,
+            Config config);
+
+    static SPIBusConfig getDefaultSPIConfig();
+
+    /**
+     * @brief Initializes the sensor with the current settings.
+     * @return true if initialization succeeded, false otherwise.
+     */
+    bool init() override;
+
+    /**
+     * @brief The self test method returns true if we read the right whoami
+     * value. We can't make a better self test due to the fact that the sensor
+     * doesn't support this feature.
+     * @return true if the right whoami has been read.
+     */
+    bool selfTest() override;
+
+    /**
+     * @brief Sets and saves the configurations passed on the parameters.
+     */
+    void setConfig(const Config& config);
+
+    /**
+     * @brief Sets and saves the oversampling on the sensor.
+     * @return True if setting succeeded, false otherwise.
+     */
+    void setAverage(AVG avg);
+
+    /**
+     * @brief Sets and saves the output data rate.
+     * @return True if setting succeeded, false otherwise.
+     */
+    void setOutputDataRate(ODR odr);
+
+private:
+    LPS22DFData sampleImpl() override;
+
+    SPISlave slave;
+    Config config;
+
+    bool isInitialized = false;
+
+    PrintLogger logger = Logging::getLogger("lps22df");
+};
+
+}  // namespace Boardcore
\ No newline at end of file
diff --git a/src/shared/sensors/LPS22DF/LPS22DFData.h b/src/shared/sensors/LPS22DF/LPS22DFData.h
new file mode 100644
index 000000000..5867f4e52
--- /dev/null
+++ b/src/shared/sensors/LPS22DF/LPS22DFData.h
@@ -0,0 +1,52 @@
+/* Copyright (c) 2023 Skyward Experimental Rocketry
+ * Author: Giulia Ghirardini
+ *
+ * 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 <sensors/SensorData.h>
+
+namespace Boardcore
+{
+
+struct LPS22DFData : public PressureData, public TemperatureData
+{
+    LPS22DFData() : PressureData{0, 0.0}, TemperatureData{0, 0.0} {}
+
+    LPS22DFData(uint64_t timestamp, float pressure, float temperature)
+        : PressureData{timestamp, pressure}, TemperatureData{timestamp,
+                                                             temperature}
+    {
+    }
+
+    static std::string header()
+    {
+        return "pressureTimestamp,pressure,temperatureTimestamp,temperature\n";
+    }
+
+    void print(std::ostream& os) const
+    {
+        os << pressureTimestamp << "," << pressure << ","
+           << temperatureTimestamp << "," << temperature << "\n";
+    }
+};
+
+}  // namespace Boardcore
diff --git a/src/shared/sensors/LPS22DF/LPS22DFDefs.h b/src/shared/sensors/LPS22DF/LPS22DFDefs.h
new file mode 100644
index 000000000..62dc2e0c0
--- /dev/null
+++ b/src/shared/sensors/LPS22DF/LPS22DFDefs.h
@@ -0,0 +1,124 @@
+/* Copyright (c) 2023 Skyward Experimental Rocketry
+ * Author: Giulia Ghirardini
+ *
+ * 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
+
+namespace Boardcore
+{
+
+namespace LPS22DFDefs
+{
+
+static constexpr uint32_t WHO_AM_I_VALUE = 0xb4;
+
+static constexpr float TEMP_SENS = 100;    ///< [LSB/°C]
+static constexpr float PRES_SENS = 40.96;  ///< [LSB/Pa]
+
+enum Registers : uint8_t
+{
+    INTERRUPT_CFG = 0x0b,  ///< Interrupt mode for pressure acquisition
+
+    THS_P_L = 0x0c,  ///< User-defined threshold LSB register
+    THS_P_H = 0x0d,  ///< User-defined threshold MSB register
+
+    IF_CTRL = 0x0e,  ///< Interface control register
+
+    WHO_AM_I = 0x0f,  ///< Device Who am I register
+
+    CTRL_REG1 = 0x10,  ///< Control Register 1 [ODR, AVG]
+    CTRL_REG2 = 0x11,  ///< Control Register 2
+    CTRL_REG3 = 0x12,  ///< Control Register 3
+    CTRL_REG4 = 0x13,  ///< Control Register 4
+
+    FIFO_CTRL = 0x14,  ///< FIFO control register
+    FIFO_WTM  = 0x15,  ///< FIFO threshold setting register
+
+    REF_P_L = 0x16,  ///< Reference pressure LSB data
+    REF_P_H = 0x17,  ///< Reference pressure MSB data
+
+    FIFO_STATUS1 = 0x25,  ///< FIFO status register 1
+    FIFO_STATUS2 = 0x26,  ///< FIFO status register 2
+
+    STATUS = 0x27,  ///< Status register
+
+    PRESS_OUT_XL = 0x28,  ///< Pressure output value LSB data
+    PRESS_OUT_L  = 0x29,  ///< Pressure output value middle data
+    PRESS_OUT_H  = 0x2a,  ///< Pressure output value MSB data
+
+    TEMP_OUT_L = 0x2b,  ///< Temperature output value LSB data
+    TEMP_OUT_H = 0x2c,  ///< Temperature output value MSB data
+
+    FIFO_DATA_OUT_PRESS_XL = 0x78,  ///< FIFO pressure output LSB data
+    FIFO_DATA_OUT_PRESS_L  = 0x79,  ///< FIFO pressure output middle data
+    FIFO_DATA_OUT_PRESS_H  = 0x7a,  ///< FIFO pressure output MSB data
+};
+
+enum IF_CTRL : uint8_t
+{
+    CS_PU_DIS   = 1 << 1,
+    INT_PD_DIS  = 1 << 2,
+    SDO_PU_EN   = 1 << 3,
+    SDA_PU_EN   = 1 << 4,
+    SIM         = 1 << 5,
+    I2C_I3C_DIS = 1 << 6,  ///< Disable I2C and I3C digital interfaces
+    INT_EN_I3C  = 1 << 7
+};
+
+enum CTRL_REG2 : uint8_t
+{
+    ONE_SHOT_START = 1 << 0,  ///< Enable one-shot mode
+    SWRESET        = 1 << 2,  ///< Software reset
+    BDU            = 1 << 3,  ///< Block data update
+    EN_LPFP        = 1 << 4,  ///< Enable low-pass filter on pressure data
+    LFPF_CFG       = 1 << 5,  ///< Low-pass filter configuration
+    FS_MODE        = 1 << 6,  ///< Full-scale selection
+    BOOT           = 1 << 7   ///< Reboot memory content
+};
+
+enum CTRL_REG3 : uint8_t
+{
+    IF_ADD_INC = 1 << 0,  ///< Increment register during a multiple byte access
+    PP_OD      = 1 << 1,  ///< Push-pull/open-drain selection on interrupt pin
+    INT_H_L    = 1 << 3   ///< Select interrupt active-high, active-low
+};
+
+enum CTRL_REG4 : uint8_t
+{
+    INT_F_OVR  = 1 << 0,  ///< FIFO overrun status on INT_DRDY pin
+    INT_F_WTM  = 1 << 1,  ///< FIFO threshold status on INT_DRDY pin
+    INT_F_FULL = 1 << 2,  ///< FIFO full flag on INT_DRDY pin
+    INT_EN     = 1 << 4,  ///< Interrupt signal on INT_DRDY pin
+    DRDY       = 1 << 5,  ///< Date-ready signal on INT_DRDY pin
+    DRDY_PLS   = 1 << 6   ///< Data-ready pulsed on INT_DRDY pin
+};
+
+enum STATUS : uint8_t
+{
+    P_DA = 1 << 0,  ///< Pressure data available
+    T_DA = 1 << 1,  ///< Temperature data available
+    P_OR = 1 << 4,  ///< Pressure data overrun
+    T_OR = 1 << 5   ///< Temperature data overrun
+};
+
+}  // namespace LPS22DFDefs
+
+}  // namespace Boardcore
\ No newline at end of file
diff --git a/src/tests/sensors/test-lps22df.cpp b/src/tests/sensors/test-lps22df.cpp
new file mode 100644
index 000000000..c23ffc3f4
--- /dev/null
+++ b/src/tests/sensors/test-lps22df.cpp
@@ -0,0 +1,91 @@
+/* Copyright (c) 2023 Skyward Experimental Rocketry
+ * Author: Giulia Ghirardini
+ *
+ * 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 <drivers/spi/SPIDriver.h>
+#include <miosix.h>
+#include <sensors/LPS22DF/LPS22DF.h>
+#include <utils/Debug.h>
+
+using namespace Boardcore;
+using namespace miosix;
+
+GpioPin clk(GPIOA_BASE, 5);
+GpioPin miso(GPIOA_BASE, 6);
+GpioPin mosi(GPIOA_BASE, 7);
+GpioPin cs(GPIOD_BASE, 14);
+
+int main()
+{
+    clk.mode(Mode::ALTERNATE);
+    clk.alternateFunction(5);
+    miso.mode(Mode::ALTERNATE);
+    miso.alternateFunction(5);
+    mosi.mode(Mode::ALTERNATE);
+    mosi.alternateFunction(5);
+    cs.mode(Mode::OUTPUT);
+    cs.high();
+
+    SPIBus bus(SPI1);
+
+    LPS22DF::Config config;
+    config.odr = LPS22DF::ONE_SHOT;
+    config.avg = LPS22DF::AVG_128;
+
+    LPS22DF sensor(bus, cs, LPS22DF::getDefaultSPIConfig(), config);
+
+    printf("Starting...\n");
+
+    if (!sensor.init())
+    {
+        printf("Init failed\n");
+        return 0;
+    }
+
+    if (!sensor.selfTest())
+    {
+        printf("Error: selfTest() returned false!\n");
+        // return 0;
+    }
+
+    printf("Trying one shot mode for 10 seconds\n");
+    for (int i = 0; i < 10 * 10; i++)
+    {
+        sensor.sample();
+        LPS22DFData data = sensor.getLastSample();
+
+        printf("%.2f C | %.2f Pa\n", data.temperature, data.pressure);
+
+        miosix::Thread::sleep(100);
+    }
+
+    printf("Now setting 10Hz continuous mode\n");
+    sensor.setOutputDataRate(LPS22DF::ODR_10);
+    while (true)
+    {
+        sensor.sample();
+        LPS22DFData data = sensor.getLastSample();
+
+        printf("%.2f C | %.2f Pa\n", data.temperature, data.pressure);
+
+        miosix::Thread::sleep(100);
+    }
+}
-- 
GitLab