diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json
index 2a83b9b7e3b7a7342b6c74588a0b44059501c90a..dc630721eef6582109b785e60a3cefa307d246cf 100644
--- a/.vscode/c_cpp_properties.json
+++ b/.vscode/c_cpp_properties.json
@@ -8,7 +8,7 @@
             "defines": [
                 "DEBUG",
                 "_ARCH_CORTEXM4_STM32F4",
-                "_BOARD_STM32F407VG_STM32F4DISCOVERY",
+                "_BOARD_STM32F4DISCOVERY",
                 "_MIOSIX_BOARDNAME=stm32f407vg_stm32f4discovery",
                 "HSE_VALUE=8000000",
                 "SYSCLK_FREQ_168MHz=168000000",
@@ -213,23 +213,23 @@
             }
         },
         {
-            "name": "stm32f429zi_parafoil",
+            "name": "stm32f429zi_skyward_parafoil",
             "cStandard": "c11",
             "cppStandard": "c++11",
             "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++",
             "defines": [
                 "DEBUG",
                 "_ARCH_CORTEXM4_STM32F4",
-                "_BOARD_STM32F429ZI_PARAFOIL",
-                "_MIOSIX_BOARDNAME=stm32f429zi_parafoil",
+                "_BOARD_STM32F429ZI_SKYWARD_PARAFOIL",
+                "_MIOSIX_BOARDNAME=stm32f429zi_skyward_parafoil",
                 "HSE_VALUE=8000000",
                 "SYSCLK_FREQ_168MHz=168000000",
                 "_MIOSIX",
                 "__cplusplus=201103L"
             ],
             "includePath": [
-                "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_parafoil",
-                "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_parafoil",
+                "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil",
+                "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil",
                 "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common",
                 "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common",
                 "${workspaceFolder}/libs/miosix-kernel/miosix",
@@ -243,8 +243,8 @@
             ],
             "browse": {
                 "path": [
-                    "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_parafoil",
-                    "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_parafoil",
+                    "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil",
+                    "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil",
                     "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common",
                     "${workspaceFolder}/libs/miosix-kernel/miosix/stdlib_integration",
                     "${workspaceFolder}/libs/miosix-kernel/miosix/arch/common",
@@ -319,7 +319,7 @@
             }
         },
         {
-            "name": "stm32f429zi_skyward_ciuti",
+            "name": "stm32f205rc_skyward_ciuti",
             "cStandard": "c11",
             "cppStandard": "c++11",
             "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++",
@@ -373,4 +373,4 @@
         }
     ],
     "version": 4
-}
\ No newline at end of file
+}
diff --git a/.vscode/settings.json b/.vscode/settings.json
index 499e63fbe0bc2fbf8adf05ba283e4de56d1fb77a..caa4ff15bf38b4658d34a4bf0af6745b62d54e44 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -1,246 +1,264 @@
 {
-    "cmake.configureSettings": {
-        "CMAKE_C_COMPILER_LAUNCHER": "ccache",
-        "CMAKE_CXX_COMPILER_LAUNCHER": "ccache"
-    },
-    "cmake.parallelJobs": 1,
-    "files.associations": {
-        "sstream": "cpp",
-        "format": "cpp",
-        "any": "cpp",
-        "array": "cpp",
-        "atomic": "cpp",
-        "bit": "cpp",
-        "*.tcc": "cpp",
-        "bitset": "cpp",
-        "cctype": "cpp",
-        "chrono": "cpp",
-        "clocale": "cpp",
-        "cmath": "cpp",
-        "codecvt": "cpp",
-        "complex": "cpp",
-        "condition_variable": "cpp",
-        "cstdarg": "cpp",
-        "cstddef": "cpp",
-        "cstdint": "cpp",
-        "cstdio": "cpp",
-        "cstdlib": "cpp",
-        "cstring": "cpp",
-        "ctime": "cpp",
-        "cwchar": "cpp",
-        "cwctype": "cpp",
-        "deque": "cpp",
-        "list": "cpp",
-        "map": "cpp",
-        "set": "cpp",
-        "unordered_map": "cpp",
-        "vector": "cpp",
-        "exception": "cpp",
-        "algorithm": "cpp",
-        "functional": "cpp",
-        "iterator": "cpp",
-        "memory": "cpp",
-        "memory_resource": "cpp",
-        "numeric": "cpp",
-        "optional": "cpp",
-        "random": "cpp",
-        "ratio": "cpp",
-        "regex": "cpp",
-        "string": "cpp",
-        "string_view": "cpp",
-        "system_error": "cpp",
-        "tuple": "cpp",
-        "type_traits": "cpp",
-        "utility": "cpp",
-        "fstream": "cpp",
-        "future": "cpp",
-        "initializer_list": "cpp",
-        "iomanip": "cpp",
-        "iosfwd": "cpp",
-        "iostream": "cpp",
-        "istream": "cpp",
-        "limits": "cpp",
-        "mutex": "cpp",
-        "new": "cpp",
-        "ostream": "cpp",
-        "shared_mutex": "cpp",
-        "stdexcept": "cpp",
-        "streambuf": "cpp",
-        "thread": "cpp",
-        "cinttypes": "cpp",
-        "typeindex": "cpp",
-        "typeinfo": "cpp",
-        "variant": "cpp",
-        "__config": "cpp",
-        "__threading_support": "cpp",
-        "__mutex_base": "cpp",
-        "__tree": "cpp",
-        "locale": "cpp",
-        "__bit_reference": "cpp",
-        "__bits": "cpp",
-        "__debug": "cpp",
-        "__errc": "cpp",
-        "__functional_base": "cpp",
-        "__hash_table": "cpp",
-        "__locale": "cpp",
-        "__node_handle": "cpp",
-        "__nullptr": "cpp",
-        "__split_buffer": "cpp",
-        "__string": "cpp",
-        "__tuple": "cpp",
-        "ios": "cpp",
-        "queue": "cpp",
-        "stack": "cpp",
-        "__functional_03": "cpp",
-        "filesystem": "cpp",
-        "unordered_set": "cpp",
-        "hash_map": "cpp",
-        "valarray": "cpp",
-        "ranges": "cpp",
-        "compare": "cpp",
-        "concepts": "cpp",
-        "core": "cpp",
-        "iterativelinearsolvers": "cpp",
-        "pastixsupport": "cpp",
-        "superlusupport": "cpp",
-        "adolcforward": "cpp",
-        "alignedvector3": "cpp",
-        "bvh": "cpp",
-        "fft": "cpp",
-        "iterativesolvers": "cpp",
-        "mprealsupport": "cpp",
-        "matrixfunctions": "cpp",
-        "nonlinearoptimization": "cpp",
-        "openglsupport": "cpp",
-        "polynomials": "cpp",
-        "autodiff": "cpp",
-        "sparseextra": "cpp",
-        "specialfunctions": "cpp"
-    },
-    "cSpell.words": [
-        "aelf",
-        "airbrakes",
-        "Airbrakes",
-        "Alessandro",
-        "AMSL",
-        "atthr",
-        "AVDD",
-        "Baro",
-        "boardcore",
-        "Boardcorev",
-        "boudrate",
-        "Corigliano",
-        "CORTEXM",
-        "cpitch",
-        "cppcheck",
-        "croll",
-        "cwise",
-        "cyaw",
-        "DATABUS",
-        "deleteme",
-        "DMEIE",
-        "Doxyfile",
-        "doxygen",
-        "DRDY",
-        "Duca",
-        "Ecompass",
-        "Eigen",
-        "elfs",
-        "Erbetta",
-        "Fatt",
-        "Fatttr",
-        "fedetft's",
-        "fiprintf",
-        "Gatttr",
-        "getdetahstate",
-        "GNSS",
-        "Gpio",
-        "GPIOA",
-        "GPIOB",
-        "GPIOC",
-        "GPIOD",
-        "GPIOE",
-        "GPIOF",
-        "GPIOG",
-        "GPIOS",
-        "gpstr",
-        "Hatt",
-        "HSCMAND",
-        "HSCMRNN",
-        "HWMAPPING",
-        "IDLEIE",
-        "irqn",
-        "irqv",
-        "Kalman",
-        "Katt",
-        "kbps",
-        "ldrex",
-        "leds",
-        "LIFCR",
-        "logdecoder",
-        "Luca",
-        "MEKF",
-        "MINC",
-        "miosix",
-        "mkdir",
-        "mosfet",
-        "mosi",
-        "MPXHZ",
-        "Musso",
-        "NATT",
-        "NBAR",
-        "NDTR",
-        "NGPS",
-        "NMAG",
-        "NMEA",
-        "NMEKF",
-        "nord",
-        "NVIC",
-        "peripehral",
-        "PINC",
-        "Pitot",
-        "Plin",
-        "Qgbw",
-        "Qget",
-        "Qhandle",
-        "Qput",
-        "Qwait",
-        "Qwakeup",
-        "Riccardo",
-        "RXNE",
-        "RXNEIE",
-        "sats",
-        "Satt",
-        "sdio",
-        "SDRAM",
-        "spitch",
-        "sqdip",
-        "sqtrp",
-        "sroll",
-        "SSCDANN",
-        "SSCDRRN",
-        "stof",
-        "syaw",
-        "TCIE",
-        "TEIE",
-        "Terraneo",
-        "testsuite",
-        "TSCPP",
-        "Ublox",
-        "UBXACK",
-        "UBXGPS",
-        "UBXNAV",
-        "Unsync",
-        "upcounter",
-        "USART",
-        "vbat",
-        "velnord",
-        "vout",
-        "vsense",
-        "Xbee",
-        "xnord",
-        "yned"
-    ],
-    "cSpell.language": "en",
-    "cSpell.enabled": true
+        "cmake.configureSettings": {
+                "CMAKE_C_COMPILER_LAUNCHER": "ccache",
+                "CMAKE_CXX_COMPILER_LAUNCHER": "ccache"
+        },
+        "cmake.parallelJobs": 1,
+        "files.associations": {
+                "sstream": "cpp",
+                "format": "cpp",
+                "any": "cpp",
+                "array": "cpp",
+                "atomic": "cpp",
+                "bit": "cpp",
+                "*.tcc": "cpp",
+                "bitset": "cpp",
+                "cctype": "cpp",
+                "chrono": "cpp",
+                "clocale": "cpp",
+                "cmath": "cpp",
+                "codecvt": "cpp",
+                "complex": "cpp",
+                "condition_variable": "cpp",
+                "cstdarg": "cpp",
+                "cstddef": "cpp",
+                "cstdint": "cpp",
+                "cstdio": "cpp",
+                "cstdlib": "cpp",
+                "cstring": "cpp",
+                "ctime": "cpp",
+                "cwchar": "cpp",
+                "cwctype": "cpp",
+                "deque": "cpp",
+                "list": "cpp",
+                "map": "cpp",
+                "set": "cpp",
+                "unordered_map": "cpp",
+                "vector": "cpp",
+                "exception": "cpp",
+                "algorithm": "cpp",
+                "functional": "cpp",
+                "iterator": "cpp",
+                "memory": "cpp",
+                "memory_resource": "cpp",
+                "numeric": "cpp",
+                "optional": "cpp",
+                "random": "cpp",
+                "ratio": "cpp",
+                "regex": "cpp",
+                "string": "cpp",
+                "string_view": "cpp",
+                "system_error": "cpp",
+                "tuple": "cpp",
+                "type_traits": "cpp",
+                "utility": "cpp",
+                "fstream": "cpp",
+                "future": "cpp",
+                "initializer_list": "cpp",
+                "iomanip": "cpp",
+                "iosfwd": "cpp",
+                "iostream": "cpp",
+                "istream": "cpp",
+                "limits": "cpp",
+                "mutex": "cpp",
+                "new": "cpp",
+                "ostream": "cpp",
+                "shared_mutex": "cpp",
+                "stdexcept": "cpp",
+                "streambuf": "cpp",
+                "thread": "cpp",
+                "cinttypes": "cpp",
+                "typeindex": "cpp",
+                "typeinfo": "cpp",
+                "variant": "cpp",
+                "__config": "cpp",
+                "__threading_support": "cpp",
+                "__mutex_base": "cpp",
+                "__tree": "cpp",
+                "locale": "cpp",
+                "__bit_reference": "cpp",
+                "__bits": "cpp",
+                "__debug": "cpp",
+                "__errc": "cpp",
+                "__functional_base": "cpp",
+                "__hash_table": "cpp",
+                "__locale": "cpp",
+                "__node_handle": "cpp",
+                "__nullptr": "cpp",
+                "__split_buffer": "cpp",
+                "__string": "cpp",
+                "__tuple": "cpp",
+                "ios": "cpp",
+                "queue": "cpp",
+                "stack": "cpp",
+                "__functional_03": "cpp",
+                "filesystem": "cpp",
+                "unordered_set": "cpp",
+                "hash_map": "cpp",
+                "valarray": "cpp",
+                "ranges": "cpp",
+                "compare": "cpp",
+                "concepts": "cpp",
+                "core": "cpp",
+                "iterativelinearsolvers": "cpp",
+                "pastixsupport": "cpp",
+                "superlusupport": "cpp",
+                "adolcforward": "cpp",
+                "alignedvector3": "cpp",
+                "bvh": "cpp",
+                "fft": "cpp",
+                "iterativesolvers": "cpp",
+                "mprealsupport": "cpp",
+                "matrixfunctions": "cpp",
+                "nonlinearoptimization": "cpp",
+                "openglsupport": "cpp",
+                "polynomials": "cpp",
+                "autodiff": "cpp",
+                "sparseextra": "cpp",
+                "specialfunctions": "cpp"
+        },
+        "cSpell.words": [
+                "ADCPRE",
+                "ADON",
+                "aelf",
+                "airbrakes",
+                "Airbrakes",
+                "Alessandro",
+                "AMSL",
+                "atthr",
+                "AVDD",
+                "Baro",
+                "boardcore",
+                "Boardcorev",
+                "boudrate",
+                "Corigliano",
+                "CORTEXM",
+                "cpitch",
+                "cppcheck",
+                "croll",
+                "cwise",
+                "cyaw",
+                "DATABUS",
+                "deleteme",
+                "DMEIE",
+                "Doxyfile",
+                "doxygen",
+                "DRDY",
+                "Duca",
+                "Ecompass",
+                "Eigen",
+                "elfs",
+                "Erbetta",
+                "Fatt",
+                "Fatttr",
+                "fedetft's",
+                "fiprintf",
+                "Gatttr",
+                "getdetahstate",
+                "GNSS",
+                "Gpio",
+                "GPIOA",
+                "GPIOB",
+                "GPIOC",
+                "GPIOD",
+                "GPIOE",
+                "GPIOF",
+                "GPIOG",
+                "GPIOS",
+                "gpstr",
+                "Hatt",
+                "HIFCR",
+                "HISR",
+                "HSCMAND",
+                "HSCMRNN",
+                "HWMAPPING",
+                "IDLEIE",
+                "irqn",
+                "irqv",
+                "JEOC",
+                "JOFR",
+                "JSQR",
+                "JSWSTART",
+                "Kalman",
+                "Katt",
+                "kbps",
+                "ldrex",
+                "leds",
+                "LIFCR",
+                "LISR",
+                "logdecoder",
+                "Luca",
+                "Matteo",
+                "MEKF",
+                "microcontrollers",
+                "MINC",
+                "miosix",
+                "mkdir",
+                "mosfet",
+                "mosi",
+                "MPXHZ",
+                "Musso",
+                "NATT",
+                "NBAR",
+                "NDTR",
+                "NGPS",
+                "Nidasio",
+                "NMAG",
+                "NMEA",
+                "NMEKF",
+                "nord",
+                "NVIC",
+                "peripehral",
+                "Piazzolla",
+                "PINC",
+                "Pitot",
+                "Plin",
+                "Qgbw",
+                "Qget",
+                "Qhandle",
+                "Qput",
+                "Qwait",
+                "Qwakeup",
+                "Riccardo",
+                "RXNE",
+                "RXNEIE",
+                "sats",
+                "Satt",
+                "sdio",
+                "SDRAM",
+                "smpr",
+                "SMPR",
+                "spitch",
+                "sqdip",
+                "sqtrp",
+                "sroll",
+                "SSCDANN",
+                "SSCDRRN",
+                "stof",
+                "SWSTART",
+                "syaw",
+                "TCIE",
+                "TCIF",
+                "TEIE",
+                "Terraneo",
+                "testsuite",
+                "TSCPP",
+                "TSVREFE",
+                "Ublox",
+                "UBXACK",
+                "UBXGPS",
+                "UBXNAV",
+                "Unsync",
+                "upcounter",
+                "USART",
+                "vbat",
+                "velnord",
+                "vout",
+                "vsense",
+                "Xbee",
+                "xnord",
+                "yned"
+        ],
+        "cSpell.language": "en",
+        "cSpell.enabled": true
 }
\ No newline at end of file
diff --git a/CMakeLists.txt b/CMakeLists.txt
index e69d0759e5b07c981fc6fb1bbfdc0996171d3cc7..3dec47d98c5ef5522710677cddbbb93df618f99d 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -40,19 +40,19 @@ add_executable(config-dsgamma src/entrypoints/config-dsgamma.cpp)
 sbs_target(config-dsgamma stm32f429zi_stm32f4discovery)
 
 add_executable(imu-calibration src/entrypoints/imu-calibration.cpp)
-sbs_target(imu-calibration stm32f429zi_parafoil)
+sbs_target(imu-calibration stm32f429zi_skyward_parafoil)
 
 add_executable(mxgui-helloworld src/entrypoints/examples/mxgui-helloworld.cpp)
 sbs_target(mxgui-helloworld stm32f429zi_stm32f4discovery)
 
 add_executable(kernel-testsuite src/entrypoints/kernel-testsuite.cpp)
-sbs_target(kernel-testsuite stm32f429zi_stm32f4discovery)
+sbs_target(kernel-testsuite stm32f205rc_skyward_ciuti)
 
 add_executable(runcam-settings src/entrypoints/runcam-settings.cpp)
 sbs_target(runcam-settings stm32f407vg_stm32f4discovery)
 
 add_executable(sdcard-benchmark src/entrypoints/sdcard-benchmark.cpp)
-sbs_target(sdcard-benchmark stm32f429zi_skyward_death_stack_x)
+sbs_target(sdcard-benchmark stm32f205rc_skyward_ciuti)
 
 #-----------------------------------------------------------------------------#
 #                                    Tests                                    #
@@ -133,13 +133,13 @@ add_executable(test-kalman-benchmark src/tests/algorithms/Kalman/test-kalman-ben
 sbs_target(test-kalman-benchmark stm32f429zi_stm32f4discovery)
 
 add_executable(test-attitude-parafoil src/tests/algorithms/NAS/test-attitude-parafoil.cpp)
-sbs_target(test-attitude-parafoil stm32f429zi_parafoil)
+sbs_target(test-attitude-parafoil stm32f429zi_skyward_parafoil)
 
 add_executable(test-attitude-stack src/tests/algorithms/NAS/test-attitude-stack.cpp)
 sbs_target(test-attitude-stack stm32f429zi_skyward_death_stack_x)
 
 add_executable(test-nas-parafoil src/tests/algorithms/NAS/test-nas-parafoil.cpp)
-sbs_target(test-nas-parafoil stm32f429zi_parafoil)
+sbs_target(test-nas-parafoil stm32f429zi_skyward_parafoil)
 
 add_executable(test-nas-stack src/tests/algorithms/NAS/test-nas-stack.cpp)
 sbs_target(test-nas-stack stm32f429zi_skyward_death_stack_x)
@@ -151,7 +151,7 @@ add_executable(test-triad src/tests/algorithms/NAS/test-triad.cpp)
 sbs_target(test-triad stm32f429zi_skyward_death_stack_x)
 
 add_executable(test-triad-parafoil src/tests/algorithms/NAS/test-triad-parafoil.cpp)
-sbs_target(test-triad-parafoil stm32f429zi_parafoil)
+sbs_target(test-triad-parafoil stm32f429zi_skyward_parafoil)
 
 add_executable(test-ada src/tests/algorithms/ADA/test-ada.cpp)
 sbs_target(test-ada stm32f429zi_skyward_death_stack_v3)
@@ -178,7 +178,7 @@ add_executable(test-general-purpose-timer src/tests/drivers/timer/test-general-p
 sbs_target(test-general-purpose-timer stm32f429zi_stm32f4discovery)
 
 add_executable(test-internal-adc src/tests/drivers/test-internal-adc.cpp)
-sbs_target(test-internal-adc stm32f429zi_skyward_death_stack_x)
+sbs_target(test-internal-adc stm32f407vg_stm32f4discovery)
 
 add_executable(test-internal-adc-dma src/tests/drivers/test-internal-adc-dma.cpp)
 sbs_target(test-internal-adc-dma stm32f429zi_stm32f4discovery)
@@ -231,6 +231,9 @@ sbs_target(test-xbee-snd stm32f429zi_stm32f4discovery)
 add_executable(test-usart src/tests/drivers/usart/test-usart.cpp)
 sbs_target(test-usart stm32f407vg_stm32f4discovery)
 
+add_executable(test-internal-temp src/tests/drivers/test-internal-temp.cpp)
+sbs_target(test-internal-temp stm32f407vg_stm32f4discovery)
+
 #-----------------------------------------------------------------------------#
 #                               Tests - Events                                #
 #-----------------------------------------------------------------------------#
@@ -349,7 +352,7 @@ add_executable(test-max31855 src/tests/sensors/test-max31855.cpp)
 sbs_target(test-max31855 stm32f429zi_stm32f4discovery)
 
 add_executable(test-mpu9250 src/tests/sensors/test-mpu9250.cpp)
-sbs_target(test-mpu9250 stm32f429zi_parafoil)
+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)
diff --git a/cmake/boardcore.cmake b/cmake/boardcore.cmake
index 6521be8564ea0db4942ef95c52f26cbbc9cf2c67..b853f0628a71eb8045e1dc9c036fcd5e25d394dc 100644
--- a/cmake/boardcore.cmake
+++ b/cmake/boardcore.cmake
@@ -43,6 +43,7 @@ foreach(OPT_BOARD ${BOARDS})
         ${SBS_BASE}/src/shared/diagnostic/PrintLogger.cpp
 
         # Drivers
+        ${SBS_BASE}/src/shared/drivers/adc/InternalTemp.cpp
         ${SBS_BASE}/src/shared/drivers/adc/InternalADC.cpp
         ${SBS_BASE}/src/shared/drivers/canbus/Canbus.cpp
         ${SBS_BASE}/src/shared/drivers/canbus/CanInterrupt.cpp
@@ -80,6 +81,7 @@ foreach(OPT_BOARD ${BOARDS})
         ${SBS_BASE}/src/shared/sensors/BMX160/BMX160WithCorrection.cpp
         ${SBS_BASE}/src/shared/sensors/HX711/HX711.cpp
         ${SBS_BASE}/src/shared/sensors/LIS3MDL/LIS3MDL.cpp
+        ${SBS_BASE}/src/shared/sensors/LIS331HH/LIS331HH.cpp
         ${SBS_BASE}/src/shared/sensors/calibration/SensorDataExtra.cpp
         ${SBS_BASE}/src/shared/sensors/MAX6675/MAX6675.cpp
         ${SBS_BASE}/src/shared/sensors/MAX31855/MAX31855.cpp
@@ -98,6 +100,7 @@ foreach(OPT_BOARD ${BOARDS})
         # Utils
         ${SBS_BASE}/src/shared/utils/AeroUtils/AeroUtils.cpp
         ${SBS_BASE}/src/shared/utils/ButtonHandler/ButtonHandler.cpp
+        ${SBS_BASE}/src/shared/utils/PinObserver/PinObserver.cpp
         ${SBS_BASE}/src/shared/utils/SkyQuaternion/SkyQuaternion.cpp
         ${SBS_BASE}/src/shared/utils/Stats/Stats.cpp
         ${SBS_BASE}/src/shared/utils/TestUtils/TestHelper.cpp
diff --git a/libs/mavlink-skyward-lib b/libs/mavlink-skyward-lib
index 4874d08b4a6340d6a9da8da9a33f96b8f01d789b..be1b8d4f61c546548d8b0c7d128dd304c9c49476 160000
--- a/libs/mavlink-skyward-lib
+++ b/libs/mavlink-skyward-lib
@@ -1 +1 @@
-Subproject commit 4874d08b4a6340d6a9da8da9a33f96b8f01d789b
+Subproject commit be1b8d4f61c546548d8b0c7d128dd304c9c49476
diff --git a/libs/miosix-kernel b/libs/miosix-kernel
index 80ae230d328892074ef362c46f8ed72ec07a3141..d63a8905149e04e1db2fb813ec2f1e3e46f3734e 160000
--- a/libs/miosix-kernel
+++ b/libs/miosix-kernel
@@ -1 +1 @@
-Subproject commit 80ae230d328892074ef362c46f8ed72ec07a3141
+Subproject commit d63a8905149e04e1db2fb813ec2f1e3e46f3734e
diff --git a/libs/mxgui b/libs/mxgui
index 3ce4e0588633ead6328e65b1e711ea39375a805e..4416880780cbf6f3aa4792d4260a15554c89fa6b 160000
--- a/libs/mxgui
+++ b/libs/mxgui
@@ -1 +1 @@
-Subproject commit 3ce4e0588633ead6328e65b1e711ea39375a805e
+Subproject commit 4416880780cbf6f3aa4792d4260a15554c89fa6b
diff --git a/src/shared/algorithms/AirBrakes/TrajectoryPoint.h b/src/shared/algorithms/AirBrakes/TrajectoryPoint.h
index 18e880d67efeddd34fc3456228392b6f184da7b7..da4adfb069e08f6d50691a1fd3e148f251ac3da1 100644
--- a/src/shared/algorithms/AirBrakes/TrajectoryPoint.h
+++ b/src/shared/algorithms/AirBrakes/TrajectoryPoint.h
@@ -78,7 +78,7 @@ public:
     TimedTrajectoryPoint() : TrajectoryPoint(), timestamp(0), vMod(0) {}
 
     explicit TimedTrajectoryPoint(NASState state)
-        : TrajectoryPoint(-state.d, -state.vn), timestamp(state.timestamp),
+        : TrajectoryPoint(-state.d, -state.vd), timestamp(state.timestamp),
           vMod(Eigen::Vector3f{state.vn, state.ve, state.vd}.norm())
     {
     }
diff --git a/src/shared/diagnostic/CpuMeter/CpuMeter.cpp b/src/shared/diagnostic/CpuMeter/CpuMeter.cpp
index 20da1e5af5a2dd6618c7ad46f9e2780c469468ca..57990c49ff064d0d5ae08ddf6c703c0c1e87a2c9 100644
--- a/src/shared/diagnostic/CpuMeter/CpuMeter.cpp
+++ b/src/shared/diagnostic/CpuMeter/CpuMeter.cpp
@@ -45,7 +45,11 @@ static volatile unsigned int update = 0;
 CpuMeterData getCpuStats()
 {
     Lock<FastMutex> l(utilizationMutex);
-    return CpuMeterData(TimestampTimer::getTimestamp(), utilization.getStats());
+    return CpuMeterData(TimestampTimer::getTimestamp(), utilization.getStats(),
+                        MemoryProfiling::getAbsoluteFreeHeap(),
+                        MemoryProfiling::getCurrentFreeHeap(),
+                        MemoryProfiling::getAbsoluteFreeStack(),
+                        MemoryProfiling::getCurrentFreeStack());
 }
 
 void resetCpuStats() { utilization.reset(); }
diff --git a/src/shared/diagnostic/CpuMeter/CpuMeterData.h b/src/shared/diagnostic/CpuMeter/CpuMeterData.h
index f091425f98bdeadf8f1a5d7f2ecf4d9719ac6b3c..a28b62a3a270284e38e808cdaae6f2fe2c1b8af6 100644
--- a/src/shared/diagnostic/CpuMeter/CpuMeterData.h
+++ b/src/shared/diagnostic/CpuMeter/CpuMeterData.h
@@ -36,12 +36,20 @@ struct CpuMeterData
     float stdDev       = 0;  ///< Standard deviation of dataset.
     uint32_t nSamples  = 0;  ///< Number of samples.
 
+    uint32_t minFreeHeap  = 0;
+    uint32_t freeHeap     = 0;
+    uint32_t minFreeStack = 0;
+    uint32_t freeStack    = 0;
+
     CpuMeterData() {}
 
-    explicit CpuMeterData(uint64_t timestamp, StatsResult stats)
+    explicit CpuMeterData(uint64_t timestamp, StatsResult stats,
+                          uint32_t freeHeap, uint32_t minFreeHeap,
+                          uint32_t minFreeStack, uint32_t freeStack)
         : timestamp(timestamp), minValue(stats.minValue),
           maxValue(stats.maxValue), mean(stats.mean), stdDev(stats.stdDev),
-          nSamples(stats.nSamples)
+          nSamples(stats.nSamples), minFreeHeap(minFreeHeap),
+          freeHeap(freeHeap), minFreeStack(minFreeStack), freeStack(freeStack)
     {
     }
 
diff --git a/src/shared/diagnostic/SkywardStack.h b/src/shared/diagnostic/SkywardStack.h
index 8b85e44b0965153080f462b80cd08aaac55c6f5b..6a27d747f85267406a2c73daa1b727e8b70bc77e 100644
--- a/src/shared/diagnostic/SkywardStack.h
+++ b/src/shared/diagnostic/SkywardStack.h
@@ -27,7 +27,11 @@
 namespace Boardcore
 {
 
+#ifndef _ARCH_CORTEXM3_STM32F2
 static const unsigned int STACK_MIN_FOR_SKYWARD = 16 * 1024;
+#else
+static const unsigned int STACK_MIN_FOR_SKYWARD = 1024;
+#endif
 
 inline unsigned int skywardStack(unsigned int stack)
 {
diff --git a/src/shared/drivers/adc/InternalADC.cpp b/src/shared/drivers/adc/InternalADC.cpp
index 5599223012b51872d29bec8cfdee357fa9fb0f33..737b2b6bc040925b2f7268ebc6154edcb17f25b3 100644
--- a/src/shared/drivers/adc/InternalADC.cpp
+++ b/src/shared/drivers/adc/InternalADC.cpp
@@ -72,9 +72,7 @@ InternalADC::InternalADC(ADC_TypeDef* adc, const float supplyVoltage,
 
     // Init indexMap
     for (auto i = 0; i < CH_NUM; i++)
-    {
         indexMap[i] = -1;
-    }
 }
 
 InternalADC::~InternalADC()
@@ -90,13 +88,13 @@ bool InternalADC::init()
     adc->CR2 |= ADC_CR2_ADON;
 
     // Set single conversion mode
-    adc->CR2 &= ~ADC_CR2_CONT;
+    // adc->CR2 &= ~ADC_CR2_CONT;
 
     // Set scan mode
-    adc->CR1 |= ADC_CR1_SCAN;
+    // adc->CR1 |= ADC_CR1_SCAN;
 
     // Data alignment
-    adc->CR2 &= ~ADC_CR2_ALIGN;  // right
+    // adc->CR2 &= ~ADC_CR2_ALIGN;  // right
 
     if (isUsingDMA)
     {
@@ -130,33 +128,22 @@ bool InternalADC::init()
     return true;
 }
 
-bool InternalADC::enableChannel(Channel channel)
-{
-    return enableChannel(channel, CYCLES_3);
-}
-
 bool InternalADC::enableChannel(Channel channel, SampleTime sampleTime)
 {
     // Check channel number
     if (channel < CH0 || channel >= CH_NUM)
-    {
         return false;
-    }
 
     // Add channel to the sequence
     if (!isUsingDMA)
     {
         if (!addInjectedChannel(channel))
-        {
             return false;
-        }
     }
     else
     {
         if (!addRegularChannel(channel))
-        {
             return false;
-        }
 
         // Update the DMA number of data
         dmaStream->NDTR = activeChannels;
@@ -168,6 +155,52 @@ bool InternalADC::enableChannel(Channel channel, SampleTime sampleTime)
     return true;
 }
 
+bool InternalADC::addRegularChannel(Channel channel)
+{
+    // Check active channels number
+    if (activeChannels >= 16)
+        return false;
+
+    // Add the channel to the sequence
+    volatile uint32_t* sqrPtr;
+    switch (activeChannels / 6)
+    {
+        case 1:
+            sqrPtr = &(adc->SQR2);
+            break;
+        case 2:
+            sqrPtr = &(adc->SQR1);
+            break;
+        default:
+            sqrPtr = &(adc->SQR3);
+    }
+    *sqrPtr = channel << ((activeChannels % 6) * 5);
+
+    // Update the channels number in the register
+    adc->SQR1 &= ~ADC_SQR1_L;
+    adc->SQR1 |= activeChannels << 20;
+
+    // Save the index of the channel in the ADC's regular sequence
+    indexMap[channel] = activeChannels;
+
+    // Update the counter
+    activeChannels++;
+
+    return true;
+}
+
+ADCData InternalADC::readChannel(Channel channel, SampleTime sampleTime)
+{
+    setChannelSampleTime(channel, sampleTime);
+    startRegularConversion();
+
+    while (!(adc->SR & ADC_SR_EOC))
+        ;
+
+    return {TimestampTimer::getTimestamp(), channel,
+            static_cast<uint16_t>(adc->DR) * supplyVoltage / RESOLUTION};
+}
+
 InternalADCData InternalADC::getVoltage(Channel channel)
 {
     float voltage = 0;
@@ -219,14 +252,14 @@ InternalADCData InternalADC::sampleImpl()
 
         // This should trigger the DMA stream for each channel's conversion
 
-        // Wait for tranfer end
+        // Wait for transfer end
         while (!(*statusReg & (transferCompleteMask | transferErrorMask)))
             ;
 
         // Clear the transfer complete flag
         *clearFlagReg |= transferCompleteMask;
 
-        // If and error has occurred (probaly due to a higher priority stream)
+        // If and error has occurred (probably due to a higher priority stream)
         // don't update the timestamp, the values should not have been updated
         if (*statusReg & transferErrorMask)
         {
@@ -244,6 +277,8 @@ InternalADCData InternalADC::sampleImpl()
     return lastSample;
 }
 
+float InternalADC::getSupplyVoltage() { return supplyVoltage; }
+
 inline void InternalADC::resetRegisters()
 {
     // Reset the ADC configuration
@@ -277,9 +312,7 @@ inline bool InternalADC::addInjectedChannel(Channel channel)
 {
     // Check active channels number
     if (activeChannels >= 4)
-    {
         return false;
-    }
 
     // Add the channel to the sequence, starting from position 4
     adc->JSQR |= channel << (15 - activeChannels * 5);
@@ -292,9 +325,7 @@ inline bool InternalADC::addInjectedChannel(Channel channel)
     for (auto i = 0; i < CH_NUM; i++)
     {
         if (indexMap[i] >= 0)
-        {
             indexMap[i]++;
-        }
     }
 
     // Set this channel index to 0
@@ -306,53 +337,15 @@ inline bool InternalADC::addInjectedChannel(Channel channel)
     return true;
 }
 
-inline bool InternalADC::addRegularChannel(Channel channel)
-{
-    // Check active channels number
-    if (activeChannels >= 16)
-    {
-        return false;
-    }
-
-    // Add the channel to the sequence
-    volatile uint32_t* sqrPtr;
-    switch (activeChannels % 6)
-    {
-        case 1:
-            sqrPtr = &(adc->SQR3);
-            break;
-        case 2:
-            sqrPtr = &(adc->SQR2);
-            break;
-        default:
-            sqrPtr = &(adc->SQR1);
-    }
-    *sqrPtr = channel << ((activeChannels % 6) * 5);
-
-    // Update the channels number in the register
-    adc->SQR1 |= activeChannels << 20;
-
-    // Save the index of the channel in the ADC's regular sequence
-    indexMap[channel] = activeChannels;
-
-    // Update the counter
-    activeChannels++;
-
-    return true;
-}
-
 inline void InternalADC::setChannelSampleTime(Channel channel,
                                               SampleTime sampleTime)
 {
     volatile uint32_t* smprPtr;
     if (channel <= 9)
-    {
         smprPtr = &(adc->SMPR2);
-    }
     else
-    {
         smprPtr = &(adc->SMPR1);
-    }
+
     *smprPtr = sampleTime << (channel * 3);
 }
 
diff --git a/src/shared/drivers/adc/InternalADC.h b/src/shared/drivers/adc/InternalADC.h
index 662419e817ef60eb8622b6326af3ad5f11bf3f72..ab0498619a7447080ab2efa4c6c6b7c53438e73b 100644
--- a/src/shared/drivers/adc/InternalADC.h
+++ b/src/shared/drivers/adc/InternalADC.h
@@ -90,6 +90,9 @@ public:
         CH13,
         CH14,
         CH15,
+        CH16,
+        CH17,
+        CH18,
         CH_NUM
     };
 
@@ -127,9 +130,14 @@ public:
      */
     bool init() override;
 
-    bool enableChannel(Channel channel);
+    /**
+     * @brief Make a regular conversion for the specified channel.
+     */
+    ADCData readChannel(Channel channel, SampleTime sampleTime = CYCLES_3);
+
+    bool enableChannel(Channel channel, SampleTime sampleTime = CYCLES_3);
 
-    bool enableChannel(Channel channel, SampleTime sampleTime);
+    bool addRegularChannel(Channel channel);
 
     InternalADCData getVoltage(Channel channel);
 
@@ -137,6 +145,8 @@ public:
 
     InternalADCData sampleImpl() override;
 
+    float getSupplyVoltage();
+
 private:
     inline void resetRegisters();
 
@@ -146,8 +156,6 @@ private:
 
     inline bool addInjectedChannel(Channel channel);
 
-    inline bool addRegularChannel(Channel channel);
-
     inline void setChannelSampleTime(Channel channel, SampleTime sampleTime);
 
     ADC_TypeDef* adc;
@@ -168,7 +176,7 @@ private:
      * We'll use up to 4 injected channel by default and up to 16 channels when
      * using DMA.
      *
-     * The differentiation is necessary because whitout DMA it is much simplier
+     * The differentiation is necessary because whiteout DMA it is much simpler
      * to use injected channel for multichannel readings. Otherwise we would
      * need to handle each channel's end of conversion interrupt or go through
      */
@@ -182,7 +190,7 @@ private:
     volatile uint32_t* clearFlagReg;
 
     static constexpr int INJECTED_CHANNEL_N = 4;
-    static constexpr int RESOLUTION         = 4096;  ///< 12 bits
+    static constexpr int RESOLUTION         = 4095;  ///< 12 bits
 };
 
 }  // namespace Boardcore
diff --git a/src/shared/drivers/adc/InternalTemp.cpp b/src/shared/drivers/adc/InternalTemp.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e6c15b2fc9629145d82ac9a6cb4f7fe6c63dcfec
--- /dev/null
+++ b/src/shared/drivers/adc/InternalTemp.cpp
@@ -0,0 +1,84 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Authors: 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 "InternalTemp.h"
+
+#ifdef _ARCH_CORTEXM4_STM32F4
+#define TEMP30_CAL_VALUE ((uint16_t*)((uint32_t)0x1FFF7A2C))
+#define TEMP110_CAL_VALUE ((uint16_t*)((uint32_t)0x1FFF7A2E))
+#define TEMP30 30
+#define TEMP110 110
+#endif
+
+namespace Boardcore
+{
+
+InternalTemp::InternalTemp(InternalADC::SampleTime sampleTime,
+                           const float supplyVoltage)
+    : adc(ADC1, supplyVoltage), sampleTime(sampleTime)
+{
+}
+
+bool InternalTemp::init()
+{
+    bool result = adc.init();
+
+#if defined(_BOARD_STM32F4DISCOVERY) || defined(_ARCH_CORTEXM3_STM32F2)
+    adc.addRegularChannel(InternalADC::CH16);
+#else
+    adc.addRegularChannel(InternalADC::CH18);
+#endif
+
+    ADC->CCR &= ~ADC_CCR_VBATE;
+    ADC->CCR |= ADC_CCR_TSVREFE;
+
+    return result;
+}
+
+bool InternalTemp::selfTest() { return adc.selfTest(); }
+
+InternalTempData InternalTemp::sampleImpl()
+{
+#if defined(_BOARD_STM32F4DISCOVERY) || defined(_ARCH_CORTEXM3_STM32F2)
+    auto adcData = adc.readChannel(InternalADC::CH16, sampleTime);
+#else
+    auto adcData = adc.readChannel(InternalADC::CH18, sampleTime);
+#endif
+
+    InternalTempData data;
+    data.temperatureTimestamp = adcData.voltageTimestamp;
+
+#ifdef _ARCH_CORTEXM3_STM32F2
+    // Default conversion
+    data.temperature = ((adcData.voltage - 0.76) / 0.0025) + 25;
+#else
+    // Factory calibration
+    float voltage30  = static_cast<float>(*TEMP30_CAL_VALUE) * 3.3 / 4095;
+    float voltage110 = static_cast<float>(*TEMP110_CAL_VALUE) * 3.3 / 4095;
+    float slope      = (voltage110 - voltage30) / (TEMP110 - TEMP30);
+    data.temperature = ((adcData.voltage - voltage30) / slope) + TEMP30;
+#endif
+
+    return data;
+}
+
+}  // namespace Boardcore
diff --git a/src/shared/drivers/adc/InternalTemp.h b/src/shared/drivers/adc/InternalTemp.h
new file mode 100644
index 0000000000000000000000000000000000000000..a66e32cafa0283ee463a82c0d8c7be4b3efa99a3
--- /dev/null
+++ b/src/shared/drivers/adc/InternalTemp.h
@@ -0,0 +1,51 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Authors: 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 <drivers/adc/InternalADC.h>
+
+#include "InternalTempData.h"
+
+namespace Boardcore
+{
+
+class InternalTemp : public Sensor<InternalTempData>
+{
+public:
+    explicit InternalTemp(
+        InternalADC::SampleTime sampleTime = InternalADC::CYCLES_480,
+        const float supplyVoltage          = 5.0);
+
+    bool init() override;
+
+    bool selfTest() override;
+
+    InternalTempData sampleImpl() override;
+
+    // InternalTempData addRegularChannel(InternalADC::Channel channel);
+
+private:
+    InternalADC adc;
+    InternalADC::SampleTime sampleTime;
+};
+
+}  // namespace Boardcore
diff --git a/src/shared/drivers/adc/InternalTempData.h b/src/shared/drivers/adc/InternalTempData.h
new file mode 100644
index 0000000000000000000000000000000000000000..96f709033d5cdcadb60b4d3e53f19d2da7901b90
--- /dev/null
+++ b/src/shared/drivers/adc/InternalTempData.h
@@ -0,0 +1,42 @@
+/* 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.
+ */
+
+#pragma once
+
+#include <sensors/SensorData.h>
+
+namespace Boardcore
+{
+
+struct InternalTempData : public TemperatureData
+{
+    InternalTempData() : TemperatureData{0, 0} {}
+
+    static std::string header() { return "timestamp,temperature\n"; }
+
+    void print(std::ostream& os) const
+    {
+        os << temperatureTimestamp << "," << temperature << "\n";
+    }
+};
+
+}  // namespace Boardcore
diff --git a/src/shared/logger/LogTypes.h b/src/shared/logger/LogTypes.h
index a2f7c2f1996beae88b85d0350576758218f6297d..309457505c60765b646868eed17381dc376ed5fc 100644
--- a/src/shared/logger/LogTypes.h
+++ b/src/shared/logger/LogTypes.h
@@ -23,6 +23,7 @@
 #pragma once
 
 #include <actuators/Servo/ServoData.h>
+#include <algorithms/ADA/ADAData.h>
 #include <algorithms/NAS/NASState.h>
 #include <diagnostic/CpuMeter/CpuMeter.h>
 #include <diagnostic/PrintLoggerData.h>
@@ -49,6 +50,7 @@
 #include <sensors/SensorData.h>
 #include <sensors/UBXGPS/UBXGPSData.h>
 #include <sensors/VN100/VN100Data.h>
+#include <sensors/analog/AnalogLoadCellData.h>
 #include <sensors/analog/BatteryVoltageSensorData.h>
 #include <sensors/analog/CurrentSensorData.h>
 #include <sensors/analog/pressure/honeywell/HSCMAND015PAData.h>
@@ -56,6 +58,8 @@
 #include <sensors/analog/pressure/honeywell/HSCMRNN160KAData.h>
 #include <sensors/analog/pressure/honeywell/SSCDANN030PAAData.h>
 #include <sensors/analog/pressure/honeywell/SSCDRRN015PDAData.h>
+#include <sensors/analog/pressure/nxp/MPXH6115AData.h>
+#include <sensors/analog/pressure/nxp/MPXH6400AData.h>
 #include <sensors/analog/pressure/nxp/MPXHZ6130AData.h>
 
 #include <fstream>
@@ -76,6 +80,7 @@ namespace LogTypes
 void registerTypes(Deserializer& ds)
 {
     ds.registerType<ServoData>();
+    ds.registerType<ADAState>();
     ds.registerType<NASState>();
     ds.registerType<CpuMeterData>();
     ds.registerType<LoggingString>();
@@ -103,14 +108,17 @@ void registerTypes(Deserializer& ds)
     ds.registerType<TemperatureData>();
     ds.registerType<UBXGPSData>();
     ds.registerType<VN100Data>();
+    ds.registerType<AnalogLoadCellData>();
     ds.registerType<BatteryVoltageSensorData>();
     ds.registerType<CurrentSensorData>();
-    ds.registerType<MPXHZ6130AData>();
     ds.registerType<HSCMAND015PAData>();
     ds.registerType<HSCMRNN030PAData>();
     ds.registerType<HSCMRNN160KAData>();
     ds.registerType<SSCDANN030PAAData>();
     ds.registerType<SSCDRRN015PDAData>();
+    ds.registerType<MPXH6115AData>();
+    ds.registerType<MPXH6400AData>();
+    ds.registerType<MPXHZ6130AData>();
 }
 
 }  // namespace LogTypes
diff --git a/src/shared/logger/Logger.cpp b/src/shared/logger/Logger.cpp
index 54fdd149f9a1d51c904e02bda506627303bb3cb2..b8c903a79268e22b4c80814f886027bd1f0826e7 100644
--- a/src/shared/logger/Logger.cpp
+++ b/src/shared/logger/Logger.cpp
@@ -55,9 +55,7 @@ bool Logger::start()
         filename = getFileName(fileNumber);
         struct stat st;
         if (stat(filename.c_str(), &st) != 0)
-        {
             break;
-        }
 
         if (fileNumber == maxFilenameNumber - 1)
             TRACE("Too many log files, appending data to last\n");
diff --git a/src/shared/logger/Logger.h b/src/shared/logger/Logger.h
index 76604ea6d95cae05d8b80aeb72224c59518662fb..496b1cf311900f722a7070447cb9234f864791f4 100644
--- a/src/shared/logger/Logger.h
+++ b/src/shared/logger/Logger.h
@@ -124,7 +124,7 @@ public:
      */
     void logStats();
 
-private:
+public:
     Logger();
 
     static std::string getFileName(int logNumber);
@@ -153,10 +153,17 @@ private:
     LoggerResult logImpl(const char *name, const void *data, unsigned int size);
 
     static constexpr unsigned int maxFilenameNumber = 100;  ///< Limit on files
-    static constexpr unsigned int maxRecordSize     = 512;  ///< Limit on data
+#ifndef _ARCH_CORTEXM3_STM32F2
+    static constexpr unsigned int maxRecordSize = 512;  ///< Limit on data
     static constexpr unsigned int numRecords = 512;  ///< Size of record queues
     static constexpr unsigned int numBuffers = 8;    ///< Number of buffers
     static constexpr unsigned int bufferSize = 64 * 1024;  ///< Size of buffers
+#else
+    static constexpr unsigned int maxRecordSize = 512;  ///< Limit on data
+    static constexpr unsigned int numRecords = 64;  ///< Size of record queues
+    static constexpr unsigned int numBuffers = 8;   ///< Number of buffers
+    static constexpr unsigned int bufferSize = 4 * 1024;  ///< Size of buffers
+#endif
 
     /**
      * A record is a single serialized logged class. Records are used to
diff --git a/src/shared/sensors/LIS331HH/LIS331HH.cpp b/src/shared/sensors/LIS331HH/LIS331HH.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..ad3f18e9690164daf45c85c9288e56ff2495508c
--- /dev/null
+++ b/src/shared/sensors/LIS331HH/LIS331HH.cpp
@@ -0,0 +1,64 @@
+/* Copyright (c) 2022 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 "LIS331HH.h"
+
+#include <drivers/timer/TimestampTimer.h>
+
+namespace Boardcore
+{
+
+LIS331HH::LIS331HH(SPIBusInterface& bus, miosix::GpioPin cs,
+                   SPIBusConfig spiConfig)
+    : slave(bus, cs, spiConfig)
+{
+}
+
+bool LIS331HH::init() { return true; }
+
+bool LIS331HH::selfTest() { return true; }
+
+LIS331HHData LIS331HH::sampleImpl()
+{
+    uint16_t val;
+    LIS331HHData data;
+
+    data.accelerationTimestamp = TimestampTimer::getTimestamp();
+
+    SPITransaction spi(slave);
+
+    val = spi.readRegister(OUT_X_L);
+    val |= spi.readRegister(OUT_X_H) << 8;
+    data.accelerationX = 6.0 / 65536.0 * val;
+
+    val = spi.readRegister(OUT_Y_L);
+    val |= spi.readRegister(OUT_Y_H) << 8;
+    data.accelerationY = 6.0 / 65536.0 * val;
+
+    val = spi.readRegister(OUT_Z_L);
+    val |= spi.readRegister(OUT_Z_H) << 8;
+    data.accelerationZ = 6.0 / 65536.0 * val;
+
+    return data;
+}
+
+}  // namespace Boardcore
diff --git a/src/shared/sensors/LIS331HH/LIS331HH.h b/src/shared/sensors/LIS331HH/LIS331HH.h
new file mode 100644
index 0000000000000000000000000000000000000000..d91cb3d904eae391ce4f3e7ac16a4deb1820104f
--- /dev/null
+++ b/src/shared/sensors/LIS331HH/LIS331HH.h
@@ -0,0 +1,74 @@
+/* Copyright (c) 2022 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.
+ */
+
+#pragma once
+
+#include <drivers/spi/SPIDriver.h>
+#include <sensors/Sensor.h>
+
+#include "LIS331HHData.h"
+
+namespace Boardcore
+{
+
+class LIS331HH : public Sensor<LIS331HHData>
+{
+public:
+    LIS331HH(SPIBusInterface& bus, miosix::GpioPin cs, SPIBusConfig spiConfig);
+
+    bool init() override;
+
+    bool selfTest() override;
+
+private:
+    LIS331HHData sampleImpl() override;
+
+    SPISlave slave;
+
+    enum Registers : uint8_t
+    {
+        CTRL_REG1       = 0x20,
+        CTRL_REG2       = 0x21,
+        CTRL_REG3       = 0x22,
+        CTRL_REG4       = 0x23,
+        CTRL_REG5       = 0x24,
+        HP_FILTER_RESET = 0x25,
+        REFERENCE       = 0x26,
+        STATUS_REG      = 0x27,
+        OUT_X_L         = 0x28,
+        OUT_X_H         = 0x29,
+        OUT_Y_L         = 0x2a,
+        OUT_Y_H         = 0x2b,
+        OUT_Z_L         = 0x2c,
+        OUT_Z_H         = 0x2d,
+        INT1_CFG        = 0x30,
+        INT1_SOURCE     = 0x31,
+        INT1_THS        = 0x32,
+        INT1_DURATION   = 0x33,
+        INT2_CFG        = 0x34,
+        INT2_SOURCE     = 0x35,
+        INT2_THS        = 0x36,
+        INT2_DURATION   = 0x37,
+    };
+};
+
+}  // namespace Boardcore
\ No newline at end of file
diff --git a/src/shared/sensors/LIS331HH/LIS331HHData.h b/src/shared/sensors/LIS331HH/LIS331HHData.h
new file mode 100644
index 0000000000000000000000000000000000000000..72a57214106d2c3475abe59e9baef9b0701ef2c8
--- /dev/null
+++ b/src/shared/sensors/LIS331HH/LIS331HHData.h
@@ -0,0 +1,47 @@
+/* Copyright (c) 2022 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.
+ */
+
+#pragma once
+
+#include <sensors/SensorData.h>
+
+namespace Boardcore
+{
+
+struct LIS331HHData : public AccelerometerData
+{
+    static std::string header()
+    {
+        return "accelerationTimestamp,accelerationX,accelerationY,"
+               "accelerationZ,temp_"
+               "timestamp,"
+               "temp\n";
+    }
+
+    void print(std::ostream& os) const
+    {
+        os << accelerationTimestamp << "," << accelerationX << ","
+           << accelerationY << "," << accelerationZ << "\n";
+    }
+};
+
+}  // namespace Boardcore
diff --git a/src/shared/sensors/LIS3DSH/LIS3DSH.h b/src/shared/sensors/LIS3DSH/LIS3DSH.h
index 89404d1fcc68ecdc4e92d9374f6a8e14fcce8566..4c048dc25e2fe3a39db5333368d4e5a8ead6be6c 100644
--- a/src/shared/sensors/LIS3DSH/LIS3DSH.h
+++ b/src/shared/sensors/LIS3DSH/LIS3DSH.h
@@ -318,9 +318,10 @@ public:
 private:
     /**
      * @brief Read new data from the accelerometer.
-     *        Acceleretions are returned in g.
      *
-     * @return boolean value indicating whether the operation succeded or not
+     * Accelerations are returned in g.
+     *
+     * @return boolean value indicating whether the operation succeeded or not
      */
     LIS3DSHData sampleImpl() override
     {
@@ -346,9 +347,9 @@ private:
     }
 
     /**
-     * @brief Read accelrometer data.
+     * @brief Read accelerometer data.
      *
-     * @return the read accelrometer sample
+     * @return the read accelerometer sample
      */
     AccelerometerData readAccelData()
     {
diff --git a/src/shared/utils/ButtonHandler/ButtonHandler.cpp b/src/shared/utils/ButtonHandler/ButtonHandler.cpp
index 56a0e5df40a5f5e5b2d12d4c3c80e2f0bfb00774..89c20e726514ba2acc90a9f5ea5d1d2266c3365f 100644
--- a/src/shared/utils/ButtonHandler/ButtonHandler.cpp
+++ b/src/shared/utils/ButtonHandler/ButtonHandler.cpp
@@ -44,6 +44,11 @@ bool ButtonHandler::registerButtonCallback(miosix::GpioPin pin,
     return false;
 }
 
+bool ButtonHandler::unregisterButtonCallback(miosix::GpioPin pin)
+{
+    return callbacks.erase(pin) != 0;
+}
+
 bool ButtonHandler::start() { return scheduler.start(); }
 
 void ButtonHandler::stop() { scheduler.stop(); }
@@ -63,12 +68,12 @@ void ButtonHandler::periodicButtonValueCheck(miosix::GpioPin pin)
     // Retrieve the pin information
     const ButtonCallback &callback = std::get<0>(callbacks[pin]);
     bool &wasPressed               = std::get<1>(callbacks[pin]);
-    int &pressedTicks              = std::get<2>(callbacks[pin]);
+    unsigned int &pressedTicks     = std::get<2>(callbacks[pin]);
 
     // Read the current button status
     // Note: The button is assumed to be pressed if the pin value is low
     // (pulldown)
-    bool isNowPressed = !pin.value();
+    const bool isNowPressed = !pin.value();
 
     if (isNowPressed)
     {
diff --git a/src/shared/utils/ButtonHandler/ButtonHandler.h b/src/shared/utils/ButtonHandler/ButtonHandler.h
index 2ff97a9beb9e4acb7e6e98c45ee88550fa3deddf..8ae5b7d583f10ed726f93e12709bb88279d8e0c3 100644
--- a/src/shared/utils/ButtonHandler/ButtonHandler.h
+++ b/src/shared/utils/ButtonHandler/ButtonHandler.h
@@ -23,8 +23,8 @@
 #pragma once
 
 #include <Singleton.h>
-#include <miosix.h>
 #include <scheduler/TaskScheduler.h>
+#include <utils/GpioPinCompare.h>
 
 #include <map>
 
@@ -33,24 +33,10 @@ namespace Boardcore
 
 enum class ButtonEvent
 {
-    PRESSED,         // Called as soon as the button is pressed
-    SHORT_PRESS,     // Called as soon as the button is released
-    LONG_PRESS,      // Called as soon as the button is released
-    VERY_LONG_PRESS  // Called as soon as the button is released
-};
-
-/**
- * @brief Comparison operator between GpioPins used for std::map.
- */
-struct GpioPinCompare
-{
-    bool operator()(const miosix::GpioPin& lhs,
-                    const miosix::GpioPin& rhs) const
-    {
-        if (lhs.getPort() == rhs.getPort())
-            return lhs.getNumber() < rhs.getNumber();
-        return lhs.getPort() < rhs.getPort();
-    }
+    PRESSED,         ///< The button is pressed.
+    SHORT_PRESS,     ///< The button is released before LONG_PRESS_TICKS.
+    LONG_PRESS,      ///< The button is released before  VERY_LONG_PRESS_TICKS.
+    VERY_LONG_PRESS  ///< The button is released after VERY_LONG_PRESS_TICKS.
 };
 
 /**
@@ -122,17 +108,12 @@ private:
     /**
      * @brief Map of all the callbacks registered in the ButtonHandler.
      *
-     * The key is the GpioPin for which the callback is registered. To used
-     * GpioPin as a map key, the GpioPinCompare operator was defined as
-     * explained here:
-     * https://stackoverflow.com/questions/1102392/how-can-i-use-stdmaps-with-user-defined-types-as-key
-     *
      * The type stored is a tuple containing:
      * - The button callback function;
      * - Whether or not the button was pressed in the last check iteration;
      * - The relative tick of the last pin value change.
      */
-    std::map<miosix::GpioPin, std::tuple<ButtonCallback, bool, int>,
+    std::map<miosix::GpioPin, std::tuple<ButtonCallback, bool, unsigned int>,
              GpioPinCompare>
         callbacks;
 };
diff --git a/src/shared/utils/GpioPinCompare.h b/src/shared/utils/GpioPinCompare.h
new file mode 100644
index 0000000000000000000000000000000000000000..428c32c0b97ce46eba3ddb52ee4887efd4ab10e9
--- /dev/null
+++ b/src/shared/utils/GpioPinCompare.h
@@ -0,0 +1,47 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Authors: 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 <miosix.h>
+
+namespace Boardcore
+{
+
+/**
+ * @brief Comparison operator between GpioPins used for std::map.
+ *
+ * This function was implemented to use GpioPin as a map key. Check here for
+ * more explanation:
+ * https://stackoverflow.com/questions/1102392/how-can-i-use-stdmaps-with-user-defined-types-as-key
+ */
+struct GpioPinCompare
+{
+    bool operator()(const miosix::GpioPin& lhs,
+                    const miosix::GpioPin& rhs) const
+    {
+        if (lhs.getPort() == rhs.getPort())
+            return lhs.getNumber() < rhs.getNumber();
+        return lhs.getPort() < rhs.getPort();
+    }
+};
+}  // namespace Boardcore
diff --git a/src/shared/utils/PinObserver.h b/src/shared/utils/PinObserver.h
deleted file mode 100644
index a09573f5453f043219bde522004011a3f2a671b7..0000000000000000000000000000000000000000
--- a/src/shared/utils/PinObserver.h
+++ /dev/null
@@ -1,228 +0,0 @@
-/* Copyright (c) 2018 Skyward Experimental Rocketry
- * Author: Luca Erbetta
- *
- * 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/StackLogger.h>
-#include <miosix.h>
-
-#include <functional>
-#include <map>
-#include <utility>
-
-#include "ActiveObject.h"
-
-using miosix::FastMutex;
-using miosix::GpioPin;
-using miosix::Lock;
-using miosix::Thread;
-using miosix::Unlock;
-
-using std::function;
-using std::map;
-using std::pair;
-
-namespace Boardcore
-{
-
-/**
- * Class used to call a callback after a pin performs a specific transition
- * (RISING or FALLING edge) and stays in the new state for a specific amount of
- * time. Useful if you want to monitor pin transitions but you want to avoid
- * spurious state changes.
- *
- * A callback to monitor each state change no matter the thresold or the
- * transition is also available, in order to be able to observe the current
- * state of the pin
- */
-class PinObserver : public ActiveObject
-{
-public:
-    /**
-     * @brief Pin transition
-     * Actual enumaration value represents the stat of the pin after the
-     * corresponding transition has occured.
-     */
-    enum class Transition : int
-    {
-        FALLING_EDGE = 0,
-        RISING_EDGE  = 1
-    };
-
-    using OnStateChangeCallback =
-        function<void(unsigned int, unsigned char, int)>;
-
-    using OnTransitionCallback = function<void(unsigned int, unsigned char)>;
-
-    /**
-     * @brief Construct a new Pin Observer object
-     *
-     * @param pollIntervalMs Pin transition polling interval
-     */
-    PinObserver(unsigned int pollIntervalMs = 20) : pollInterval(pollIntervalMs)
-    {
-    }
-
-    /**
-     * Observe a pin for a specific transition, and optionally for every
-     * single state change.
-     *
-     * The @param transitionCb function is called only if the two following
-     * conditions are verified:
-     * 1.  The transition specified in the @param transition is detected
-     * 2.  The pin stays in the new state for at least detection_threshols
-     * samples.
-     *
-     * The @param onstatechangeCb function [optional] is called at each state
-     * change, both rising and falling edge, regardless of the @param
-     * detectionThreshold
-     *
-     * @param p GPIOA_BASE, GPIOB_BASE ...
-     * @param n Which pin (0 to 15)
-     * @param transition What transition to detect (RISING or FALLING edge)
-     * @param transitionCb Function to call when the transition is detected and
-     * the pin stays in the new configuration for at least @param
-     * detectionThreshold samples
-     * @param detectionThreshold How many times the pin should be observed in
-     * the post-transition state to trigger the actual transition callback.
-     * @param onstatechangeCb Function to be called at each pin state change,
-     * no matter the threshold or the transition
-     */
-    void observePin(unsigned int p, unsigned char n, Transition transition,
-                    OnTransitionCallback transitionCb,
-                    unsigned int detectionThreshold       = 1,
-                    OnStateChangeCallback onstatechangeCb = nullptr)
-    {
-        Lock<FastMutex> lock(mtxMap);
-        observedPins.insert(
-            std::make_pair(pair<unsigned int, unsigned char>({p, n}),
-                           ObserverData{GpioPin{p, n}, transition, transitionCb,
-                                        onstatechangeCb, detectionThreshold}));
-    }
-
-    /**
-     * @brief Stop monitoring the specified pin
-     *
-     * @param p GPIOA_BASE, GPIOB_BASE ...
-     * @param n Which pin (0 to 15)
-     */
-    void removeObservedPin(unsigned int p, unsigned char n)
-    {
-        Lock<FastMutex> lock(mtxMap);
-        observedPins.erase({p, n});
-    }
-
-protected:
-    void run()
-    {
-        while (true)
-        {
-            {
-                Lock<FastMutex> lock(mtxMap);
-
-                for (auto it = observedPins.begin(); it != observedPins.end();
-                     it++)
-                {
-                    pair<int, int> key    = it->first;
-                    ObserverData& pinData = it->second;
-
-                    int oldState = pinData.state;
-                    int newState = pinData.pin.value();
-
-                    // Save current state in the struct
-                    pinData.state = newState;
-
-                    // Are we in a post-transition state?
-                    if (pinData.state == static_cast<int>(pinData.transition))
-                    {
-                        ++pinData.detectedCount;
-                    }
-                    else
-                    {
-                        pinData.detectedCount = 0;
-                    }
-
-                    // Pre-calcualate conditions in order to unlock the mutex
-                    // only one time
-
-                    bool stateChange = pinData.onstatechangeCallback &&
-                                       oldState != pinData.state;
-                    bool pinTriggered =
-                        pinData.detectedCount == pinData.detectionThreshold;
-
-                    {
-                        Unlock<FastMutex> unlock(lock);
-
-                        if (stateChange)
-                        {
-                            pinData.onstatechangeCallback(key.first, key.second,
-                                                          newState);
-                        }
-
-                        if (pinTriggered)
-                        {
-                            pinData.transitionCallback(key.first, key.second);
-                        }
-                    }
-                }
-            }
-
-            StackLogger::getInstance().updateStack(THID_PIN_OBS);
-
-            Thread::sleep(pollInterval);
-        }
-    }
-
-private:
-    struct ObserverData
-    {
-        GpioPin pin;
-        Transition transition;
-        OnTransitionCallback transitionCallback;
-        OnStateChangeCallback onstatechangeCallback;
-        unsigned int detectionThreshold;
-        unsigned int detectedCount;
-        int state;  // 1 if HIGH, 0 if LOW
-
-        ObserverData(GpioPin pin, Transition transition,
-                     OnTransitionCallback transitionCallback,
-                     OnStateChangeCallback onstatechangeCallback,
-                     unsigned int detectionThreshold)
-            : pin(pin), transition(transition),
-              transitionCallback(transitionCallback),
-              onstatechangeCallback(onstatechangeCallback),
-              detectionThreshold(detectionThreshold),
-              // Set to this value to avoid detection if the pin is already in
-              // the ending state of the "trigger" transition
-              detectedCount(detectionThreshold + 1), state(0)
-        {
-        }
-    };
-
-    map<pair<unsigned int, unsigned char>, ObserverData> observedPins;
-    FastMutex mtxMap;
-
-    unsigned int pollInterval;
-    bool stopped = true;
-};
-
-}  // namespace Boardcore
diff --git a/src/shared/utils/PinObserver/PinObserver.cpp b/src/shared/utils/PinObserver/PinObserver.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..0eb65db1488357178ae8058de54e209b6c59eb3c
--- /dev/null
+++ b/src/shared/utils/PinObserver/PinObserver.cpp
@@ -0,0 +1,107 @@
+/* Copyright (c) 2018-2022 Skyward Experimental Rocketry
+ * Author: Luca Erbetta, 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 "PinObserver.h"
+
+#include <drivers/timer/TimestampTimer.h>
+
+#include <functional>
+
+namespace Boardcore
+{
+
+bool PinObserver::registerPinCallback(miosix::GpioPin pin, PinCallback callback,
+                                      uint32_t detectionThreshold)
+{
+    // Try to insert the callback
+    auto result = callbacks.insert(
+        {pin, {callback, detectionThreshold, 0, 0, pin.value() == 1, 0}});
+
+    // Check if the insertion took place
+    if (result.second)
+    {
+        if (scheduler.addTask(
+                std::bind(&PinObserver::periodicPinValueCheck, this, pin),
+                SAMPLE_PERIOD, TaskScheduler::Policy::SKIP))
+            return true;
+        else
+            callbacks.erase(pin);
+    }
+
+    return false;
+}
+
+bool PinObserver::start() { return scheduler.start(); }
+
+void PinObserver::stop() { scheduler.stop(); }
+
+bool PinObserver::isRunning() { return scheduler.isRunning(); }
+
+PinData PinObserver::getPinData(miosix::GpioPin pin) { return callbacks[pin]; }
+
+void PinObserver::resetPinChangesCount(miosix::GpioPin pin)
+{
+    callbacks[pin].changesCount = 0;
+}
+
+PinObserver::PinObserver() { scheduler.start(); }
+
+void PinObserver::periodicPinValueCheck(miosix::GpioPin pin)
+{
+    // Make sure the pin informations are still present
+    if (callbacks.find(pin) == callbacks.end())
+        return;
+
+    auto &pinData = callbacks[pin];
+
+    // Retrieve the pin information
+    uint32_t &count = pinData.periodCount;
+
+    // Read the current pin status
+    const bool newState = pin.value();
+
+    // Are we in a transition?
+    if (pinData.lastState != newState)
+    {
+        count = 0;               // Yes, reset the counter
+        pinData.changesCount++;  // And register the change
+    }
+    else
+    {
+        count++;  // No, continue to increment
+
+        // If the count reaches the threshold, then trigger the event
+        if (count > pinData.threshold)
+        {
+            if (newState)
+                pinData.callback(PinTransition::RISING_EDGE);
+            else
+                pinData.callback(PinTransition::FALLING_EDGE);
+        }
+    }
+
+    // Save the current pin status
+    pinData.lastStateTimestamp = TimestampTimer::getTimestamp();
+    pinData.lastState          = newState;
+}
+
+}  // namespace Boardcore
diff --git a/src/shared/utils/PinObserver/PinObserver.h b/src/shared/utils/PinObserver/PinObserver.h
new file mode 100644
index 0000000000000000000000000000000000000000..a81f6e2b84bd21f252e0ef0b1ae720a89ba44528
--- /dev/null
+++ b/src/shared/utils/PinObserver/PinObserver.h
@@ -0,0 +1,141 @@
+/* Copyright (c) 2018-2022 Skyward Experimental Rocketry
+ * Author: Luca Erbetta, 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 <Singleton.h>
+#include <scheduler/TaskScheduler.h>
+#include <utils/GpioPinCompare.h>
+
+#include <map>
+
+namespace Boardcore
+{
+
+/**
+ * @brief Pin transition.
+ */
+enum class PinTransition
+{
+    FALLING_EDGE,  ///< The pin goes from high to low.
+    RISING_EDGE    ///< The pin goes from low to high.
+};
+
+/**
+ * @brief Pin informations.
+ */
+struct PinData
+{
+    std::function<void(PinTransition)> callback;  ///< The callback function.
+    uint32_t threshold;           ///< Number of periods to trigger an event.
+    uint32_t periodCount;         ///< Number of periods the value was the same.
+    uint64_t lastStateTimestamp;  ///< Timestamp of the last measurement.
+    bool lastState;               ///< The last measured pin state.
+    uint32_t changesCount;        ///< Incremental count of the pin changes.
+};
+
+/**
+ * Class used to call a callback after a pin performs a specific transition
+ * (RISING or FALLING edge) and stays in the new state for a specific amount of
+ * time. Useful if you want to monitor pin transitions but you want to avoid
+ * spurious state changes.
+ *
+ * A callback to monitor each state change no matter the threshold or the
+ * transition is also available, in order to be able to observe the current
+ * state of the pin.
+ */
+class PinObserver : public Singleton<PinObserver>
+{
+    friend Singleton<PinObserver>;
+
+    static constexpr uint32_t SAMPLE_PERIOD = 100;  // 10Hz
+
+public:
+    using PinCallback = std::function<void(PinTransition)>;
+
+    /**
+     * Observe a pin for a specific transition, and optionally for every
+     * single state change.
+     *
+     * @param pin Pin to listen to.
+     * @param callback Function to call on button events.
+     * @param detectionThreshold How many times the pin should be observed in
+     * the post-transition state to trigger the actual transition callback,
+     * defaults to 1.
+     * @return False if another callback was already registered for the pin.
+     */
+    bool registerPinCallback(miosix::GpioPin pin, PinCallback callback,
+                             uint32_t detectionThreshold = 1);
+
+    /**
+     * @brief Starts the PinObserver's task scheduler.
+     *
+     * Note that the scheduler is started as soon as the PinObserver is first
+     * used.
+     *
+     * @return Whether the task scheduler was started or not.
+     */
+    bool start();
+
+    /**
+     * @brief Stops the PinObserver's task scheduler.
+     */
+    void stop();
+
+    /**
+     * @brief True if the PinObserver started correctly.
+     */
+    bool isRunning();
+
+    /**
+     * @brief Returns the information for the specified pin.
+     */
+    PinData getPinData(miosix::GpioPin pin);
+
+    /**
+     * @brief Resets the changes counter for the specified pin.
+     */
+    void resetPinChangesCount(miosix::GpioPin pin);
+
+private:
+    /**
+     * @brief Construct a new PinObserver object.
+     *
+     * @param pollInterval Pin transition polling interval, defaults to 20 [ms].
+     */
+    PinObserver();
+
+    /**
+     * @brief This function is added to the scheduler for every pin registered
+     * in the PinObserver.
+     *
+     * @param pin Pin whose value need to be checked.
+     */
+    void periodicPinValueCheck(miosix::GpioPin pin);
+
+    TaskScheduler scheduler;
+
+    /// Map of all the callbacks registered in the PinObserver.
+    std::map<miosix::GpioPin, PinData, GpioPinCompare> callbacks;
+};
+
+}  // namespace Boardcore
diff --git a/src/tests/drivers/test-internal-temp.cpp b/src/tests/drivers/test-internal-temp.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..23fd7844a83f5ae4978d26f092253f76067814e3
--- /dev/null
+++ b/src/tests/drivers/test-internal-temp.cpp
@@ -0,0 +1,44 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Authors: 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/adc/InternalTemp.h>
+#include <drivers/timer/TimestampTimer.h>
+#include <miosix.h>
+#include <utils/ClockUtils.h>
+
+using namespace Boardcore;
+
+int main()
+{
+    ADC->CCR |= ADC_CCR_ADCPRE_0 | ADC_CCR_ADCPRE_1;
+
+    InternalTemp temp(InternalADC::CYCLES_480, 3.0);
+    temp.init();
+
+    for (;;)
+    {
+        temp.sample();
+        printf("Temperature: %2.3f\n", temp.getLastSample().temperature);
+
+        miosix::delayMs(1000);
+    }
+}
diff --git a/src/tests/test-pinobserver.cpp b/src/tests/test-pinobserver.cpp
index 1fe87708a4f27d22bf72f4d84455860331c34b0e..9856200ef36e72da7b604ae2d496a830ee3dc912 100644
--- a/src/tests/test-pinobserver.cpp
+++ b/src/tests/test-pinobserver.cpp
@@ -21,10 +21,14 @@
  */
 
 #include <miosix.h>
-#include <utils/PinObserver.h>
+#include <utils/PinObserver/PinObserver.h>
+
+#include <functional>
 
 using namespace Boardcore;
 using namespace miosix;
+using namespace std;
+using namespace std::placeholders;
 
 static constexpr unsigned int POLL_INTERVAL = 20;
 
@@ -35,60 +39,38 @@ static constexpr unsigned char PIN1_PIN = 5;
 static constexpr unsigned int PIN2_PORT = GPIOE_BASE;
 static constexpr unsigned char PIN2_PIN = 6;
 
-void onStateChange(unsigned int p, unsigned char n, int state)
+void onTransition(GpioPin pin, PinTransition transition)
 {
-    if (p == BTN_PORT && n == BTN_PIN)
-    {
-        printf("BTN state change: %d\n", state);
-    }
-    if (p == PIN1_PORT && n == PIN1_PIN)
-    {
-        printf("PIN1 state change: %d\n", state);
-    }
-    if (p == PIN2_PORT && n == PIN2_PIN)
-    {
-        printf("PIN2 state change: %d\n", state);
-    }
-}
+    if (pin.getPort() == BTN_PORT && pin.getNumber() == BTN_PIN)
+        printf("BTN transition: ");
+    if (pin.getPort() == PIN1_PORT && pin.getNumber() == PIN1_PIN)
+        printf("PIN1 transition: ");
+    if (pin.getPort() == PIN2_PORT && pin.getNumber() == PIN2_PIN)
+        printf("PIN2 transition: ");
 
-void onTransition(unsigned int p, unsigned char n)
-{
-    if (p == BTN_PORT && n == BTN_PIN)
-    {
-        printf("BTN transition.\n");
-    }
-    if (p == PIN1_PORT && n == PIN1_PIN)
-    {
-        printf("PIN1 transition.\n");
-    }
-    if (p == PIN2_PORT && n == PIN2_PIN)
-    {
-        printf("PIN2 transition.\n");
-    }
+    if (transition == PinTransition::FALLING_EDGE)
+        printf("FALLING_EDGE\n");
+    else
+        printf("RISING_EDGE\n");
 }
 
 int main()
 {
-    GpioPin(BTN_PORT, BTN_PIN).mode(Mode::INPUT);
-    GpioPin(PIN1_PORT, PIN1_PIN).mode(Mode::INPUT_PULL_DOWN);
-    GpioPin(PIN2_PORT, PIN2_PIN).mode(Mode::INPUT_PULL_UP);
-
-    PinObserver observer;
-
-    observer.observePin(BTN_PORT, BTN_PIN, PinObserver::Transition::RISING_EDGE,
-                        &onTransition, 1, onStateChange);
+    auto btn  = GpioPin(BTN_PORT, BTN_PIN);
+    auto pin1 = GpioPin(PIN1_PORT, PIN1_PIN);
+    auto pin2 = GpioPin(PIN2_PORT, PIN2_PIN);
 
-    observer.observePin(PIN1_PORT, PIN1_PIN,
-                        PinObserver::Transition::FALLING_EDGE, &onTransition,
-                        1000 / POLL_INTERVAL, onStateChange);
+    btn.mode(Mode::INPUT);
+    pin1.mode(Mode::INPUT_PULL_DOWN);
+    pin2.mode(Mode::INPUT_PULL_UP);
 
-    observer.observePin(PIN2_PORT, PIN2_PIN,
-                        PinObserver::Transition::RISING_EDGE, &onTransition,
-                        1000 / POLL_INTERVAL, onStateChange);
+    PinObserver::getInstance().registerPinCallback(
+        btn, std::bind(onTransition, btn, _1), 10);
+    PinObserver::getInstance().registerPinCallback(
+        pin1, std::bind(onTransition, pin1, _1), 10);
+    PinObserver::getInstance().registerPinCallback(
+        pin2, std::bind(onTransition, pin2, _1), 10);
 
-    observer.start();
-    for (;;)
-    {
+    while (true)
         Thread::sleep(10000);
-    }
 }