From 1b75f9562b10cbe05307d4734c4ee855b9268b68 Mon Sep 17 00:00:00 2001
From: Alberto Nidasio <alberto.nidasio@skywarder.eu>
Date: Tue, 1 Feb 2022 00:33:04 +0100
Subject: [PATCH] Updated boardcore submodule and everything along with it

---
 .vscode/c_cpp_properties.json                 |  12 +-
 skyward-boardcore                             |   2 +-
 .../DeathStack/AirBrakes/AirBrakesAlgorithm.h |  14 +-
 .../AirBrakes/AirBrakesController.h           |  32 +--
 .../DeathStack/AirBrakes/AirBrakesServo.cpp   |  17 +-
 .../DeathStack/AirBrakes/AirBrakesServo.h     |   5 +-
 .../ApogeeDetectionAlgorithm/ADAAlgorithm.cpp |   7 +-
 .../ApogeeDetectionAlgorithm/ADACalibrator.h  |   2 -
 .../ApogeeDetectionAlgorithm/ADAController.h  |  73 +++---
 .../ApogeeDetectionAlgorithm/ADAData.h        |   3 +-
 src/boards/DeathStack/DeathStack.h            |  44 ++--
 .../Deployment/DeploymentController.cpp       |  47 ++--
 .../Deployment/DeploymentController.h         |   2 +-
 .../DeathStack/Deployment/DeploymentData.h    |   1 -
 .../DeathStack/Deployment/DeploymentServo.h   |  20 +-
 .../FlightModeManager/FMMController.cpp       | 136 +++++------
 .../FlightStatsRecorder/FSRController.cpp     |  96 ++++----
 .../FlightStatsRecorder/FSRController.h       |  11 +-
 .../DeathStack/LoggerService/LoggerService.h  |   4 +-
 src/boards/DeathStack/Main/Radio.cpp          |  18 +-
 src/boards/DeathStack/Main/Sensors.cpp        | 159 +++++++------
 src/boards/DeathStack/Main/Sensors.h          |   7 +-
 src/boards/DeathStack/Main/StateMachines.cpp  |  18 +-
 src/boards/DeathStack/Main/StateMachines.h    |   4 +-
 .../NavigationAttitudeSystem/InitStates.h     |   1 -
 .../DeathStack/NavigationAttitudeSystem/NAS.h |  46 ++--
 .../NavigationAttitudeSystem/NASCalibrator.h  |   6 +-
 .../NavigationAttitudeSystem/NASController.h  |  54 ++---
 .../DeathStack/PinHandler/PinHandler.cpp      |  36 +--
 .../TelemetriesTelecommands/TCHandler.cpp     |  28 ++-
 .../TelemetriesTelecommands/TCHandler.h       |   2 +-
 .../TMTCController.cpp                        |  72 +++---
 .../TelemetriesTelecommands/TMTCController.h  |   2 +-
 .../TelemetriesTelecommands/TmRepository.cpp  | 211 +++++++++---------
 .../TelemetriesTelecommands/TmRepository.h    |  16 +-
 src/boards/DeathStack/configs/ADAConfig.h     |  12 +-
 .../DeathStack/configs/AirBrakesConfig.h      |  17 +-
 src/boards/DeathStack/configs/CutterConfig.h  |   3 +-
 .../DeathStack/configs/DeploymentConfig.h     |  12 +-
 src/boards/DeathStack/configs/NASConfig.h     |   3 +-
 src/boards/DeathStack/configs/SensorsConfig.h |   4 +-
 src/boards/Payload/Main/Radio.cpp             |  32 +--
 src/boards/Payload/Main/Sensors.cpp           | 126 +++++------
 src/boards/Payload/Main/Sensors.h             |   6 +-
 src/boards/Payload/PayloadBoard.h             |  34 ++-
 src/boards/Payload/PinHandler/PinHandler.cpp  |  17 +-
 src/boards/Payload/WingControl/WingServo.cpp  |  28 +--
 src/boards/Payload/WingControl/WingServo.h    |  12 +-
 src/boards/Payload/configs/SensorsConfig.h    |   5 +-
 src/boards/Payload/configs/WingConfig.h       |  22 +-
 .../death-stack-x-decoder/LogTypes.h          |  18 +-
 src/entrypoints/death-stack-x-entry.cpp       |  15 +-
 src/entrypoints/death-stack-x-testsuite.cpp   |  11 +-
 .../hardware_in_the_loop/hil-entry.cpp        |  19 +-
 src/entrypoints/payload-entry.cpp             |   9 +-
 src/entrypoints/windtunnel-entry.cpp          |   6 +-
 .../windtunnel-test-decoder/LogTypes.h        |   4 +-
 .../HILFlightPhasesManager.h                  |  19 +-
 .../HIL_sensors/HILBarometer.h                |   2 +-
 .../HIL_sensors/HILSensor.h                   |   4 +-
 .../simulator_communication/SerialInterface.h |   1 -
 src/mocksensors/MockGPS.h                     |  36 +--
 src/mocksensors/MockIMU.h                     |  36 +--
 src/mocksensors/MockPressureSensor.h          |  14 +-
 src/mocksensors/MockSensorsData.h             |  22 +-
 src/mocksensors/MockSpeedSensor.h             |   4 +-
 .../lynx_flight_data/lynx_airspeed_data.h     |   2 -
 .../lynx_flight_data/lynx_gps_data.h          |   2 +-
 .../mock_data/test-mock-sensors.cpp           |   5 +-
 .../airbrakes/test-airbrakes-interactive.cpp  |  10 +-
 .../ada/ada_kalman_p/test-ada-simulation.cpp  |  25 +--
 .../catch/ada/kalman_acc/test-kalman-acc.cpp  |   3 +-
 src/tests/catch/ada/test-rogallo-dts.cpp      |   2 +-
 src/tests/catch/catch-tests-entry.cpp         |   4 +-
 src/tests/catch/fsm/test-ada.cpp              |   9 +-
 src/tests/catch/fsm/test-airbrakes.cpp        |   6 +-
 src/tests/catch/fsm/test-deployment.cpp       |   8 +-
 .../catch/fsm/test-flightstatsrecorder.cpp    |   9 +-
 src/tests/catch/fsm/test-fmm.cpp              |   9 +-
 src/tests/catch/fsm/test-ignition.cpp         |  14 +-
 src/tests/catch/fsm/test-nas.cpp              |   7 +-
 src/tests/catch/fsm/test-tmtc.cpp             |   9 +-
 src/tests/catch/nas/test-nas-simulation.cpp   |  33 +--
 .../deathstack-boards/test-analog-board.cpp   |  35 ++-
 .../deathstack-boards/test-power-board.cpp    |  15 +-
 src/tests/deathstack-boards/test-rf-board.cpp |  28 +--
 .../deathstack-boards/test-stm-board.cpp      |   4 -
 .../test-deployment-interactive.cpp           |  12 +-
 src/tests/drivers/test-cutter.cpp             |  44 ++--
 src/tests/drivers/test-imus.cpp               |   1 -
 src/tests/drivers/test-mavlink.cpp            |   1 -
 src/tests/drivers/test-servo.cpp              |  15 +-
 src/tests/eigen-test.cpp                      |   1 -
 .../test-HIL+ADA+Aerobrake.cpp                |   7 +-
 .../test-HIL+ADA+AerobrakeController+nas.cpp  |   7 +-
 .../test-HIL+ADA/test-HIL+ADA.cpp             |   9 +-
 .../test-HIL+Aerobrake/test-HIL+Aerobrake.cpp |   3 -
 .../test-HIL/test-HIL.cpp                     |   3 -
 .../test-SerialInterface.cpp                  |   2 -
 src/tests/mock_sensors/test-mock-sensors.cpp  |   5 +-
 src/tests/ram_test/ramtest.cpp                |  94 ++++----
 src/tests/test-ada-dpl-simulation.cpp         |  17 +-
 src/tests/test-fmm-interactive.cpp            |   8 +-
 src/tests/test-kalman-hitl.cpp                |  13 +-
 src/tests/test-logproxy.cpp                   |   1 -
 src/tests/test-pinhandler.cpp                 |   3 -
 src/tests/test-sensormanager.cpp              |   7 +-
 src/tests/test-sm+tmtc.cpp                    |  11 +-
 src/tests/test-tmtc.cpp                       |   6 +-
 109 files changed, 1083 insertions(+), 1187 deletions(-)

diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json
index 3e76f3ac8..dbed30c87 100755
--- a/.vscode/c_cpp_properties.json
+++ b/.vscode/c_cpp_properties.json
@@ -21,14 +21,16 @@
                 "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common",
                 "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/common",
                 "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix",
-                "${workspaceFolder}/skyward-boardcore/libs/simple-template-matrix",
+                "${workspaceFolder}/skyward-boardcore/libs/mavlink_skyward_lib",
                 "${workspaceFolder}/skyward-boardcore/libs/fmt/include",
                 "${workspaceFolder}/skyward-boardcore/libs/eigen",
                 "${workspaceFolder}/skyward-boardcore/libs",
                 "${workspaceFolder}/skyward-boardcore/src/shared",
                 "${workspaceFolder}/skyward-boardcore/src/tests",
                 "${workspaceFolder}/src/boards/DeathStack",
-                "${workspaceFolder}/src/boards"
+                "${workspaceFolder}/src/boards",
+                "${workspaceFolder}/src/common",
+                "${workspaceFolder}/src"
             ],
             "browse": {
                 "path": [
@@ -43,7 +45,6 @@
                     "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/util",
                     "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/e20",
                     "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/*",
-                    "${workspaceFolder}/skyward-boardcore/libs/simple-template-matrix",
                     "${workspaceFolder}/skyward-boardcore/libs/mavlink_skyward_lib",
                     "${workspaceFolder}/skyward-boardcore/libs/eigen",
                     "${workspaceFolder}/skyward-boardcore/libs/tscpp",
@@ -51,8 +52,11 @@
                     "${workspaceFolder}/skyward-boardcore/libs/fmt",
                     "${workspaceFolder}/skyward-boardcore/src/shared",
                     "${workspaceFolder}/skyward-boardcore/src/tests",
+                    "${workspaceFolder}/src/boards/DeathStack",
                     "${workspaceFolder}/src/boards",
-                    "${workspaceFolder}/src/tests"
+                    "${workspaceFolder}/src/tests",
+                    "${workspaceFolder}/src/common",
+                    "${workspaceFolder}/src"
                 ],
                 "limitSymbolsToIncludedHeaders": true
             },
diff --git a/skyward-boardcore b/skyward-boardcore
index 3a951420e..5fc8d0141 160000
--- a/skyward-boardcore
+++ b/skyward-boardcore
@@ -1 +1 @@
-Subproject commit 3a951420eb4de92f6c5b45cf65abe12869ad585a
+Subproject commit 5fc8d0141d1881cf7dd690a5308c336166c3118c
diff --git a/src/boards/DeathStack/AirBrakes/AirBrakesAlgorithm.h b/src/boards/DeathStack/AirBrakes/AirBrakesAlgorithm.h
index 853292ae1..8f85fdfaa 100644
--- a/src/boards/DeathStack/AirBrakes/AirBrakesAlgorithm.h
+++ b/src/boards/DeathStack/AirBrakes/AirBrakesAlgorithm.h
@@ -28,9 +28,9 @@
 #include <Algorithm.h>
 #include <LoggerService/LoggerService.h>
 #include <ServoInterface.h>
-#include <TimestampTimer.h>
 #include <configs/AirBrakesConfig.h>
 #include <diagnostic/PrintLogger.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <sensors/Sensor.h>
 
 #include <algorithm>
@@ -89,7 +89,7 @@ public:
 #ifdef HARDWARE_IN_THE_LOOP
         else
         {
-            HIL::getInstance()->send(0.0);
+            HIL::getInstance().send(0.0);
         }
 #endif
     }
@@ -212,8 +212,8 @@ public:
     void logAirbrakesData(uint64_t t);
 
 private:
-    int indexMinVal       = 0;
-    float alpha           = 0;
+    int indexMinVal = 0;
+    float alpha     = 0;
 
     uint64_t last_input_ts = 0;
     uint64_t begin_ts      = 0;
@@ -239,7 +239,7 @@ template <class T>
 AirBrakesControlAlgorithm<T>::AirBrakesControlAlgorithm(
     Sensor<T>& sensor, ServoInterface* actuator)
     : actuator(actuator), sensor(sensor), pid(Kp, Ki),
-      logger(*(LoggerService::getInstance()))
+      logger(LoggerService::getInstance())
 {
 }
 
@@ -253,7 +253,7 @@ void AirBrakesControlAlgorithm<T>::begin()
 
     running = true;
 
-    begin_ts = TimestampTimer::getTimestamp();
+    begin_ts = TimestampTimer::getInstance().getTimestamp();
 
     last_input_ts = (sensor.getLastSample()).timestamp;
 
@@ -275,7 +275,7 @@ void AirBrakesControlAlgorithm<T>::step()
         alpha         = computeAlpha(input, false);
     }
 
-    uint64_t curr_ts = TimestampTimer::getTimestamp();
+    uint64_t curr_ts = TimestampTimer::getInstance().getTimestamp();
 
 #ifdef EUROC
     if (curr_ts - begin_ts < AIRBRAKES_ACTIVATION_AFTER_SHADOW_MODE * 1000)
diff --git a/src/boards/DeathStack/AirBrakes/AirBrakesController.h b/src/boards/DeathStack/AirBrakes/AirBrakesController.h
index 281e1644e..3ddb7aa73 100644
--- a/src/boards/DeathStack/AirBrakes/AirBrakesController.h
+++ b/src/boards/DeathStack/AirBrakes/AirBrakesController.h
@@ -26,9 +26,9 @@
 #include <AirBrakes/AirBrakesData.h>
 #include <AirBrakes/AirBrakesServo.h>
 #include <System/StackLogger.h>
-#include <TimestampTimer.h>
 #include <configs/AirBrakesConfig.h>
 #include <diagnostic/PrintLogger.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 #include <events/FSM.h>
@@ -95,14 +95,14 @@ AirBrakesController<T>::AirBrakesController(Sensor<T>& sensor,
       servo(servo), algorithm(sensor, servo)
 {
     memset(&status, 0, sizeof(AirBrakesControllerStatus));
-    sEventBroker->subscribe(this, TOPIC_FLIGHT_EVENTS);
-    sEventBroker->subscribe(this, TOPIC_ABK);
+    sEventBroker.subscribe(this, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.subscribe(this, TOPIC_ABK);
 }
 
 template <class T>
 AirBrakesController<T>::~AirBrakesController()
 {
-    sEventBroker->unsubscribe(this);
+    sEventBroker.unsubscribe(this);
 }
 
 template <class T>
@@ -114,7 +114,7 @@ void AirBrakesController<T>::update()
 template <class T>
 void AirBrakesController<T>::state_initialization(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -141,7 +141,7 @@ void AirBrakesController<T>::state_initialization(const Event& ev)
 template <class T>
 void AirBrakesController<T>::state_idle(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -185,12 +185,12 @@ void AirBrakesController<T>::state_idle(const Event& ev)
 template <class T>
 void AirBrakesController<T>::state_shadowMode(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
             ev_shadow_mode_timeout_id =
-                sEventBroker->postDelayed<SHADOW_MODE_DURATION>(
+                sEventBroker.postDelayed<SHADOW_MODE_DURATION>(
                     Event{EV_SHADOW_MODE_TIMEOUT}, TOPIC_ABK);
 
             logStatus(AirBrakesControllerState::SHADOW_MODE);
@@ -223,7 +223,7 @@ void AirBrakesController<T>::state_shadowMode(const Event& ev)
 template <class T>
 void AirBrakesController<T>::state_enabled(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -259,7 +259,7 @@ void AirBrakesController<T>::state_enabled(const Event& ev)
 template <class T>
 void AirBrakesController<T>::state_end(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -287,7 +287,7 @@ void AirBrakesController<T>::state_end(const Event& ev)
 template <class T>
 void AirBrakesController<T>::state_disabled(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -315,7 +315,7 @@ void AirBrakesController<T>::state_disabled(const Event& ev)
 template <class T>
 void AirBrakesController<T>::state_testAirbrakes(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -329,7 +329,7 @@ void AirBrakesController<T>::state_testAirbrakes(const Event& ev)
 
             logStatus(AirBrakesControllerState::TEST_AEROBRAKES);
 
-            sEventBroker->post(Event{EV_TEST_TIMEOUT}, TOPIC_ABK);
+            sEventBroker.post(Event{EV_TEST_TIMEOUT}, TOPIC_ABK);
             break;
         }
         case EV_EXIT:
@@ -392,12 +392,12 @@ void AirBrakesController<T>::incrementallyClose()
 template <class T>
 void AirBrakesController<T>::logStatus(AirBrakesControllerState state)
 {
-    status.timestamp = TimestampTimer::getTimestamp();
+    status.timestamp = TimestampTimer::getInstance().getTimestamp();
     status.state     = state;
 
-    LoggerService::getInstance()->log(status);
+    LoggerService::getInstance().log(status);
 
-    StackLogger::getInstance()->updateStack(THID_ABK_FSM);
+    StackLogger::getInstance().updateStack(THID_ABK_FSM);
 }
 
 template <class T>
diff --git a/src/boards/DeathStack/AirBrakes/AirBrakesServo.cpp b/src/boards/DeathStack/AirBrakes/AirBrakesServo.cpp
index cfd5cb472..b6a2c35cc 100644
--- a/src/boards/DeathStack/AirBrakes/AirBrakesServo.cpp
+++ b/src/boards/DeathStack/AirBrakes/AirBrakesServo.cpp
@@ -43,19 +43,9 @@ AirBrakesServo::AirBrakesServo(float minPosition, float maxPosition,
 
 AirBrakesServo::~AirBrakesServo() {}
 
-void AirBrakesServo::enable()
-{
-    servo.setMaxPulseWidth(2500);
-    servo.setMinPulseWidth(500);
-    servo.enable(AB_SERVO_PWM_CH);
-    servo.start();
-}
+void AirBrakesServo::enable() { servo.enable(); }
 
-void AirBrakesServo::disable()
-{
-    servo.stop();
-    servo.disable(AB_SERVO_PWM_CH);
-}
+void AirBrakesServo::disable() { servo.disable(); }
 
 void AirBrakesServo::selfTest()
 {
@@ -80,8 +70,7 @@ void AirBrakesServo::selfTest()
 void AirBrakesServo::setPosition(float angle)
 {
     currentPosition = angle;
-    // map position to [0;1] interval for the servo driver
-    servo.setPosition(AirBrakesConfigs::AB_SERVO_PWM_CH, angle / 180.0f);
+    servo.setPosition180Deg(angle);
 
 #ifdef HARDWARE_IN_THE_LOOP
     simulator->send(angle);
diff --git a/src/boards/DeathStack/AirBrakes/AirBrakesServo.h b/src/boards/DeathStack/AirBrakes/AirBrakesServo.h
index 7332d38d3..8551324c3 100644
--- a/src/boards/DeathStack/AirBrakes/AirBrakesServo.h
+++ b/src/boards/DeathStack/AirBrakes/AirBrakesServo.h
@@ -26,7 +26,7 @@
 #include <LoggerService/LoggerService.h>
 #include <common/ServoInterface.h>
 #include <configs/AirBrakesConfig.h>
-#include <drivers/servo/servo.h>
+#include <drivers/servo/Servo.h>
 #include <miosix.h>
 
 #ifdef HARDWARE_IN_THE_LOOP
@@ -59,7 +59,8 @@ public:
     void selfTest() override;
 
 private:
-    Servo servo{AirBrakesConfigs::AB_SERVO_TIMER};
+    Servo servo{AirBrakesConfigs::AB_SERVO_TIMER, AB_SERVO_PWM_CH, 50, 500,
+                2500};
 
 #ifdef HARDWARE_IN_THE_LOOP
     HIL *simulator = HIL::getInstance();
diff --git a/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAAlgorithm.cpp b/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAAlgorithm.cpp
index 0edebf458..126834ac6 100644
--- a/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAAlgorithm.cpp
+++ b/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAAlgorithm.cpp
@@ -21,10 +21,9 @@
  */
 
 #include <ApogeeDetectionAlgorithm/ADAAlgorithm.h>
-#include <Debug.h>
-#include <TimestampTimer.h>
 #include <configs/ADAConfig.h>
 #include <diagnostic/CpuMeter.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 #include <utils/aero/AeroUtils.h>
@@ -52,7 +51,7 @@ void ADAAlgorithm::updateBaro(float pressure)
     updatePressureKalman(pressure);
 
     // Convert filter data to altitudes & speeds
-    ada_data.timestamp    = TimestampTimer::getTimestamp();
+    ada_data.timestamp    = TimestampTimer::getInstance().getTimestamp();
     ada_data.msl_altitude = pressureToAltitude(filter.getState()(0, 0));
     ada_data.agl_altitude = altitudeMSLtoAGL(ada_data.msl_altitude);
     ada_data.vert_speed   = aeroutils::verticalSpeed(
@@ -103,7 +102,7 @@ float ADAAlgorithm::altitudeMSLtoAGL(float altitude_msl) const
 ADAKalmanState ADAAlgorithm::getKalmanState()
 {
     ADAKalmanState state;
-    state.timestamp = TimestampTimer::getTimestamp();
+    state.timestamp = TimestampTimer::getInstance().getTimestamp();
 
     state.x0 = filter.getState()(0, 0);
     state.x1 = filter.getState()(1, 0);
diff --git a/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADACalibrator.h b/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADACalibrator.h
index 2f03b0a4c..a963aaeaa 100644
--- a/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADACalibrator.h
+++ b/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADACalibrator.h
@@ -23,8 +23,6 @@
 #pragma once
 
 #include <ApogeeDetectionAlgorithm/ADAData.h>
-#include <Common.h>
-#include <Debug.h>
 #include <diagnostic/PrintLogger.h>
 #include <math/Stats.h>
 #include <miosix.h>
diff --git a/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAController.h b/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAController.h
index d70a3b4a6..d1f7aa655 100644
--- a/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAController.h
+++ b/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAController.h
@@ -29,6 +29,7 @@
 #include <System/StackLogger.h>
 #include <configs/ADAConfig.h>
 #include <diagnostic/PrintLogger.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 #include <events/FSM.h>
@@ -221,7 +222,7 @@ private:
     unsigned int n_samples_abk_disable_detected =
         0;  //  Number of consecutive samples for abk disable
 
-    LoggerService& logger = *(LoggerService::getInstance());  // Logger
+    LoggerService& logger = LoggerService::getInstance();  // Logger
     PrintLogger log       = Logging::getLogger("deathstack.fms.ada");
 };
 
@@ -232,8 +233,8 @@ ADAController<Press, GPS>::ADAController(Sensor<Press>& barometer,
       ada(ADAReferenceValues{}), barometer(barometer), gps(gps)
 {
     // Subscribe to topics
-    sEventBroker->subscribe(this, TOPIC_FLIGHT_EVENTS);
-    sEventBroker->subscribe(this, TOPIC_ADA);
+    sEventBroker.subscribe(this, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.subscribe(this, TOPIC_ADA);
 
     status.state = ADAState::IDLE;
 }
@@ -248,9 +249,9 @@ void ADAController<Press, GPS>::update()
 {
     // if new gps data available, update GPS, regardless of the current state
     GPS gps_data = gps.getLastSample();
-    if (gps_data.gps_timestamp != last_gps_timestamp)
+    if (gps_data.gpsTimestamp != last_gps_timestamp)
     {
-        last_gps_timestamp = gps_data.gps_timestamp;
+        last_gps_timestamp = gps_data.gpsTimestamp;
 
         ada.updateGPS(gps_data.latitude, gps_data.longitude, gps_data.fix);
     }
@@ -258,11 +259,11 @@ void ADAController<Press, GPS>::update()
     // if new pressure data available, update baro, according to current state
     Press press_data = barometer.getLastSample();
 
-    if (press_data.press_timestamp != last_press_timestamp)
+    if (press_data.pressureTimestamp != last_press_timestamp)
     {
-        last_press_timestamp = press_data.press_timestamp;
+        last_press_timestamp = press_data.pressureTimestamp;
 
-        updateBaroAccordingToState(press_data.press);
+        updateBaroAccordingToState(press_data.pressure);
     }
 }
 
@@ -303,7 +304,7 @@ void ADAController<Press, GPS>::updateBaroAccordingToState(float pressure)
             // Log the altitude & vertical speed but don't use kalman pressure
             // while we are on the ramp
             ADAData d;
-            d.timestamp    = TimestampTimer::getTimestamp();
+            d.timestamp    = TimestampTimer::getInstance().getTimestamp();
             d.msl_altitude = ada.pressureToAltitude(pressure);
             d.agl_altitude = ada.altitudeMSLtoAGL(d.msl_altitude);
             d.vert_speed   = 0;
@@ -321,8 +322,8 @@ void ADAController<Press, GPS>::updateBaroAccordingToState(float pressure)
             if (ada.getVerticalSpeed() < APOGEE_VERTICAL_SPEED_TARGET)
             {
                 // Log
-                ApogeeDetected apogee{TimestampTimer::getTimestamp(),
-                                      status.state};
+                ApogeeDetected apogee{
+                    TimestampTimer::getInstance().getTimestamp(), status.state};
                 logger.log(apogee);
             }
 
@@ -341,13 +342,13 @@ void ADAController<Press, GPS>::updateBaroAccordingToState(float pressure)
                 if (++n_samples_apogee_detected >= APOGEE_N_SAMPLES)
                 {
                     // Active state send notifications for apogee
-                    sEventBroker->post({EV_ADA_APOGEE_DETECTED}, TOPIC_ADA);
+                    sEventBroker.post({EV_ADA_APOGEE_DETECTED}, TOPIC_ADA);
                     status.apogee_reached = true;
                 }
 
                 // Log
-                ApogeeDetected apogee{TimestampTimer::getTimestamp(),
-                                      status.state};
+                ApogeeDetected apogee{
+                    TimestampTimer::getInstance().getTimestamp(), status.state};
                 logger.log(apogee);
             }
             else if (n_samples_apogee_detected != 0)
@@ -361,8 +362,8 @@ void ADAController<Press, GPS>::updateBaroAccordingToState(float pressure)
                 if (++n_samples_abk_disable_detected >= ABK_DISABLE_N_SAMPLES)
                 {
                     // Active state send notifications for disabling airbrakes
-                    sEventBroker->post({EV_ADA_DISABLE_ABK},
-                                       TOPIC_FLIGHT_EVENTS);
+                    sEventBroker.post({EV_ADA_DISABLE_ABK},
+                                      TOPIC_FLIGHT_EVENTS);
                     status.disable_airbrakes = true;
                 }
             }
@@ -385,8 +386,8 @@ void ADAController<Press, GPS>::updateBaroAccordingToState(float pressure)
             {
                 if (++n_samples_deployment_detected >= DEPLOYMENT_N_SAMPLES)
                 {
-                    logger.log(
-                        DplAltitudeReached{TimestampTimer::getTimestamp()});
+                    logger.log(DplAltitudeReached{
+                        TimestampTimer::getInstance().getTimestamp()});
                 }
             }
             else if (n_samples_deployment_detected != 0)
@@ -407,10 +408,10 @@ void ADAController<Press, GPS>::updateBaroAccordingToState(float pressure)
             {
                 if (++n_samples_deployment_detected >= DEPLOYMENT_N_SAMPLES)
                 {
-                    logger.log(
-                        DplAltitudeReached{TimestampTimer::getTimestamp()});
+                    logger.log(DplAltitudeReached{
+                        TimestampTimer::getInstance().getTimestamp()});
 
-                    sEventBroker->post({EV_ADA_DPL_ALT_DETECTED}, TOPIC_ADA);
+                    sEventBroker.post({EV_ADA_DPL_ALT_DETECTED}, TOPIC_ADA);
                 }
             }
             else if (n_samples_deployment_detected != 0)
@@ -503,7 +504,7 @@ void ADAController<Press, GPS>::finalizeCalibration()
         LOG_INFO(log, "Finalized calibration");
 
         // ADA READY!
-        sEventBroker->post({EV_ADA_READY}, TOPIC_ADA);
+        sEventBroker.post({EV_ADA_READY}, TOPIC_ADA);
 
         logger.log(calibrator.getReferenceValues());
         logger.log(ada.getKalmanState());
@@ -513,7 +514,7 @@ void ADAController<Press, GPS>::finalizeCalibration()
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::state_idle(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -541,7 +542,7 @@ void ADAController<Press, GPS>::state_idle(const Event& ev)
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::state_calibrating(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -579,7 +580,7 @@ void ADAController<Press, GPS>::state_calibrating(const Event& ev)
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::state_ready(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -612,12 +613,12 @@ void ADAController<Press, GPS>::state_ready(const Event& ev)
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::state_shadowMode(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
             shadow_delayed_event_id =
-                sEventBroker->postDelayed<TIMEOUT_ADA_SHADOW_MODE>(
+                sEventBroker.postDelayed<TIMEOUT_ADA_SHADOW_MODE>(
                     {EV_SHADOW_MODE_TIMEOUT}, TOPIC_ADA);
             logStatus(ADAState::SHADOW_MODE);
             LOG_DEBUG(log, "Entering state shadowMode");
@@ -625,7 +626,7 @@ void ADAController<Press, GPS>::state_shadowMode(const Event& ev)
         }
         case EV_EXIT:
         {
-            sEventBroker->removeDelayed(shadow_delayed_event_id);
+            sEventBroker.removeDelayed(shadow_delayed_event_id);
             LOG_DEBUG(log, "Exiting state shadowMode");
             break;
         }
@@ -644,7 +645,7 @@ void ADAController<Press, GPS>::state_shadowMode(const Event& ev)
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::state_active(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -672,12 +673,12 @@ void ADAController<Press, GPS>::state_active(const Event& ev)
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::state_pressureStabilization(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
             pressure_delayed_event_id =
-                sEventBroker->postDelayed<TIMEOUT_ADA_P_STABILIZATION>(
+                sEventBroker.postDelayed<TIMEOUT_ADA_P_STABILIZATION>(
                     {EV_TIMEOUT_PRESS_STABILIZATION}, TOPIC_ADA);
             logStatus(ADAState::PRESSURE_STABILIZATION);
             LOG_DEBUG(log, "Entering state pressureStabilization");
@@ -685,7 +686,7 @@ void ADAController<Press, GPS>::state_pressureStabilization(const Event& ev)
         }
         case EV_EXIT:
         {
-            sEventBroker->removeDelayed(pressure_delayed_event_id);
+            sEventBroker.removeDelayed(pressure_delayed_event_id);
             LOG_DEBUG(log, "Exiting state pressureStabilization");
             break;
         }
@@ -704,7 +705,7 @@ void ADAController<Press, GPS>::state_pressureStabilization(const Event& ev)
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::state_drogueDescent(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -736,7 +737,7 @@ void ADAController<Press, GPS>::state_drogueDescent(const Event& ev)
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::state_end(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -766,10 +767,10 @@ void ADAController<Press, GPS>::logStatus(ADAState state)
 template <typename Press, typename GPS>
 void ADAController<Press, GPS>::logStatus()
 {
-    status.timestamp = TimestampTimer::getTimestamp();
+    status.timestamp = TimestampTimer::getInstance().getTimestamp();
     logger.log(status);
 
-    StackLogger::getInstance()->updateStack(THID_ADA_FSM);
+    StackLogger::getInstance().updateStack(THID_ADA_FSM);
 }
 
 template <typename Press, typename GPS>
diff --git a/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAData.h b/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAData.h
index f9441bb31..7889a867c 100644
--- a/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAData.h
+++ b/src/boards/DeathStack/ApogeeDetectionAlgorithm/ADAData.h
@@ -25,7 +25,8 @@
 #include <configs/ADAConfig.h>
 #include <configs/config.h>
 #include <math/Stats.h>
-#include <Constants.h>
+#include <utils/Constants.h>
+
 #include <ostream>
 
 using namespace Boardcore;
diff --git a/src/boards/DeathStack/DeathStack.h b/src/boards/DeathStack/DeathStack.h
index bff9d078a..202703941 100644
--- a/src/boards/DeathStack/DeathStack.h
+++ b/src/boards/DeathStack/DeathStack.h
@@ -22,9 +22,7 @@
 
 #pragma once
 
-#include <Common.h>
 #include <DeathStackStatus.h>
-#include <Debug.h>
 #include <LoggerService/LoggerService.h>
 #include <Main/Actuators.h>
 #include <Main/Bus.h>
@@ -36,9 +34,9 @@
 #include <System/TaskID.h>
 #include <events/EventBroker.h>
 #include <events/EventData.h>
-#include <events/utils/EventInjector.h>
 #include <events/Events.h>
 #include <events/Topics.h>
+#include <events/utils/EventInjector.h>
 #include <events/utils/EventSniffer.h>
 
 #include <functional>
@@ -69,7 +67,6 @@ class DeathStack : public Singleton<DeathStack>
 
 public:
     // Shared Components
-    EventBroker* broker;
     LoggerService* logger;
 
     EventSniffer* sniffer;
@@ -90,7 +87,7 @@ public:
 
     void start()
     {
-        if (!broker->start())
+        if (!sEventBroker.start())
         {
             LOG_ERR(log, "Error starting EventBroker");
             status.setError(&DeathStackStatus::ev_broker);
@@ -134,12 +131,12 @@ public:
         if (status.death_stack != COMP_OK)
         {
             LOG_ERR(log, "Initalization failed\n");
-            sEventBroker->post(Event{EV_INIT_ERROR}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post(Event{EV_INIT_ERROR}, TOPIC_FLIGHT_EVENTS);
         }
         else
         {
             LOG_INFO(log, "Initalization ok");
-            sEventBroker->post(Event{EV_INIT_OK}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post(Event{EV_INIT_OK}, TOPIC_FLIGHT_EVENTS);
         }
     }
 
@@ -156,7 +153,7 @@ public:
             status.setError(&DeathStackStatus::logger);
         }
 
-        logger->log(logger->getLogger().getLogStats());
+        logger->log(logger->getLogger().getLoggerStats());
     }
 
 private:
@@ -166,19 +163,16 @@ private:
     DeathStack()
     {
         /* Shared components */
-        logger = Singleton<LoggerService>::getInstance();
+        logger = &LoggerService::getInstance();
         startLogger();
 
-        TimestampTimer::enableTimestampTimer();
-
-        broker = sEventBroker;
-
         // Bind the logEvent function to the event sniffer in order to log every
         // event
         {
             using namespace std::placeholders;
-            sniffer = new EventSniffer(
-                *broker, TOPIC_LIST, bind(&DeathStack::logEvent, this, _1, _2));
+            sniffer =
+                new EventSniffer(sEventBroker, TOPIC_LIST,
+                                 bind(&DeathStack::logEvent, this, _1, _2));
         }
 
 #ifdef HARDWARE_IN_THE_LOOP
@@ -221,7 +215,8 @@ private:
      */
     void logEvent(uint8_t event, uint8_t topic)
     {
-        EventData ev{(long long)TimestampTimer::getTimestamp(), event, topic};
+        EventData ev{(long long)TimestampTimer::getInstance().getTimestamp(),
+                     event, topic};
         logger->log(ev);
 
 #ifdef DEBUG
@@ -239,25 +234,26 @@ private:
 #endif
     }
 
-    inline void postEvent(Event ev, uint8_t topic) { broker->post(ev, topic); }
+    inline void postEvent(Event ev, uint8_t topic)
+    {
+        sEventBroker.post(ev, topic);
+    }
 
     void addSchedulerStatsTask()
     {
         // add lambda to log scheduler tasks statistics
-        scheduler->add(
-            [&]() {
+        scheduler->addTask(
+            [&]()
+            {
                 std::vector<TaskStatResult> scheduler_stats =
                     scheduler->getTaskStats();
 
                 for (TaskStatResult stat : scheduler_stats)
-                {
                     logger->log(stat);
-                }
 
-                StackLogger::getInstance()->updateStack(THID_TASK_SCHEDULER);
+                StackLogger::getInstance().updateStack(THID_TASK_SCHEDULER);
             },
-            1000,  // 1 hz
-            TASK_SCHEDULER_STATS_ID, miosix::getTick());
+            1000, TASK_SCHEDULER_STATS_ID);
     }
 
     EventInjector* injector;
diff --git a/src/boards/DeathStack/Deployment/DeploymentController.cpp b/src/boards/DeathStack/Deployment/DeploymentController.cpp
index 008d9b86f..b3cfc11f2 100644
--- a/src/boards/DeathStack/Deployment/DeploymentController.cpp
+++ b/src/boards/DeathStack/Deployment/DeploymentController.cpp
@@ -23,15 +23,8 @@
 #include <Deployment/DeploymentController.h>
 #include <LoggerService/LoggerService.h>
 #include <System/StackLogger.h>
-#include <TimestampTimer.h>
-#include <configs/DeploymentConfig.h>
-#include <events/EventBroker.h>
-#include <events/Events.h>
-
-#include <LoggerService/LoggerService.h>
-#include <System/StackLogger.h>
-#include <TimestampTimer.h>
 #include <configs/DeploymentConfig.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 
@@ -41,38 +34,38 @@ namespace DeathStackBoard
 {
 
 DeploymentController::DeploymentController(ServoInterface* ejection_servo)
-    : FSM(&DeploymentController::state_initialization),
-      ejection_servo{ejection_servo}
+    : FSM(&DeploymentController::state_initialization), ejection_servo{
+                                                            ejection_servo}
 {
-    sEventBroker->subscribe(this, TOPIC_DPL);
+    sEventBroker.subscribe(this, TOPIC_DPL);
 }
 
 DeploymentController::~DeploymentController()
 {
-    sEventBroker->unsubscribe(this);
+    sEventBroker.unsubscribe(this);
 }
 
 void DeploymentController::logStatus(DeploymentControllerState current_state)
 {
-    status.timestamp            = TimestampTimer::getTimestamp();
-    status.state                = current_state;
-    status.servo_position       = ejection_servo->getCurrentPosition();
+    status.timestamp      = TimestampTimer::getInstance().getTimestamp();
+    status.state          = current_state;
+    status.servo_position = ejection_servo->getCurrentPosition();
     if (current_state == DeploymentControllerState::CUTTING)
     {
         status.cutters_enabled = true;
     }
-    else 
+    else
     {
         status.cutters_enabled = false;
     }
 
-    LoggerService::getInstance()->log(status);
-    StackLogger::getInstance()->updateStack(THID_DPL_FSM);
+    LoggerService::getInstance().log(status);
+    StackLogger::getInstance().updateStack(THID_DPL_FSM);
 }
 
 void DeploymentController::state_initialization(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -80,7 +73,7 @@ void DeploymentController::state_initialization(const Event& ev)
 
             ejection_servo->enable();
             ejection_servo->reset();
-            
+
             logStatus(DeploymentControllerState::INITIALIZATION);
 
             transition(&DeploymentController::state_idle);
@@ -101,7 +94,7 @@ void DeploymentController::state_initialization(const Event& ev)
 
 void DeploymentController::state_idle(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -148,7 +141,7 @@ void DeploymentController::state_idle(const Event& ev)
 
 void DeploymentController::state_noseconeEjection(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -156,7 +149,7 @@ void DeploymentController::state_noseconeEjection(const Event& ev)
 
             ejectNosecone();
 
-            ev_nc_open_timeout_id = sEventBroker->postDelayed<NC_OPEN_TIMEOUT>(
+            ev_nc_open_timeout_id = sEventBroker.postDelayed<NC_OPEN_TIMEOUT>(
                 Event{EV_NC_OPEN_TIMEOUT}, TOPIC_DPL);
 
             logStatus(DeploymentControllerState::NOSECONE_EJECTION);
@@ -170,7 +163,7 @@ void DeploymentController::state_noseconeEjection(const Event& ev)
         case EV_NC_DETACHED:
         {
             LOG_DEBUG(log, "Nosecone detached event");
-            sEventBroker->removeDelayed(ev_nc_open_timeout_id);
+            sEventBroker.removeDelayed(ev_nc_open_timeout_id);
             transition(&DeploymentController::state_idle);
             break;
         }
@@ -189,7 +182,7 @@ void DeploymentController::state_noseconeEjection(const Event& ev)
 
 void DeploymentController::state_cutting(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -197,7 +190,7 @@ void DeploymentController::state_cutting(const Event& ev)
 
             startCutting();
 
-            ev_nc_cutting_timeout_id = sEventBroker->postDelayed<CUT_DURATION>(
+            ev_nc_cutting_timeout_id = sEventBroker.postDelayed<CUT_DURATION>(
                 Event{EV_CUTTING_TIMEOUT}, TOPIC_DPL);
 
             logStatus(DeploymentControllerState::CUTTING);
@@ -207,7 +200,7 @@ void DeploymentController::state_cutting(const Event& ev)
         case EV_EXIT:
         {
             stopCutting();
-        
+
             LOG_DEBUG(log, "Exiting state cutting");
 
             break;
diff --git a/src/boards/DeathStack/Deployment/DeploymentController.h b/src/boards/DeathStack/Deployment/DeploymentController.h
index 8523cc4ae..c1f3363ae 100644
--- a/src/boards/DeathStack/Deployment/DeploymentController.h
+++ b/src/boards/DeathStack/Deployment/DeploymentController.h
@@ -27,7 +27,7 @@
 #include <configs/CutterConfig.h>
 #include <diagnostic/PrintLogger.h>
 #include <drivers/hbridge/HBridge.h>
-#include <drivers/servo/servo.h>
+#include <drivers/servo/Servo.h>
 #include <events/Events.h>
 #include <events/FSM.h>
 
diff --git a/src/boards/DeathStack/Deployment/DeploymentData.h b/src/boards/DeathStack/Deployment/DeploymentData.h
index 48f504a58..bb5c5fda8 100644
--- a/src/boards/DeathStack/Deployment/DeploymentData.h
+++ b/src/boards/DeathStack/Deployment/DeploymentData.h
@@ -22,7 +22,6 @@
 
 #pragma once
 
-#include <drivers/hbridge/HBridgeData.h>
 #include <stdint.h>
 
 #include <iostream>
diff --git a/src/boards/DeathStack/Deployment/DeploymentServo.h b/src/boards/DeathStack/Deployment/DeploymentServo.h
index 473b82ced..29632f1b8 100644
--- a/src/boards/DeathStack/Deployment/DeploymentServo.h
+++ b/src/boards/DeathStack/Deployment/DeploymentServo.h
@@ -24,7 +24,7 @@
 
 #include <common/ServoInterface.h>
 #include <configs/DeploymentConfig.h>
-#include <drivers/servo/servo.h>
+#include <drivers/servo/Servo.h>
 #include <miosix.h>
 
 using namespace Boardcore;
@@ -37,7 +37,7 @@ using namespace DeathStackBoard::DeploymentConfigs;
 class DeploymentServo : public ServoInterface
 {
 public:
-    Servo servo{DPL_SERVO_TIMER};
+    Servo servo{DPL_SERVO_TIMER, DPL_SERVO_PWM_CH, 50, 500, 2500};
 
     DeploymentServo()
         : ServoInterface(DPL_SERVO_MIN_POS, DPL_SERVO_MAX_POS,
@@ -50,19 +50,9 @@ public:
     {
     }
 
-    void enable() override
-    {
-        servo.setMinPulseWidth(500);
-        servo.setMaxPulseWidth(2500);
-        servo.enable(DPL_SERVO_PWM_CH);
-        servo.start();
-    }
+    void enable() override { servo.enable(); }
 
-    void disable() override
-    {
-        servo.stop();
-        servo.disable(DPL_SERVO_PWM_CH);
-    }
+    void disable() override { servo.disable(); }
 
     /**
      * @brief Perform wiggle around the reset position.
@@ -82,7 +72,7 @@ protected:
     void setPosition(float angle) override
     {
         currentPosition = angle;
-        servo.setPosition(DPL_SERVO_PWM_CH, currentPosition / 180.0f);
+        servo.setPosition180Deg(currentPosition);
     }
 
 private:
diff --git a/src/boards/DeathStack/FlightModeManager/FMMController.cpp b/src/boards/DeathStack/FlightModeManager/FMMController.cpp
index 35940b9e1..4b2dac76f 100644
--- a/src/boards/DeathStack/FlightModeManager/FMMController.cpp
+++ b/src/boards/DeathStack/FlightModeManager/FMMController.cpp
@@ -34,28 +34,28 @@ namespace DeathStackBoard
 FMMController::FMMController()
     : HSM(&FMMController::state_initialization, STACK_MIN_FOR_SKYWARD,
           FMM_PRIORITY),
-      logger(*(LoggerService::getInstance()))
+      logger(LoggerService::getInstance())
 {
-    sEventBroker->subscribe(this, TOPIC_ADA);
-    sEventBroker->subscribe(this, TOPIC_NAS);
-    sEventBroker->subscribe(this, TOPIC_TMTC);
-    sEventBroker->subscribe(this, TOPIC_FMM);
-    sEventBroker->subscribe(this, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.subscribe(this, TOPIC_ADA);
+    sEventBroker.subscribe(this, TOPIC_NAS);
+    sEventBroker.subscribe(this, TOPIC_TMTC);
+    sEventBroker.subscribe(this, TOPIC_FMM);
+    sEventBroker.subscribe(this, TOPIC_FLIGHT_EVENTS);
 }
 
 FMMController::~FMMController()
 {
     // Unsubscribe from all topics
-    sEventBroker->unsubscribe(this);
+    sEventBroker.unsubscribe(this);
 }
 
 void FMMController::logState(FMMState current_state)
 {
-    status.timestamp = TimestampTimer::getTimestamp();
+    status.timestamp = TimestampTimer::getInstance().getTimestamp();
     status.state     = current_state;
 
     logger.log(status);
-    StackLogger::getInstance()->updateStack(THID_FMM_FSM);
+    StackLogger::getInstance().updateStack(THID_FMM_FSM);
 }
 
 State FMMController::state_initialization(const Event& ev)
@@ -69,7 +69,7 @@ State FMMController::state_initialization(const Event& ev)
 State FMMController::state_onGround(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
@@ -106,7 +106,7 @@ State FMMController::state_onGround(const Event& ev)
         default: /* If an event is not handled here, try with super-state */
         {
             // Since this is an outer super-state, the parent is HSM_top
-            retState = tran_super(&FMMController::Hsm_top);
+            retState = tranSuper(&FMMController::Hsm_top);
             break;
         }
     }
@@ -116,7 +116,7 @@ State FMMController::state_onGround(const Event& ev)
 State FMMController::state_init(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
@@ -146,7 +146,7 @@ State FMMController::state_init(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_onGround);
+            retState = tranSuper(&FMMController::state_onGround);
             break;
         }
     }
@@ -156,7 +156,7 @@ State FMMController::state_init(const Event& ev)
 State FMMController::state_initError(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
@@ -181,7 +181,7 @@ State FMMController::state_initError(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_onGround);
+            retState = tranSuper(&FMMController::state_onGround);
             break;
         }
     }
@@ -191,7 +191,7 @@ State FMMController::state_initError(const Event& ev)
 State FMMController::state_initDone(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
@@ -221,7 +221,7 @@ State FMMController::state_initDone(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_onGround);
+            retState = tranSuper(&FMMController::state_onGround);
             break;
         }
     }
@@ -231,7 +231,7 @@ State FMMController::state_initDone(const Event& ev)
 State FMMController::state_sensorsCalibration(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
@@ -239,8 +239,8 @@ State FMMController::state_sensorsCalibration(const Event& ev)
 
             LOG_DEBUG(log, "Entering sensors_calibration");
 
-            DeathStack::getInstance()->sensors->calibrate();
-            sEventBroker->post({EV_SENSORS_READY}, TOPIC_FLIGHT_EVENTS);
+            DeathStack::getInstance().sensors->calibrate();
+            sEventBroker.post({EV_SENSORS_READY}, TOPIC_FLIGHT_EVENTS);
 
             break;
         }
@@ -266,7 +266,7 @@ State FMMController::state_sensorsCalibration(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_onGround);
+            retState = tranSuper(&FMMController::state_onGround);
             break;
         }
     }
@@ -276,14 +276,14 @@ State FMMController::state_sensorsCalibration(const Event& ev)
 State FMMController::state_algosCalibration(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
             logState(FMMState::ALGOS_CALIBRATION);
 
-            sEventBroker->post({EV_CALIBRATE_ADA}, TOPIC_ADA);
-            sEventBroker->post({EV_CALIBRATE_NAS}, TOPIC_NAS);
+            sEventBroker.post({EV_CALIBRATE_ADA}, TOPIC_ADA);
+            sEventBroker.post({EV_CALIBRATE_NAS}, TOPIC_NAS);
 
             LOG_DEBUG(log, "Entering algos_calibration");
             break;
@@ -308,8 +308,8 @@ State FMMController::state_algosCalibration(const Event& ev)
             ada_ready = true;
             if (nas_ready)
             {
-                sEventBroker->post(Event{EV_CALIBRATION_OK},
-                                   TOPIC_FLIGHT_EVENTS);
+                sEventBroker.post(Event{EV_CALIBRATION_OK},
+                                  TOPIC_FLIGHT_EVENTS);
             }
             break;
         }
@@ -318,8 +318,8 @@ State FMMController::state_algosCalibration(const Event& ev)
             nas_ready = true;
             if (ada_ready)
             {
-                sEventBroker->post(Event{EV_CALIBRATION_OK},
-                                   TOPIC_FLIGHT_EVENTS);
+                sEventBroker.post(Event{EV_CALIBRATION_OK},
+                                  TOPIC_FLIGHT_EVENTS);
             }
             break;
         }
@@ -330,7 +330,7 @@ State FMMController::state_algosCalibration(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_onGround);
+            retState = tranSuper(&FMMController::state_onGround);
             break;
         }
     }
@@ -340,11 +340,11 @@ State FMMController::state_algosCalibration(const Event& ev)
 State FMMController::state_disarmed(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
-            sEventBroker->post({EV_DISARMED}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post({EV_DISARMED}, TOPIC_FLIGHT_EVENTS);
             logState(FMMState::DISARMED);
             LOG_DEBUG(log, "Entering disarmed");
 
@@ -380,7 +380,7 @@ State FMMController::state_disarmed(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_onGround);
+            retState = tranSuper(&FMMController::state_onGround);
             break;
         }
     }
@@ -390,11 +390,11 @@ State FMMController::state_disarmed(const Event& ev)
 State FMMController::state_armed(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
-            sEventBroker->post({EV_ARMED}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post({EV_ARMED}, TOPIC_FLIGHT_EVENTS);
             logState(FMMState::ARMED);
 
             LOG_DEBUG(log, "Entering armed");
@@ -423,7 +423,7 @@ State FMMController::state_armed(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::Hsm_top);
+            retState = tranSuper(&FMMController::Hsm_top);
             break;
         }
     }
@@ -433,7 +433,7 @@ State FMMController::state_armed(const Event& ev)
 State FMMController::state_testMode(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
@@ -455,37 +455,37 @@ State FMMController::state_testMode(const Event& ev)
         }
         case EV_TC_NC_OPEN:
         {
-            sEventBroker->post(Event{EV_NC_OPEN}, TOPIC_DPL);
+            sEventBroker.post(Event{EV_NC_OPEN}, TOPIC_DPL);
             break;
         }
         case EV_TC_DPL_WIGGLE_SERVO:
         {
-            sEventBroker->post(Event{EV_WIGGLE_SERVO}, TOPIC_DPL);
+            sEventBroker.post(Event{EV_WIGGLE_SERVO}, TOPIC_DPL);
             break;
         }
         case EV_TC_DPL_RESET_SERVO:
         {
-            sEventBroker->post(Event{EV_RESET_SERVO}, TOPIC_DPL);
+            sEventBroker.post(Event{EV_RESET_SERVO}, TOPIC_DPL);
             break;
         }
         case EV_TC_CUT_DROGUE:
         {
-            sEventBroker->post(Event{EV_CUT_DROGUE}, TOPIC_DPL);
+            sEventBroker.post(Event{EV_CUT_DROGUE}, TOPIC_DPL);
             break;
         }
         case EV_TC_ABK_WIGGLE_SERVO:
         {
-            sEventBroker->post(Event{EV_WIGGLE_SERVO}, TOPIC_ABK);
+            sEventBroker.post(Event{EV_WIGGLE_SERVO}, TOPIC_ABK);
             break;
         }
         case EV_TC_ABK_RESET_SERVO:
         {
-            sEventBroker->post(Event{EV_RESET_SERVO}, TOPIC_ABK);
+            sEventBroker.post(Event{EV_RESET_SERVO}, TOPIC_ABK);
             break;
         }
         case EV_TC_TEST_ABK:
         {
-            sEventBroker->post(Event{EV_TEST_ABK}, TOPIC_ABK);
+            sEventBroker.post(Event{EV_TEST_ABK}, TOPIC_ABK);
             break;
         }
         case EV_TC_CLOSE_LOG:
@@ -495,12 +495,12 @@ State FMMController::state_testMode(const Event& ev)
         }
         case EV_TC_START_LOG:
         {
-            DeathStackBoard::DeathStack::getInstance()->startLogger();
+            DeathStackBoard::DeathStack::getInstance().startLogger();
             break;
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_onGround);
+            retState = tranSuper(&FMMController::state_onGround);
             break;
         }
     }
@@ -510,20 +510,20 @@ State FMMController::state_testMode(const Event& ev)
 State FMMController::state_flying(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
             logState(FMMState::FLYING);
 
-            sEventBroker->post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
             // Start timeout for closing file descriptors
             end_mission_d_event_id =
-                sEventBroker->postDelayed<TIMEOUT_END_MISSION>(
+                sEventBroker.postDelayed<TIMEOUT_END_MISSION>(
                     {EV_TIMEOUT_END_MISSION}, TOPIC_FMM);
 
 #ifdef USE_MOCK_SENSORS
-            DeathStack::getInstance()->sensors->signalLiftoff();
+            DeathStack::getInstance().ensors->signalLiftoff();
 #endif
 
             LOG_DEBUG(log, "Entering flying");
@@ -540,21 +540,21 @@ State FMMController::state_flying(const Event& ev)
         {
             LOG_DEBUG(log, "Exiting flying");
 
-            sEventBroker->removeDelayed(end_mission_d_event_id);
+            sEventBroker.removeDelayed(end_mission_d_event_id);
             break;
         }
         case EV_TC_NC_OPEN:
         {
             // Open nosecone command sent by GS in case of problems
             // during flight
-            sEventBroker->post(Event{EV_NC_OPEN}, TOPIC_DPL);
+            sEventBroker.post(Event{EV_NC_OPEN}, TOPIC_DPL);
             break;
         }
         case EV_TC_ABK_DISABLE:
         {
             // Disable airbrakes command sent by GS in case of problems
             // during flight
-            sEventBroker->post(Event{EV_DISABLE_ABK}, TOPIC_ABK);
+            sEventBroker.post(Event{EV_DISABLE_ABK}, TOPIC_ABK);
             break;
         }
         case EV_TC_END_MISSION:
@@ -565,7 +565,7 @@ State FMMController::state_flying(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::Hsm_top);
+            retState = tranSuper(&FMMController::Hsm_top);
             break;
         }
     }
@@ -575,7 +575,7 @@ State FMMController::state_flying(const Event& ev)
 State FMMController::state_ascending(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
@@ -597,7 +597,7 @@ State FMMController::state_ascending(const Event& ev)
         case EV_ADA_APOGEE_DETECTED:
         {
             // Notify of apogee all components
-            sEventBroker->post(Event{EV_APOGEE}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post(Event{EV_APOGEE}, TOPIC_FLIGHT_EVENTS);
 
             retState = transition(&FMMController::state_drogueDescent);
             break;
@@ -605,14 +605,14 @@ State FMMController::state_ascending(const Event& ev)
         case EV_ADA_DISABLE_ABK:
         {
             // Send disable airbrakes
-            sEventBroker->post(Event{EV_DISABLE_ABK}, TOPIC_ABK);
+            sEventBroker.post(Event{EV_DISABLE_ABK}, TOPIC_ABK);
 
             retState = transition(&FMMController::state_ascending);
             break;
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_flying);
+            retState = tranSuper(&FMMController::state_flying);
             break;
         }
     }
@@ -622,12 +622,12 @@ State FMMController::state_ascending(const Event& ev)
 State FMMController::state_drogueDescent(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
             // Open nosecone
-            sEventBroker->post(Event{EV_NC_OPEN}, TOPIC_DPL);
+            sEventBroker.post(Event{EV_NC_OPEN}, TOPIC_DPL);
 
             logState(FMMState::DROGUE_DESCENT);
             LOG_DEBUG(log, "Entering drogueDescent");
@@ -651,7 +651,7 @@ State FMMController::state_drogueDescent(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_flying);
+            retState = tranSuper(&FMMController::state_flying);
             break;
         }
     }
@@ -661,13 +661,13 @@ State FMMController::state_drogueDescent(const Event& ev)
 State FMMController::state_terminalDescent(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
-            sEventBroker->post({EV_DPL_ALTITUDE}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post({EV_DPL_ALTITUDE}, TOPIC_FLIGHT_EVENTS);
 
-            sEventBroker->post(Event{EV_CUT_DROGUE}, TOPIC_DPL);
+            sEventBroker.post(Event{EV_CUT_DROGUE}, TOPIC_DPL);
 
             logState(FMMState::TERMINAL_DESCENT);
 
@@ -684,12 +684,12 @@ State FMMController::state_terminalDescent(const Event& ev)
         }
         case EV_TC_CUT_DROGUE:  // if you want to repeat cutting
         {
-            sEventBroker->post(Event{EV_CUT_DROGUE}, TOPIC_DPL);
+            sEventBroker.post(Event{EV_CUT_DROGUE}, TOPIC_DPL);
             break;
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::state_flying);
+            retState = tranSuper(&FMMController::state_flying);
             break;
         }
     }
@@ -699,14 +699,14 @@ State FMMController::state_terminalDescent(const Event& ev)
 State FMMController::state_landed(const Event& ev)
 {
     State retState = HANDLED;
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY: /* Executed everytime state is entered */
         {
             logState(FMMState::LANDED);
 
             // Announce landing to all components
-            sEventBroker->post(Event{EV_LANDED}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post(Event{EV_LANDED}, TOPIC_FLIGHT_EVENTS);
             logger.stop();
 
             LOG_DEBUG(log, "Entering landed");
@@ -722,7 +722,7 @@ State FMMController::state_landed(const Event& ev)
         }
         default: /* If an event is not handled here, try with super-state */
         {
-            retState = tran_super(&FMMController::Hsm_top);
+            retState = tranSuper(&FMMController::Hsm_top);
             break;
         }
     }
diff --git a/src/boards/DeathStack/FlightStatsRecorder/FSRController.cpp b/src/boards/DeathStack/FlightStatsRecorder/FSRController.cpp
index c077390bb..1205db39d 100644
--- a/src/boards/DeathStack/FlightStatsRecorder/FSRController.cpp
+++ b/src/boards/DeathStack/FlightStatsRecorder/FSRController.cpp
@@ -35,12 +35,12 @@ namespace DeathStackBoard
 FlightStatsRecorder::FlightStatsRecorder()
     : FSM(&FlightStatsRecorder::state_idle)
 {
-    sEventBroker->subscribe(this, TOPIC_FLIGHT_EVENTS);
-    sEventBroker->subscribe(this, TOPIC_DPL);
-    sEventBroker->subscribe(this, TOPIC_STATS);
+    sEventBroker.subscribe(this, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.subscribe(this, TOPIC_DPL);
+    sEventBroker.subscribe(this, TOPIC_STATS);
 }
 
-FlightStatsRecorder::~FlightStatsRecorder() { sEventBroker->unsubscribe(this); }
+FlightStatsRecorder::~FlightStatsRecorder() { sEventBroker.unsubscribe(this); }
 
 void FlightStatsRecorder::update(const ADAKalmanState& t)
 {
@@ -125,9 +125,9 @@ void FlightStatsRecorder::update(const MS5803Data& t)
     {
         case FSRState::ASCENDING:
         {
-            if (t.press < apogee_stats.digital_min_pressure)
+            if (t.pressure < apogee_stats.digital_min_pressure)
             {
-                apogee_stats.digital_min_pressure = t.press;
+                apogee_stats.digital_min_pressure = t.pressure;
             }
             break;
         }
@@ -142,9 +142,9 @@ void FlightStatsRecorder::update(const MPXHZ6130AData& t)
     {
         case FSRState::ASCENDING:
         {
-            if (t.press < apogee_stats.static_min_pressure)
+            if (t.pressure < apogee_stats.static_min_pressure)
             {
-                apogee_stats.static_min_pressure = t.press;
+                apogee_stats.static_min_pressure = t.pressure;
             }
             break;
         }
@@ -159,9 +159,9 @@ void FlightStatsRecorder::update(const SSCDANN030PAAData& t)
     {
         case FSRState::ASCENDING:
         {
-            if (t.press > drogue_dpl_stats.max_dpl_vane_pressure)
+            if (t.pressure > drogue_dpl_stats.max_dpl_vane_pressure)
             {
-                drogue_dpl_stats.max_dpl_vane_pressure = t.press;
+                drogue_dpl_stats.max_dpl_vane_pressure = t.pressure;
             }
             break;
         }
@@ -177,19 +177,19 @@ void FlightStatsRecorder::update(const BMX160WithCorrectionData& t)
     {
         case FSRState::LIFTOFF:
         {
-            if (fabs(t.accel_x) > liftoff_stats.acc_max)
+            if (fabs(t.accelerationX) > liftoff_stats.acc_max)
             {
                 liftoff_stats.T_max_acc =
                     static_cast<uint32_t>(miosix::getTick());
-                liftoff_stats.acc_max = fabs(t.accel_x);
+                liftoff_stats.acc_max = fabs(t.accelerationX);
             }
             break;
         }
         case FSRState::DROGUE_DPL:
         {
-            if (fabs(t.accel_x) > fabs(drogue_dpl_stats.max_dpl_acc))
+            if (fabs(t.accelerationX) > fabs(drogue_dpl_stats.max_dpl_acc))
             {
-                drogue_dpl_stats.max_dpl_acc = t.accel_x;
+                drogue_dpl_stats.max_dpl_acc = t.accelerationX;
                 drogue_dpl_stats.T_dpl =
                     static_cast<uint32_t>(miosix::getTick());
             }
@@ -197,9 +197,9 @@ void FlightStatsRecorder::update(const BMX160WithCorrectionData& t)
         }
         case FSRState::MAIN_DPL:
         {
-            if (fabs(t.accel_x) > fabs(main_dpl_stats.max_dpl_acc))
+            if (fabs(t.accelerationX) > fabs(main_dpl_stats.max_dpl_acc))
             {
-                main_dpl_stats.max_dpl_acc = t.accel_x;
+                main_dpl_stats.max_dpl_acc = t.accelerationX;
             }
             break;
         }
@@ -208,7 +208,7 @@ void FlightStatsRecorder::update(const BMX160WithCorrectionData& t)
     }
 }
 
-void FlightStatsRecorder::update(const UbloxGPSData& t)
+void FlightStatsRecorder::update(const GPSData& t)
 {
     switch (state)
     {
@@ -232,7 +232,7 @@ void FlightStatsRecorder::update(const HILImuData& t)
 {
     BMX160Data d;
     d.accel_timestamp = t.accel_timestamp;
-    d.accel_x         = t.accel_x;
+    d.accelerationX   = t.accelerationX;
     d.accel_y         = t.accel_y;
     d.accel_z         = t.accel_z;
     d.gyro_timestamp  = t.gyro_timestamp;
@@ -250,13 +250,13 @@ void FlightStatsRecorder::update(const HILBaroData& t)
 {
     MS5803Data d;
     d.press_timestamp = t.press_timestamp;
-    d.press           = t.press;
+    d.pressure        = t.press;
     this->update(d);
 }
 
 void FlightStatsRecorder::update(const HILGpsData& t)
 {
-    UbloxGPSData d;
+    GPSData d;
     d.latitude       = t.latitude;
     d.longitude      = t.longitude;
     d.height         = t.height;
@@ -273,15 +273,15 @@ void FlightStatsRecorder::update(const HILGpsData& t)
 
 void FlightStatsRecorder::state_idle(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
             LOG_DEBUG(log, "Entering IDLE state");
-            
+
             state = FSRState::IDLE;
 
-            StackLogger::getInstance()->updateStack(THID_STATS_FSM);
+            StackLogger::getInstance().updateStack(THID_STATS_FSM);
             break;
         }
         case EV_EXIT:
@@ -309,7 +309,7 @@ void FlightStatsRecorder::state_idle(const Event& ev)
 
 void FlightStatsRecorder::state_liftOff(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -320,22 +320,22 @@ void FlightStatsRecorder::state_liftOff(const Event& ev)
             // Collect liftoff stats until this event is received
             ev_timeout_id =
                 sEventBroker
-                    ->postDelayed<FlightStatsConfig::TIMEOUT_LIFTOFF_STATS>(
+                    .postDelayed<FlightStatsConfig::TIMEOUT_LIFTOFF_STATS>(
                         {EV_STATS_TIMEOUT}, TOPIC_STATS);
 
             // Save liftoff time
             liftoff_stats.T_liftoff = static_cast<uint32_t>(miosix::getTick());
 
-            StackLogger::getInstance()->updateStack(THID_STATS_FSM);
+            StackLogger::getInstance().updateStack(THID_STATS_FSM);
             break;
         }
         case EV_EXIT:
         {
             LOG_DEBUG(log, "Exiting LIFTOFF state");
 
-            LoggerService::getInstance()->log(liftoff_stats);
+            LoggerService::getInstance().log(liftoff_stats);
 
-            sEventBroker->removeDelayed(ev_timeout_id);
+            sEventBroker.removeDelayed(ev_timeout_id);
             break;
         }
         case EV_STATS_TIMEOUT:
@@ -352,7 +352,7 @@ void FlightStatsRecorder::state_liftOff(const Event& ev)
 
 void FlightStatsRecorder::state_ascending(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -360,16 +360,16 @@ void FlightStatsRecorder::state_ascending(const Event& ev)
 
             state = FSRState::ASCENDING;
 
-            StackLogger::getInstance()->updateStack(THID_STATS_FSM);
+            StackLogger::getInstance().updateStack(THID_STATS_FSM);
             break;
         }
         case EV_EXIT:
         {
             LOG_DEBUG(log, "Exiting ASCENDING state");
 
-            LoggerService::getInstance()->log(apogee_stats);
+            LoggerService::getInstance().log(apogee_stats);
 
-            sEventBroker->removeDelayed(ev_timeout_id);
+            sEventBroker.removeDelayed(ev_timeout_id);
             break;
         }
         case EV_APOGEE:
@@ -381,7 +381,7 @@ void FlightStatsRecorder::state_ascending(const Event& ev)
             // seconds in order to record the maximum altitude.
             ev_timeout_id =
                 sEventBroker
-                    ->postDelayed<FlightStatsConfig::TIMEOUT_APOGEE_STATS>(
+                    .postDelayed<FlightStatsConfig::TIMEOUT_APOGEE_STATS>(
                         {EV_STATS_TIMEOUT}, TOPIC_STATS);
             break;
         }
@@ -400,7 +400,7 @@ void FlightStatsRecorder::state_ascending(const Event& ev)
 
 void FlightStatsRecorder::state_drogueDeployment(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -411,19 +411,19 @@ void FlightStatsRecorder::state_drogueDeployment(const Event& ev)
             // Collect stats until this event is received
             ev_timeout_id =
                 sEventBroker
-                    ->postDelayed<FlightStatsConfig::TIMEOUT_DROGUE_DPL_STATS>(
+                    .postDelayed<FlightStatsConfig::TIMEOUT_DROGUE_DPL_STATS>(
                         {EV_STATS_TIMEOUT}, TOPIC_STATS);
 
-            StackLogger::getInstance()->updateStack(THID_STATS_FSM);
+            StackLogger::getInstance().updateStack(THID_STATS_FSM);
             break;
         }
         case EV_EXIT:
         {
             LOG_DEBUG(log, "Exiting DROGUE_DPL state");
 
-            LoggerService::getInstance()->log(drogue_dpl_stats);
+            LoggerService::getInstance().log(drogue_dpl_stats);
 
-            sEventBroker->removeDelayed(ev_timeout_id);
+            sEventBroker.removeDelayed(ev_timeout_id);
             break;
         }
         case EV_STATS_TIMEOUT:
@@ -440,7 +440,7 @@ void FlightStatsRecorder::state_drogueDeployment(const Event& ev)
 
 void FlightStatsRecorder::state_mainDeployment(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -454,19 +454,19 @@ void FlightStatsRecorder::state_mainDeployment(const Event& ev)
             // Record stats until this event occurs
             ev_timeout_id =
                 sEventBroker
-                    ->postDelayed<FlightStatsConfig::TIMEOUT_MAIN_DPL_STATS>(
+                    .postDelayed<FlightStatsConfig::TIMEOUT_MAIN_DPL_STATS>(
                         {EV_STATS_TIMEOUT}, TOPIC_STATS);
 
-            StackLogger::getInstance()->updateStack(THID_STATS_FSM);
+            StackLogger::getInstance().updateStack(THID_STATS_FSM);
             break;
         }
         case EV_EXIT:
         {
             LOG_DEBUG(log, "Exiting MAIN_DPL state");
 
-            LoggerService::getInstance()->log(main_dpl_stats);
+            LoggerService::getInstance().log(main_dpl_stats);
 
-            sEventBroker->removeDelayed(ev_timeout_id);
+            sEventBroker.removeDelayed(ev_timeout_id);
             break;
         }
         case EV_STATS_TIMEOUT:
@@ -484,7 +484,7 @@ void FlightStatsRecorder::state_mainDeployment(const Event& ev)
 /*
 void FlightStatsRecorder::state_testingCutters(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -494,10 +494,10 @@ void FlightStatsRecorder::state_testingCutters(const Event& ev)
 
             const int timeout = CutterConfig::CUT_TEST_DURATION;
 
-            ev_timeout_id = sEventBroker->postDelayed<timeout>(
+            ev_timeout_id = sEventBroker.postDelayed<timeout>(
                 {EV_STATS_TIMEOUT}, TOPIC_STATS);
 
-            StackLogger::getInstance()->updateStack(THID_STATS_FSM);
+            StackLogger::getInstance().updateStack(THID_STATS_FSM);
             LOG_DEBUG(log, "Entering CUTTER_TEST state");
             break;
         }
@@ -508,8 +508,8 @@ void FlightStatsRecorder::state_testingCutters(const Event& ev)
             cutters_stats.cutter_2_avg =
                 cutters_stats.cutter_2_avg / cutters_stats.n_samples_2;
 
-            LoggerService::getInstance()->log(cutters_stats);
-            sEventBroker->removeDelayed(ev_timeout_id);
+            LoggerService::getInstance().log(cutters_stats);
+            sEventBroker.removeDelayed(ev_timeout_id);
 
             LOG_DEBUG(log, "Exiting CUTTER_TEST state");
             break;
diff --git a/src/boards/DeathStack/FlightStatsRecorder/FSRController.h b/src/boards/DeathStack/FlightStatsRecorder/FSRController.h
index 018de20a1..f00899138 100644
--- a/src/boards/DeathStack/FlightStatsRecorder/FSRController.h
+++ b/src/boards/DeathStack/FlightStatsRecorder/FSRController.h
@@ -27,7 +27,6 @@
 #include <Main/SensorsData.h>
 #include <configs/FlightStatsConfig.h>
 #include <diagnostic/PrintLogger.h>
-#include <drivers/gps/ublox/UbloxGPSData.h>
 #include <events/FSM.h>
 #include <sensors/BMX160/BMX160WithCorrectionData.h>
 #include <sensors/MS5803/MS5803Data.h>
@@ -60,11 +59,11 @@ public:
 
     void update(const ADAKalmanState& t);
     void update(const ADAData& t);
-    void update(const UbloxGPSData& t);
+    void update(const GPSData& t);
     void update(const BMX160WithCorrectionData& t);
-    //void update(const CurrentSensorData& t);
-    void update(const MS5803Data& t);      // digitl baro
-    void update(const MPXHZ6130AData& t);  // static ports baro
+    // void update(const CurrentSensorData& t);
+    void update(const MS5803Data& t);         // digitl baro
+    void update(const MPXHZ6130AData& t);     // static ports baro
     void update(const SSCDANN030PAAData& t);  // DPL vane baro
     void update(const AirSpeedPitot& t);
 
@@ -104,7 +103,7 @@ private:
     ApogeeStats apogee_stats{};
     DrogueDPLStats drogue_dpl_stats{};
     MainDPLStats main_dpl_stats{};
-    //CutterTestStats cutters_stats{};
+    // CutterTestStats cutters_stats{};
     FSRState state      = FSRState::IDLE;
     long long T_liftoff = 0;
 
diff --git a/src/boards/DeathStack/LoggerService/LoggerService.h b/src/boards/DeathStack/LoggerService/LoggerService.h
index 8f6584bd2..c4593aa70 100644
--- a/src/boards/DeathStack/LoggerService/LoggerService.h
+++ b/src/boards/DeathStack/LoggerService/LoggerService.h
@@ -46,7 +46,7 @@ public:
      * @brief Generic log function, to be implemented for each loggable struct.
      */
     template <typename T>
-    inline LogResult log(const T& t)
+    inline LoggerResult log(const T& t)
     {
         {
             miosix::PauseKernelLock kLock;
@@ -86,7 +86,7 @@ private:
      * @brief Private constructor to enforce the singleton
      */
     LoggerService()
-        : logger(Logger::instance()), tmRepo(*(TmRepository::getInstance()))
+        : logger(Logger::getInstance()), tmRepo(TmRepository::getInstance())
     {
     }
 
diff --git a/src/boards/DeathStack/Main/Radio.cpp b/src/boards/DeathStack/Main/Radio.cpp
index 1f6248121..aa50827f5 100644
--- a/src/boards/DeathStack/Main/Radio.cpp
+++ b/src/boards/DeathStack/Main/Radio.cpp
@@ -42,9 +42,9 @@ void __attribute__((used)) EXTI10_IRQHandlerImpl()
 {
     using namespace DeathStackBoard;
 
-    if (DeathStack::getInstance()->radio->xbee != nullptr)
+    if (DeathStack::getInstance().radio->xbee != nullptr)
     {
-        DeathStack::getInstance()->radio->xbee->handleATTNInterrupt();
+        DeathStack::getInstance().radio->xbee->handleATTNInterrupt();
     }
 }
 
@@ -55,7 +55,7 @@ Radio::Radio(SPIBusInterface& xbee_bus) : xbee_bus(xbee_bus)
 {
     SPIBusConfig xbee_cfg{};
 
-    xbee_cfg.clock_div = SPIClockDivider::DIV16;
+    xbee_cfg.clockDivider = SPI::ClockDivider::DIV_16;
 
     xbee = new Xbee::Xbee(xbee_bus, xbee_cfg, miosix::xbee::cs::getPin(),
                           miosix::xbee::attn::getPin(),
@@ -70,7 +70,7 @@ Radio::Radio(SPIBusInterface& xbee_bus) : xbee_bus(xbee_bus)
 
     tmtc_manager = new TMTCController();
 
-    tm_repo = TmRepository::getInstance();
+    tm_repo = &(TmRepository::getInstance());
 
     enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::FALLING_EDGE);
 }
@@ -89,11 +89,11 @@ bool Radio::start() { return mav_driver->start() && tmtc_manager->start(); }
 
 void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
 {
-    LoggerService& logger = *LoggerService::getInstance();
+    LoggerService& logger = LoggerService::getInstance();
 
     using namespace Xbee;
     bool logged = false;
-    switch (frame.frame_type)
+    switch (frame.frameType)
     {
         case FTYPE_AT_COMMAND:
         {
@@ -168,9 +168,9 @@ void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
 void Radio::logStatus()
 {
     MavlinkStatus status = mav_driver->getStatus();
-    status.timestamp     = TimestampTimer::getTimestamp();
-    LoggerService::getInstance()->log(status);
-    LoggerService::getInstance()->log(xbee->getStatus());
+    status.timestamp     = TimestampTimer::getInstance().getTimestamp();
+    LoggerService::getInstance().log(status);
+    LoggerService::getInstance().log(xbee->getStatus());
 }
 
 }  // namespace DeathStackBoard
\ No newline at end of file
diff --git a/src/boards/DeathStack/Main/Sensors.cpp b/src/boards/DeathStack/Main/Sensors.cpp
index 3242f76a9..78721d919 100644
--- a/src/boards/DeathStack/Main/Sensors.cpp
+++ b/src/boards/DeathStack/Main/Sensors.cpp
@@ -22,11 +22,10 @@
 
 #include <ApogeeDetectionAlgorithm/ADAController.h>
 #include <DeathStack.h>
-#include <Debug.h>
 #include <LoggerService/LoggerService.h>
-#include <TimestampTimer.h>
 #include <configs/SensorsConfig.h>
 #include <drivers/interrupt/external_interrupts.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <interfaces-impl/hwmapping.h>
 #include <sensors/Sensor.h>
 #include <utils/aero/AeroUtils.h>
@@ -37,17 +36,15 @@
 using std::bind;
 using std::function;
 
-using namespace Boardcore;
-
 // BMX160 Watermark interrupt
 void __attribute__((used)) EXTI5_IRQHandlerImpl()
 {
     using namespace DeathStackBoard;
 
-    if (DeathStack::getInstance()->sensors->imu_bmx160 != nullptr)
+    if (DeathStack::getInstance().sensors->imu_bmx160 != nullptr)
     {
-        DeathStack::getInstance()->sensors->imu_bmx160->IRQupdateTimestamp(
-            TimestampTimer::getTimestamp());
+        DeathStack::getInstance().sensors->imu_bmx160->IRQupdateTimestamp(
+            TimestampTimer::getInstance().getTimestamp());
     }
 }
 
@@ -78,7 +75,7 @@ Sensors::Sensors(SPIBusInterface& spi1_bus, TaskScheduler* scheduler)
     mockSensorsInit();
 #endif
 
-    sensor_manager = new SensorManager(scheduler, sensors_map);
+    sensor_manager = new SensorManager(sensors_map, scheduler);
 }
 
 Sensors::~Sensors()
@@ -123,7 +120,7 @@ bool Sensors::start()
         updateSensorsStatus();
     }
 
-    LoggerService::getInstance()->log(status);
+    LoggerService::getInstance().log(status);
 
     return sm_start_result;
 }
@@ -131,7 +128,7 @@ bool Sensors::start()
 void Sensors::calibrate()
 {
     imu_bmx160_with_correction->calibrate();
-    LoggerService::getInstance()->log(
+    LoggerService::getInstance().log(
         imu_bmx160_with_correction->getGyroscopeBiases());
 
     press_pitot->calibrate();
@@ -142,7 +139,7 @@ void Sensors::calibrate()
     for (unsigned int i = 0; i < PRESS_STATIC_CALIB_SAMPLES_NUM / 10; i++)
     {
         Thread::sleep(SAMPLE_PERIOD_PRESS_DIGITAL);
-        press_digi_stats.add(press_digital->getLastSample().press);
+        press_digi_stats.add(press_digital->getLastSample().pressure);
     }
     press_static_port->setReferencePressure(press_digi_stats.getStats().mean);
     press_static_port->calibrate();
@@ -165,12 +162,12 @@ void Sensors::signalLiftoff()
 
 void Sensors::internalAdcInit()
 {
-    internal_adc = new InternalADC(*ADC3, INTERNAL_ADC_VREF);
+    internal_adc = new InternalADC(ADC3, INTERNAL_ADC_VREF);
 
     internal_adc->enableChannel(ADC_BATTERY_VOLTAGE);
 
     SensorInfo info("InternalADC", SAMPLE_PERIOD_INTERNAL_ADC,
-                    bind(&Sensors::internalAdcCallback, this), false, true);
+                    bind(&Sensors::internalAdcCallback, this));
     sensors_map.emplace(std::make_pair(internal_adc, info));
 
     LOG_INFO(log, "InternalADC setup done!");
@@ -184,7 +181,7 @@ void Sensors::batteryVoltageInit()
         new BatteryVoltageSensor(voltage_fun, BATTERY_VOLTAGE_COEFF);
 
     SensorInfo info("BatterySensor", SAMPLE_PERIOD_INTERNAL_ADC,
-                    bind(&Sensors::batteryVoltageCallback, this), false, true);
+                    bind(&Sensors::batteryVoltageCallback, this));
 
     sensors_map.emplace(std::make_pair(battery_voltage, info));
 
@@ -194,13 +191,13 @@ void Sensors::batteryVoltageInit()
 void Sensors::pressDigiInit()
 {
     SPIBusConfig spi_cfg{};
-    spi_cfg.clock_div = SPIClockDivider::DIV16;
+    spi_cfg.clockDivider = SPI::ClockDivider::DIV_16;
 
     press_digital = new MS5803(spi1_bus, miosix::sensors::ms5803::cs::getPin(),
                                spi_cfg, TEMP_DIVIDER_PRESS_DIGITAL);
 
     SensorInfo info("DigitalBarometer", SAMPLE_PERIOD_PRESS_DIGITAL,
-                    bind(&Sensors::pressDigiCallback, this), false, true);
+                    bind(&Sensors::pressDigiCallback, this));
 
     sensors_map.emplace(std::make_pair(press_digital, info));
 
@@ -210,7 +207,7 @@ void Sensors::pressDigiInit()
 void Sensors::ADS1118Init()
 {
     SPIBusConfig spi_cfg = ADS1118::getDefaultSPIConfig();
-    spi_cfg.clock_div    = SPIClockDivider::DIV64;
+    spi_cfg.clockDivider = SPI::ClockDivider::DIV_64;
 
     ADS1118::ADS1118Config ads1118Config = ADS1118::ADS1118_DEFAULT_CONFIG;
     ads1118Config.bits.mode = ADS1118::ADS1118Mode::CONTIN_CONV_MODE;
@@ -229,7 +226,7 @@ void Sensors::ADS1118Init()
     adc_ads1118->enableInput(ADC_CH_VREF, ADC_DR_VREF, ADC_PGA_VREF);
 
     SensorInfo info("ADS1118", SAMPLE_PERIOD_ADC_ADS1118,
-                    bind(&Sensors::ADS1118Callback, this), false, true);
+                    bind(&Sensors::ADS1118Callback, this));
     sensors_map.emplace(std::make_pair(adc_ads1118, info));
 
     LOG_INFO(log, "ADS1118 setup done!");
@@ -243,7 +240,7 @@ void Sensors::pressPitotInit()
                                     PRESS_PITOT_CALIB_SAMPLES_NUM);
 
     SensorInfo info("DiffBarometer", SAMPLE_PERIOD_PRESS_PITOT,
-                    bind(&Sensors::pressPitotCallback, this), false, true);
+                    bind(&Sensors::pressPitotCallback, this));
 
     sensors_map.emplace(std::make_pair(press_pitot, info));
 
@@ -257,7 +254,7 @@ void Sensors::pressDPLVaneInit()
     press_dpl_vane = new SSCDANN030PAA(voltage_fun, REFERENCE_VOLTAGE);
 
     SensorInfo info("DeploymentBarometer", SAMPLE_PERIOD_PRESS_DPL,
-                    bind(&Sensors::pressDPLVaneCallback, this), false, true);
+                    bind(&Sensors::pressDPLVaneCallback, this));
 
     sensors_map.emplace(std::make_pair(press_dpl_vane, info));
 
@@ -273,7 +270,7 @@ void Sensors::pressStaticInit()
                                        PRESS_STATIC_MOVING_AVG_COEFF);
 
     SensorInfo info("StaticPortsBarometer", SAMPLE_PERIOD_PRESS_STATIC,
-                    bind(&Sensors::pressStaticCallback, this), false, true);
+                    bind(&Sensors::pressStaticCallback, this));
 
     sensors_map.emplace(std::make_pair(press_static_port, info));
 
@@ -283,29 +280,29 @@ void Sensors::pressStaticInit()
 void Sensors::imuBMXInit()
 {
     SPIBusConfig spi_cfg;
-    spi_cfg.clock_div = SPIClockDivider::DIV8;
+    spi_cfg.clockDivider = SPI::ClockDivider::DIV_8;
 
     BMX160Config bmx_config;
-    bmx_config.fifo_mode      = BMX160Config::FifoMode::HEADER;
-    bmx_config.fifo_watermark = IMU_BMX_FIFO_WATERMARK;
-    bmx_config.fifo_int       = BMX160Config::FifoInterruptPin::PIN_INT1;
+    bmx_config.fifoMode      = BMX160Config::FifoMode::HEADER;
+    bmx_config.fifoWatermark = IMU_BMX_FIFO_WATERMARK;
+    bmx_config.fifoInterrupt = BMX160Config::FifoInterruptPin::PIN_INT1;
 
-    bmx_config.temp_divider = IMU_BMX_TEMP_DIVIDER;
+    bmx_config.temperatureDivider = IMU_BMX_TEMP_DIVIDER;
 
-    bmx_config.acc_range = IMU_BMX_ACC_FULLSCALE_ENUM;
-    bmx_config.gyr_range = IMU_BMX_GYRO_FULLSCALE_ENUM;
+    bmx_config.accelerometerRange = IMU_BMX_ACC_FULLSCALE_ENUM;
+    bmx_config.gyroscopeRange     = IMU_BMX_GYRO_FULLSCALE_ENUM;
 
-    bmx_config.acc_odr = IMU_BMX_ACC_GYRO_ODR_ENUM;
-    bmx_config.gyr_odr = IMU_BMX_ACC_GYRO_ODR_ENUM;
-    bmx_config.mag_odr = IMU_BMX_MAG_ODR_ENUM;
+    bmx_config.accelerometerDataRate = IMU_BMX_ACC_GYRO_ODR_ENUM;
+    bmx_config.gyroscopeDataRate     = IMU_BMX_ACC_GYRO_ODR_ENUM;
+    bmx_config.magnetometerRate      = IMU_BMX_MAG_ODR_ENUM;
 
-    bmx_config.gyr_unit = BMX160Config::GyroscopeMeasureUnit::RAD;
+    bmx_config.gyroscopeUnit = BMX160Config::GyroscopeMeasureUnit::RAD;
 
     imu_bmx160 = new BMX160(spi1_bus, miosix::sensors::bmx160::cs::getPin(),
                             bmx_config, spi_cfg);
 
     SensorInfo info("BMX160", SAMPLE_PERIOD_IMU_BMX,
-                    bind(&Sensors::imuBMXCallback, this), false, true);
+                    bind(&Sensors::imuBMXCallback, this));
 
     sensors_map.emplace(std::make_pair(imu_bmx160, info));
 
@@ -353,8 +350,7 @@ void Sensors::imuBMXWithCorrectionInit()
         imu_bmx160, correctionParameters, BMX160_AXIS_ROTATION);
 
     SensorInfo info("BMX160WithCorrection", SAMPLE_PERIOD_IMU_BMX,
-                    bind(&Sensors::imuBMXWithCorrectionCallback, this), false,
-                    true);
+                    bind(&Sensors::imuBMXWithCorrectionCallback, this));
 
     sensors_map.emplace(std::make_pair(imu_bmx160_with_correction, info));
 
@@ -364,7 +360,7 @@ void Sensors::imuBMXWithCorrectionInit()
 void Sensors::magLISinit()
 {
     SPIBusConfig busConfig;
-    busConfig.clock_div = SPIClockDivider::DIV32;
+    busConfig.clockDivider = SPI::ClockDivider::DIV_32;
 
     LIS3MDL::Config config;
     config.odr                = MAG_LIS_ODR_ENUM;
@@ -375,7 +371,7 @@ void Sensors::magLISinit()
                               busConfig, config);
 
     SensorInfo info("LIS3MDL", SAMPLE_PERIOD_MAG_LIS,
-                    bind(&Sensors::magLISCallback, this), false, true);
+                    bind(&Sensors::magLISCallback, this));
 
     sensors_map.emplace(std::make_pair(mag_lis3mdl, info));
 
@@ -384,10 +380,10 @@ void Sensors::magLISinit()
 
 void Sensors::gpsUbloxInit()
 {
-    gps_ublox = new UbloxGPS(GPS_BAUD_RATE, GPS_SAMPLE_RATE);
+    gps_ublox = new UbloxGPSSerial(GPS_BAUD_RATE, GPS_SAMPLE_RATE);
 
     SensorInfo info("UbloxGPS", GPS_SAMPLE_PERIOD,
-                    bind(&Sensors::gpsUbloxCallback, this), false, true);
+                    bind(&Sensors::gpsUbloxCallback, this));
 
     sensors_map.emplace(std::make_pair(gps_ublox, info));
 
@@ -396,12 +392,12 @@ void Sensors::gpsUbloxInit()
 
 void Sensors::internalAdcCallback()
 {
-    // LoggerService::getInstance()->log(internal_adc->getLastSample());
+    // LoggerService::getInstance().log(internal_adc->getLastSample());
 }
 
 void Sensors::batteryVoltageCallback()
 {
-    static float v = battery_voltage->getLastSample().bat_voltage;
+    static float v = battery_voltage->getLastSample().batVoltage;
     if (v < BATTERY_MIN_SAFE_VOLTAGE)
     {
         battery_critical_counter++;
@@ -413,18 +409,18 @@ void Sensors::batteryVoltageCallback()
         }
     }
 
-    LoggerService::getInstance()->log(battery_voltage->getLastSample());
+    LoggerService::getInstance().log(battery_voltage->getLastSample());
 }
 
 #ifdef HARDWARE_IN_THE_LOOP
 void Sensors::hilBarometerInit()
 {
-    HILTransceiver* simulator = HIL::getInstance()->simulator;
+    HILTransceiver* simulator = HIL::getInstance().simulator;
 
     hil_baro = new HILBarometer(simulator, N_DATA_BARO);
 
     SensorInfo info_baro("HILBaro", HIL_BARO_PERIOD,
-                         bind(&Sensors::hilBaroCallback, this), false, true);
+                         bind(&Sensors::hilBaroCallback, this));
 
     sensors_map.emplace(std::make_pair(hil_baro, info_baro));
 
@@ -432,12 +428,12 @@ void Sensors::hilBarometerInit()
 }
 void Sensors::hilImuInit()
 {
-    HILTransceiver* simulator = HIL::getInstance()->simulator;
+    HILTransceiver* simulator = HIL::getInstance().simulator;
 
     hil_imu = new HILImu(simulator, N_DATA_IMU);
 
     SensorInfo info_imu("HILImu", HIL_IMU_PERIOD,
-                        bind(&Sensors::hilIMUCallback, this), false, true);
+                        bind(&Sensors::hilIMUCallback, this));
 
     sensors_map.emplace(std::make_pair(hil_imu, info_imu));
 
@@ -446,12 +442,12 @@ void Sensors::hilImuInit()
 
 void Sensors::hilGpsInit()
 {
-    HILTransceiver* simulator = HIL::getInstance()->simulator;
+    HILTransceiver* simulator = HIL::getInstance().simulator;
 
     hil_gps = new HILGps(simulator, N_DATA_GPS);
 
     SensorInfo info_gps("HILGps", HIL_GPS_PERIOD,
-                        bind(&Sensors::hilGPSCallback, this), false, true);
+                        bind(&Sensors::hilGPSCallback, this));
 
     sensors_map.emplace(std::make_pair(hil_gps, info_gps));
 
@@ -465,11 +461,11 @@ void Sensors::mockSensorsInit()
     mock_gps = new MockGPS();
 
     SensorInfo info_baro("MockBaro", SAMPLE_PERIOD_PRESS_STATIC,
-                         bind(&Sensors::mockBaroCallback, this), false, true);
+                         bind(&Sensors::mockBaroCallback, this));
     SensorInfo info_imu("MockIMU", SAMPLE_PERIOD_IMU_BMX,
-                        bind(&Sensors::mockImuCallback, this), false, true);
+                        bind(&Sensors::mockImuCallback, this));
     SensorInfo info_gps("MockGPS", GPS_SAMPLE_PERIOD,
-                        bind(&Sensors::mockGpsCallback, this), false, true);
+                        bind(&Sensors::mockGpsCallback, this));
 
     sensors_map.emplace(std::make_pair(mock_baro, info_baro));
     sensors_map.emplace(std::make_pair(mock_imu, info_imu));
@@ -481,43 +477,44 @@ void Sensors::mockSensorsInit()
 
 void Sensors::pressDigiCallback()
 {
-    LoggerService::getInstance()->log(press_digital->getLastSample());
+    LoggerService::getInstance().log(press_digital->getLastSample());
 }
 
 void Sensors::ADS1118Callback()
 {
-    LoggerService::getInstance()->log(adc_ads1118->getLastSample());
+    LoggerService::getInstance().log(adc_ads1118->getLastSample());
 }
 
 void Sensors::pressPitotCallback()
 {
     SSCDRRN015PDAData d = press_pitot->getLastSample();
-    LoggerService::getInstance()->log(d);
+    LoggerService::getInstance().log(d);
 
     ADAReferenceValues rv =
         DeathStack::getInstance()
-            ->state_machines->ada_controller->getReferenceValues();
+            .state_machines->ada_controller->getReferenceValues();
 
     float rel_density = aeroutils::relDensity(
-        press_digital->getLastSample().press, rv.ref_pressure, rv.ref_altitude,
-        rv.ref_temperature);
+        press_digital->getLastSample().pressure, rv.ref_pressure,
+        rv.ref_altitude, rv.ref_temperature);
     if (rel_density != 0.0f)
     {
-        float airspeed = sqrtf(2 * fabs(d.press) / rel_density);
+        float airspeed = sqrtf(2 * fabs(d.pressure) / rel_density);
 
-        AirSpeedPitot aspeed_data{TimestampTimer::getTimestamp(), airspeed};
-        LoggerService::getInstance()->log(aspeed_data);
+        AirSpeedPitot aspeed_data{TimestampTimer::getInstance().getTimestamp(),
+                                  airspeed};
+        LoggerService::getInstance().log(aspeed_data);
     }
 }
 
 void Sensors::pressDPLVaneCallback()
 {
-    LoggerService::getInstance()->log(press_dpl_vane->getLastSample());
+    LoggerService::getInstance().log(press_dpl_vane->getLastSample());
 }
 
 void Sensors::pressStaticCallback()
 {
-    LoggerService::getInstance()->log(press_static_port->getLastSample());
+    LoggerService::getInstance().log(press_static_port->getLastSample());
 }
 
 void Sensors::imuBMXCallback()
@@ -525,94 +522,92 @@ void Sensors::imuBMXCallback()
     uint8_t fifo_size = imu_bmx160->getLastFifoSize();
     auto& fifo        = imu_bmx160->getLastFifo();
 
-    LoggerService::getInstance()->log(imu_bmx160->getTemperature());
+    LoggerService::getInstance().log(imu_bmx160->getTemperature());
 
     for (uint8_t i = 0; i < fifo_size; ++i)
     {
-        LoggerService::getInstance()->log(fifo.at(i));
+        LoggerService::getInstance().log(fifo.at(i));
     }
 
-    LoggerService::getInstance()->log(imu_bmx160->getFifoStats());
+    LoggerService::getInstance().log(imu_bmx160->getFifoStats());
 }
 
 void Sensors::imuBMXWithCorrectionCallback()
 {
-    LoggerService::getInstance()->log(
+    LoggerService::getInstance().log(
         imu_bmx160_with_correction->getLastSample());
 }
 
 void Sensors::magLISCallback()
 {
-    LoggerService::getInstance()->log(mag_lis3mdl->getLastSample());
+    LoggerService::getInstance().log(mag_lis3mdl->getLastSample());
 }
 
 void Sensors::gpsUbloxCallback()
 {
-    LoggerService::getInstance()->log(gps_ublox->getLastSample());
+    LoggerService::getInstance().log(gps_ublox->getLastSample());
 }
 
 #ifdef HARDWARE_IN_THE_LOOP
 void Sensors::hilIMUCallback()
 {
-    LoggerService::getInstance()->log(hil_imu->getLastSample());
+    LoggerService::getInstance().log(hil_imu->getLastSample());
 }
 
 void Sensors::hilBaroCallback()
 {
-    LoggerService::getInstance()->log(hil_baro->getLastSample());
+    LoggerService::getInstance().log(hil_baro->getLastSample());
 }
 
 void Sensors::hilGPSCallback()
 {
-    LoggerService::getInstance()->log(hil_gps->getLastSample());
+    LoggerService::getInstance().log(hil_gps->getLastSample());
 }
 #elif defined(USE_MOCK_SENSORS)
 void Sensors::mockBaroCallback()
 {
-    LoggerService::getInstance()->log(mock_imu->getLastSample());
+    LoggerService::getInstance().log(mock_imu->getLastSample());
 }
 
 void Sensors::mockImuCallback()
 {
-    LoggerService::getInstance()->log(mock_baro->getLastSample());
+    LoggerService::getInstance().log(mock_baro->getLastSample());
 }
 
 void Sensors::mockGpsCallback()
 {
-    LoggerService::getInstance()->log(mock_gps->getLastSample());
+    LoggerService::getInstance().log(mock_gps->getLastSample());
 }
 #endif
 
 void Sensors::updateSensorsStatus()
 {
-    SensorInfo info;
-
-    info = sensor_manager->getSensorInfo(imu_bmx160);
-    if (!info.is_initialized)
+    SensorInfo info = sensor_manager->getSensorInfo(imu_bmx160);
+    if (!info.isInitialized)
     {
         status.bmx160 = SensorDriverStatus::DRIVER_ERROR;
     }
 
     info = sensor_manager->getSensorInfo(mag_lis3mdl);
-    if (!info.is_initialized)
+    if (!info.isInitialized)
     {
         status.lis3mdl = SensorDriverStatus::DRIVER_ERROR;
     }
 
     info = sensor_manager->getSensorInfo(gps_ublox);
-    if (!info.is_initialized)
+    if (!info.isInitialized)
     {
         status.gps = SensorDriverStatus::DRIVER_ERROR;
     }
 
     info = sensor_manager->getSensorInfo(internal_adc);
-    if (!info.is_initialized)
+    if (!info.isInitialized)
     {
         status.internal_adc = SensorDriverStatus::DRIVER_ERROR;
     }
 
     info = sensor_manager->getSensorInfo(adc_ads1118);
-    if (!info.is_initialized)
+    if (!info.isInitialized)
     {
         status.ads1118 = SensorDriverStatus::DRIVER_ERROR;
     }
diff --git a/src/boards/DeathStack/Main/Sensors.h b/src/boards/DeathStack/Main/Sensors.h
index 44f335a07..1587e1a87 100644
--- a/src/boards/DeathStack/Main/Sensors.h
+++ b/src/boards/DeathStack/Main/Sensors.h
@@ -24,16 +24,17 @@
 
 #include <Main/SensorsData.h>
 #include <diagnostic/PrintLogger.h>
-#include <drivers/adc/ADS1118/ADS1118.h>
-#include <drivers/adc/InternalADC/InternalADC.h>
-#include <drivers/gps/ublox/UbloxGPS.h>
+#include <drivers/adc/InternalADC.h>
 #include <drivers/spi/SPIBusInterface.h>
+#include <scheduler/TaskScheduler.h>
+#include <sensors/ADS1118/ADS1118.h>
 #include <sensors/BMX160/BMX160.h>
 #include <sensors/BMX160/BMX160WithCorrection.h>
 #include <sensors/LIS3MDL/LIS3MDL.h>
 #include <sensors/MS5803/MS5803.h>
 #include <sensors/SensorData.h>
 #include <sensors/SensorManager.h>
+#include <sensors/UbloxGPS/UbloxGPS.h>
 #include <sensors/analog/battery/BatteryVoltageSensor.h>
 #include <sensors/analog/current/CurrentSensor.h>
 #include <sensors/analog/pressure/MPXHZ6130A/MPXHZ6130A.h>
diff --git a/src/boards/DeathStack/Main/StateMachines.cpp b/src/boards/DeathStack/Main/StateMachines.cpp
index f0f08297e..021e82d27 100644
--- a/src/boards/DeathStack/Main/StateMachines.cpp
+++ b/src/boards/DeathStack/Main/StateMachines.cpp
@@ -47,7 +47,7 @@ StateMachines::StateMachines(IMUType& imu, PressType& press, GPSType& gps,
     fmm            = new FMMController();
 
 #ifdef HARDWARE_IN_THE_LOOP
-    HIL::getInstance()->setNAS(&nas_controller->getNAS());
+    HIL::getInstance().setNAS(&nas_controller->getNAS());
 #endif
 
     addAlgorithmsToScheduler(scheduler);
@@ -72,14 +72,18 @@ void StateMachines::addAlgorithmsToScheduler(TaskScheduler* scheduler)
 {
     uint64_t start_time = miosix::getTick() + 10;
 
-    scheduler->add(std::bind(&ADAControllerType::update, ada_controller),
-                   ADA_UPDATE_PERIOD, TASK_ADA_ID, start_time);
+    scheduler->addTask(std::bind(&ADAControllerType::update, ada_controller),
+                       ADA_UPDATE_PERIOD, TASK_ADA_ID,
+                       TaskScheduler::Policy::RECOVER, start_time);
 
-    scheduler->add(std::bind(&NASControllerType::update, nas_controller),
-                   NAS_UPDATE_PERIOD, TASK_NAS_ID, start_time);
+    scheduler->addTask(std::bind(&NASControllerType::update, nas_controller),
+                       NAS_UPDATE_PERIOD, TASK_NAS_ID,
+                       TaskScheduler::Policy::RECOVER, start_time);
 
-    scheduler->add(std::bind(&AirBrakesControllerType::update, arb_controller),
-                   ABK_UPDATE_PERIOD, TASK_ABK_ID, start_time);
+    scheduler->addTask(
+        std::bind(&AirBrakesControllerType::update, arb_controller),
+        ABK_UPDATE_PERIOD, TASK_ABK_ID, TaskScheduler::Policy::RECOVER,
+        start_time);
 }
 
 void StateMachines::setReferenceTemperature(float t)
diff --git a/src/boards/DeathStack/Main/StateMachines.h b/src/boards/DeathStack/Main/StateMachines.h
index a00692b76..d109922f1 100644
--- a/src/boards/DeathStack/Main/StateMachines.h
+++ b/src/boards/DeathStack/Main/StateMachines.h
@@ -24,9 +24,9 @@
 
 #include <LoggerService/LoggerService.h>
 #include <NavigationAttitudeSystem/NASData.h>
-#include <drivers/gps/ublox/UbloxGPS.h>
 #include <scheduler/TaskScheduler.h>
 #include <sensors/BMX160/BMX160WithCorrection.h>
+#include <sensors/UbloxGPS/UbloxGPS.h>
 #include <sensors/analog/pressure/MPXHZ6130A/MPXHZ6130A.h>
 
 #ifdef HARDWARE_IN_THE_LOOP
@@ -112,8 +112,6 @@ public:
 
 private:
     void addAlgorithmsToScheduler(TaskScheduler* scheduler);
-
-    LoggerService& logger = *(LoggerService::getInstance());
 };
 
 }  // namespace DeathStackBoard
\ No newline at end of file
diff --git a/src/boards/DeathStack/NavigationAttitudeSystem/InitStates.h b/src/boards/DeathStack/NavigationAttitudeSystem/InitStates.h
index a2dff0521..6a4dd11bd 100644
--- a/src/boards/DeathStack/NavigationAttitudeSystem/InitStates.h
+++ b/src/boards/DeathStack/NavigationAttitudeSystem/InitStates.h
@@ -29,7 +29,6 @@
 
 #pragma once
 
-#include <Common.h>
 #include <configs/NASConfig.h>
 #include <diagnostic/PrintLogger.h>
 #include <math/SkyQuaternion.h>
diff --git a/src/boards/DeathStack/NavigationAttitudeSystem/NAS.h b/src/boards/DeathStack/NavigationAttitudeSystem/NAS.h
index 6e62ccb2d..9310e21f7 100644
--- a/src/boards/DeathStack/NavigationAttitudeSystem/NAS.h
+++ b/src/boards/DeathStack/NavigationAttitudeSystem/NAS.h
@@ -40,8 +40,8 @@
 #include <NavigationAttitudeSystem/ExtendedKalmanEigen.h>
 #include <NavigationAttitudeSystem/InitStates.h>
 #include <NavigationAttitudeSystem/NASData.h>
-#include <TimestampTimer.h>
 #include <diagnostic/PrintLogger.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <math/SkyQuaternion.h>
 #include <sensors/Sensor.h>
 
@@ -187,7 +187,7 @@ bool NAS<IMU, Press, GPS>::init()
 
     initialized = true;
 
-    LoggerService::getInstance()->log(getTriadResult());
+    LoggerService::getInstance().log(getTriadResult());
 
     return initialized;
 }
@@ -211,52 +211,54 @@ NASData NAS<IMU, Press, GPS>::sampleImpl()
     Press pressure_data = barometer.getLastSample();
 
     // update ekf with new accel and gyro measures
-    if (imu_data.accel_timestamp != last_accel_timestamp &&
-        imu_data.gyro_timestamp != last_gyro_timestamp)
+    if (imu_data.accelerationTimestamp != last_accel_timestamp &&
+        imu_data.angularVelocityTimestamp != last_gyro_timestamp)
     {
-        last_accel_timestamp = imu_data.accel_timestamp;
-        last_gyro_timestamp  = imu_data.gyro_timestamp;
+        last_accel_timestamp = imu_data.accelerationTimestamp;
+        last_gyro_timestamp  = imu_data.angularVelocityTimestamp;
 
-        Vector3f accel_readings(imu_data.accel_x, imu_data.accel_y,
-                                imu_data.accel_z);
+        Vector3f accel_readings(imu_data.accelerationX, imu_data.accelerationY,
+                                imu_data.accelerationZ);
         filter.predict(accel_readings);
 
-        Vector3f gyro_readings(imu_data.gyro_x, imu_data.gyro_y,
-                               imu_data.gyro_z);
+        Vector3f gyro_readings(imu_data.angularVelocityX,
+                               imu_data.angularVelocityY,
+                               imu_data.angularVelocityZ);
         filter.predictMEKF(gyro_readings);
     }
 
     // check if new pressure data is available
-    if (pressure_data.press_timestamp != last_press_timestamp)
+    if (pressure_data.pressureTimestamp != last_press_timestamp)
     {
-        last_press_timestamp = pressure_data.press_timestamp;
+        last_press_timestamp = pressure_data.pressureTimestamp;
 
-        filter.correctBaro(pressure_data.press, ref_values.msl_pressure,
+        filter.correctBaro(pressure_data.pressure, ref_values.msl_pressure,
                            ref_values.msl_temperature);
     }
 
     // check if new gps data is available and the gps has fix
-    if (gps_data.gps_timestamp != last_gps_timestamp && gps_data.fix == true)
+    if (gps_data.gpsTimestamp != last_gps_timestamp && gps_data.fix == true)
     {
-        last_gps_timestamp = gps_data.gps_timestamp;
+        last_gps_timestamp = gps_data.gpsTimestamp;
 
         Vector3f gps_readings(gps_data.latitude, gps_data.longitude,
                               gps_data.height);
         Vector3f gps_ned = geodetic2NED(gps_readings);
 
-        Vector4f pos_vel(gps_ned(0), gps_ned(1), gps_data.velocity_north,
-                         gps_data.velocity_east);
-        filter.correctGPS(pos_vel, gps_data.num_satellites);
+        Vector4f pos_vel(gps_ned(0), gps_ned(1), gps_data.velocityNorth,
+                         gps_data.velocityEast);
+        filter.correctGPS(pos_vel, gps_data.satellites);
     }
 
     // check if new magnetometer data is available
-    if (imu_data.mag_timestamp != last_mag_timestamp)
+    if (imu_data.magneticFieldTimestamp != last_mag_timestamp)
     {
-        Vector3f mag_readings(imu_data.mag_x, imu_data.mag_y, imu_data.mag_z);
+        Vector3f mag_readings(imu_data.magneticFieldX, imu_data.magneticFieldY,
+                              imu_data.magneticFieldZ);
 
         if (mag_readings.norm() < EMF * JAMMING_FACTOR)
         {
-            last_mag_timestamp = imu_data.mag_timestamp;
+            last_mag_timestamp = imu_data.magneticFieldTimestamp;
 
             mag_readings.normalize();
             filter.correctMEKF(mag_readings);
@@ -351,7 +353,7 @@ void NAS<IMU, Press, GPS>::setInitialOrientation(float roll, float pitch,
 template <typename IMU, typename Press, typename GPS>
 void NAS<IMU, Press, GPS>::updateNASData()
 {
-    nas_data.timestamp = TimestampTimer::getTimestamp();
+    nas_data.timestamp = TimestampTimer::getInstance().getTimestamp();
 
     nas_data.x = x(0);
     nas_data.y = x(1);
diff --git a/src/boards/DeathStack/NavigationAttitudeSystem/NASCalibrator.h b/src/boards/DeathStack/NavigationAttitudeSystem/NASCalibrator.h
index 7a115db5a..c8d12a06c 100644
--- a/src/boards/DeathStack/NavigationAttitudeSystem/NASCalibrator.h
+++ b/src/boards/DeathStack/NavigationAttitudeSystem/NASCalibrator.h
@@ -22,8 +22,6 @@
 
 #pragma once
 
-#include <Common.h>
-#include <Debug.h>
 #include <NavigationAttitudeSystem/NASData.h>
 #include <math/Stats.h>
 #include <miosix.h>
@@ -99,8 +97,8 @@ private:
     Stats mag_z_stats;
 
     // Refernece flags
-    bool ref_coordinates_set  = false;
-    bool ref_altitude_set  = false;
+    bool ref_coordinates_set = false;
+    bool ref_altitude_set    = false;
     bool ref_temperature_set = false;
 };
 
diff --git a/src/boards/DeathStack/NavigationAttitudeSystem/NASController.h b/src/boards/DeathStack/NavigationAttitudeSystem/NASController.h
index 425df09ce..307116324 100644
--- a/src/boards/DeathStack/NavigationAttitudeSystem/NASController.h
+++ b/src/boards/DeathStack/NavigationAttitudeSystem/NASController.h
@@ -121,11 +121,11 @@ NASController<IMU, Press, GPS>::NASController(Sensor<IMU>& imu,
                                               Sensor<GPS>& gps)
     : NASFsm(&NASCtrl::state_idle), calibrator(CALIBRATION_N_SAMPLES), imu(imu),
       barometer(baro), gps(gps), nas(imu, baro, gps),
-      logger(*(LoggerService::getInstance()))
+      logger(LoggerService::getInstance())
 {
     memset(&status, 0, sizeof(NASStatus));
-    sEventBroker->subscribe(this, TOPIC_FLIGHT_EVENTS);
-    sEventBroker->subscribe(this, TOPIC_NAS);
+    sEventBroker.subscribe(this, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.subscribe(this, TOPIC_NAS);
 
     status.state = NASState::IDLE;
 }
@@ -133,7 +133,7 @@ NASController<IMU, Press, GPS>::NASController(Sensor<IMU>& imu,
 template <typename IMU, typename Press, typename GPS>
 NASController<IMU, Press, GPS>::~NASController()
 {
-    sEventBroker->unsubscribe(this);
+    sEventBroker.unsubscribe(this);
 }
 
 template <typename IMU, typename Press, typename GPS>
@@ -157,31 +157,33 @@ void NASController<IMU, Press, GPS>::update()
             {
                 Lock<FastMutex> l(mutex);
 
-                if (imu_data.accel_timestamp != last_accel_timestamp)
+                if (imu_data.accelerationTimestamp != last_accel_timestamp)
                 {
-                    last_accel_timestamp = imu_data.accel_timestamp;
-                    calibrator.addAccelSample(
-                        imu_data.accel_x, imu_data.accel_y, imu_data.accel_z);
+                    last_accel_timestamp = imu_data.accelerationTimestamp;
+                    calibrator.addAccelSample(imu_data.accelerationX,
+                                              imu_data.accelerationY,
+                                              imu_data.accelerationZ);
                 }
 
-                if (imu_data.mag_timestamp != last_mag_timestamp)
+                if (imu_data.magneticFieldTimestamp != last_mag_timestamp)
                 {
-                    last_mag_timestamp = imu_data.mag_timestamp;
-                    calibrator.addMagSample(imu_data.mag_x, imu_data.mag_y,
-                                            imu_data.mag_z);
+                    last_mag_timestamp = imu_data.magneticFieldTimestamp;
+                    calibrator.addMagSample(imu_data.magneticFieldX,
+                                            imu_data.magneticFieldY,
+                                            imu_data.magneticFieldZ);
                 }
 
                 // Add samples to the calibration
-                if (press_data.press_timestamp != last_press_timestamp)
+                if (press_data.pressureTimestamp != last_press_timestamp)
                 {
-                    last_press_timestamp = press_data.press_timestamp;
-                    calibrator.addBaroSample(press_data.press);
+                    last_press_timestamp = press_data.pressureTimestamp;
+                    calibrator.addBaroSample(press_data.pressure);
                 }
 
                 if (gps_data.fix == true &&
-                    gps_data.gps_timestamp != last_gps_timestamp)
+                    gps_data.gpsTimestamp != last_gps_timestamp)
                 {
-                    last_gps_timestamp = gps_data.gps_timestamp;
+                    last_gps_timestamp = gps_data.gpsTimestamp;
                     calibrator.addGPSSample(gps_data.latitude,
                                             gps_data.longitude);
                 }
@@ -240,14 +242,14 @@ void NASController<IMU, Press, GPS>::finalizeCalibration()
 
         LOG_INFO(log, "Finalized calibration and TRIAD");
 
-        sEventBroker->post({EV_NAS_READY}, TOPIC_NAS);
+        sEventBroker.post({EV_NAS_READY}, TOPIC_NAS);
     }
 }
 
 template <typename IMU, typename Press, typename GPS>
 void NASController<IMU, Press, GPS>::state_idle(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -275,7 +277,7 @@ void NASController<IMU, Press, GPS>::state_idle(const Event& ev)
 template <typename IMU, typename Press, typename GPS>
 void NASController<IMU, Press, GPS>::state_calibrating(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -315,7 +317,7 @@ void NASController<IMU, Press, GPS>::state_calibrating(const Event& ev)
 template <typename IMU, typename Press, typename GPS>
 void NASController<IMU, Press, GPS>::state_ready(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -348,7 +350,7 @@ void NASController<IMU, Press, GPS>::state_ready(const Event& ev)
 template <typename IMU, typename Press, typename GPS>
 void NASController<IMU, Press, GPS>::state_active(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -376,7 +378,7 @@ void NASController<IMU, Press, GPS>::state_active(const Event& ev)
 template <typename IMU, typename Press, typename GPS>
 void NASController<IMU, Press, GPS>::state_end(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
@@ -457,18 +459,18 @@ void NASController<IMU, Press, GPS>::setReferenceAltitude(float altitude)
 template <typename IMU, typename Press, typename GPS>
 void NASController<IMU, Press, GPS>::logStatus(NASState state)
 {
-    status.timestamp = TimestampTimer::getTimestamp();
+    status.timestamp = TimestampTimer::getInstance().getTimestamp();
     status.state     = state;
     logger.log(status);
 
-    StackLogger::getInstance()->updateStack(THID_NAS_FSM);
+    StackLogger::getInstance().updateStack(THID_NAS_FSM);
 }
 
 template <typename IMU, typename Press, typename GPS>
 void NASController<IMU, Press, GPS>::logData()
 {
     NASKalmanState kalman_state = nas.getKalmanState();
-    kalman_state.timestamp      = TimestampTimer::getTimestamp();
+    kalman_state.timestamp      = TimestampTimer::getInstance().getTimestamp();
     logger.log(kalman_state);
     logger.log(nas.getLastSample());
 }
diff --git a/src/boards/DeathStack/PinHandler/PinHandler.cpp b/src/boards/DeathStack/PinHandler/PinHandler.cpp
index 352c73db9..ef710a411 100644
--- a/src/boards/DeathStack/PinHandler/PinHandler.cpp
+++ b/src/boards/DeathStack/PinHandler/PinHandler.cpp
@@ -20,12 +20,12 @@
  * THE SOFTWARE.
  */
 
+#include <DeathStack.h>
 #include <LoggerService/LoggerService.h>
 #include <PinHandler/PinHandler.h>
 #include <diagnostic/PrintLogger.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
-#include <DeathStack.h>
 
 #include <functional>
 
@@ -40,7 +40,7 @@ namespace DeathStackBoard
 {
 
 PinHandler::PinHandler()
-    : pin_obs(PIN_POLL_INTERVAL), logger(LoggerService::getInstance())
+    : pin_obs(PIN_POLL_INTERVAL), logger(&LoggerService::getInstance())
 {
     // Used for _1, _2. See std::bind cpp reference
     using namespace std::placeholders;
@@ -85,16 +85,17 @@ void PinHandler::onLaunchPinTransition(unsigned int p, unsigned char n)
     UNUSED(n);
 
 #ifdef HARDWARE_IN_THE_LOOP
-    HIL::getInstance()->signalLiftoff();
+    HIL::getInstance().signalLiftoff();
 #elif defined(USE_MOCK_SENSORS)
-    DeathStack::getInstance()->sensors->signalLiftoff();
+    DeathStack::getInstance().ensors->signalLiftoff();
 #endif
 
-    sEventBroker->post(Event{EV_UMBILICAL_DETACHED}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post(Event{EV_UMBILICAL_DETACHED}, TOPIC_FLIGHT_EVENTS);
 
     LOG_INFO(log, "Launch pin detached!");
 
-    status_pin_launch.last_detection_time = TimestampTimer::getTimestamp();
+    status_pin_launch.last_detection_time =
+        TimestampTimer::getInstance().getTimestamp();
     logger->log(status_pin_launch);
 }
 
@@ -102,11 +103,12 @@ void PinHandler::onNCPinTransition(unsigned int p, unsigned char n)
 {
     UNUSED(p);
     UNUSED(n);
-    sEventBroker->post(Event{EV_NC_DETACHED}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post(Event{EV_NC_DETACHED}, TOPIC_FLIGHT_EVENTS);
 
     LOG_INFO(log, "Nosecone detached!");
 
-    status_pin_nosecone.last_detection_time = TimestampTimer::getTimestamp();
+    status_pin_nosecone.last_detection_time =
+        TimestampTimer::getInstance().getTimestamp();
     logger->log(status_pin_nosecone);
 }
 
@@ -118,7 +120,8 @@ void PinHandler::onDPLServoPinTransition(unsigned int p, unsigned char n)
     LOG_INFO(log, "Deployment servo actuated!");
 
     // do not post any event, just log the timestamp
-    status_pin_dpl_servo.last_detection_time = TimestampTimer::getTimestamp();
+    status_pin_dpl_servo.last_detection_time =
+        TimestampTimer::getInstance().getTimestamp();
     logger->log(status_pin_dpl_servo);
 }
 
@@ -128,8 +131,9 @@ void PinHandler::onLaunchPinStateChange(unsigned int p, unsigned char n,
     UNUSED(p);
     UNUSED(n);
 
-    status_pin_launch.state             = (uint8_t)state;
-    status_pin_launch.last_state_change = TimestampTimer::getTimestamp();
+    status_pin_launch.state = (uint8_t)state;
+    status_pin_launch.last_state_change =
+        TimestampTimer::getInstance().getTimestamp();
     status_pin_launch.num_state_changes += 1;
 
     LOG_INFO(log,
@@ -145,8 +149,9 @@ void PinHandler::onNCPinStateChange(unsigned int p, unsigned char n, int state)
     UNUSED(p);
     UNUSED(n);
 
-    status_pin_nosecone.state             = (uint8_t)state;
-    status_pin_nosecone.last_state_change = TimestampTimer::getTimestamp();
+    status_pin_nosecone.state = (uint8_t)state;
+    status_pin_nosecone.last_state_change =
+        TimestampTimer::getInstance().getTimestamp();
     status_pin_nosecone.num_state_changes += 1;
 
     LOG_INFO(log, "Nosecone pin state change at time {}: new state = {}",
@@ -161,8 +166,9 @@ void PinHandler::onDPLServoPinStateChange(unsigned int p, unsigned char n,
     UNUSED(p);
     UNUSED(n);
 
-    status_pin_dpl_servo.state             = (uint8_t)state;
-    status_pin_dpl_servo.last_state_change = TimestampTimer::getTimestamp();
+    status_pin_dpl_servo.state = (uint8_t)state;
+    status_pin_dpl_servo.last_state_change =
+        TimestampTimer::getInstance().getTimestamp();
     status_pin_dpl_servo.num_state_changes += 1;
 
     LOG_INFO(log,
diff --git a/src/boards/DeathStack/TelemetriesTelecommands/TCHandler.cpp b/src/boards/DeathStack/TelemetriesTelecommands/TCHandler.cpp
index aba74b7bb..b34959d82 100644
--- a/src/boards/DeathStack/TelemetriesTelecommands/TCHandler.cpp
+++ b/src/boards/DeathStack/TelemetriesTelecommands/TCHandler.cpp
@@ -67,7 +67,7 @@ const std::map<uint8_t, uint8_t> tcMap = {
 void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
 {
     // log status
-    DeathStack::getInstance()->radio->logStatus();
+    DeathStack::getInstance().radio->logStatus();
 
     // acknowledge
     sendAck(mav_driver, msg);
@@ -83,7 +83,7 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
             // search for the corresponding event and post it
             auto it = tcMap.find(commandId);
             if (it != tcMap.end())
-                sEventBroker->post(Event{it->second}, TOPIC_TMTC);
+                sEventBroker.post(Event{it->second}, TOPIC_TMTC);
             else
                 LOG_WARN(print_logger, "Unknown NOARG command {:d}", commandId);
 
@@ -100,7 +100,7 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
                     LOG_INFO(print_logger, "Received command CLOSE_LOG");
                     break;
                 case MAV_CMD_START_LOGGING:
-                    DeathStack::getInstance()->startLogger();
+                    DeathStack::getInstance().startLogger();
                     sendTelemetry(mav_driver, MAV_LOGGER_TM_ID);
                     LOG_INFO(print_logger, "Received command START_LOG");
                     break;
@@ -128,8 +128,7 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
                 print_logger,
                 "Received SET_REFERENCE_ALTITUDE command. Ref altitude: {:f} m",
                 alt);
-            DeathStack::getInstance()->state_machines->setReferenceAltitude(
-                alt);
+            DeathStack::getInstance().state_machines->setReferenceAltitude(alt);
             break;
         }
         case MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC:
@@ -140,7 +139,7 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
                 print_logger,
                 "Received SET_REFERENCE_TEMPERATURE command. Temp: {:f} degC",
                 temp);
-            DeathStack::getInstance()->state_machines->setReferenceTemperature(
+            DeathStack::getInstance().state_machines->setReferenceTemperature(
                 temp);
             break;
         }
@@ -153,7 +152,7 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
                 "Received SET_DEPLOYMENT_ALTITUDE command. Dpl alt: {:f} m",
                 alt);
             DeathStack::getInstance()
-                ->state_machines->ada_controller->setDeploymentAltitude(alt);
+                .state_machines->ada_controller->setDeploymentAltitude(alt);
             break;
         }
         case MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC:
@@ -166,7 +165,7 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
                       "Received SET_INITIAL_ORIENTATION command. roll: {:f}, "
                       "pitch: {:f}, yaw: {:f}",
                       roll, pitch, yaw);
-            DeathStack::getInstance()->state_machines->setInitialOrientation(
+            DeathStack::getInstance().state_machines->setInitialOrientation(
                 roll, pitch, yaw);
             break;
         }
@@ -182,7 +181,7 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
                 "Received SET_INITIAL_COORDINATES command. latitude: {:f}, "
                 "longitude: {:f}",
                 latitude, longitude);
-            DeathStack::getInstance()->state_machines->setInitialCoordinates(
+            DeathStack::getInstance().state_machines->setInitialCoordinates(
                 latitude, longitude);
             break;
         }
@@ -191,8 +190,8 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
             LOG_DEBUG(print_logger, "Received RAW_EVENT command");
 
             // post given event on given topic
-            sEventBroker->post({mavlink_msg_raw_event_tc_get_Event_id(&msg)},
-                               mavlink_msg_raw_event_tc_get_Topic_id(&msg));
+            sEventBroker.post({mavlink_msg_raw_event_tc_get_Event_id(&msg)},
+                              mavlink_msg_raw_event_tc_get_Topic_id(&msg));
             break;
         }
 
@@ -205,7 +204,7 @@ void handleMavlinkMessage(MavDriver* mav_driver, const mavlink_message_t& msg)
         {
             float pos = mavlink_msg_set_aerobrake_angle_tc_get_angle(&msg);
             DeathStack::getInstance()
-                ->state_machines->arb_controller->setAirBrakesPosition(pos);
+                .state_machines->arb_controller->setAirBrakesPosition(pos);
             LOG_DEBUG(print_logger, "Received set ab pos: {:.1f} deg", pos);
 
             break;
@@ -231,11 +230,10 @@ bool sendTelemetry(MavDriver* mav_driver, const uint8_t tm_id)
 {
     // enqueue the TM packet taking it from the TM repo (pauses kernel to
     // guarantee synchronicity)
-    bool ok =
-        mav_driver->enqueueMsg(TmRepository::getInstance()->packTM(tm_id));
+    bool ok = mav_driver->enqueueMsg(TmRepository::getInstance().packTM(tm_id));
 
     // update status
-    DeathStack::getInstance()->radio->logStatus();
+    DeathStack::getInstance().radio->logStatus();
 
     return ok;
 }
diff --git a/src/boards/DeathStack/TelemetriesTelecommands/TCHandler.h b/src/boards/DeathStack/TelemetriesTelecommands/TCHandler.h
index 7ac29dc46..5921a37de 100644
--- a/src/boards/DeathStack/TelemetriesTelecommands/TCHandler.h
+++ b/src/boards/DeathStack/TelemetriesTelecommands/TCHandler.h
@@ -37,7 +37,7 @@ bool sendTelemetry(MavDriver* mav_driver, const uint8_t tm_id);
 
 void logMavlinkStatus(MavDriver* mav_driver);
 
-static LoggerService* logger = LoggerService::getInstance();
+static LoggerService* logger = &LoggerService::getInstance();
 
 static PrintLogger print_logger =
     Logging::getLogger("deathstack.tmtc.tchandler");
diff --git a/src/boards/DeathStack/TelemetriesTelecommands/TMTCController.cpp b/src/boards/DeathStack/TelemetriesTelecommands/TMTCController.cpp
index 77559358c..9d564a18d 100644
--- a/src/boards/DeathStack/TelemetriesTelecommands/TMTCController.cpp
+++ b/src/boards/DeathStack/TelemetriesTelecommands/TMTCController.cpp
@@ -34,23 +34,23 @@ TMTCController::TMTCController()
     : FSM(&TMTCController::stateGroundTM, skywardStack(16 * 1024))
 {
     // init FSM
-    sEventBroker->subscribe(this, TOPIC_FLIGHT_EVENTS);
-    sEventBroker->subscribe(this, TOPIC_TMTC);
+    sEventBroker.subscribe(this, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.subscribe(this, TOPIC_TMTC);
 
     LOG_DEBUG(log, "Created TMTCController");
 }
 
-TMTCController::~TMTCController() { sEventBroker->unsubscribe(this); }
+TMTCController::~TMTCController() { sEventBroker.unsubscribe(this); }
 
 bool TMTCController::send(const uint8_t tm_id)
 {
-    MavDriver* mav_driver = DeathStack::getInstance()->radio->mav_driver;
-    TmRepository* tm_repo = DeathStack::getInstance()->radio->tm_repo;
+    MavDriver* mav_driver = DeathStack::getInstance().radio->mav_driver;
+    TmRepository* tm_repo = DeathStack::getInstance().radio->tm_repo;
     // enqueue the TM packet taking it from the TM repo (pauses kernel to
     // guarantee synchronicity)
     bool ok = mav_driver->enqueueMsg(tm_repo->packTM(tm_id));
     // update status
-    DeathStack::getInstance()->radio->logStatus();
+    DeathStack::getInstance().radio->logStatus();
     return ok;
 }
 
@@ -60,7 +60,7 @@ void TMTCController::sendSerialTelemetry()
     // TODO : this has a problem, mavlink bytes are printed along with debug
     //        messages, which confuses everything
 #ifdef DEBUG
-    TmRepository* tm_repo = DeathStack::getInstance()->radio->tm_repo;
+    TmRepository* tm_repo = DeathStack::getInstance().radio->tm_repo;
     uint8_t buf[256];
     mavlink_message_t msg = tm_repo->packTM(MAV_HR_TM_ID);
     uint16_t len          = mavlink_msg_to_send_buffer(buf, &msg);
@@ -71,29 +71,29 @@ void TMTCController::sendSerialTelemetry()
 
 void TMTCController::stateGroundTM(const Event& ev)
 {
-    // TmRepository* tm_repo = DeathStack::getInstance()->radio->tm_repo;
-    switch (ev.sig)
+    // TmRepository* tm_repo = DeathStack::getInstance().radio->tm_repo;
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
             // add periodic events
-            periodicHrEvId = sEventBroker->postDelayed<HR_TM_GROUND_TIMEOUT>(
+            periodicHrEvId = sEventBroker.postDelayed<HR_TM_GROUND_TIMEOUT>(
                 Event{EV_SEND_HR_TM}, TOPIC_TMTC);
             // periodicSensEvId =
-            //     sEventBroker->postDelayed<GROUND_SENS_TM_TIMEOUT>(
+            //     sEventBroker.postDelayed<GROUND_SENS_TM_TIMEOUT>(
             //         Event{EV_SEND_SENS_TM}, TOPIC_TMTC);
 
             LOG_DEBUG(log, "Entering stateGroundTM");
 
             // log stack usage
-            StackLogger::getInstance()->updateStack(THID_TMTC_FSM);
+            StackLogger::getInstance().updateStack(THID_TMTC_FSM);
             break;
         }
         case EV_EXIT:
         {
             // remove periodic events
-            sEventBroker->removeDelayed(periodicHrEvId);
-            sEventBroker->removeDelayed(periodicSensEvId);
+            sEventBroker.removeDelayed(periodicHrEvId);
+            sEventBroker.removeDelayed(periodicSensEvId);
 
             LOG_DEBUG(log, "Exiting stateGroundTM");
             break;
@@ -101,7 +101,7 @@ void TMTCController::stateGroundTM(const Event& ev)
         case EV_SEND_HR_TM:
         {
             // repost periodic event
-            periodicHrEvId = sEventBroker->postDelayed<HR_TM_GROUND_TIMEOUT>(
+            periodicHrEvId = sEventBroker.postDelayed<HR_TM_GROUND_TIMEOUT>(
                 Event{EV_SEND_HR_TM}, TOPIC_TMTC);
 
             send(MAV_HR_TM_ID);
@@ -112,7 +112,7 @@ void TMTCController::stateGroundTM(const Event& ev)
         {
             // LOG_DEBUG(log, "Sending SENS_TM");
             // periodicSensEvId =
-            //     sEventBroker->postDelayed<GROUND_SENS_TM_TIMEOUT>(
+            //     sEventBroker.postDelayed<GROUND_SENS_TM_TIMEOUT>(
             //         Event{EV_SEND_SENS_TM}, TOPIC_TMTC);
 
             // send tm
@@ -142,28 +142,28 @@ void TMTCController::stateGroundTM(const Event& ev)
 
 void TMTCController::stateFlightTM(const Event& ev)
 {
-    switch (ev.sig)
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
             // add periodic events
-            periodicLrEvId = sEventBroker->postDelayed<LR_TM_TIMEOUT>(
+            periodicLrEvId = sEventBroker.postDelayed<LR_TM_TIMEOUT>(
                 Event{EV_SEND_LR_TM}, TOPIC_TMTC);
-            periodicHrEvId = sEventBroker->postDelayed<HR_TM_TIMEOUT>(
+            periodicHrEvId = sEventBroker.postDelayed<HR_TM_TIMEOUT>(
                 Event{EV_SEND_HR_TM}, TOPIC_TMTC);
 
             LOG_DEBUG(log, "Entering stateFlightTM");
 
             // log stack usage
-            StackLogger::getInstance()->updateStack(THID_TMTC_FSM);
+            StackLogger::getInstance().updateStack(THID_TMTC_FSM);
             break;
         }
 
         case EV_EXIT:
         {
             // remove periodic events
-            sEventBroker->removeDelayed(periodicLrEvId);
-            sEventBroker->removeDelayed(periodicHrEvId);
+            sEventBroker.removeDelayed(periodicLrEvId);
+            sEventBroker.removeDelayed(periodicHrEvId);
 
             LOG_DEBUG(log, "Exiting stateFlightTM");
             break;
@@ -171,7 +171,7 @@ void TMTCController::stateFlightTM(const Event& ev)
         case EV_SEND_HR_TM:
         {
             // repost periodic event
-            periodicHrEvId = sEventBroker->postDelayed<HR_TM_TIMEOUT>(
+            periodicHrEvId = sEventBroker.postDelayed<HR_TM_TIMEOUT>(
                 Event{EV_SEND_HR_TM}, TOPIC_TMTC);
 
             // send tm once 4 packets are filled
@@ -186,7 +186,7 @@ void TMTCController::stateFlightTM(const Event& ev)
         case EV_SEND_LR_TM:
         {
             // repost periodic event
-            periodicLrEvId = sEventBroker->postDelayed<LR_TM_TIMEOUT>(
+            periodicLrEvId = sEventBroker.postDelayed<LR_TM_TIMEOUT>(
                 Event{EV_SEND_LR_TM}, TOPIC_TMTC);
 
             // send low rate tm
@@ -207,25 +207,25 @@ void TMTCController::stateFlightTM(const Event& ev)
 
 void TMTCController::stateSensorTM(const Event& ev)
 {
-    // TmRepository* tm_repo = DeathStack::getInstance()->radio->tm_repo;
-    switch (ev.sig)
+    // TmRepository* tm_repo = DeathStack::getInstance().radio->tm_repo;
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
             // add periodic events
-            periodicSensEvId = sEventBroker->postDelayed<SENS_TM_TIMEOUT>(
+            periodicSensEvId = sEventBroker.postDelayed<SENS_TM_TIMEOUT>(
                 Event{EV_SEND_SENS_TM}, TOPIC_TMTC);
 
             LOG_DEBUG(log, "Entering stateSensorTM");
 
             // log stack usage
-            StackLogger::getInstance()->updateStack(THID_TMTC_FSM);
+            StackLogger::getInstance().updateStack(THID_TMTC_FSM);
             break;
         }
         case EV_EXIT:
         {
             // remove periodic events
-            sEventBroker->removeDelayed(periodicSensEvId);
+            sEventBroker.removeDelayed(periodicSensEvId);
 
             LOG_DEBUG(log, "Exiting stateSensorTM");
             break;
@@ -233,7 +233,7 @@ void TMTCController::stateSensorTM(const Event& ev)
         case EV_SEND_SENS_TM:
         {
             // repost periodic event
-            periodicSensEvId = sEventBroker->postDelayed<SENS_TM_TIMEOUT>(
+            periodicSensEvId = sEventBroker.postDelayed<SENS_TM_TIMEOUT>(
                 Event{EV_SEND_SENS_TM}, TOPIC_TMTC);
 
             send(MAV_SENSORS_TM_ID);
@@ -258,25 +258,25 @@ void TMTCController::stateSensorTM(const Event& ev)
 
 void TMTCController::stateSerialDebugTM(const Event& ev)
 {
-    // TmRepository* tm_repo = DeathStack::getInstance()->radio->tm_repo;
-    switch (ev.sig)
+    // TmRepository* tm_repo = DeathStack::getInstance().radio->tm_repo;
+    switch (ev.code)
     {
         case EV_ENTRY:
         {
             // add periodic events
-            periodicHrEvId = sEventBroker->postDelayed<HR_TM_GROUND_TIMEOUT>(
+            periodicHrEvId = sEventBroker.postDelayed<HR_TM_GROUND_TIMEOUT>(
                 Event{EV_SEND_HR_TM_OVER_SERIAL}, TOPIC_TMTC);
 
             LOG_DEBUG(log, "Entering stateSerialDebugTM");
 
             // log stack usage
-            StackLogger::getInstance()->updateStack(THID_TMTC_FSM);
+            StackLogger::getInstance().updateStack(THID_TMTC_FSM);
             break;
         }
         case EV_EXIT:
         {
             // remove periodic events
-            sEventBroker->removeDelayed(periodicHrEvId);
+            sEventBroker.removeDelayed(periodicHrEvId);
 
             LOG_DEBUG(log, "Exiting stateSerialDebugTM");
             break;
@@ -284,7 +284,7 @@ void TMTCController::stateSerialDebugTM(const Event& ev)
         case EV_SEND_HR_TM_OVER_SERIAL:
         {
             // repost periodic event
-            periodicHrEvId = sEventBroker->postDelayed<HR_TM_GROUND_TIMEOUT>(
+            periodicHrEvId = sEventBroker.postDelayed<HR_TM_GROUND_TIMEOUT>(
                 Event{EV_SEND_HR_TM_OVER_SERIAL}, TOPIC_TMTC);
 
             sendSerialTelemetry();
diff --git a/src/boards/DeathStack/TelemetriesTelecommands/TMTCController.h b/src/boards/DeathStack/TelemetriesTelecommands/TMTCController.h
index 880070170..a1fd9d3cd 100644
--- a/src/boards/DeathStack/TelemetriesTelecommands/TMTCController.h
+++ b/src/boards/DeathStack/TelemetriesTelecommands/TMTCController.h
@@ -77,7 +77,7 @@ private:
     void stateFlightTM(const Event& ev);
     void stateSerialDebugTM(const Event& ev);
 
-    LoggerService& logger = *(LoggerService::getInstance());
+    LoggerService& logger = LoggerService::getInstance();
 
     uint16_t periodicHrEvId   = 0;
     uint16_t periodicLrEvId   = 0;
diff --git a/src/boards/DeathStack/TelemetriesTelecommands/TmRepository.cpp b/src/boards/DeathStack/TelemetriesTelecommands/TmRepository.cpp
index 4edbb81c6..3028f8037 100644
--- a/src/boards/DeathStack/TelemetriesTelecommands/TmRepository.cpp
+++ b/src/boards/DeathStack/TelemetriesTelecommands/TmRepository.cpp
@@ -21,15 +21,14 @@
  * THE SOFTWARE.
  */
 
-#include <Constants.h>
 #include <DeathStack.h>
-#include <Debug.h>
 #include <FlightStatsRecorder/FSRController.h>
 #include <LoggerService/LoggerService.h>
 #include <System/TaskID.h>
 #include <TelemetriesTelecommands/TmRepository.h>
 #include <configs/SensorsConfig.h>
 #include <configs/TMTCConfig.h>
+#include <utils/Constants.h>
 
 using namespace Boardcore;
 
@@ -209,18 +208,18 @@ template <>
 void TmRepository::update<BatteryVoltageSensorData>(
     const BatteryVoltageSensorData& t)
 {
-    if (t.channel_id == DeathStackBoard::SensorConfigs::ADC_BATTERY_VOLTAGE)
+    if (t.channelId == DeathStackBoard::SensorConfigs::ADC_BATTERY_VOLTAGE)
     {
-        tm_repository.hr_tm.vbat         = t.bat_voltage;
-        tm_repository.sensors_tm.vbat    = t.bat_voltage;
-        tm_repository.adc_tm.bat_voltage = t.bat_voltage;
+        tm_repository.hr_tm.vbat         = t.batVoltage;
+        tm_repository.sensors_tm.vbat    = t.batVoltage;
+        tm_repository.adc_tm.bat_voltage = t.batVoltage;
     }
 }
 
 template <>
 void TmRepository::update<ADS1118Data>(const ADS1118Data& t)
 {
-    if (t.channel_id == SensorConfigs::ADC_CH_VREF)
+    if (t.channelId == SensorConfigs::ADC_CH_VREF)
     {
         // tm_repository.wind_tm.pressure_dpl = t.voltage;
         tm_repository.sensors_tm.vsupply_5v = t.voltage;
@@ -232,17 +231,17 @@ void TmRepository::update<ADS1118Data>(const ADS1118Data& t)
 template <>
 void TmRepository::update<MS5803Data>(const MS5803Data& t)
 {
-    tm_repository.wind_tm.pressure_digital = t.press;
-    tm_repository.sensors_tm.ms5803_press  = t.press;
-    tm_repository.digital_baro_tm.pressure = t.press;
+    tm_repository.wind_tm.pressure_digital = t.pressure;
+    tm_repository.sensors_tm.ms5803_press  = t.pressure;
+    tm_repository.digital_baro_tm.pressure = t.pressure;
 
 #if !defined(HARDWARE_IN_THE_LOOP) && !defined(USE_MOCK_SENSORS)
-    tm_repository.hr_tm.pressure_digi = t.press;
-#endif 
+    tm_repository.hr_tm.pressure_digi = t.pressure;
+#endif
 
-    tm_repository.sensors_tm.ms5803_temp      = t.temp;
-    tm_repository.hr_tm.temperature           = t.temp;
-    tm_repository.digital_baro_tm.temperature = t.temp;
+    tm_repository.sensors_tm.ms5803_temp      = t.temperature;
+    tm_repository.hr_tm.temperature           = t.temperature;
+    tm_repository.digital_baro_tm.temperature = t.temperature;
 
     stats_rec.update(t);
 }
@@ -250,12 +249,12 @@ void TmRepository::update<MS5803Data>(const MS5803Data& t)
 template <>
 void TmRepository::update<MPXHZ6130AData>(const MPXHZ6130AData& t)
 {
-    tm_repository.wind_tm.pressure_static = t.press;
-    tm_repository.sensors_tm.static_press = t.press;
-    tm_repository.adc_tm.static_pressure  = t.press;
+    tm_repository.wind_tm.pressure_static = t.pressure;
+    tm_repository.sensors_tm.static_press = t.pressure;
+    tm_repository.adc_tm.static_pressure  = t.pressure;
 
 #if !defined(HARDWARE_IN_THE_LOOP) && !defined(USE_MOCK_SENSORS)
-    tm_repository.hr_tm.pressure_static = t.press;
+    tm_repository.hr_tm.pressure_static = t.pressure;
 #endif
 
     stats_rec.update(t);
@@ -264,9 +263,9 @@ void TmRepository::update<MPXHZ6130AData>(const MPXHZ6130AData& t)
 template <>
 void TmRepository::update<SSCDRRN015PDAData>(const SSCDRRN015PDAData& t)
 {
-    tm_repository.wind_tm.pressure_differential = t.press;
-    tm_repository.sensors_tm.pitot_press        = t.press;
-    tm_repository.adc_tm.pitot_pressure         = t.press;
+    tm_repository.wind_tm.pressure_differential = t.pressure;
+    tm_repository.sensors_tm.pitot_press        = t.pressure;
+    tm_repository.adc_tm.pitot_pressure         = t.pressure;
 }
 
 template <>
@@ -280,10 +279,10 @@ void TmRepository::update<AirSpeedPitot>(const AirSpeedPitot& t)
 template <>
 void TmRepository::update<SSCDANN030PAAData>(const SSCDANN030PAAData& t)
 {
-    tm_repository.wind_tm.pressure_dpl = t.press;
-    tm_repository.sensors_tm.dpl_press = t.press;
-    tm_repository.hr_tm.pressure_dpl   = t.press;
-    tm_repository.adc_tm.dpl_pressure  = t.press;
+    tm_repository.wind_tm.pressure_dpl = t.pressure;
+    tm_repository.sensors_tm.dpl_press = t.pressure;
+    tm_repository.hr_tm.pressure_dpl   = t.pressure;
+    tm_repository.adc_tm.dpl_pressure  = t.pressure;
 
     stats_rec.update(t);
 }
@@ -292,40 +291,40 @@ void TmRepository::update<SSCDANN030PAAData>(const SSCDANN030PAAData& t)
 template <>
 void TmRepository::update<BMX160Data>(const BMX160Data& t)
 {
-    tm_repository.sensors_tm.bmx160_acc_x  = t.accel_x;
-    tm_repository.sensors_tm.bmx160_acc_y  = t.accel_y;
-    tm_repository.sensors_tm.bmx160_acc_z  = t.accel_z;
-    tm_repository.sensors_tm.bmx160_gyro_x = t.gyro_x;
-    tm_repository.sensors_tm.bmx160_gyro_y = t.gyro_y;
-    tm_repository.sensors_tm.bmx160_gyro_z = t.gyro_z;
-    tm_repository.sensors_tm.bmx160_mag_x  = t.mag_x;
-    tm_repository.sensors_tm.bmx160_mag_y  = t.mag_y;
-    tm_repository.sensors_tm.bmx160_mag_z  = t.mag_z;
+    tm_repository.sensors_tm.bmx160_acc_x  = t.accelerationX;
+    tm_repository.sensors_tm.bmx160_acc_y  = t.accelerationY;
+    tm_repository.sensors_tm.bmx160_acc_z  = t.accelerationZ;
+    tm_repository.sensors_tm.bmx160_gyro_x = t.angularVelocityX;
+    tm_repository.sensors_tm.bmx160_gyro_y = t.angularVelocityY;
+    tm_repository.sensors_tm.bmx160_gyro_z = t.angularVelocityZ;
+    tm_repository.sensors_tm.bmx160_mag_x  = t.magneticFieldX;
+    tm_repository.sensors_tm.bmx160_mag_y  = t.magneticFieldY;
+    tm_repository.sensors_tm.bmx160_mag_z  = t.magneticFieldZ;
 }
 
 template <>
 void TmRepository::update<BMX160WithCorrectionData>(
     const BMX160WithCorrectionData& t)
 {
-    tm_repository.bmx_tm.acc_x  = t.accel_x;
-    tm_repository.bmx_tm.acc_y  = t.accel_y;
-    tm_repository.bmx_tm.acc_z  = t.accel_z;
-    tm_repository.bmx_tm.gyro_x = t.gyro_x;
-    tm_repository.bmx_tm.gyro_y = t.gyro_y;
-    tm_repository.bmx_tm.gyro_z = t.gyro_z;
-    tm_repository.bmx_tm.mag_x  = t.mag_x;
-    tm_repository.bmx_tm.mag_y  = t.mag_y;
-    tm_repository.bmx_tm.mag_z  = t.mag_z;
-
-    tm_repository.hr_tm.acc_x  = t.accel_x;
-    tm_repository.hr_tm.acc_y  = t.accel_y;
-    tm_repository.hr_tm.acc_z  = t.accel_z;
-    tm_repository.hr_tm.gyro_x = t.gyro_x;
-    tm_repository.hr_tm.gyro_y = t.gyro_y;
-    tm_repository.hr_tm.gyro_z = t.gyro_z;
-    tm_repository.hr_tm.mag_x  = t.mag_x;
-    tm_repository.hr_tm.mag_y  = t.mag_y;
-    tm_repository.hr_tm.mag_z  = t.mag_z;
+    tm_repository.bmx_tm.acc_x  = t.accelerationX;
+    tm_repository.bmx_tm.acc_y  = t.accelerationY;
+    tm_repository.bmx_tm.acc_z  = t.accelerationZ;
+    tm_repository.bmx_tm.gyro_x = t.angularVelocityX;
+    tm_repository.bmx_tm.gyro_y = t.angularVelocityY;
+    tm_repository.bmx_tm.gyro_z = t.angularVelocityZ;
+    tm_repository.bmx_tm.mag_x  = t.magneticFieldX;
+    tm_repository.bmx_tm.mag_y  = t.magneticFieldY;
+    tm_repository.bmx_tm.mag_z  = t.magneticFieldZ;
+
+    tm_repository.hr_tm.acc_x  = t.accelerationX;
+    tm_repository.hr_tm.acc_y  = t.accelerationY;
+    tm_repository.hr_tm.acc_z  = t.accelerationZ;
+    tm_repository.hr_tm.gyro_x = t.angularVelocityX;
+    tm_repository.hr_tm.gyro_y = t.angularVelocityY;
+    tm_repository.hr_tm.gyro_z = t.angularVelocityZ;
+    tm_repository.hr_tm.mag_x  = t.magneticFieldX;
+    tm_repository.hr_tm.mag_y  = t.magneticFieldY;
+    tm_repository.hr_tm.mag_z  = t.magneticFieldZ;
 
     stats_rec.update(t);
 }
@@ -334,22 +333,22 @@ void TmRepository::update<BMX160WithCorrectionData>(
 template <>
 void TmRepository::update<BMX160Temperature>(const BMX160Temperature& t)
 {
-    tm_repository.sensors_tm.bmx160_temp = t.temp;
-    tm_repository.bmx_tm.temp            = t.temp;
+    tm_repository.sensors_tm.bmx160_temp = t.temperature;
+    tm_repository.bmx_tm.temp            = t.temperature;
 }
 
 template <>
 void TmRepository::update<LIS3MDLData>(const LIS3MDLData& t)
 {
-    tm_repository.sensors_tm.lis3mdl_mag_x = t.mag_x;
-    tm_repository.sensors_tm.lis3mdl_mag_y = t.mag_y;
-    tm_repository.sensors_tm.lis3mdl_mag_z = t.mag_z;
-    tm_repository.sensors_tm.lis3mdl_temp  = t.temp;
+    tm_repository.sensors_tm.lis3mdl_mag_x = t.magneticFieldX;
+    tm_repository.sensors_tm.lis3mdl_mag_y = t.magneticFieldY;
+    tm_repository.sensors_tm.lis3mdl_mag_z = t.magneticFieldZ;
+    tm_repository.sensors_tm.lis3mdl_temp  = t.temperature;
 
-    tm_repository.lis3mdl_tm.mag_x = t.mag_x;
-    tm_repository.lis3mdl_tm.mag_y = t.mag_y;
-    tm_repository.lis3mdl_tm.mag_z = t.mag_z;
-    tm_repository.lis3mdl_tm.temp  = t.temp;
+    tm_repository.lis3mdl_tm.mag_x = t.magneticFieldX;
+    tm_repository.lis3mdl_tm.mag_y = t.magneticFieldY;
+    tm_repository.lis3mdl_tm.mag_z = t.magneticFieldZ;
+    tm_repository.lis3mdl_tm.temp  = t.temperature;
 }
 
 #if !defined(HARDWARE_IN_THE_LOOP) && !defined(USE_MOCK_SENSORS)
@@ -357,19 +356,19 @@ void TmRepository::update<LIS3MDLData>(const LIS3MDLData& t)
  * @brief GPS.
  */
 template <>
-void TmRepository::update<UbloxGPSData>(const UbloxGPSData& t)
+void TmRepository::update<GPSData>(const GPSData& t)
 {
     // GPS_TM
     tm_repository.gps_tm.latitude     = t.latitude;
     tm_repository.gps_tm.longitude    = t.longitude;
     tm_repository.gps_tm.height       = t.height;
-    tm_repository.gps_tm.vel_north    = t.velocity_north;
-    tm_repository.gps_tm.vel_east     = t.velocity_east;
-    tm_repository.gps_tm.vel_down     = t.velocity_down;
+    tm_repository.gps_tm.vel_north    = t.velocityNorth;
+    tm_repository.gps_tm.vel_east     = t.velocityEast;
+    tm_repository.gps_tm.vel_down     = t.velocityDown;
     tm_repository.gps_tm.speed        = t.speed;
     tm_repository.gps_tm.fix          = (uint8_t)t.fix;
     tm_repository.gps_tm.track        = t.track;
-    tm_repository.gps_tm.n_satellites = t.num_satellites;
+    tm_repository.gps_tm.n_satellites = t.satellites;
 
     // HR TM
     tm_repository.hr_tm.gps_lat = t.latitude;
@@ -378,7 +377,7 @@ void TmRepository::update<UbloxGPSData>(const UbloxGPSData& t)
     tm_repository.hr_tm.gps_fix = (uint8_t)t.fix;
 
     // TEST TM
-    tm_repository.test_tm.gps_nsats = t.num_satellites;
+    tm_repository.test_tm.gps_nsats = t.satellites;
 
     stats_rec.update(t);
 }
@@ -399,9 +398,9 @@ template <>
 void TmRepository::update<Xbee::ATCommandResponseFrameLog>(
     const Xbee::ATCommandResponseFrameLog& t)
 {
-    if (strncmp(t.at_command, "DB", 2) == 0 && t.command_data_length == 1)
+    if (strncmp(t.atCommand, "DB", 2) == 0 && t.commandDataLength == 1)
     {
-        tm_repository.wind_tm.last_RSSI = -t.command_data[0];
+        tm_repository.wind_tm.last_RSSI = -t.commandData[0];
     }
 }
 
@@ -550,23 +549,23 @@ void TmRepository::update<PinStatus>(const PinStatus& t)
  * @brief Logger.
  */
 template <>
-void TmRepository::update<LogStats>(const LogStats& t)
+void TmRepository::update<LoggerStats>(const LoggerStats& t)
 {
     tm_repository.logger_tm.statLogNumber       = t.logNumber;
-    tm_repository.logger_tm.statTooLargeSamples = t.statTooLargeSamples;
-    tm_repository.logger_tm.statDroppedSamples  = t.statDroppedSamples;
-    tm_repository.logger_tm.statQueuedSamples   = t.statQueuedSamples;
-    tm_repository.logger_tm.statBufferFilled    = t.statBufferFilled;
-    tm_repository.logger_tm.statBufferWritten   = t.statBufferWritten;
-    tm_repository.logger_tm.statWriteFailed     = t.statWriteFailed;
-    tm_repository.logger_tm.statWriteError      = t.statWriteError;
-    tm_repository.logger_tm.statWriteTime       = t.statWriteTime;
-    tm_repository.logger_tm.statMaxWriteTime    = t.statMaxWriteTime;
+    tm_repository.logger_tm.statTooLargeSamples = t.tooLargeSamples;
+    tm_repository.logger_tm.statDroppedSamples  = t.droppedSamples;
+    tm_repository.logger_tm.statQueuedSamples   = t.queuedSamples;
+    tm_repository.logger_tm.statBufferFilled    = t.buffersFilled;
+    tm_repository.logger_tm.statBufferWritten   = t.buffersWritten;
+    tm_repository.logger_tm.statWriteFailed     = t.writesFailed;
+    tm_repository.logger_tm.statWriteError      = t.lastWriteError;
+    tm_repository.logger_tm.statWriteTime       = t.writeTime;
+    tm_repository.logger_tm.statMaxWriteTime    = t.maxWriteTime;
 
     tm_repository.wind_tm.log_num    = t.logNumber;
-    tm_repository.wind_tm.log_status = t.opened ? t.statWriteError : -1000;
+    tm_repository.wind_tm.log_status = t.lastWriteError;
 
-    tm_repository.hr_tm.logger_error = t.opened ? t.statWriteError : -1;
+    tm_repository.hr_tm.logger_error = t.lastWriteError;
 }
 
 /**
@@ -576,21 +575,21 @@ template <>
 void TmRepository::update<MavlinkStatus>(const MavlinkStatus& t)
 {
     // mavchannel stats
-    tm_repository.tmtc_tm.n_send_queue   = t.n_send_queue;
-    tm_repository.tmtc_tm.max_send_queue = t.max_send_queue;
-    tm_repository.tmtc_tm.n_send_errors  = t.n_send_errors;
-    tm_repository.tmtc_tm.msg_received   = t.mav_stats.msg_received;
+    tm_repository.tmtc_tm.n_send_queue   = t.nSendQueue;
+    tm_repository.tmtc_tm.max_send_queue = t.maxSendQueue;
+    tm_repository.tmtc_tm.n_send_errors  = t.nSendErrors;
+    tm_repository.tmtc_tm.msg_received   = t.mavStats.msg_received;
     // mav stats
-    tm_repository.tmtc_tm.buffer_overrun = t.mav_stats.buffer_overrun;
-    tm_repository.tmtc_tm.parse_error    = t.mav_stats.parse_error;
-    tm_repository.tmtc_tm.parse_state    = t.mav_stats.parse_state;
-    tm_repository.tmtc_tm.packet_idx     = t.mav_stats.packet_idx;
-    tm_repository.tmtc_tm.current_rx_seq = t.mav_stats.current_rx_seq;
-    tm_repository.tmtc_tm.current_tx_seq = t.mav_stats.current_tx_seq;
+    tm_repository.tmtc_tm.buffer_overrun = t.mavStats.buffer_overrun;
+    tm_repository.tmtc_tm.parse_error    = t.mavStats.parse_error;
+    tm_repository.tmtc_tm.parse_state    = t.mavStats.parse_state;
+    tm_repository.tmtc_tm.packet_idx     = t.mavStats.packet_idx;
+    tm_repository.tmtc_tm.current_rx_seq = t.mavStats.current_rx_seq;
+    tm_repository.tmtc_tm.current_tx_seq = t.mavStats.current_tx_seq;
     tm_repository.tmtc_tm.packet_rx_success_count =
-        t.mav_stats.packet_rx_success_count;
+        t.mavStats.packet_rx_success_count;
     tm_repository.tmtc_tm.packet_rx_drop_count =
-        t.mav_stats.packet_rx_drop_count;
+        t.mavStats.packet_rx_drop_count;
 }
 
 /**
@@ -692,7 +691,7 @@ void TmRepository::update<TaskStatResult>(const TaskStatResult& t)
             tm_repository.task_stats_tm.task_sensors_6ms_mean =
                 t.periodStats.mean;
             tm_repository.task_stats_tm.task_sensors_6ms_stddev =
-                t.periodStats.stdev;
+                t.periodStats.stdDev;
             break;
         case TASK_SENSORS_15_MS_ID:
             tm_repository.task_stats_tm.task_sensors_15ms_max =
@@ -702,7 +701,7 @@ void TmRepository::update<TaskStatResult>(const TaskStatResult& t)
             tm_repository.task_stats_tm.task_sensors_15ms_mean =
                 t.periodStats.mean;
             tm_repository.task_stats_tm.task_sensors_15ms_stddev =
-                t.periodStats.stdev;
+                t.periodStats.stdDev;
             break;
         case TASK_SENSORS_20_MS_ID:
             tm_repository.task_stats_tm.task_sensors_20ms_max =
@@ -712,7 +711,7 @@ void TmRepository::update<TaskStatResult>(const TaskStatResult& t)
             tm_repository.task_stats_tm.task_sensors_20ms_mean =
                 t.periodStats.mean;
             tm_repository.task_stats_tm.task_sensors_20ms_stddev =
-                t.periodStats.stdev;
+                t.periodStats.stdDev;
             break;
         case TASK_SENSORS_24_MS_ID:
             tm_repository.task_stats_tm.task_sensors_24ms_max =
@@ -722,7 +721,7 @@ void TmRepository::update<TaskStatResult>(const TaskStatResult& t)
             tm_repository.task_stats_tm.task_sensors_24ms_mean =
                 t.periodStats.mean;
             tm_repository.task_stats_tm.task_sensors_24ms_stddev =
-                t.periodStats.stdev;
+                t.periodStats.stdDev;
             break;
         case TASK_SENSORS_40_MS_ID:
             tm_repository.task_stats_tm.task_sensors_40ms_max =
@@ -732,7 +731,7 @@ void TmRepository::update<TaskStatResult>(const TaskStatResult& t)
             tm_repository.task_stats_tm.task_sensors_40ms_mean =
                 t.periodStats.mean;
             tm_repository.task_stats_tm.task_sensors_40ms_stddev =
-                t.periodStats.stdev;
+                t.periodStats.stdDev;
             break;
         case TASK_SENSORS_1000_MS_ID:
             tm_repository.task_stats_tm.task_sensors_1000ms_max =
@@ -742,25 +741,25 @@ void TmRepository::update<TaskStatResult>(const TaskStatResult& t)
             tm_repository.task_stats_tm.task_sensors_1000ms_mean =
                 t.periodStats.mean;
             tm_repository.task_stats_tm.task_sensors_1000ms_stddev =
-                t.periodStats.stdev;
+                t.periodStats.stdDev;
             break;
         case TASK_ADA_ID:
             tm_repository.task_stats_tm.task_ada_max  = t.periodStats.maxValue;
             tm_repository.task_stats_tm.task_ada_min  = t.periodStats.minValue;
             tm_repository.task_stats_tm.task_ada_mean = t.periodStats.mean;
-            tm_repository.task_stats_tm.task_ada_stddev = t.periodStats.stdev;
+            tm_repository.task_stats_tm.task_ada_stddev = t.periodStats.stdDev;
             break;
         case TASK_ABK_ID:
             tm_repository.task_stats_tm.task_abk_max  = t.periodStats.maxValue;
             tm_repository.task_stats_tm.task_abk_min  = t.periodStats.minValue;
             tm_repository.task_stats_tm.task_abk_mean = t.periodStats.mean;
-            tm_repository.task_stats_tm.task_abk_stddev = t.periodStats.stdev;
+            tm_repository.task_stats_tm.task_abk_stddev = t.periodStats.stdDev;
             break;
         case TASK_NAS_ID:
             tm_repository.task_stats_tm.task_nas_max  = t.periodStats.maxValue;
             tm_repository.task_stats_tm.task_nas_min  = t.periodStats.minValue;
             tm_repository.task_stats_tm.task_nas_mean = t.periodStats.mean;
-            tm_repository.task_stats_tm.task_nas_stddev = t.periodStats.stdev;
+            tm_repository.task_stats_tm.task_nas_stddev = t.periodStats.stdDev;
             break;
             // case TASK_SCHEDULER_STATS_ID:
             //     tm_repository.task_stats_tm.task_250hz_max    =
@@ -770,7 +769,7 @@ void TmRepository::update<TaskStatResult>(const TaskStatResult& t)
             //     tm_repository.task_stats_tm.task_250hz_mean   =
             //     t.periodStats.mean;
             //     tm_repository.task_stats_tm.task_250hz_stddev =
-            //     t.periodStats.stdev; break;
+            //     t.periodStats.stdDev; break;
 
         default:
             break;
diff --git a/src/boards/DeathStack/TelemetriesTelecommands/TmRepository.h b/src/boards/DeathStack/TelemetriesTelecommands/TmRepository.h
index fa1077442..c8141b2ac 100644
--- a/src/boards/DeathStack/TelemetriesTelecommands/TmRepository.h
+++ b/src/boards/DeathStack/TelemetriesTelecommands/TmRepository.h
@@ -29,17 +29,17 @@
 #include <FlightModeManager/FMMStatus.h>
 #include <FlightStatsRecorder/FSRController.h>
 #include <FlightStatsRecorder/FSRData.h>
+#include <Main/SensorsData.h>
 #include <NavigationAttitudeSystem/NASData.h>
 #include <PinHandler/PinHandlerData.h>
 #include <Singleton.h>
 #include <SystemData.h>
-#include <Main/SensorsData.h>
 #include <TelemetriesTelecommands/Mavlink.h>
+#include <configs/TMTCConfig.h>
 #include <diagnostic/PrintLogger.h>
 #include <drivers/Xbee/APIFramesLog.h>
-#include <drivers/adc/ADS1118/ADS1118Data.h>
-#include <drivers/gps/ublox/UbloxGPSData.h>
 #include <scheduler/TaskSchedulerData.h>
+#include <sensors/ADS1118/ADS1118Data.h>
 #include <sensors/BMX160/BMX160WithCorrectionData.h>
 #include <sensors/LIS3MDL/LIS3MDLData.h>
 #include <sensors/MS5803/MS5803Data.h>
@@ -49,8 +49,6 @@
 #include <sensors/analog/pressure/honeywell/SSCDANN030PAAData.h>
 #include <sensors/analog/pressure/honeywell/SSCDRRN015PDAData.h>
 
-#include <configs/TMTCConfig.h>
-
 #ifdef HARDWARE_IN_THE_LOOP
 #include <hardware_in_the_loop/HIL_sensors/HILSensors.h>
 #elif defined(USE_MOCK_SENSORS)
@@ -175,7 +173,7 @@ void TmRepository::update<AirSpeedPitot>(const AirSpeedPitot& t);
 template <>
 void TmRepository::update<SSCDANN030PAAData>(const SSCDANN030PAAData& t);
 
-#if !defined(HARDWARE_IN_THE_LOOP) && !defined(USE_MOCK_SENSORS) 
+#if !defined(HARDWARE_IN_THE_LOOP) && !defined(USE_MOCK_SENSORS)
 template <>
 void TmRepository::update<BMX160Data>(const BMX160Data& t);
 
@@ -190,9 +188,9 @@ void TmRepository::update<BMX160Temperature>(const BMX160Temperature& t);
 template <>
 void TmRepository::update<LIS3MDLData>(const LIS3MDLData& t);
 
-#if !defined(HARDWARE_IN_THE_LOOP) && !defined(USE_MOCK_SENSORS) 
+#if !defined(HARDWARE_IN_THE_LOOP) && !defined(USE_MOCK_SENSORS)
 template <>
-void TmRepository::update<UbloxGPSData>(const UbloxGPSData& t);
+void TmRepository::update<GPSData>(const GPSData& t);
 #endif
 
 template <>
@@ -213,7 +211,7 @@ void TmRepository::update<Xbee::ATCommandResponseFrameLog>(
  * @brief Logger.
  */
 template <>
-void TmRepository::update<LogStats>(const LogStats& t);
+void TmRepository::update<LoggerStats>(const LoggerStats& t);
 
 /**
  * @brief Initialization status of the board.
diff --git a/src/boards/DeathStack/configs/ADAConfig.h b/src/boards/DeathStack/configs/ADAConfig.h
index ce0a20746..2d4734402 100644
--- a/src/boards/DeathStack/configs/ADAConfig.h
+++ b/src/boards/DeathStack/configs/ADAConfig.h
@@ -74,12 +74,12 @@ static const float KALMAN_INITIAL_ACCELERATION = -500;
 static const uint8_t KALMAN_STATES_NUM  = 3;
 static const uint8_t KALMAN_OUTPUTS_NUM = 1;
 
-using MatrixNN = Matrix<float, KALMAN_STATES_NUM, KALMAN_STATES_NUM>;
-using MatrixPN = Matrix<float, KALMAN_OUTPUTS_NUM, KALMAN_STATES_NUM>;
-using MatrixNP = Matrix<float, KALMAN_STATES_NUM, KALMAN_OUTPUTS_NUM>;
-using MatrixPP = Matrix<float, KALMAN_OUTPUTS_NUM, KALMAN_OUTPUTS_NUM>;
-using CVectorN = Matrix<float, KALMAN_STATES_NUM, 1>;
-using CVectorP = Matrix<float, KALMAN_OUTPUTS_NUM, 1>;
+using MatrixNN = Eigen::Matrix<float, KALMAN_STATES_NUM, KALMAN_STATES_NUM>;
+using MatrixPN = Eigen::Matrix<float, KALMAN_OUTPUTS_NUM, KALMAN_STATES_NUM>;
+using MatrixNP = Eigen::Matrix<float, KALMAN_STATES_NUM, KALMAN_OUTPUTS_NUM>;
+using MatrixPP = Eigen::Matrix<float, KALMAN_OUTPUTS_NUM, KALMAN_OUTPUTS_NUM>;
+using CVectorN = Eigen::Matrix<float, KALMAN_STATES_NUM, 1>;
+using CVectorP = Eigen::Matrix<float, KALMAN_OUTPUTS_NUM, 1>;
 
 // clang-format off
 static inline MatrixNN f_init()
diff --git a/src/boards/DeathStack/configs/AirBrakesConfig.h b/src/boards/DeathStack/configs/AirBrakesConfig.h
index cef109a53..e01b39474 100644
--- a/src/boards/DeathStack/configs/AirBrakesConfig.h
+++ b/src/boards/DeathStack/configs/AirBrakesConfig.h
@@ -22,9 +22,8 @@
 
 #pragma once
 
-#include <Constants.h>
-#include <drivers/HardwareTimer.h>
-#include <drivers/pwm/pwm.h>
+#include <drivers/timer/PWM.h>
+#include <utils/Constants.h>
 
 namespace DeathStackBoard
 {
@@ -32,17 +31,15 @@ namespace DeathStackBoard
 namespace AirBrakesConfigs
 {
 
-static const PWM::Timer AB_SERVO_TIMER{
-    TIM8, &(RCC->APB2ENR), RCC_APB2ENR_TIM8EN,
-    TimerUtils::getPrescalerInputFrequency(TimerUtils::InputClock::APB2)};
-
-static constexpr PWMChannel AB_SERVO_PWM_CH = PWMChannel::CH2;
+static TIM_TypeDef* const AB_SERVO_TIMER = TIM8;
+static constexpr TimerUtils::Channel AB_SERVO_PWM_CH =
+    TimerUtils::Channel::CHANNEL_2;
 
 // Rocket's parameters
 #ifdef EUROC
 static constexpr float M = 27.0; /**< rocket's mass */
 #else
-static constexpr float M                 = 18.362;       /**< rocket's mass */
+static constexpr float M                  = 18.362;       /**< rocket's mass */
 #endif
 
 static constexpr float D        = 0.15; /**< rocket's diameter */
@@ -87,7 +84,7 @@ static constexpr float FILTER_COEFF     = 0.9;
 #ifdef HARDWARE_IN_THE_LOOP
 static constexpr float ABK_UPDATE_PERIOD = 0.1 * 1000;  // ms -> 10 Hz
 #else
-static constexpr float ABK_UPDATE_PERIOD = 0.05 * 1000;  // ms -> 20 Hz
+static constexpr float ABK_UPDATE_PERIOD  = 0.05 * 1000;  // ms -> 20 Hz
 #endif
 
 static constexpr float ABK_UPDATE_PERIOD_SECONDS = ABK_UPDATE_PERIOD / 1000;
diff --git a/src/boards/DeathStack/configs/CutterConfig.h b/src/boards/DeathStack/configs/CutterConfig.h
index 964a59300..daed3af10 100644
--- a/src/boards/DeathStack/configs/CutterConfig.h
+++ b/src/boards/DeathStack/configs/CutterConfig.h
@@ -22,8 +22,7 @@
 
 #pragma once
 
-#include <drivers/HardwareTimer.h>
-#include <drivers/pwm/pwm.h>
+#include <drivers/timer/PWM.h>
 #include <interfaces-impl/hwmapping.h>
 
 namespace DeathStackBoard
diff --git a/src/boards/DeathStack/configs/DeploymentConfig.h b/src/boards/DeathStack/configs/DeploymentConfig.h
index 04f0d71a5..b2fdaace3 100644
--- a/src/boards/DeathStack/configs/DeploymentConfig.h
+++ b/src/boards/DeathStack/configs/DeploymentConfig.h
@@ -22,8 +22,8 @@
 
 #pragma once
 
-#include <drivers/HardwareTimer.h>
-#include <drivers/pwm/pwm.h>
+#include <drivers/timer/PWM.h>
+#include <drivers/timer/TimerUtils.h>
 
 using namespace Boardcore;
 
@@ -33,11 +33,9 @@ namespace DeathStackBoard
 namespace DeploymentConfigs
 {
 
-static const PWM::Timer DPL_SERVO_TIMER{
-    TIM4, &(RCC->APB1ENR), RCC_APB1ENR_TIM4EN,
-    TimerUtils::getPrescalerInputFrequency(TimerUtils::InputClock::APB1)};
-
-static constexpr PWMChannel DPL_SERVO_PWM_CH = PWMChannel::CH1;
+static TIM_TypeDef* const DPL_SERVO_TIMER = TIM4;
+static constexpr TimerUtils::Channel DPL_SERVO_PWM_CH =
+    TimerUtils::Channel::CHANNEL_1;
 
 static constexpr int NC_OPEN_TIMEOUT = 5000;
 
diff --git a/src/boards/DeathStack/configs/NASConfig.h b/src/boards/DeathStack/configs/NASConfig.h
index 0fe5edeff..5c8d00f1c 100644
--- a/src/boards/DeathStack/configs/NASConfig.h
+++ b/src/boards/DeathStack/configs/NASConfig.h
@@ -22,7 +22,8 @@
 
 #pragma once
 
-#include "Constants.h"
+#include <utils/Constants.h>
+
 #include "Eigen/Dense"
 
 using namespace Eigen;
diff --git a/src/boards/DeathStack/configs/SensorsConfig.h b/src/boards/DeathStack/configs/SensorsConfig.h
index e1c82647a..d0cfd9573 100644
--- a/src/boards/DeathStack/configs/SensorsConfig.h
+++ b/src/boards/DeathStack/configs/SensorsConfig.h
@@ -22,9 +22,9 @@
 
 #pragma once
 
-#include <drivers/adc/ADS1118/ADS1118.h>
-#include <drivers/adc/InternalADC/InternalADC.h>
+#include <drivers/adc/InternalADC.h>
 #include <interfaces-impl/hwmapping.h>
+#include <sensors/ADS1118/ADS1118.h>
 #include <sensors/BMX160/BMX160Config.h>
 #include <sensors/LIS3MDL/LIS3MDL.h>
 #include <sensors/calibration/Calibration.h>
diff --git a/src/boards/Payload/Main/Radio.cpp b/src/boards/Payload/Main/Radio.cpp
index 39944320e..31a52fabf 100644
--- a/src/boards/Payload/Main/Radio.cpp
+++ b/src/boards/Payload/Main/Radio.cpp
@@ -42,9 +42,9 @@ void __attribute__((used)) EXTI10_IRQHandlerImpl()
 {
     using namespace PayloadBoard;
 
-    /*if (DeathStack::getInstance()->radio->xbee != nullptr)
+    /*if (DeathStack::getInstance().radio->xbee != nullptr)
     {
-        DeathStack::getInstance()->radio->xbee->handleATTNInterrupt();
+        DeathStack::getInstance().radio->xbee->handleATTNInterrupt();
     }*/
 }
 
@@ -55,7 +55,7 @@ Radio::Radio(SPIBusInterface& xbee_bus) : xbee_bus(xbee_bus)
 {
     SPIBusConfig xbee_cfg{};
 
-    xbee_cfg.clock_div = SPIClockDivider::DIV16;
+    xbee_cfg.clockDivider = SPI::ClockDivider::DIV_16;
 
     xbee = new Xbee::Xbee(xbee_bus, xbee_cfg, miosix::xbee::cs::getPin(),
                           miosix::xbee::attn::getPin(),
@@ -93,11 +93,11 @@ bool Radio::start()
 
 void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
 {
-    //LoggerService& logger = *LoggerService::getInstance();
+    // LoggerService& logger = *LoggerService::getInstance();
 
     using namespace Xbee;
     bool logged = false;
-    switch (frame.frame_type)
+    switch (frame.frameType)
     {
         case FTYPE_AT_COMMAND:
         {
@@ -105,7 +105,7 @@ void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
             logged = ATCommandFrameLog::toFrameType(frame, &dest);
             if (logged)
             {
-                //logger.log(dest);
+                // logger.log(dest);
             }
             break;
         }
@@ -115,7 +115,7 @@ void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
             logged = ATCommandResponseFrameLog::toFrameType(frame, &dest);
             if (logged)
             {
-                //logger.log(dest);
+                // logger.log(dest);
             }
             break;
         }
@@ -125,7 +125,7 @@ void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
             logged = ModemStatusFrameLog::toFrameType(frame, &dest);
             if (logged)
             {
-                //logger.log(dest);
+                // logger.log(dest);
             }
             break;
         }
@@ -135,7 +135,7 @@ void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
             logged = TXRequestFrameLog::toFrameType(frame, &dest);
             if (logged)
             {
-                //logger.log(dest);
+                // logger.log(dest);
             }
             break;
         }
@@ -145,7 +145,7 @@ void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
             logged = TXStatusFrameLog::toFrameType(frame, &dest);
             if (logged)
             {
-                //logger.log(dest);
+                // logger.log(dest);
             }
             break;
         }
@@ -155,7 +155,7 @@ void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
             logged = RXPacketFrameLog::toFrameType(frame, &dest);
             if (logged)
             {
-                //logger.log(dest);
+                // logger.log(dest);
             }
             break;
         }
@@ -165,16 +165,16 @@ void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
     {
         APIFrameLog api;
         APIFrameLog::fromAPIFrame(frame, &api);
-        //logger.log(api);
+        // logger.log(api);
     }
 }
 
 void Radio::logStatus()
 {
-    //MavlinkStatus status = mav_driver->getStatus();
-    //status.timestamp     = TimestampTimer::getTimestamp();
-    //LoggerService::getInstance()->log(status);
-    //LoggerService::getInstance()->log(xbee->getStatus());
+    // MavlinkStatus status = mav_driver->getStatus();
+    // status.timestamp     = TimestampTimer::getInstance().getTimestamp();
+    // LoggerService::getInstance().log(status);
+    // LoggerService::getInstance().log(xbee->getStatus());
 }
 
 }  // namespace PayloadBoard
\ No newline at end of file
diff --git a/src/boards/Payload/Main/Sensors.cpp b/src/boards/Payload/Main/Sensors.cpp
index 48d38f6ed..695403d72 100644
--- a/src/boards/Payload/Main/Sensors.cpp
+++ b/src/boards/Payload/Main/Sensors.cpp
@@ -22,11 +22,10 @@
 
 //#include <ApogeeDetectionAlgorithm/ADAController.h>
 #include <Payload/PayloadBoard.h>
-#include <Debug.h>
 //#include <LoggerService/LoggerService.h>
-#include <TimestampTimer.h>
 #include <Payload/configs/SensorsConfig.h>
 #include <drivers/interrupt/external_interrupts.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <interfaces-impl/hwmapping.h>
 #include <sensors/Sensor.h>
 #include <utils/aero/AeroUtils.h>
@@ -44,10 +43,10 @@ void __attribute__((used)) EXTI5_IRQHandlerImpl()
 {
     using namespace PayloadBoard;
 
-    /*if (Payload::getInstance()->sensors->imu_bmx160 != nullptr)
+    /*if (Payload::getInstance().sensors->imu_bmx160 != nullptr)
     {
-        Payload::getInstance()->sensors->imu_bmx160->IRQupdateTimestamp(
-            TimestampTimer::getTimestamp());
+        Payload::getInstance().ensors->imu_bmx160->IRQupdateTimestamp(
+            TimestampTimer::getInstance().getTimestamp());
     }*/
 }
 
@@ -72,7 +71,7 @@ Sensors::Sensors(SPIBusInterface& spi1_bus, TaskScheduler* scheduler)
     internalAdcInit();
     batteryVoltageInit();
 
-    sensor_manager = new SensorManager(scheduler, sensors_map);
+    sensor_manager = new SensorManager(sensors_map, scheduler);
 }
 
 Sensors::~Sensors()
@@ -108,7 +107,7 @@ bool Sensors::start()
         updateSensorsStatus();
     }
 
-    //LoggerService::getInstance()->log(status);
+    // LoggerService::getInstance().log(status);
 
     return sm_start_result;
 }
@@ -116,7 +115,7 @@ bool Sensors::start()
 void Sensors::calibrate()
 {
     imu_bmx160_with_correction->calibrate();
-    //LoggerService::getInstance()->log(
+    // LoggerService::getInstance().log(
     //      imu_bmx160_with_correction->getGyroscopeBiases());
 
     press_pitot->calibrate();
@@ -127,7 +126,7 @@ void Sensors::calibrate()
     for (unsigned int i = 0; i < PRESS_STATIC_CALIB_SAMPLES_NUM / 10; i++)
     {
         Thread::sleep(SAMPLE_PERIOD_PRESS_DIGITAL);
-        press_digi_stats.add(press_digital->getLastSample().press);
+        press_digi_stats.add(press_digital->getLastSample().pressure);
     }
     press_static_port->setReferencePressure(press_digi_stats.getStats().mean);
     press_static_port->calibrate();
@@ -141,12 +140,12 @@ void Sensors::calibrate()
 
 void Sensors::internalAdcInit()
 {
-    internal_adc = new InternalADC(*ADC3, INTERNAL_ADC_VREF);
+    internal_adc = new InternalADC(ADC3, INTERNAL_ADC_VREF);
 
     internal_adc->enableChannel(ADC_BATTERY_VOLTAGE);
 
     SensorInfo info("InternalADC", SAMPLE_PERIOD_INTERNAL_ADC,
-                    bind(&Sensors::internalAdcCallback, this), false, true);
+                    bind(&Sensors::internalAdcCallback, this));
     sensors_map.emplace(std::make_pair(internal_adc, info));
 
     LOG_INFO(log, "InternalADC setup done!");
@@ -160,7 +159,7 @@ void Sensors::batteryVoltageInit()
         new BatteryVoltageSensor(voltage_fun, BATTERY_VOLTAGE_COEFF);
 
     SensorInfo info("BatterySensor", SAMPLE_PERIOD_INTERNAL_ADC,
-                    bind(&Sensors::batteryVoltageCallback, this), false, true);
+                    bind(&Sensors::batteryVoltageCallback, this));
 
     sensors_map.emplace(std::make_pair(battery_voltage, info));
 
@@ -170,13 +169,13 @@ void Sensors::batteryVoltageInit()
 void Sensors::pressDigiInit()
 {
     SPIBusConfig spi_cfg{};
-    spi_cfg.clock_div = SPIClockDivider::DIV16;
+    spi_cfg.clockDivider = SPI::ClockDivider::DIV_16;
 
     press_digital = new MS5803(spi1_bus, miosix::sensors::ms5803::cs::getPin(),
                                spi_cfg, TEMP_DIVIDER_PRESS_DIGITAL);
 
     SensorInfo info("DigitalBarometer", SAMPLE_PERIOD_PRESS_DIGITAL,
-                    bind(&Sensors::pressDigiCallback, this), false, true);
+                    bind(&Sensors::pressDigiCallback, this));
 
     sensors_map.emplace(std::make_pair(press_digital, info));
 
@@ -186,7 +185,7 @@ void Sensors::pressDigiInit()
 void Sensors::ADS1118Init()
 {
     SPIBusConfig spi_cfg = ADS1118::getDefaultSPIConfig();
-    spi_cfg.clock_div    = SPIClockDivider::DIV64;
+    spi_cfg.clockDivider = SPI::ClockDivider::DIV_64;
 
     ADS1118::ADS1118Config ads1118Config = ADS1118::ADS1118_DEFAULT_CONFIG;
     ads1118Config.bits.mode = ADS1118::ADS1118Mode::CONTIN_CONV_MODE;
@@ -205,7 +204,7 @@ void Sensors::ADS1118Init()
     adc_ads1118->enableInput(ADC_CH_VREF, ADC_DR_VREF, ADC_PGA_VREF);
 
     SensorInfo info("ADS1118", SAMPLE_PERIOD_ADC_ADS1118,
-                    bind(&Sensors::ADS1118Callback, this), false, true);
+                    bind(&Sensors::ADS1118Callback, this));
     sensors_map.emplace(std::make_pair(adc_ads1118, info));
 
     LOG_INFO(log, "ADS1118 setup done!");
@@ -219,7 +218,7 @@ void Sensors::pressPitotInit()
                                     PRESS_PITOT_CALIB_SAMPLES_NUM);
 
     SensorInfo info("DiffBarometer", SAMPLE_PERIOD_PRESS_PITOT,
-                    bind(&Sensors::pressPitotCallback, this), false, true);
+                    bind(&Sensors::pressPitotCallback, this));
 
     sensors_map.emplace(std::make_pair(press_pitot, info));
 
@@ -233,7 +232,7 @@ void Sensors::pressDPLVaneInit()
     press_dpl_vane = new SSCDANN030PAA(voltage_fun, REFERENCE_VOLTAGE);
 
     SensorInfo info("DeploymentBarometer", SAMPLE_PERIOD_PRESS_DPL,
-                    bind(&Sensors::pressDPLVaneCallback, this), false, true);
+                    bind(&Sensors::pressDPLVaneCallback, this));
 
     sensors_map.emplace(std::make_pair(press_dpl_vane, info));
 
@@ -249,7 +248,7 @@ void Sensors::pressStaticInit()
                                        PRESS_STATIC_MOVING_AVG_COEFF);
 
     SensorInfo info("StaticPortsBarometer", SAMPLE_PERIOD_PRESS_STATIC,
-                    bind(&Sensors::pressStaticCallback, this), false, true);
+                    bind(&Sensors::pressStaticCallback, this));
 
     sensors_map.emplace(std::make_pair(press_static_port, info));
 
@@ -259,29 +258,29 @@ void Sensors::pressStaticInit()
 void Sensors::imuBMXInit()
 {
     SPIBusConfig spi_cfg;
-    spi_cfg.clock_div = SPIClockDivider::DIV8;
+    spi_cfg.clockDivider = SPI::ClockDivider::DIV_8;
 
     BMX160Config bmx_config;
-    bmx_config.fifo_mode      = BMX160Config::FifoMode::HEADER;
-    bmx_config.fifo_watermark = IMU_BMX_FIFO_WATERMARK;
-    bmx_config.fifo_int       = BMX160Config::FifoInterruptPin::PIN_INT1;
+    bmx_config.fifoMode      = BMX160Config::FifoMode::HEADER;
+    bmx_config.fifoWatermark = IMU_BMX_FIFO_WATERMARK;
+    bmx_config.fifoInterrupt = BMX160Config::FifoInterruptPin::PIN_INT1;
 
-    bmx_config.temp_divider = IMU_BMX_TEMP_DIVIDER;
+    bmx_config.temperatureDivider = IMU_BMX_TEMP_DIVIDER;
 
-    bmx_config.acc_range = IMU_BMX_ACC_FULLSCALE_ENUM;
-    bmx_config.gyr_range = IMU_BMX_GYRO_FULLSCALE_ENUM;
+    bmx_config.accelerometerRange = IMU_BMX_ACC_FULLSCALE_ENUM;
+    bmx_config.gyroscopeRange     = IMU_BMX_GYRO_FULLSCALE_ENUM;
 
-    bmx_config.acc_odr = IMU_BMX_ACC_GYRO_ODR_ENUM;
-    bmx_config.gyr_odr = IMU_BMX_ACC_GYRO_ODR_ENUM;
-    bmx_config.mag_odr = IMU_BMX_MAG_ODR_ENUM;
+    bmx_config.accelerometerDataRate = IMU_BMX_ACC_GYRO_ODR_ENUM;
+    bmx_config.gyroscopeDataRate     = IMU_BMX_ACC_GYRO_ODR_ENUM;
+    bmx_config.magnetometerRate      = IMU_BMX_MAG_ODR_ENUM;
 
-    bmx_config.gyr_unit = BMX160Config::GyroscopeMeasureUnit::RAD;
+    bmx_config.gyroscopeUnit = BMX160Config::GyroscopeMeasureUnit::RAD;
 
     imu_bmx160 = new BMX160(spi1_bus, miosix::sensors::bmx160::cs::getPin(),
                             bmx_config, spi_cfg);
 
     SensorInfo info("BMX160", SAMPLE_PERIOD_IMU_BMX,
-                    bind(&Sensors::imuBMXCallback, this), false, true);
+                    bind(&Sensors::imuBMXCallback, this));
 
     sensors_map.emplace(std::make_pair(imu_bmx160, info));
 
@@ -329,8 +328,7 @@ void Sensors::imuBMXWithCorrectionInit()
         imu_bmx160, correctionParameters, BMX160_AXIS_ROTATION);
 
     SensorInfo info("BMX160WithCorrection", SAMPLE_PERIOD_IMU_BMX,
-                    bind(&Sensors::imuBMXWithCorrectionCallback, this), false,
-                    true);
+                    bind(&Sensors::imuBMXWithCorrectionCallback, this));
 
     sensors_map.emplace(std::make_pair(imu_bmx160_with_correction, info));
 
@@ -340,7 +338,7 @@ void Sensors::imuBMXWithCorrectionInit()
 void Sensors::magLISinit()
 {
     SPIBusConfig busConfig;
-    busConfig.clock_div = SPIClockDivider::DIV32;
+    busConfig.clockDivider = SPI::ClockDivider::DIV_32;
 
     LIS3MDL::Config config;
     config.odr                = MAG_LIS_ODR_ENUM;
@@ -351,7 +349,7 @@ void Sensors::magLISinit()
                               busConfig, config);
 
     SensorInfo info("LIS3MDL", SAMPLE_PERIOD_MAG_LIS,
-                    bind(&Sensors::magLISCallback, this), false, true);
+                    bind(&Sensors::magLISCallback, this));
 
     sensors_map.emplace(std::make_pair(mag_lis3mdl, info));
 
@@ -360,10 +358,10 @@ void Sensors::magLISinit()
 
 void Sensors::gpsUbloxInit()
 {
-    gps_ublox = new UbloxGPS(GPS_BAUD_RATE, GPS_SAMPLE_RATE);
+    gps_ublox = new UbloxGPSSerial(GPS_BAUD_RATE, GPS_SAMPLE_RATE);
 
     SensorInfo info("UbloxGPS", GPS_SAMPLE_PERIOD,
-                    bind(&Sensors::gpsUbloxCallback, this), false, true);
+                    bind(&Sensors::gpsUbloxCallback, this));
 
     sensors_map.emplace(std::make_pair(gps_ublox, info));
 
@@ -372,12 +370,12 @@ void Sensors::gpsUbloxInit()
 
 void Sensors::internalAdcCallback()
 {
-    //LoggerService::getInstance()->log(internal_adc->getLastSample());
+    // LoggerService::getInstance().log(internal_adc->getLastSample());
 }
 
 void Sensors::batteryVoltageCallback()
 {
-    static float v = battery_voltage->getLastSample().bat_voltage;
+    static float v = battery_voltage->getLastSample().batVoltage;
     if (v < BATTERY_MIN_SAFE_VOLTAGE)
     {
         battery_critical_counter++;
@@ -389,48 +387,48 @@ void Sensors::batteryVoltageCallback()
         }
     }
 
-    //LoggerService::getInstance()->log(battery_voltage->getLastSample());
+    // LoggerService::getInstance().log(battery_voltage->getLastSample());
 }
 
 void Sensors::pressDigiCallback()
 {
-    //LoggerService::getInstance()->log(press_digital->getLastSample());
+    // LoggerService::getInstance().log(press_digital->getLastSample());
 }
 
 void Sensors::ADS1118Callback()
 {
-    //LoggerService::getInstance()->log(adc_ads1118->getLastSample());
+    // LoggerService::getInstance().log(adc_ads1118->getLastSample());
 }
 
 void Sensors::pressPitotCallback()
 {
     SSCDRRN015PDAData d = press_pitot->getLastSample();
-    //LoggerService::getInstance()->log(d);
+    // LoggerService::getInstance().log(d);
 
     /*ADAReferenceValues rv =
         DeathStack::getInstance()
             ->state_machines->ada_controller->getReferenceValues();
 
     float rel_density = aeroutils::relDensity(
-        press_digital->getLastSample().press, rv.ref_pressure, rv.ref_altitude,
-        rv.ref_temperature);
-    if (rel_density != 0.0f)
+        press_digital->getLastSample().pressure, rv.ref_pressure,
+    rv.ref_altitude, rv.ref_temperature); if (rel_density != 0.0f)
     {
-        float airspeed = sqrtf(2 * fabs(d.press) / rel_density);
+        float airspeed = sqrtf(2 * fabs(d.pressure) / rel_density);
 
-        AirSpeedPitot aspeed_data{TimestampTimer::getTimestamp(), airspeed};
-        //LoggerService::getInstance()->log(aspeed_data);
+        AirSpeedPitot
+    aspeed_data{TimestampTimer::getInstance().getTimestamp(), airspeed};
+        //LoggerService::getInstance().log(aspeed_data);
     }*/
 }
 
 void Sensors::pressDPLVaneCallback()
 {
-    //LoggerService::getInstance()->log(press_dpl_vane->getLastSample());
+    // LoggerService::getInstance().log(press_dpl_vane->getLastSample());
 }
 
 void Sensors::pressStaticCallback()
 {
-    //LoggerService::getInstance()->log(press_static_port->getLastSample());
+    // LoggerService::getInstance().log(press_static_port->getLastSample());
 }
 
 void Sensors::imuBMXCallback()
@@ -438,62 +436,60 @@ void Sensors::imuBMXCallback()
     uint8_t fifo_size = imu_bmx160->getLastFifoSize();
     auto& fifo        = imu_bmx160->getLastFifo();
 
-    //LoggerService::getInstance()->log(imu_bmx160->getTemperature());
+    // LoggerService::getInstance().log(imu_bmx160->getTemperature());
 
     for (uint8_t i = 0; i < fifo_size; ++i)
     {
-        //LoggerService::getInstance()->log(fifo.at(i));
+        // LoggerService::getInstance().log(fifo.at(i));
     }
 
-    //LoggerService::getInstance()->log(imu_bmx160->getFifoStats());
+    // LoggerService::getInstance().log(imu_bmx160->getFifoStats());
 }
 
 void Sensors::imuBMXWithCorrectionCallback()
 {
-    //LoggerService::getInstance()->log(
+    // LoggerService::getInstance().log(
     //    imu_bmx160_with_correction->getLastSample());
 }
 
 void Sensors::magLISCallback()
 {
-    //LoggerService::getInstance()->log(mag_lis3mdl->getLastSample());
+    // LoggerService::getInstance().log(mag_lis3mdl->getLastSample());
 }
 
 void Sensors::gpsUbloxCallback()
 {
-    //LoggerService::getInstance()->log(gps_ublox->getLastSample());
+    // LoggerService::getInstance().log(gps_ublox->getLastSample());
 }
 
 void Sensors::updateSensorsStatus()
 {
-    SensorInfo info;
-
-    info = sensor_manager->getSensorInfo(imu_bmx160);
-    if (!info.is_initialized)
+    SensorInfo info = sensor_manager->getSensorInfo(imu_bmx160);
+    if (!info.isInitialized)
     {
         status.bmx160 = SensorDriverStatus::DRIVER_ERROR;
     }
 
     info = sensor_manager->getSensorInfo(mag_lis3mdl);
-    if (!info.is_initialized)
+    if (!info.isInitialized)
     {
         status.lis3mdl = SensorDriverStatus::DRIVER_ERROR;
     }
 
     info = sensor_manager->getSensorInfo(gps_ublox);
-    if (!info.is_initialized)
+    if (!info.isInitialized)
     {
         status.gps = SensorDriverStatus::DRIVER_ERROR;
     }
 
     info = sensor_manager->getSensorInfo(internal_adc);
-    if (!info.is_initialized)
+    if (!info.isInitialized)
     {
         status.internal_adc = SensorDriverStatus::DRIVER_ERROR;
     }
 
     info = sensor_manager->getSensorInfo(adc_ads1118);
-    if (!info.is_initialized)
+    if (!info.isInitialized)
     {
         status.ads1118 = SensorDriverStatus::DRIVER_ERROR;
     }
diff --git a/src/boards/Payload/Main/Sensors.h b/src/boards/Payload/Main/Sensors.h
index 4811c2c2b..0263065e3 100644
--- a/src/boards/Payload/Main/Sensors.h
+++ b/src/boards/Payload/Main/Sensors.h
@@ -24,16 +24,16 @@
 
 #include <Payload/Main/SensorsData.h>
 #include <diagnostic/PrintLogger.h>
-#include <drivers/adc/ADS1118/ADS1118.h>
-#include <drivers/adc/InternalADC/InternalADC.h>
-#include <drivers/gps/ublox/UbloxGPS.h>
+#include <drivers/adc/InternalADC.h>
 #include <drivers/spi/SPIBusInterface.h>
+#include <sensors/ADS1118/ADS1118.h>
 #include <sensors/BMX160/BMX160.h>
 #include <sensors/BMX160/BMX160WithCorrection.h>
 #include <sensors/LIS3MDL/LIS3MDL.h>
 #include <sensors/MS5803/MS5803.h>
 #include <sensors/SensorData.h>
 #include <sensors/SensorManager.h>
+#include <sensors/UbloxGPS/UbloxGPS.h>
 #include <sensors/analog/battery/BatteryVoltageSensor.h>
 #include <sensors/analog/current/CurrentSensor.h>
 #include <sensors/analog/pressure/MPXHZ6130A/MPXHZ6130A.h>
diff --git a/src/boards/Payload/PayloadBoard.h b/src/boards/Payload/PayloadBoard.h
index c01728f44..dc591cf3b 100644
--- a/src/boards/Payload/PayloadBoard.h
+++ b/src/boards/Payload/PayloadBoard.h
@@ -22,9 +22,7 @@
 
 #pragma once
 
-#include <Common.h>
 #include <Payload/PayloadStatus.h>
-#include <Debug.h>
 //#include <LoggerService/LoggerService.h>
 #include <Payload/Main/Actuators.h>
 #include <Payload/Main/Bus.h>
@@ -36,9 +34,9 @@
 #include <System/TaskID.h>
 #include <events/EventBroker.h>
 #include <events/EventData.h>
-#include <events/utils/EventInjector.h>
 #include <events/Events.h>
 #include <events/Topics.h>
+#include <events/utils/EventInjector.h>
 #include <events/utils/EventSniffer.h>
 
 #include <functional>
@@ -66,11 +64,11 @@ class Payload : public Singleton<Payload>
 public:
     // Shared Components
     EventBroker* broker;
-    //LoggerService* logger;
+    // LoggerService* logger;
 
     EventSniffer* sniffer;
 
-    //StateMachines* state_machines;
+    // StateMachines* state_machines;
     Bus* bus;
     Sensors* sensors;
     Radio* radio;
@@ -116,18 +114,18 @@ public:
         injector->start();
 #endif
 
-        //logger->log(status);
+        // logger->log(status);
 
         // If there was an error, signal it to the FMM and light a LED.
         if (status.payload_board != COMP_OK)
         {
             LOG_ERR(log, "Initalization failed\n");
-            sEventBroker->post(Event{EV_INIT_ERROR}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post(Event{EV_INIT_ERROR}, TOPIC_FLIGHT_EVENTS);
         }
         else
         {
             LOG_INFO(log, "Initalization ok");
-            sEventBroker->post(Event{EV_INIT_OK}, TOPIC_FLIGHT_EVENTS);
+            sEventBroker.post(Event{EV_INIT_OK}, TOPIC_FLIGHT_EVENTS);
         }
     }
 
@@ -144,7 +142,7 @@ public:
             status.setError(&PayloadStatus::logger);
         }
 
-        logger->log(logger->getLogger().getLogStats());
+        logger->log(logger->getLogger().getLoggerStats());
     }*/
 
 private:
@@ -154,12 +152,10 @@ private:
     Payload()
     {
         /* Shared components */
-        //logger = Singleton<LoggerService>::getInstance();
-        //startLogger();
-
-        TimestampTimer::enableTimestampTimer();
+        // logger = Singleton<LoggerService>::getInstance();
+        // startLogger();
 
-        broker = sEventBroker;
+        broker = &sEventBroker;
 
         // Bind the logEvent function to the event sniffer in order to log every
         // event
@@ -190,8 +186,8 @@ private:
      */
     /*void logEvent(uint8_t event, uint8_t topic)
     {
-        EventData ev{(long long)TimestampTimer::getTimestamp(), event, topic};
-        logger->log(ev);
+        EventData ev{(long long)TimestampTimer::getInstance().getTimestamp(),
+event, topic}; logger->log(ev);
 
 #ifdef DEBUG
         // Don't TRACE if event is in the blacklist to avoid cluttering the
@@ -213,17 +209,17 @@ private:
     /*void addSchedulerStatsTask()
     {
         // add lambda to log scheduler tasks statistics
-        scheduler->add(
+        scheduler.add(
             [&]() {
                 std::vector<TaskStatResult> scheduler_stats =
-                    scheduler->getTaskStats();
+                    scheduler.getTaskStats();
 
                 for (TaskStatResult stat : scheduler_stats)
                 {
                     logger->log(stat);
                 }
 
-                StackLogger::getInstance()->updateStack(THID_TASK_SCHEDULER);
+                StackLogger::getInstance().updateStack(THID_TASK_SCHEDULER);
             },
             1000,  // 1 hz
             TASK_SCHEDULER_STATS_ID, miosix::getTick());
diff --git a/src/boards/Payload/PinHandler/PinHandler.cpp b/src/boards/Payload/PinHandler/PinHandler.cpp
index 165b0a87a..7fb6eedf2 100644
--- a/src/boards/Payload/PinHandler/PinHandler.cpp
+++ b/src/boards/Payload/PinHandler/PinHandler.cpp
@@ -23,6 +23,7 @@
 //#include <LoggerService/LoggerService.h>
 #include <Payload/PinHandler/PinHandler.h>
 #include <diagnostic/PrintLogger.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 //#include <Payload/PayloadBoard.h>
@@ -36,7 +37,7 @@ namespace PayloadBoard
 {
 
 PinHandler::PinHandler()
-    : pin_obs(PIN_POLL_INTERVAL) //, logger(LoggerService::getInstance())
+    : pin_obs(PIN_POLL_INTERVAL)  //, logger(LoggerService::getInstance())
 {
     // Used for _1, _2. See std::bind cpp reference
     using namespace std::placeholders;
@@ -57,12 +58,13 @@ void PinHandler::onNCPinTransition(unsigned int p, unsigned char n)
 {
     UNUSED(p);
     UNUSED(n);
-    sEventBroker->post(Event{EV_NC_DETACHED}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post(Event{EV_NC_DETACHED}, TOPIC_FLIGHT_EVENTS);
 
     LOG_INFO(log, "Nosecone detached!");
 
-    status_pin_nosecone.last_detection_time = TimestampTimer::getTimestamp();
-    //logger->log(status_pin_nosecone);
+    status_pin_nosecone.last_detection_time =
+        TimestampTimer::getInstance().getTimestamp();
+    // logger->log(status_pin_nosecone);
 }
 
 void PinHandler::onNCPinStateChange(unsigned int p, unsigned char n, int state)
@@ -70,14 +72,15 @@ void PinHandler::onNCPinStateChange(unsigned int p, unsigned char n, int state)
     UNUSED(p);
     UNUSED(n);
 
-    status_pin_nosecone.state             = (uint8_t)state;
-    status_pin_nosecone.last_state_change = TimestampTimer::getTimestamp();
+    status_pin_nosecone.state = (uint8_t)state;
+    status_pin_nosecone.last_state_change =
+        TimestampTimer::getInstance().getTimestamp();
     status_pin_nosecone.num_state_changes += 1;
 
     LOG_INFO(log, "Nosecone pin state change at time {}: new state = {}",
              status_pin_nosecone.last_state_change, status_pin_nosecone.state);
 
-    //logger->log(status_pin_nosecone);
+    // logger->log(status_pin_nosecone);
 }
 
 }  // namespace PayloadBoard
\ No newline at end of file
diff --git a/src/boards/Payload/WingControl/WingServo.cpp b/src/boards/Payload/WingControl/WingServo.cpp
index 6587d27db..16f534eab 100644
--- a/src/boards/Payload/WingControl/WingServo.cpp
+++ b/src/boards/Payload/WingControl/WingServo.cpp
@@ -27,34 +27,18 @@ namespace PayloadBoard
 
 using namespace WingConfigs;
 
-WingServo::WingServo(PWM::Timer servo_timer, PWMChannel servo_ch)
-    : ServoInterface(WING_SERVO_MIN_POS, WING_SERVO_MAX_POS),
-      servo(servo_timer), servo_channel(servo_ch)
-{
-}
-
-WingServo::WingServo(PWM::Timer servo_timer, PWMChannel servo_ch,
+WingServo::WingServo(TIM_TypeDef* const timer, TimerUtils::Channel channel,
                      float minPosition, float maxPosition)
-    : ServoInterface(minPosition, maxPosition), servo(servo_timer),
-      servo_channel(servo_ch)
+    : ServoInterface(minPosition, maxPosition),
+      servo(timer, channel, 50, 500, 2500)
 {
 }
 
 WingServo::~WingServo() {}
 
-void WingServo::enable()
-{
-    servo.setMaxPulseWidth(2500);
-    servo.setMinPulseWidth(500);
-    servo.enable(servo_channel);
-    servo.start();
-}
+void WingServo::enable() { servo.enable(); }
 
-void WingServo::disable()
-{
-    servo.stop();
-    servo.disable(servo_channel);
-}
+void WingServo::disable() { servo.disable(); }
 
 void WingServo::selfTest()
 {
@@ -80,7 +64,7 @@ void WingServo::setPosition(float angle)
 {
     this->currentPosition = angle;
     // map position to [0;1] interval for the servo driver
-    servo.setPosition(servo_channel, angle / 180.0f);
+    servo.setPosition180Deg(angle);
 }
 
 }  // namespace PayloadBoard
\ No newline at end of file
diff --git a/src/boards/Payload/WingControl/WingServo.h b/src/boards/Payload/WingControl/WingServo.h
index 2c9f1893b..4c42ddd28 100644
--- a/src/boards/Payload/WingControl/WingServo.h
+++ b/src/boards/Payload/WingControl/WingServo.h
@@ -22,9 +22,9 @@
 
 #pragma once
 
-#include <common/ServoInterface.h>
 #include <Payload/configs/WingConfig.h>
-#include <drivers/servo/servo.h>
+#include <common/ServoInterface.h>
+#include <drivers/servo/Servo.h>
 #include <miosix.h>
 
 using namespace Boardcore;
@@ -36,10 +36,9 @@ class WingServo : public ServoInterface
 {
 
 public:
-    WingServo(PWM::Timer servo_timer, PWMChannel servo_ch);
-
-    WingServo(PWM::Timer servo_timer, PWMChannel servo_ch, float minPosition,
-              float maxPosition);
+    WingServo(TIM_TypeDef* const timer, TimerUtils::Channel channel,
+              float minPosition = WingConfigs::WING_SERVO_MIN_POS,
+              float maxPosition = WingConfigs::WING_SERVO_MAX_POS);
 
     virtual ~WingServo();
 
@@ -54,7 +53,6 @@ public:
 
 private:
     Servo servo;
-    PWMChannel servo_channel;
 
 protected:
     /**
diff --git a/src/boards/Payload/configs/SensorsConfig.h b/src/boards/Payload/configs/SensorsConfig.h
index e84959be0..14e657ad6 100644
--- a/src/boards/Payload/configs/SensorsConfig.h
+++ b/src/boards/Payload/configs/SensorsConfig.h
@@ -22,9 +22,9 @@
 
 #pragma once
 
-#include <drivers/adc/ADS1118/ADS1118.h>
-#include <drivers/adc/InternalADC/InternalADC.h>
+#include <drivers/adc/InternalADC.h>
 #include <interfaces-impl/hwmapping.h>
+#include <sensors/ADS1118/ADS1118.h>
 #include <sensors/BMX160/BMX160Config.h>
 #include <sensors/LIS3MDL/LIS3MDL.h>
 #include <sensors/calibration/Calibration.h>
@@ -36,6 +36,7 @@ namespace PayloadBoard
 
 namespace SensorConfigs
 {
+
 static constexpr float INTERNAL_ADC_VREF = 3.3;
 static constexpr InternalADC::Channel ADC_BATTERY_VOLTAGE =
     InternalADC::Channel::CH5;
diff --git a/src/boards/Payload/configs/WingConfig.h b/src/boards/Payload/configs/WingConfig.h
index 4eb08d4b2..1665891f9 100644
--- a/src/boards/Payload/configs/WingConfig.h
+++ b/src/boards/Payload/configs/WingConfig.h
@@ -22,9 +22,9 @@
 
 #pragma once
 
-#include <Constants.h>
-#include <drivers/HardwareTimer.h>
-#include <drivers/pwm/pwm.h>
+#include <drivers/timer/PWM.h>
+#include <drivers/timer/TimestampTimer.h>
+#include <utils/Constants.h>
 
 using namespace Boardcore;
 
@@ -34,17 +34,13 @@ namespace PayloadBoard
 namespace WingConfigs
 {
 
-static const PWM::Timer WING_SERVO_1_TIMER{
-    TIM8, &(RCC->APB2ENR), RCC_APB2ENR_TIM8EN,
-    TimerUtils::getPrescalerInputFrequency(TimerUtils::InputClock::APB2)};
+static TIM_TypeDef* const WING_SERVO_1_TIMER = TIM8;
+static constexpr TimerUtils::Channel WING_SERVO_1_PWM_CH =
+    TimerUtils::Channel::CHANNEL_2;
 
-static constexpr PWMChannel WING_SERVO_1_PWM_CH = PWMChannel::CH2;
-
-static const PWM::Timer WING_SERVO_2_TIMER{
-    TIM8, &(RCC->APB2ENR), RCC_APB2ENR_TIM8EN,
-    TimerUtils::getPrescalerInputFrequency(TimerUtils::InputClock::APB2)};
-
-static constexpr PWMChannel WING_SERVO_2_PWM_CH = PWMChannel::CH2;
+static const TIM_TypeDef* WING_SERVO_2_TIMER = TIM4;
+static constexpr TimerUtils::Channel WING_SERVO_2_PWM_CH =
+    TimerUtils::Channel::CHANNEL_1;
 
 // Wing servo configs
 static constexpr float WING_SERVO_MAX_POS = 180.0;  // deg
diff --git a/src/entrypoints/death-stack-x-decoder/LogTypes.h b/src/entrypoints/death-stack-x-decoder/LogTypes.h
index a6f1c0fe5..facc537a7 100644
--- a/src/entrypoints/death-stack-x-decoder/LogTypes.h
+++ b/src/entrypoints/death-stack-x-decoder/LogTypes.h
@@ -23,7 +23,7 @@
 #pragma once
 
 #include <drivers/adc/ADS1118/ADS1118Data.h>
-#include <drivers/gps/ublox/UbloxGPSData.h>
+#include <drivers/gps/ublox/GPSData.h>
 #include <sensors/BMX160/BMX160Data.h>
 #include <sensors/BMX160/BMX160WithCorrectionData.h>
 #include <sensors/LIS3MDL/LIS3MDLData.h>
@@ -37,13 +37,15 @@
 #include <fstream>
 #include <iostream>
 
-#include "ApogeeDetectionAlgorithm/ADAData.h"
 #include "AirBrakes/AirBrakesData.h"
+#include "ApogeeDetectionAlgorithm/ADAData.h"
 //#include "AirBrakes/WindData.h"
+#include "../../hardware_in_the_loop/HIL_sensors/HILSensorsData.h"
 #include "DeathStackStatus.h"
 #include "Deployment/DeploymentData.h"
 #include "FlightModeManager/FMMStatus.h"
-#include "LogStats.h"
+#include "FlightStatsRecorder/FSRData.h"
+#include "LoggerStats.h"
 #include "Main/SensorsData.h"
 #include "NavigationAttitudeSystem/NASData.h"
 #include "PinHandler/PinHandlerData.h"
@@ -56,8 +58,6 @@
 #include "events/EventData.h"
 #include "logger/Deserializer.h"
 #include "scheduler/TaskSchedulerData.h"
-#include "FlightStatsRecorder/FSRData.h"
-#include "../../hardware_in_the_loop/HIL_sensors/HILSensorsData.h"
 
 // Serialized classes
 using std::ofstream;
@@ -87,7 +87,7 @@ void registerTypes(Deserializer& ds)
     // Sensors
     registerType<CurrentSensorData>(ds);
     registerType<BatteryVoltageSensorData>(ds);
-    registerType<UbloxGPSData>(ds);
+    registerType<GPSData>(ds);
     registerType<BMX160Data>(ds);
     registerType<BMX160WithCorrectionData>(ds);
     registerType<BMX160GyroscopeCalibrationBiases>(ds);
@@ -107,7 +107,7 @@ void registerTypes(Deserializer& ds)
     registerType<SensorsStatus>(ds);
     registerType<FMMStatus>(ds);
     registerType<PinStatus>(ds);
-    registerType<LogStats>(ds);
+    registerType<LoggerStats>(ds);
     registerType<DeploymentStatus>(ds);
     registerType<ADAControllerStatus>(ds);
 
@@ -142,7 +142,7 @@ void registerTypes(Deserializer& ds)
     registerType<AirBrakesAlgorithmData>(ds);
     registerType<AirBrakesChosenTrajectory>(ds);
 
-     // FlightStatsRecorder
+    // FlightStatsRecorder
     registerType<LiftOffStats>(ds);
     registerType<ApogeeStats>(ds);
     registerType<DrogueDPLStats>(ds);
@@ -155,5 +155,5 @@ void registerTypes(Deserializer& ds)
 
     // Others
     registerType<EventData>(ds);
-    //registerType<WindData>(ds);
+    // registerType<WindData>(ds);
 }
diff --git a/src/entrypoints/death-stack-x-entry.cpp b/src/entrypoints/death-stack-x-entry.cpp
index b21dd0366..428b7d8f3 100644
--- a/src/entrypoints/death-stack-x-entry.cpp
+++ b/src/entrypoints/death-stack-x-entry.cpp
@@ -21,7 +21,6 @@
  */
 
 #include <DeathStack.h>
-#include <Debug.h>
 #include <FlightStatsRecorder/FSRController.h>
 #include <diagnostic/CpuMeter.h>
 #include <math/Stats.h>
@@ -45,17 +44,17 @@ int main()
     SystemData system_data;
 
     // Instantiate the stack
-    DeathStack::getInstance()->start();
+    DeathStack::getInstance().start();
     LOG_INFO(log, "Death stack started");
 
-    LoggerService* logger_service = LoggerService::getInstance();
+    LoggerService& logger_service = LoggerService::getInstance();
 
     for (;;)
     {
         Thread::sleep(1000);
-        logger_service->log(logger_service->getLogger().getLogStats());
+        logger_service.log(logger_service.getLogger().getLoggerStats());
 
-        StackLogger::getInstance()->updateStack(THID_ENTRYPOINT);
+        StackLogger::getInstance().updateStack(THID_ENTRYPOINT);
 
         system_data.timestamp = miosix::getTick();
         system_data.cpu_usage = averageCpuUtilization();
@@ -69,8 +68,8 @@ int main()
         system_data.min_free_heap = MemoryProfiling::getAbsoluteFreeHeap();
         system_data.free_heap     = MemoryProfiling::getCurrentFreeHeap();
 
-        logger_service->log(system_data);
-        
-        StackLogger::getInstance()->log();
+        logger_service.log(system_data);
+
+        StackLogger::getInstance().log();
     }
 }
\ No newline at end of file
diff --git a/src/entrypoints/death-stack-x-testsuite.cpp b/src/entrypoints/death-stack-x-testsuite.cpp
index c2184e33a..b23445418 100644
--- a/src/entrypoints/death-stack-x-testsuite.cpp
+++ b/src/entrypoints/death-stack-x-testsuite.cpp
@@ -21,18 +21,18 @@
  */
 
 #include <AirBrakes/AirBrakesServo.h>
-#include <Common.h>
 #include <Deployment/DeploymentServo.h>
-#include <drivers/adc/ADS1118/ADS1118.h>
-#include <drivers/adc/InternalADC/InternalADC.h>
-#include <drivers/gps/ublox/UbloxGPS.h>
+#include <drivers/adc/InternalADC.h>
 #include <drivers/hbridge/HBridge.h>
+#include <drivers/servo/Servo.h>
 #include <drivers/spi/SPIDriver.h>
 #include <interfaces-impl/hwmapping.h>
 #include <miosix.h>
+#include <sensors/ADS1118/ADS1118.h>
 #include <sensors/BMX160/BMX160.h>
 #include <sensors/LIS3MDL/LIS3MDL.h>
 #include <sensors/MS5803/MS5803.h>
+#include <sensors/UbloxGPS/UbloxGPS.h>
 #include <sensors/analog/battery/BatteryVoltageSensor.h>
 #include <sensors/analog/pressure/MPXHZ6130A/MPXHZ6130A.h>
 #include <sensors/analog/pressure/honeywell/SSCDANN030PAA.h>
@@ -44,7 +44,6 @@
 #include <vector>
 
 #include "PinHandler/PinHandler.h"
-#include "drivers/servo/servo.h"
 #include "math/Stats.h"
 
 using namespace std;
@@ -73,8 +72,6 @@ int menu();
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     switch (menu())
     {
         case 1:
diff --git a/src/entrypoints/hardware_in_the_loop/hil-entry.cpp b/src/entrypoints/hardware_in_the_loop/hil-entry.cpp
index 42780794c..0ca4f829f 100644
--- a/src/entrypoints/hardware_in_the_loop/hil-entry.cpp
+++ b/src/entrypoints/hardware_in_the_loop/hil-entry.cpp
@@ -22,7 +22,6 @@
 
 #define EIGEN_NO_MALLOC  // enable eigen malloc usage assert
 
-#include <Common.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 #include <events/utils/EventCounter.h>
@@ -70,7 +69,7 @@ void threadFunc(void* arg)
 
     /*-------------- [FPM] Flight Phases Manager --------------*/
     HILFlightPhasesManager* flightPhasesManager =
-        HIL::getInstance()->flightPhasesManager;
+        HIL::getInstance().flightPhasesManager;
 
     /*flightPhasesManager->registerToFlightPhase(
         SIMULATION_STOPPED, bind(&setIsSimulationRunning, false));*/
@@ -83,7 +82,7 @@ void threadFunc(void* arg)
         SIMULATION_STOPPED, bind(&TaskScheduler::stop, &scheduler));
 
     /*-------------- [HIL] HILTransceiver --------------*/
-    HILTransceiver* simulator = HIL::getInstance()->simulator;
+    HILTransceiver* simulator = HIL::getInstance().imulator;
 
     /*-------------- Sensors & Actuators --------------*/
 
@@ -130,7 +129,7 @@ void threadFunc(void* arg)
     NASController<HILImuData, HILBaroData, HILGpsData> nas_controller(
         *sensors.imu, *sensors.barometer, *sensors.gps);
 
-    HIL::getInstance()->setNAS(&nas_controller.getNAS());
+    HIL::getInstance().etNAS(&nas_controller.getNAS());
 
     /*-------------- [CA] Control Algorithm --------------*/
     AirBrakesController<NASData> airbrakes_controller(nas_controller.getNAS());
@@ -143,7 +142,7 @@ void threadFunc(void* arg)
 
     /*-------------- Events --------------*/
 
-    EventCounter counter{*sEventBroker};
+    EventCounter counter{sEventBroker};
     counter.subscribe(TOPIC_FLIGHT_EVENTS);
     counter.subscribe(TOPIC_ADA);
     counter.subscribe(TOPIC_NAS);
@@ -187,7 +186,7 @@ void threadFunc(void* arg)
 
     /*---------- Starting threads --------*/
 
-    sEventBroker->start();
+    sEventBroker.start();
     fmm.start();
     ada_controller.start();
     nas_controller.start();
@@ -196,10 +195,10 @@ void threadFunc(void* arg)
     // pin_handler.start();
     scheduler.start();  // started only the scheduler instead of the SM
 
-    sEventBroker->post({EV_INIT_OK}, TOPIC_FMM);
+    sEventBroker.post({EV_INIT_OK}, TOPIC_FMM);
     Thread::sleep(100);
 
-    HIL::getInstance()->start();  // wait for first message from simulator
+    HIL::getInstance().tart();  // wait for first message from simulator
 
     /*---------- Wait for simulator to startup ----------*/
     while (!flightPhasesManager->isSimulationStarted())
@@ -214,15 +213,13 @@ void threadFunc(void* arg)
 
     scheduler.stop();
 
-    sEventBroker->post({EV_LANDED}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post({EV_LANDED}, TOPIC_FLIGHT_EVENTS);
 
     Thread::sleep(1000);
 }
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     Thread::create(threadFunc, STACK_MIN_FOR_SKYWARD, MAIN_PRIORITY, nullptr);
 
     unsigned int counter = 0;
diff --git a/src/entrypoints/payload-entry.cpp b/src/entrypoints/payload-entry.cpp
index ecf8b8c1e..583f1612a 100644
--- a/src/entrypoints/payload-entry.cpp
+++ b/src/entrypoints/payload-entry.cpp
@@ -20,7 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include <Debug.h>
 #include <Payload/PayloadBoard.h>
 #include <SystemData.h>
 #include <diagnostic/CpuMeter.h>
@@ -44,7 +43,7 @@ int main()
     SystemData system_data;
 
     // Instantiate the payload
-    Payload::getInstance()->start();
+    Payload::getInstance().start();
     LOG_INFO(log, "Payload started");
 
     // LoggerService* logger_service = LoggerService::getInstance();
@@ -52,9 +51,9 @@ int main()
     for (;;)
     {
         Thread::sleep(1000);
-        // logger_service->log(logger_service->getLogger().getLogStats());
+        // logger_service->log(logger_service->getLogger().getLoggerStats());
 
-        // StackLogger::getInstance()->updateStack(THID_ENTRYPOINT);
+        // StackLogger::getInstance().updateStack(THID_ENTRYPOINT);
 
         system_data.timestamp = miosix::getTick();
         system_data.cpu_usage = averageCpuUtilization();
@@ -70,6 +69,6 @@ int main()
 
         // logger_service->log(system_data);
 
-        // StackLogger::getInstance()->log();
+        // StackLogger::getInstance().log();
     }
 }
\ No newline at end of file
diff --git a/src/entrypoints/windtunnel-entry.cpp b/src/entrypoints/windtunnel-entry.cpp
index 8c6a85792..89e4deeb3 100644
--- a/src/entrypoints/windtunnel-entry.cpp
+++ b/src/entrypoints/windtunnel-entry.cpp
@@ -33,15 +33,15 @@ int main()
 {
     TRACE("Starting windtunnel test....\n");
     // Instantiate the stack
-    DeathStack::getInstance()->start();
+    DeathStack::getInstance().start();
     TRACE("Running\n");
 
     // bool printed = false;
     for (;;)
     {
         Thread::sleep(1000);
-        LoggerService::getInstance()->log(
-            LoggerService::getInstance()->getLogger().getLogStats());
+        LoggerService::getInstance().log(
+            LoggerService::getInstance().getLogger().getLoggerStats());
         // if(buf_adc_pitot.size() >= GLOBAL_BUF_LEN && !printed)
         // {
         //     printed = true;
diff --git a/src/entrypoints/windtunnel-test-decoder/LogTypes.h b/src/entrypoints/windtunnel-test-decoder/LogTypes.h
index a093dd70e..5b370ad57 100644
--- a/src/entrypoints/windtunnel-test-decoder/LogTypes.h
+++ b/src/entrypoints/windtunnel-test-decoder/LogTypes.h
@@ -34,7 +34,7 @@
 #include "drivers/mavlink/MavlinkStatus.h"
 #include "events/EventData.h"
 #include "logger/Deserializer.h"
-#include "logger/LogStats.h"
+#include "logger/LoggerStats.h"
 #include "sensors/MS580301BA07/MS580301BA07Data.h"
 #include "sensors/analog/pressure/MPXHZ6130A/MPXHZ6130AData.h"
 #include "sensors/analog/pressure/honeywell/SSCDANN030PAAData.h"
@@ -59,7 +59,7 @@ void registerType(Deserializer& ds)
 
 void registerTypes(Deserializer& ds)
 {
-    registerType<LogStats>(ds);
+    registerType<LoggerStats>(ds);
     registerType<EventData>(ds);
 
     registerType<MS5803Data>(ds);
diff --git a/src/hardware_in_the_loop/HILFlightPhasesManager.h b/src/hardware_in_the_loop/HILFlightPhasesManager.h
index 0da4add27..d60c9d5db 100644
--- a/src/hardware_in_the_loop/HILFlightPhasesManager.h
+++ b/src/hardware_in_the_loop/HILFlightPhasesManager.h
@@ -67,7 +67,7 @@ struct Outcomes
 
     Outcomes() : t(0), z(0), vz(0) {}
     Outcomes(float z, float vz)
-        : t(TimestampTimer::getTimestamp()), z(z), vz(vz)
+        : t(TimestampTimer::getInstance().getTimestamp()), z(z), vz(vz)
     {
     }
 
@@ -90,16 +90,16 @@ public:
     HILFlightPhasesManager()
     {
         updateFlags({0, 0, 0, 0, 0, 0});
-        counter_flight_events = new EventCounter(*sEventBroker);
+        counter_flight_events = new EventCounter(sEventBroker);
         counter_flight_events->subscribe(TOPIC_FLIGHT_EVENTS);
 
-        counter_airbrakes = new EventCounter(*sEventBroker);
+        counter_airbrakes = new EventCounter(sEventBroker);
         counter_airbrakes->subscribe(TOPIC_ABK);
 
-        counter_ada = new EventCounter(*sEventBroker);
+        counter_ada = new EventCounter(sEventBroker);
         counter_ada->subscribe(TOPIC_ADA);
 
-        counter_dpl = new EventCounter(*sEventBroker);
+        counter_dpl = new EventCounter(sEventBroker);
         counter_dpl->subscribe(TOPIC_DPL);
     }
 
@@ -135,7 +135,7 @@ public:
         // set true when the first packet from the simulator arrives
         if (isSetTrue(SIMULATION_STARTED))
         {
-            t_start = TimestampTimer::getTimestamp();
+            t_start = TimestampTimer::getInstance().getTimestamp();
 
             TRACE("[HIL] ------- SIMULATION STARTED ! ------- \n");
             changed_flags.push_back(SIMULATION_STARTED);
@@ -162,9 +162,8 @@ public:
         {
             if (isSetTrue(FLYING))
             {
-                t_liftoff = TimestampTimer::getTimestamp();
-                sEventBroker->post({EV_UMBILICAL_DETACHED},
-                                   TOPIC_FLIGHT_EVENTS);
+                t_liftoff = TimestampTimer::getInstance().getTimestamp();
+                sEventBroker.post({EV_UMBILICAL_DETACHED}, TOPIC_FLIGHT_EVENTS);
 
                 TRACE("[HIL] ------- LIFTOFF ! ------- \n");
                 changed_flags.push_back(FLYING);
@@ -211,7 +210,7 @@ public:
         else if (isSetTrue(SIMULATION_STOPPED))
         {
             changed_flags.push_back(SIMULATION_STOPPED);
-            t_stop = TimestampTimer::getTimestamp();
+            t_stop = TimestampTimer::getInstance().getTimestamp();
             TRACE("[HIL] ------- SIMULATION STOPPED ! -------: %f \n\n\n",
                   (double)t_stop / 1000000.0f);
             printOutcomes();
diff --git a/src/hardware_in_the_loop/HIL_sensors/HILBarometer.h b/src/hardware_in_the_loop/HIL_sensors/HILBarometer.h
index 3c23d7211..16e5d2d5e 100644
--- a/src/hardware_in_the_loop/HIL_sensors/HILBarometer.h
+++ b/src/hardware_in_the_loop/HIL_sensors/HILBarometer.h
@@ -45,7 +45,7 @@ protected:
     {
         HILBaroData tempData;
 
-        tempData.press = sensorData->barometer.measures[sampleCounter];
+        tempData.pressure = sensorData->barometer.measures[sampleCounter];
         tempData.press_timestamp = updateTimestamp();
 
         return tempData;
diff --git a/src/hardware_in_the_loop/HIL_sensors/HILSensor.h b/src/hardware_in_the_loop/HIL_sensors/HILSensor.h
index 57a1f0768..253e8e135 100644
--- a/src/hardware_in_the_loop/HIL_sensors/HILSensor.h
+++ b/src/hardware_in_the_loop/HIL_sensors/HILSensor.h
@@ -24,6 +24,7 @@
 
 #include <typeinfo>
 
+#include "HILSensorsData.h"
 #include "HILTimestampManagement.h"
 #include "TimestampTimer.h"
 #include "hardware_in_the_loop/HILConfig.h"
@@ -31,7 +32,6 @@
 #include "math/Vec3.h"
 #include "sensors/Sensor.h"
 #include "sensors/SensorData.h"
-#include "HILSensorsData.h"
 
 /**
  * @brief Fake sensor base used for the simulation. Every sensor for the
@@ -140,7 +140,7 @@ protected:
     uint64_t updateTimestamp()
     {
         sampleCounter++;
-        return TimestampTimer::getTimestamp();
+        return TimestampTimer::getInstance().getTimestamp();
     }
 
     /**
diff --git a/src/hardware_in_the_loop/simulator_communication/SerialInterface.h b/src/hardware_in_the_loop/simulator_communication/SerialInterface.h
index 37857e3d1..e8ba4476b 100644
--- a/src/hardware_in_the_loop/simulator_communication/SerialInterface.h
+++ b/src/hardware_in_the_loop/simulator_communication/SerialInterface.h
@@ -22,7 +22,6 @@
 
 #pragma once
 
-#include <Common.h>
 #include <fcntl.h>
 #include <stdio.h>
 
diff --git a/src/mocksensors/MockGPS.h b/src/mocksensors/MockGPS.h
index 17ecf424d..17b04b9a8 100644
--- a/src/mocksensors/MockGPS.h
+++ b/src/mocksensors/MockGPS.h
@@ -22,10 +22,10 @@
 
 #pragma once
 
-#include <TimestampTimer.h>
-#include <sensors/Sensor.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <mocksensors/MockSensorsData.h>
 #include <mocksensors/lynx_flight_data/lynx_gps_data.h>
+#include <sensors/Sensor.h>
 
 namespace DeathStackBoard
 {
@@ -54,28 +54,28 @@ public:
 
         MockGPSData data;
 
-        data.gps_timestamp = TimestampTimer::getTimestamp();
-        data.fix           = true;
+        data.gpsTimestamp = TimestampTimer::getInstance().getTimestamp();
+        data.fix          = true;
 
         if (before_liftoff)
         {
-            data.latitude       = GPS_DATA_LAT[0];
-            data.longitude      = GPS_DATA_LON[0];
-            data.velocity_north = GPS_DATA_VNORD[0];
-            data.velocity_east  = GPS_DATA_VEAST[0];
-            data.velocity_down  = GPS_DATA_VDOWN[0];
-            data.num_satellites = GPS_DATA_NSATS[0];
-            data.fix            = true;
+            data.latitude      = GPS_DATA_LAT[0];
+            data.longitude     = GPS_DATA_LON[0];
+            data.velocityNorth = GPS_DATA_VNORD[0];
+            data.velocityEast  = GPS_DATA_VEAST[0];
+            data.velocityDown  = GPS_DATA_VDOWN[0];
+            data.satellites    = GPS_DATA_NSATS[0];
+            data.fix           = true;
         }
         else if (i < GPS_DATA_SIZE)
         {
-            data.latitude       = GPS_DATA_LAT[i];
-            data.longitude      = GPS_DATA_LON[i];
-            data.velocity_north = GPS_DATA_VNORD[i];
-            data.velocity_east  = GPS_DATA_VEAST[i];
-            data.velocity_down  = GPS_DATA_VDOWN[i];
-            data.num_satellites = GPS_DATA_NSATS[i];
-            data.fix            = true;
+            data.latitude      = GPS_DATA_LAT[i];
+            data.longitude     = GPS_DATA_LON[i];
+            data.velocityNorth = GPS_DATA_VNORD[i];
+            data.velocityEast  = GPS_DATA_VEAST[i];
+            data.velocityDown  = GPS_DATA_VDOWN[i];
+            data.satellites    = GPS_DATA_NSATS[i];
+            data.fix           = true;
             i++;
         }
 
diff --git a/src/mocksensors/MockIMU.h b/src/mocksensors/MockIMU.h
index 94ac9f373..acd1bf1e3 100644
--- a/src/mocksensors/MockIMU.h
+++ b/src/mocksensors/MockIMU.h
@@ -22,10 +22,10 @@
 
 #pragma once
 
-#include <TimestampTimer.h>
-#include <sensors/Sensor.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <mocksensors/MockSensorsData.h>
 #include <mocksensors/lynx_flight_data/lynx_imu_data.h>
+#include <sensors/Sensor.h>
 
 namespace DeathStackBoard
 {
@@ -47,22 +47,22 @@ public:
         }
 
         MockIMUData data;
-        uint64_t t = TimestampTimer::getTimestamp();
-
-        data.accel_timestamp = t;
-        data.accel_x         = ACCEL_DATA[index][0];
-        data.accel_y         = ACCEL_DATA[index][1];
-        data.accel_z         = ACCEL_DATA[index][2];
-
-        data.gyro_timestamp = t;
-        data.gyro_x         = GYRO_DATA[index][0];
-        data.gyro_y         = GYRO_DATA[index][1];
-        data.gyro_z         = GYRO_DATA[index][2];
-
-        data.mag_timestamp = t;
-        data.mag_x         = MAG_DATA[index][0];
-        data.mag_y         = MAG_DATA[index][1];
-        data.mag_z         = MAG_DATA[index][2];
+        uint64_t t = TimestampTimer::getInstance().getTimestamp();
+
+        data.accelerationTimestamp = t;
+        data.accelerationX         = ACCEL_DATA[index][0];
+        data.accelerationY         = ACCEL_DATA[index][1];
+        data.accelerationZ         = ACCEL_DATA[index][2];
+
+        data.angularVelocityTimestamp = t;
+        data.angularVelocityX         = GYRO_DATA[index][0];
+        data.angularVelocityY         = GYRO_DATA[index][1];
+        data.angularVelocityZ         = GYRO_DATA[index][2];
+
+        data.magneticFieldTimestamp = t;
+        data.magneticFieldX         = MAG_DATA[index][0];
+        data.magneticFieldY         = MAG_DATA[index][1];
+        data.magneticFieldZ         = MAG_DATA[index][2];
 
         // when finished, go back to the beginning
         index = (index + 1) % IMU_DATA_SIZE;
diff --git a/src/mocksensors/MockPressureSensor.h b/src/mocksensors/MockPressureSensor.h
index 7100f81b9..1a6b7ccc7 100644
--- a/src/mocksensors/MockPressureSensor.h
+++ b/src/mocksensors/MockPressureSensor.h
@@ -22,11 +22,11 @@
 
 #pragma once
 
-#include <Common.h>
 #include <mocksensors/MockSensorsData.h>
 //#include <mocksensors/lynx_flight_data/lynx_press_data.h>
 #include <mocksensors/lynx_flight_data/lynx_pressure_static_data.h>
 #include <sensors/Sensor.h>
+
 #include <random>
 
 namespace DeathStackBoard
@@ -45,31 +45,31 @@ public:
     {
         MockPressureData data;
 
-        data.press_timestamp = TimestampTimer::getTimestamp();
+        data.pressureTimestamp = TimestampTimer::getInstance().getTimestamp();
 
         if (before_liftoff)
         {
-            data.press = PRESSURE_STATIC_DATA[0];
+            data.pressure = PRESSURE_STATIC_DATA[0];
         }
         else
         {
             if (i < PRESSURE_STATIC_DATA_SIZE)
             {
-                data.press = PRESSURE_STATIC_DATA[i++];
+                data.pressure = PRESSURE_STATIC_DATA[i++];
             }
             else
             {
-                data.press =
+                data.pressure =
                     PRESSURE_STATIC_DATA[PRESSURE_STATIC_DATA_SIZE - 1];
             }
         }
 
         if (with_noise)
         {
-            data.press = addNoise(data.press);
+            data.pressure = addNoise(data.pressure);
         }
 
-        data.press = movingAverage(data.press);
+        data.pressure = movingAverage(data.pressure);
 
         return data;
     }
diff --git a/src/mocksensors/MockSensorsData.h b/src/mocksensors/MockSensorsData.h
index 4358df593..d9edc2220 100644
--- a/src/mocksensors/MockSensorsData.h
+++ b/src/mocksensors/MockSensorsData.h
@@ -37,10 +37,12 @@ struct MockIMUData : public AccelerometerData,
 
     void print(std::ostream& os) const
     {
-        os << accel_timestamp << "," << accel_x << "," << accel_y << ","
-           << accel_z << "," << gyro_timestamp << "," << gyro_x << "," << gyro_y
-           << "," << gyro_z << "," << mag_timestamp << "," << mag_x << ","
-           << mag_y << "," << mag_z << "\n";
+        os << accelerationTimestamp << "," << accelerationX << ","
+           << accelerationY << "," << accelerationZ << ","
+           << angularVelocityTimestamp << "," << angularVelocityX << ","
+           << angularVelocityY << "," << angularVelocityZ << ","
+           << magneticFieldTimestamp << "," << magneticFieldX << ","
+           << magneticFieldY << "," << magneticFieldZ << "\n";
     }
 };
 
@@ -53,7 +55,7 @@ struct MockPressureData : public PressureData
 
     void print(std::ostream& os) const
     {
-        os << press_timestamp << "," << press << "\n";
+        os << pressureTimestamp << "," << pressure << "\n";
     }
 };
 
@@ -65,12 +67,12 @@ struct MockGPSData : public GPSData
                "velocity_east,velocity_down,speed,track,num_satellites,fix\n";
     }
 
-    void print(std::ostream &os) const
+    void print(std::ostream& os) const
     {
-        os << gps_timestamp << "," << latitude << "," << longitude << ","
-           << height << "," << velocity_north << "," << velocity_east << ","
-           << velocity_down << "," << speed << "," << track << ","
-           << (int)num_satellites << "," << (int)fix << "\n";
+        os << gpsTimestamp << "," << latitude << "," << longitude << ","
+           << height << "," << velocityNorth << "," << velocityEast << ","
+           << velocityDown << "," << speed << "," << track << ","
+           << (int)satellites << "," << (int)fix << "\n";
     }
 };
 
diff --git a/src/mocksensors/MockSpeedSensor.h b/src/mocksensors/MockSpeedSensor.h
index a9dd3b3f9..c7c01cae0 100644
--- a/src/mocksensors/MockSpeedSensor.h
+++ b/src/mocksensors/MockSpeedSensor.h
@@ -22,10 +22,10 @@
 
 #pragma once
 
-#include <Common.h>
 #include <mocksensors/MockSensorsData.h>
 #include <mocksensors/lynx_flight_data/lynx_airspeed_data.h>
 #include <sensors/Sensor.h>
+
 #include <random>
 
 namespace DeathStackBoard
@@ -44,7 +44,7 @@ public:
     {
         MockSpeedData data;
 
-        data.timestamp = TimestampTimer::getTimestamp();
+        data.timestamp = TimestampTimer::getInstance().getTimestamp();
 
         if (before_liftoff)
         {
diff --git a/src/mocksensors/lynx_flight_data/lynx_airspeed_data.h b/src/mocksensors/lynx_flight_data/lynx_airspeed_data.h
index d0948bffb..7fa3e38da 100644
--- a/src/mocksensors/lynx_flight_data/lynx_airspeed_data.h
+++ b/src/mocksensors/lynx_flight_data/lynx_airspeed_data.h
@@ -22,8 +22,6 @@
 
 #pragma once
 
-#include <Common.h>
-
 /**
  * Pitot airspeed data from Lynx flight test in Roccaraso.
  * Sampled at 42 Hz (24 ms period).
diff --git a/src/mocksensors/lynx_flight_data/lynx_gps_data.h b/src/mocksensors/lynx_flight_data/lynx_gps_data.h
index a82162aca..3318c3a51 100644
--- a/src/mocksensors/lynx_flight_data/lynx_gps_data.h
+++ b/src/mocksensors/lynx_flight_data/lynx_gps_data.h
@@ -22,7 +22,7 @@
 
 #pragma once
 
-#include <Common.h>
+#include <stdint.h>
 
 /**
  * Ublox Neo-M9N GPS data from Lynx flight test in Roccaraso.
diff --git a/src/mocksensors/mock_data/test-mock-sensors.cpp b/src/mocksensors/mock_data/test-mock-sensors.cpp
index d21fa7b4e..2181291ea 100644
--- a/src/mocksensors/mock_data/test-mock-sensors.cpp
+++ b/src/mocksensors/mock_data/test-mock-sensors.cpp
@@ -20,15 +20,12 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <mocksensors/MockSensors.h>
 
 using namespace DeathStackBoard;
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     MockGPS gps;
     MockPressureSensor p_sensor;
     MockIMU imu;
@@ -55,7 +52,7 @@ int main()
         p_sensor.sample();
         PressureData pressure = p_sensor.getLastSample();
         TRACE("PRESSURE SAMPLE: \n");
-        TRACE("pressure = %f \n\n", pressure.press);
+        TRACE("pressure = %f \n\n", pressure.pressure);
 
         imu.sample();
         MockIMUData imu_data = imu.getLastSample();
diff --git a/src/tests/airbrakes/test-airbrakes-interactive.cpp b/src/tests/airbrakes/test-airbrakes-interactive.cpp
index f15d6d74f..36fcdf1ae 100644
--- a/src/tests/airbrakes/test-airbrakes-interactive.cpp
+++ b/src/tests/airbrakes/test-airbrakes-interactive.cpp
@@ -90,7 +90,7 @@ float resetPosition = AirBrakesConfigs::AB_SERVO_MIN_POS;
 
 int main()
 {
-    sEventBroker->start();
+    sEventBroker.start();
 
     miosix::GpioPin pwmPin = miosix::GpioPin(GPIOC_BASE, 7);
     pwmPin.mode(miosix::Mode::ALTERNATE);
@@ -164,13 +164,13 @@ void testAlgorithm()
     // Start the state machine
     airbrakesController.start();
     sensor.sample();
-    EventCounter counter{*sEventBroker};
+    EventCounter counter{sEventBroker};
     counter.subscribe(TOPIC_FLIGHT_EVENTS);
     counter.subscribe(TOPIC_ABK);
 
     // Start test
     cout << "Starting airbrakes test\n";
-    sEventBroker->post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
     while (counter.getCount(EV_SHADOW_MODE_TIMEOUT) < 1)
     {
         Thread::sleep(10);
@@ -208,12 +208,12 @@ void testAirBrakes()
 
     // Start the state machine
     airbrakesController.start();
-    EventCounter counter{*sEventBroker};
+    EventCounter counter{sEventBroker};
     counter.subscribe(TOPIC_ABK);
 
     // Start test
     cout << "Starting airbrakes test\n";
-    sEventBroker->post({EV_TEST_ABK}, TOPIC_ABK);
+    sEventBroker.post({EV_TEST_ABK}, TOPIC_ABK);
 
     while (counter.getCount(EV_TEST_TIMEOUT) < 1)
     {
diff --git a/src/tests/catch/ada/ada_kalman_p/test-ada-simulation.cpp b/src/tests/catch/ada/ada_kalman_p/test-ada-simulation.cpp
index d88c8b7c1..74070c368 100644
--- a/src/tests/catch/ada/ada_kalman_p/test-ada-simulation.cpp
+++ b/src/tests/catch/ada/ada_kalman_p/test-ada-simulation.cpp
@@ -26,22 +26,20 @@
 
 #define EIGEN_NO_MALLOC
 
-
-#include <catch2/catch.hpp>
-
 #include <Eigen/Dense>
+#include <catch2/catch.hpp>
 
 #define private public
 #define protected public
 
-#include <ApogeeDetectionAlgorithm/ADAController.h>
 #include <ApogeeDetectionAlgorithm/ADAAlgorithm.h>
+#include <ApogeeDetectionAlgorithm/ADAController.h>
 #include <DeathStack.h>
-#include <Common.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 #include <events/FSM.h>
 #include <events/utils/EventCounter.h>
+
 #include <algorithm>
 #include <cmath>
 #include <iostream>
@@ -88,7 +86,8 @@ public:
             }
         }
 
-        return PressureData{TimestampTimer::getTimestamp(), press};
+        return PressureData{TimestampTimer::getInstance().getTimestamp(),
+                            press};
     }
 
     void signalLiftoff() { before_liftoff = false; }
@@ -145,14 +144,12 @@ void checkState(unsigned int i, ADAKalmanState state)
 
 TEST_CASE("Testing ada_controller from calibration to first descent phase")
 {
-    TimestampTimer::enableTimestampTimer();
-
     ada_controller = new ADACtrl(mock_baro, mock_gps);
     TRACE("ADA init : %d \n", ada_controller->start());
 
     // Start event broker and ada_controller
-    sEventBroker->start();
-    EventCounter counter{*sEventBroker};
+    sEventBroker.start();
+    EventCounter counter{sEventBroker};
     counter.subscribe(TOPIC_ADA);
 
     // Startup: we should be in idle
@@ -160,7 +157,7 @@ TEST_CASE("Testing ada_controller from calibration to first descent phase")
     REQUIRE(ada_controller->testState(&ADACtrl::state_idle));
 
     // Enter Calibrating and REQUIRE
-    sEventBroker->post({EV_CALIBRATE_ADA}, TOPIC_ADA);
+    sEventBroker.post({EV_CALIBRATE_ADA}, TOPIC_ADA);
     Thread::sleep(100);
     REQUIRE(ada_controller->testState(&ADACtrl::state_calibrating));
 
@@ -216,7 +213,7 @@ TEST_CASE("Testing ada_controller from calibration to first descent phase")
     REQUIRE(ada_controller->testState(&ADACtrl::state_ready));
 
     // Send liftoff event: should be in shadow mode
-    sEventBroker->post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
     mock_baro.signalLiftoff();
     Thread::sleep(100);
     REQUIRE(ada_controller->testState(&ADACtrl::state_shadowMode));
@@ -230,7 +227,7 @@ TEST_CASE("Testing ada_controller from calibration to first descent phase")
         mock_baro.sample();
         Thread::sleep(5);
         ada_controller->update();
-        float noisy_p = mock_baro.getLastSample().press;
+        float noisy_p = mock_baro.getLastSample().pressure;
         // Thread::sleep(100);
         ADAKalmanState state = ada_controller->ada.getKalmanState();
         printf("%d,%f,%f,%f\n", (int)i, noisy_p, state.x0,
@@ -252,7 +249,7 @@ TEST_CASE("Testing ada_controller from calibration to first descent phase")
         mock_baro.sample();
         Thread::sleep(5);
         ada_controller->update();
-        float noisy_p = mock_baro.getLastSample().press;
+        float noisy_p = mock_baro.getLastSample().pressure;
         // Thread::sleep(100);
         ADAKalmanState state = ada_controller->ada.getKalmanState();
         printf("%d,%f,%f,%f\n", (int)i, noisy_p, state.x0,
diff --git a/src/tests/catch/ada/kalman_acc/test-kalman-acc.cpp b/src/tests/catch/ada/kalman_acc/test-kalman-acc.cpp
index 8169ac0fe..52accdb46 100644
--- a/src/tests/catch/ada/kalman_acc/test-kalman-acc.cpp
+++ b/src/tests/catch/ada/kalman_acc/test-kalman-acc.cpp
@@ -27,13 +27,12 @@
 #define private public
 
 #include <ADA/ADA.h>
-#include <Common.h>
 #include <configs/ADAConfig.h>
 
+#include <catch2/catch.hpp>
 #include <iostream>
 #include <random>
 #include <sstream>
-#include <catch2/catch.hpp>
 
 #include "test-kalman-acc-data.h"
 
diff --git a/src/tests/catch/ada/test-rogallo-dts.cpp b/src/tests/catch/ada/test-rogallo-dts.cpp
index ac887b85e..2770af03b 100644
--- a/src/tests/catch/ada/test-rogallo-dts.cpp
+++ b/src/tests/catch/ada/test-rogallo-dts.cpp
@@ -119,7 +119,7 @@ TEST_CASE("[RogalloDTS] Test Launch Hazard Circles")
 
 TEST_CASE("[Rogallo DTS] Test deployment altitude")
 {
-    EventCounter c{*sEventBroker};
+    EventCounter c{sEventBroker};
     c.subscribe(TOPIC_ADA);
 
     RogalloDTS dts;
diff --git a/src/tests/catch/catch-tests-entry.cpp b/src/tests/catch/catch-tests-entry.cpp
index 389ee6f73..3167810e3 100644
--- a/src/tests/catch/catch-tests-entry.cpp
+++ b/src/tests/catch/catch-tests-entry.cpp
@@ -55,9 +55,9 @@
 
 #include <miosix.h>
 
+#include <catch2/catch.hpp>
 #include <cstring>
 #include <string>
-#include <catch2/catch.hpp>
 #include <vector>
 
 using miosix::Thread;
@@ -137,7 +137,7 @@ int main()
     }
 
     // Run tests with the provided arguments
-    int result = Catch::Session().run(argc, argv);
+    Catch::Session().run(argc, argv);
 
     // Clear memory
     for (size_t i = 0; i < argc; i++)
diff --git a/src/tests/catch/fsm/test-ada.cpp b/src/tests/catch/fsm/test-ada.cpp
index 51ee14fe9..775ae083f 100644
--- a/src/tests/catch/fsm/test-ada.cpp
+++ b/src/tests/catch/fsm/test-ada.cpp
@@ -29,9 +29,8 @@
 
 #include <miosix.h>
 
-#include <catch2/catch.hpp>
-
 #include <Eigen/Dense>
+#include <catch2/catch.hpp>
 
 #define private public
 #define protected public
@@ -53,7 +52,7 @@ public:
     // This is called at the beginning of each test / section
     ADAControllerFixture()
     {
-        sEventBroker->start();
+        sEventBroker.start();
         controller = new ADACtrl(mock_baro, mock_gps);
         controller->start();
     }
@@ -62,8 +61,8 @@ public:
     ~ADAControllerFixture()
     {
         controller->stop();
-        sEventBroker->unsubscribe(controller);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(controller);
+        sEventBroker.clearDelayedEvents();
         delete controller;
     }
 
diff --git a/src/tests/catch/fsm/test-airbrakes.cpp b/src/tests/catch/fsm/test-airbrakes.cpp
index 0eb3af90c..51d7ec5bb 100644
--- a/src/tests/catch/fsm/test-airbrakes.cpp
+++ b/src/tests/catch/fsm/test-airbrakes.cpp
@@ -75,7 +75,7 @@ public:
     AirBrakesControllerFixture()
     {
         controller = new AirBrakesController<InputClass>(sensor);
-        sEventBroker->start();
+        sEventBroker.start();
         controller->start();
     }
 
@@ -83,8 +83,8 @@ public:
     ~AirBrakesControllerFixture()
     {
         controller->stop();
-        sEventBroker->unsubscribe(controller);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(controller);
+        sEventBroker.clearDelayedEvents();
         delete controller;
     }
 
diff --git a/src/tests/catch/fsm/test-deployment.cpp b/src/tests/catch/fsm/test-deployment.cpp
index 68d0df735..137f2f925 100644
--- a/src/tests/catch/fsm/test-deployment.cpp
+++ b/src/tests/catch/fsm/test-deployment.cpp
@@ -29,7 +29,7 @@
 #define protected public
 
 #include <Deployment/DeploymentController.h>
-#include <drivers/servo/servo.h>
+#include <drivers/servo/Servo.h>
 #include <miosix.h>
 
 #include <catch2/catch.hpp>
@@ -48,7 +48,7 @@ public:
     DeploymentControllerFixture()
     {
         controller = new DeploymentController(&ejection_servo);
-        sEventBroker->start();
+        sEventBroker.start();
         controller->start();
     }
 
@@ -56,8 +56,8 @@ public:
     ~DeploymentControllerFixture()
     {
         controller->stop();
-        sEventBroker->unsubscribe(controller);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(controller);
+        sEventBroker.clearDelayedEvents();
         delete controller;
     }
 
diff --git a/src/tests/catch/fsm/test-flightstatsrecorder.cpp b/src/tests/catch/fsm/test-flightstatsrecorder.cpp
index 45e9cee8e..1ca268fbe 100644
--- a/src/tests/catch/fsm/test-flightstatsrecorder.cpp
+++ b/src/tests/catch/fsm/test-flightstatsrecorder.cpp
@@ -30,9 +30,8 @@
 
 #include <miosix.h>
 
-#include <catch2/catch.hpp>
-
 #include <Eigen/Dense>
+#include <catch2/catch.hpp>
 
 #define private public
 #define protected public
@@ -51,7 +50,7 @@ public:
     // This is called at the beginning of each test / section
     FlightStatsFixture()
     {
-        sEventBroker->start();
+        sEventBroker.start();
         fsm = new FlightStatsRecorder();
         fsm->start();
     }
@@ -60,8 +59,8 @@ public:
     ~FlightStatsFixture()
     {
         fsm->stop();
-        sEventBroker->unsubscribe(fsm);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(fsm);
+        sEventBroker.clearDelayedEvents();
         delete fsm;
     }
 
diff --git a/src/tests/catch/fsm/test-fmm.cpp b/src/tests/catch/fsm/test-fmm.cpp
index 793a6a547..0b65370bb 100644
--- a/src/tests/catch/fsm/test-fmm.cpp
+++ b/src/tests/catch/fsm/test-fmm.cpp
@@ -29,12 +29,11 @@
 
 #include <miosix.h>
 
+#include <Eigen/Dense>
 #include <catch2/catch.hpp>
 
 #include "events/Events.h"
 
-#include <Eigen/Dense>
-
 #define private public
 #define protected public
 
@@ -51,7 +50,7 @@ public:
     // This is called at the beginning of each test / section
     FMMFixture()
     {
-        sEventBroker->start();
+        sEventBroker.start();
         fsm = new FMMController();
         fsm->start();
     }
@@ -60,8 +59,8 @@ public:
     ~FMMFixture()
     {
         fsm->stop();
-        sEventBroker->unsubscribe(fsm);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(fsm);
+        sEventBroker.clearDelayedEvents();
         delete fsm;
     }
 
diff --git a/src/tests/catch/fsm/test-ignition.cpp b/src/tests/catch/fsm/test-ignition.cpp
index 5df0ea6a9..19afdf1c2 100644
--- a/src/tests/catch/fsm/test-ignition.cpp
+++ b/src/tests/catch/fsm/test-ignition.cpp
@@ -55,8 +55,8 @@ public:
     }
     ~IgnitionTestFixture()
     {
-        sEventBroker->unsubscribe(ign);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(ign);
+        sEventBroker.clearDelayedEvents();
         delete ign;
         delete can;
         delete can_mgr;
@@ -161,7 +161,7 @@ class IgnitionTestFixture2
 public:
     IgnitionTestFixture2()
     {
-        sEventBroker->start();
+        sEventBroker.start();
         can_mgr = new CanManager(CAN1);
         can     = new CanProxy(can_mgr);
         ign     = new IgnitionController(can);
@@ -170,8 +170,8 @@ public:
     ~IgnitionTestFixture2()
     {
         ign->stop();
-        sEventBroker->unsubscribe(ign);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(ign);
+        sEventBroker.clearDelayedEvents();
         delete ign;
         delete can;
         delete can_mgr;
@@ -201,7 +201,7 @@ TEST_CASE_METHOD(IgnitionTestFixture2, "Igntiion: Testing IDLE functions")
         {
             TRACE("Beginning of section\n");
 
-            EventCounter counter{*sEventBroker};
+            EventCounter counter{sEventBroker};
             counter.subscribe(TOPIC_FLIGHT_EVENTS);
 
             // Sending ign status
@@ -251,7 +251,7 @@ TEST_CASE_METHOD(IgnitionTestFixture2, "Igntiion: Testing IDLE functions")
                                                   // the delayed ev_ign_offline
                                                   // should be deleted
     {
-        EventCounter counter{*sEventBroker};
+        EventCounter counter{sEventBroker};
         counter.subscribe(TOPIC_FLIGHT_EVENTS);
 
         Thread::sleep(TIMEOUT_IGN_OFFLINE / 2);
diff --git a/src/tests/catch/fsm/test-nas.cpp b/src/tests/catch/fsm/test-nas.cpp
index 1d1b51496..5aea6b14c 100644
--- a/src/tests/catch/fsm/test-nas.cpp
+++ b/src/tests/catch/fsm/test-nas.cpp
@@ -34,6 +34,7 @@
 #include <NavigationAttitudeSystem/NASCalibrator.h>
 #include <NavigationAttitudeSystem/NASController.h>
 #include <mocksensors/MockSensors.h>
+
 #include "events/Events.h"
 #include "utils/testutils/TestHelper.h"
 
@@ -47,7 +48,7 @@ public:
     // This is called at the beginning of each test / section
     NASControllerFixture() : controller(mock_imu, mock_baro, mock_gps)
     {
-        sEventBroker->start();
+        sEventBroker.start();
         controller.start();
     }
 
@@ -55,8 +56,8 @@ public:
     ~NASControllerFixture()
     {
         controller.stop();
-        sEventBroker->unsubscribe(&controller);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(&controller);
+        sEventBroker.clearDelayedEvents();
     }
 
 protected:
diff --git a/src/tests/catch/fsm/test-tmtc.cpp b/src/tests/catch/fsm/test-tmtc.cpp
index 65b7478eb..8d6943553 100644
--- a/src/tests/catch/fsm/test-tmtc.cpp
+++ b/src/tests/catch/fsm/test-tmtc.cpp
@@ -30,9 +30,8 @@
 
 #include <miosix.h>
 
-#include <catch2/catch.hpp>
-
 #include <Eigen/Dense>
+#include <catch2/catch.hpp>
 
 #define private public
 #define protected public
@@ -51,7 +50,7 @@ public:
     // This is called at the beginning of each test / section
     TMTCFixture()
     {
-        sEventBroker->start();
+        sEventBroker.start();
         fsm = new TMTCController();
         fsm->start();
     }
@@ -60,8 +59,8 @@ public:
     ~TMTCFixture()
     {
         fsm->stop();
-        sEventBroker->unsubscribe(fsm);
-        sEventBroker->clearDelayedEvents();
+        sEventBroker.unsubscribe(fsm);
+        sEventBroker.clearDelayedEvents();
         delete fsm;
     }
 
diff --git a/src/tests/catch/nas/test-nas-simulation.cpp b/src/tests/catch/nas/test-nas-simulation.cpp
index 0ba5573b6..75fced107 100644
--- a/src/tests/catch/nas/test-nas-simulation.cpp
+++ b/src/tests/catch/nas/test-nas-simulation.cpp
@@ -64,12 +64,10 @@ void signalLiftoff()
 
 TEST_CASE("Testing Navigation System Controller")
 {
-    TimestampTimer::enableTimestampTimer();
-
-    sEventBroker->start();
+    sEventBroker.start();
     controller.start();
 
-    EventCounter counter{*sEventBroker};
+    EventCounter counter{sEventBroker};
     counter.subscribe(TOPIC_NAS);
 
     // Startup: we should be in idle
@@ -77,7 +75,7 @@ TEST_CASE("Testing Navigation System Controller")
     REQUIRE(controller.testState(&NASCtrl::state_idle));
 
     // Enter Calibrating and REQUIRE
-    sEventBroker->post(Event{EV_CALIBRATE_NAS}, TOPIC_NAS);
+    sEventBroker.post(Event{EV_CALIBRATE_NAS}, TOPIC_NAS);
     Thread::sleep(100);
     REQUIRE(controller.testState(&NASCtrl::state_calibrating));
 
@@ -101,9 +99,11 @@ TEST_CASE("Testing Navigation System Controller")
     MockIMUData imu_data =
         mock_imu.getLastSample();  // still before liftoff ...
     NASReferenceValues ref_values{
-        press_data.press, gps_data.latitude, gps_data.longitude,
-        imu_data.accel_x, imu_data.accel_y,  imu_data.accel_z,
-        imu_data.mag_x,   imu_data.mag_y,    imu_data.mag_z};
+        press_data.pressure,     gps_data.latitude,
+        gps_data.longitude,      imu_data.accelerationX,
+        imu_data.accelerationY,  imu_data.accelerationZ,
+        imu_data.magneticFieldX, imu_data.magneticFieldY,
+        imu_data.magneticFieldZ};
     REQUIRE(ref_values == controller.calibrator.getReferenceValues());
 
     // Now we should be in ready
@@ -115,7 +115,7 @@ TEST_CASE("Testing Navigation System Controller")
     Thread::sleep(100);
 
     // retry the calibration phase
-    sEventBroker->post({EV_CALIBRATE_NAS}, TOPIC_NAS);
+    sEventBroker.post({EV_CALIBRATE_NAS}, TOPIC_NAS);
     Thread::sleep(100);
     REQUIRE(controller.testState(&NASCtrl::state_calibrating));
     // sample some data for calibration
@@ -130,11 +130,14 @@ TEST_CASE("Testing Navigation System Controller")
     // i.e. the first element of the arrays from which the sensors get the data
     press_data = mock_baro.getLastSample();  // still before liftoff
                                              // (same as SIMULATED_PRESSURE[0])
-    gps_data   = mock_gps.getLastSample();   // still before liftoff ...
-    imu_data   = mock_imu.getLastSample();   // still before liftoff ...
-    ref_values = NASReferenceValues{press_data.press, gps_data.latitude, gps_data.longitude,
-                  imu_data.accel_x, imu_data.accel_y,  imu_data.accel_z,
-                  imu_data.mag_x,   imu_data.mag_y,    imu_data.mag_z};
+    gps_data = mock_gps.getLastSample();     // still before liftoff ...
+    imu_data = mock_imu.getLastSample();     // still before liftoff ...
+    ref_values =
+        NASReferenceValues{press_data.pressure,     gps_data.latitude,
+                           gps_data.longitude,      imu_data.accelerationX,
+                           imu_data.accelerationY,  imu_data.accelerationZ,
+                           imu_data.magneticFieldX, imu_data.magneticFieldY,
+                           imu_data.magneticFieldZ};
     REQUIRE(ref_values == controller.calibrator.getReferenceValues());
 
     // Now we should be in ready
@@ -144,7 +147,7 @@ TEST_CASE("Testing Navigation System Controller")
     REQUIRE(controller.testState(&NASCtrl::state_ready));
 
     // Send liftoff event: should be in state active
-    sEventBroker->post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
     signalLiftoff();
     Thread::sleep(100);
     REQUIRE(controller.testState(&NASCtrl::state_active));
diff --git a/src/tests/deathstack-boards/test-analog-board.cpp b/src/tests/deathstack-boards/test-analog-board.cpp
index bc8dcd064..bf05c3c92 100644
--- a/src/tests/deathstack-boards/test-analog-board.cpp
+++ b/src/tests/deathstack-boards/test-analog-board.cpp
@@ -36,10 +36,9 @@
  * Deatachment pins
  */
 
-#include <Common.h>
-#include <drivers/adc/ADS1118/ADS1118.h>
 #include <interfaces-impl/hwmapping.h>
 #include <miosix.h>
+#include <sensors/ADS1118/ADS1118.h>
 #include <sensors/MS5803/MS5803.h>
 #include <sensors/analog/pressure/MPXHZ6130A/MPXHZ6130A.h>
 #include <sensors/analog/pressure/honeywell/SSCDANN030PAA.h>
@@ -76,8 +75,6 @@ void sampleAll();
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     switch (menu())
     {
         case 1:
@@ -148,7 +145,7 @@ void sampleAnalogPressureSensor(ADS1118::ADS1118Mux channel)
 
     SPIBus spiBus(SPI1);
     SPIBusConfig spiConfig = ADS1118::getDefaultSPIConfig();
-    spiConfig.clock_div    = SPIClockDivider::DIV64;
+    spiConfig.clockDivider = SPI::ClockDivider::DIV_64;
     SPISlave spiSlave(spiBus, miosix::sensors::ads1118::cs::getPin(),
                       spiConfig);
 
@@ -169,8 +166,8 @@ void sampleAnalogPressureSensor(ADS1118::ADS1118Mux channel)
     {
         ads1118.sample();
         pressureSensor.sample();
-        printf("%llu,%.2f\n", pressureSensor.getLastSample().press_timestamp,
-               pressureSensor.getLastSample().press);
+        printf("%llu,%.2f\n", pressureSensor.getLastSample().pressureTimestamp,
+               pressureSensor.getLastSample().pressure);
 
         miosix::delayMs(1000 / SAMPLING_FREQUENCY);
     }
@@ -183,7 +180,7 @@ void sampleMS5803()
 
     // Sensor setup
     SPIBusConfig spiCfg{};
-    spiCfg.clock_div = SPIClockDivider::DIV16;
+    spiCfg.clockDivider = SPI::ClockDivider::DIV_16;
     SPIBus spiBus(SPI1);
     SPISlave spiSlave(spiBus, miosix::sensors::ms5803::cs::getPin(), spiCfg);
     MS5803 ms5803 = MS5803(spiSlave);
@@ -193,7 +190,7 @@ void sampleMS5803()
     for (int i = 0; i < seconds * SAMPLING_FREQUENCY; i++)
     {
         ms5803.sample();
-        printf("%.2f\n", ms5803.getLastSample().press);
+        printf("%.2f\n", ms5803.getLastSample().pressure);
 
         miosix::delayMs(1000 / SAMPLING_FREQUENCY);
     }
@@ -208,9 +205,9 @@ void sampleAll()
 
     SPIBus spiBus(SPI1);
     SPIBusConfig adsSpiConfig = ADS1118::getDefaultSPIConfig();
-    adsSpiConfig.clock_div    = SPIClockDivider::DIV64;
+    adsSpiConfig.clockDivider = SPI::ClockDivider::DIV_64;
     SPISlave adsSpiSlave(spiBus, miosix::sensors::ads1118::cs::getPin(),
-                      adsSpiConfig);
+                         adsSpiConfig);
 
     ADS1118::ADS1118Config ads1118Config = ADS1118::ADS1118_DEFAULT_CONFIG;
     ads1118Config.bits.mode = ADS1118::ADS1118Mode::CONTIN_CONV_MODE;
@@ -240,10 +237,11 @@ void sampleAll()
                              SUPPLIED_VOLTAGE);
     SSCDRRN015PDA honeywell2(get_voltage_function_honeywell_2,
                              SUPPLIED_VOLTAGE);
-    
+
     SPIBusConfig ms5803SpiCfg{};
-    ms5803SpiCfg.clock_div = SPIClockDivider::DIV16;
-    SPISlave ms5803SpiSlave(spiBus, miosix::sensors::ms5803::cs::getPin(), ms5803SpiCfg);
+    ms5803SpiCfg.clockDivider = SPI::ClockDivider::DIV_16;
+    SPISlave ms5803SpiSlave(spiBus, miosix::sensors::ms5803::cs::getPin(),
+                            ms5803SpiCfg);
     MS5803 ms5803 = MS5803(ms5803SpiSlave);
     ms5803.init();
 
@@ -257,10 +255,11 @@ void sampleAll()
         honeywell2.sample();
         ms5803.sample();
         printf("%llu,%.2f,%.2f,%.2f,%.2f,%.2f\n",
-               ads1118.getLastSample().adc_timestamp,
-               npx1.getLastSample().press, npx2.getLastSample().press,
-               honeywell1.getLastSample().press,
-               honeywell2.getLastSample().press, ms5803.getLastSample().press);
+               ads1118.getLastSample().voltageTimestamp,
+               npx1.getLastSample().pressure, npx2.getLastSample().pressure,
+               honeywell1.getLastSample().pressure,
+               honeywell2.getLastSample().pressure,
+               ms5803.getLastSample().pressure);
 
         miosix::delayMs(1000 / SAMPLING_FREQUENCY);
     }
diff --git a/src/tests/deathstack-boards/test-power-board.cpp b/src/tests/deathstack-boards/test-power-board.cpp
index acc36ed2f..72d942bbd 100644
--- a/src/tests/deathstack-boards/test-power-board.cpp
+++ b/src/tests/deathstack-boards/test-power-board.cpp
@@ -29,11 +29,10 @@
  */
 
 #include <AirBrakes/AirBrakesServo.h>
-#include <Common.h>
 #include <Deployment/DeploymentServo.h>
-#include <drivers/adc/InternalADC/InternalADC.h>
+#include <drivers/adc/InternalADC.h>
 #include <drivers/hbridge/HBridge.h>
-#include <drivers/servo/servo.h>
+#include <drivers/servo/Servo.h>
 #include <sensors/analog/battery/BatteryVoltageSensor.h>
 
 #include <cstdio>
@@ -62,8 +61,6 @@ void sampleBatteryVoltage();
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     switch (menu())
     {
         case 1:
@@ -120,7 +117,7 @@ void sampleBatteryVoltage()
 
     // Sensor setup
 
-    InternalADC internalADC = InternalADC(*ADC3, 3.3);
+    InternalADC internalADC = InternalADC(ADC3, 3.3);
     internalADC.enableChannel(InternalADC::CH5);
     internalADC.init();
 
@@ -138,10 +135,10 @@ void sampleBatteryVoltage()
         BatteryVoltageSensorData data = batterySensor.getLastSample();
 
         // Calculate a simple linear battery percentage
-        float batteryPercentage = 100 * (data.bat_voltage - 9.6) / (12.6 - 9.6);
+        float batteryPercentage = 100 * (data.batVoltage - 9.6) / (12.6 - 9.6);
 
-        printf("%llu,%.3f,%.3f,%.1f\n", data.adc_timestamp, data.voltage,
-               data.bat_voltage, batteryPercentage);
+        printf("%llu,%.3f,%.3f,%.1f\n", data.voltageTimestamp, data.voltage,
+               data.batVoltage, batteryPercentage);
 
         miosix::delayMs(1000 / SAMPLING_FREQUENCY);
     }
diff --git a/src/tests/deathstack-boards/test-rf-board.cpp b/src/tests/deathstack-boards/test-rf-board.cpp
index 6448e6d7a..b24ab76a9 100644
--- a/src/tests/deathstack-boards/test-rf-board.cpp
+++ b/src/tests/deathstack-boards/test-rf-board.cpp
@@ -31,13 +31,12 @@
  * SD card
  */
 
-#include <Common.h>
-#include <drivers/gps/ublox/UbloxGPS.h>
 #include <drivers/spi/SPIDriver.h>
 #include <interfaces-impl/hwmapping.h>
 #include <miosix.h>
 #include <sensors/BMX160/BMX160.h>
 #include <sensors/LIS3MDL/LIS3MDL.h>
+#include <sensors/UbloxGPS/UbloxGPS.h>
 
 #include <ctime>
 #include <iostream>
@@ -46,6 +45,8 @@
 
 #include "math/Stats.h"
 
+using namespace Boardcore;
+
 namespace SDCardBenchmark
 {
 #include "../../skyward-boardcore/src/entrypoints/sdcard-benchmark.cpp"
@@ -132,8 +133,8 @@ void sampleLIS3MDL()
 
     SPIBus spiBus(SPI1);
     SPIBusConfig spiConfig;
-    spiConfig.clock_div = SPIClockDivider::DIV32;
-    spiConfig.mode      = SPIMode::MODE1;
+    spiConfig.clockDivider = SPI::ClockDivider::DIV_32;
+    spiConfig.mode         = SPI::Mode::MODE_1;
 
     LIS3MDL::Config lis3mdlConfig;
     lis3mdlConfig.odr                = LIS3MDL::ODR_560_HZ;
@@ -167,9 +168,9 @@ void sampleBMX160()
     SPIBus spiBus(SPI1);
 
     BMX160Config bmx160Config;
-    bmx160Config.fifo_mode    = BMX160Config::FifoMode::DISABLED;
-    bmx160Config.fifo_int     = BMX160Config::FifoInterruptPin::PIN_INT1;
-    bmx160Config.temp_divider = 1;
+    bmx160Config.fifoMode           = BMX160Config::FifoMode::DISABLED;
+    bmx160Config.fifoInterrupt      = BMX160Config::FifoInterruptPin::PIN_INT1;
+    bmx160Config.temperatureDivider = 1;
 
     BMX160 bmx160 =
         BMX160(spiBus, miosix::sensors::bmx160::cs::getPin(), bmx160Config);
@@ -197,8 +198,8 @@ void sampleAll()
 
     SPIBus spiBus(SPI1);
     SPIBusConfig spiConfig;
-    spiConfig.clock_div = SPIClockDivider::DIV32;
-    spiConfig.mode      = SPIMode::MODE1;
+    spiConfig.clockDivider = SPI::ClockDivider::DIV_32;
+    spiConfig.mode         = SPI::Mode::MODE_1;
 
     LIS3MDL::Config lis3mdlConfig;
     lis3mdlConfig.odr                = LIS3MDL::ODR_560_HZ;
@@ -210,9 +211,9 @@ void sampleAll()
     lis3mdl.init();
 
     BMX160Config bmx160Config;
-    bmx160Config.fifo_mode    = BMX160Config::FifoMode::DISABLED;
-    bmx160Config.fifo_int     = BMX160Config::FifoInterruptPin::PIN_INT1;
-    bmx160Config.temp_divider = 1;
+    bmx160Config.fifoMode           = BMX160Config::FifoMode::DISABLED;
+    bmx160Config.fifoInterrupt      = BMX160Config::FifoInterruptPin::PIN_INT1;
+    bmx160Config.temperatureDivider = 1;
 
     BMX160 bmx160 =
         BMX160(spiBus, miosix::sensors::bmx160::cs::getPin(), bmx160Config);
@@ -240,7 +241,8 @@ void sampleGPS()
 
     // Sensor setup
 
-    UbloxGPS gps(38400);
+    UbloxGPSSerial gps;
+
     gps.init();
     miosix::delayMs(200);
     gps.start();
diff --git a/src/tests/deathstack-boards/test-stm-board.cpp b/src/tests/deathstack-boards/test-stm-board.cpp
index 053619d50..5f1d3133c 100644
--- a/src/tests/deathstack-boards/test-stm-board.cpp
+++ b/src/tests/deathstack-boards/test-stm-board.cpp
@@ -28,8 +28,6 @@
  *     External oscillator
  */
 
-#include <Common.h>
-
 #include <iostream>
 #include <sstream>
 
@@ -53,8 +51,6 @@ int askSeconds();
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     switch (menu())
     {
         case 1:
diff --git a/src/tests/deployment/test-deployment-interactive.cpp b/src/tests/deployment/test-deployment-interactive.cpp
index eba886c72..c0bcf55ca 100644
--- a/src/tests/deployment/test-deployment-interactive.cpp
+++ b/src/tests/deployment/test-deployment-interactive.cpp
@@ -73,7 +73,7 @@ int main()
     ejection_servo.enable();
     ejection_servo.reset();
 
-    sEventBroker->start();
+    sEventBroker.start();
 
     string temp;
     for (;;)
@@ -172,7 +172,7 @@ void cuttingSequence()
     deploymentController.start();
 
     Thread::sleep(1000);
-    sEventBroker->post({EV_CUT_DROGUE}, TOPIC_DPL);
+    sEventBroker.post({EV_CUT_DROGUE}, TOPIC_DPL);
 
     waitForEvent(EV_CUTTING_TIMEOUT, TOPIC_DPL, waitEventTimeout);
 
@@ -220,12 +220,12 @@ void cutterContinuity()
     if (cutter == 1)
     {
         cout << "Activating primary cutter...\n";
-        sEventBroker->post({EV_TEST_CUT_PRIMARY}, TOPIC_DPL);
+        sEventBroker.post({EV_TEST_CUT_PRIMARY}, TOPIC_DPL);
     }
     else
     {
         cout << "Activating backup cutter...\n";
-        sEventBroker->post({EV_TEST_CUT_BACKUP}, TOPIC_DPL);
+        sEventBroker.post({EV_TEST_CUT_BACKUP}, TOPIC_DPL);
     }
 
     waitForEvent(EV_CUTTING_TIMEOUT, TOPIC_DPL);
@@ -243,7 +243,7 @@ void noseconeEjection()
 
     waitUserInput();
 
-    EventCounter counter{*sEventBroker};
+    EventCounter counter{sEventBroker};
 
     HBridge primaryCutter{PrimaryCutterEna::getPin(), CUTTER_TIM,
                           CUTTER_CHANNEL_PRIMARY, primaryCutterFrequency,
@@ -266,7 +266,7 @@ void noseconeEjection()
     }
 
     deploymentController.start();
-    sEventBroker->post({EV_NC_OPEN}, TOPIC_DPL);
+    sEventBroker.post({EV_NC_OPEN}, TOPIC_DPL);
 
     for (;;)
     {
diff --git a/src/tests/drivers/test-cutter.cpp b/src/tests/drivers/test-cutter.cpp
index 5b1f45b74..e7eed18de 100644
--- a/src/tests/drivers/test-cutter.cpp
+++ b/src/tests/drivers/test-cutter.cpp
@@ -20,9 +20,8 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <configs/CutterConfig.h>
-#include <drivers/adc/InternalADC/InternalADC.h>
+#include <drivers/adc/InternalADC.h>
 #include <drivers/hbridge/HBridge.h>
 #include <sensors/analog/current/CurrentSensor.h>
 
@@ -40,6 +39,7 @@
  */
 
 using namespace std;
+using namespace miosix;
 using namespace Boardcore;
 using namespace DeathStackBoard::CutterConfig;
 
@@ -51,18 +51,18 @@ constexpr int SAMPLING_FREQUENCY      = 20;
  * They are not useful for activating the COTS ones
  * (i.e. they are currently used only in the test-cutter entrypoint)
  */
-static const PWM::Timer CUTTER_TIM{
-    TIM9, &(RCC->APB2ENR), RCC_APB2ENR_TIM9EN,
-    TimerUtils::getPrescalerInputFrequency(TimerUtils::InputClock::APB2)};
+static TIM_TypeDef *const CUTTER_TIM = TIM9;
 
-static const PWMChannel CUTTER_CHANNEL_PRIMARY         = PWMChannel::CH2;
-static const PWMChannel CUTTER_CHANNEL_BACKUP          = PWMChannel::CH2;
+static const TimerUtils::Channel CUTTER_CHANNEL_PRIMARY =
+    TimerUtils::Channel::CHANNEL_2;
+static const TimerUtils::Channel CUTTER_CHANNEL_BACKUP =
+    TimerUtils::Channel::CHANNEL_2;
 static const unsigned int PRIMARY_CUTTER_PWM_FREQUENCY = 10000;  // Hz
 static constexpr float PRIMARY_CUTTER_PWM_DUTY_CYCLE   = 0.45f;
 static const unsigned int BACKUP_CUTTER_PWM_FREQUENCY  = 10000;  // Hz
 static constexpr float BACKUP_CUTTER_PWM_DUTY_CYCLE    = 0.45f;
 static constexpr float CUTTER_TEST_PWM_DUTY_CYCLE      = 0.1f;
-static constexpr int CUT_TEST_DURATION = 1 * 1000;
+static constexpr int CUT_TEST_DURATION                 = 1 * 1000;
 
 // This could go into CutterConfig
 static constexpr InternalADC::Channel ADC_CHANNEL_PRIMARY =
@@ -79,13 +79,15 @@ static constexpr float ADC_TO_CURR_COEFF = ADC_TO_CURR_DKILIS / ADC_TO_CURR_RIS;
 static constexpr float ADC_TO_CURR_OFFSET =
     ADC_TO_CURR_DKILIS * ADC_TO_CURR_IISOFF;
 
-function<float(float)> adc_to_current = [](float adc_in) {
+function<float(float)> adc_to_current = [](float adc_in)
+{
     return ADC_TO_CURR_DKILIS * (adc_in / ADC_TO_CURR_RIS - ADC_TO_CURR_IISOFF);
 };
 
 bool finished = false;
 
-void menu(unsigned int *cutterNo, uint32_t *frequency, float *dutyCycle, uint32_t *cutDuration);
+void menu(unsigned int *cutterNo, uint32_t *frequency, float *dutyCycle,
+          uint32_t *cutDuration);
 
 void elapsedTimeAndCsense(void *args);
 
@@ -94,9 +96,7 @@ int main()
     unsigned int cutterNo = 0;
     uint32_t frequency    = 0;
     float dutyCycle       = 0;
-    uint32_t cutDuration  = 0; // for cots cutters
-
-    TimestampTimer::enableTimestampTimer();
+    uint32_t cutDuration  = 0;  // for cots cutters
 
     // Set the clock divider for the analog circuitry (/8)
     ADC->CCR |= ADC_CCR_ADCPRE_0 | ADC_CCR_ADCPRE_1;
@@ -107,7 +107,7 @@ int main()
     // Cutter setup
 
     GpioPin *ena_pin;
-    PWMChannel pwmChannel;
+    TimerUtils::Channel pwmChannel;
 
     if (cutterNo == 3)  // COTS cutters
     {
@@ -125,19 +125,17 @@ int main()
     {  // SRAD cutters
         if (cutterNo == 1)
         {
-            ena_pin = new GpioPin(
-                PrimaryCutterEna::getPin());
+            ena_pin    = new GpioPin(PrimaryCutterEna::getPin());
             pwmChannel = CUTTER_CHANNEL_PRIMARY;
         }
         else  // if (cutterNo == 2)
         {
-            ena_pin = new GpioPin(
-                BackupCutterEna::getPin());
+            ena_pin    = new GpioPin(BackupCutterEna::getPin());
             pwmChannel = CUTTER_CHANNEL_BACKUP;
         }
 
-        HBridge cutter(*ena_pin, CUTTER_TIM,
-                       pwmChannel, frequency, dutyCycle / 100.0f);
+        HBridge cutter(*ena_pin, CUTTER_TIM, pwmChannel, frequency,
+                       dutyCycle / 100.0f);
 
         // Start the test
 
@@ -221,7 +219,7 @@ void elapsedTimeAndCsense(void *args)
     int cutterNo = *(unsigned int *)args;
     // Sensors setup
 
-    InternalADC internalADC(*ADC3, 3.3);
+    InternalADC internalADC(ADC3, 3.3);
     internalADC.init();
     internalADC.enableChannel(ADC_CHANNEL_PRIMARY);
     internalADC.enableChannel(ADC_CHANNEL_BACKUP);
@@ -243,14 +241,14 @@ void elapsedTimeAndCsense(void *args)
     current_sensor.init();
 
     // Save the cuttent timestamp
-    uint64_t t  = TimestampTimer::getTimestamp() / 1000;
+    uint64_t t  = TimestampTimer::getInstance().getTimestamp() / 1000;
     uint64_t t0 = t;
 
     while (t < t0 + MAX_CUTTING_TIME && !finished)
     {
         Thread::sleep(1000 / SAMPLING_FREQUENCY);
 
-        t = TimestampTimer::getTimestamp() / 1000;
+        t = TimestampTimer::getInstance().getTimestamp() / 1000;
         internalADC.sample();
         current_sensor.sample();
 
diff --git a/src/tests/drivers/test-imus.cpp b/src/tests/drivers/test-imus.cpp
index 78c6b4b9d..321068864 100644
--- a/src/tests/drivers/test-imus.cpp
+++ b/src/tests/drivers/test-imus.cpp
@@ -20,7 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <interfaces-impl/hwmapping.h>
 
 #include "configs/SensorManagerConfig.h"
diff --git a/src/tests/drivers/test-mavlink.cpp b/src/tests/drivers/test-mavlink.cpp
index 45f2e47a7..8f5aecab8 100644
--- a/src/tests/drivers/test-mavlink.cpp
+++ b/src/tests/drivers/test-mavlink.cpp
@@ -20,7 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <configs/TMTCConfig.h>
 #include <drivers/Xbee/Xbee.h>
 #include <drivers/gamma868/Gamma868.h>
diff --git a/src/tests/drivers/test-servo.cpp b/src/tests/drivers/test-servo.cpp
index 4fdf14806..7df7efba4 100644
--- a/src/tests/drivers/test-servo.cpp
+++ b/src/tests/drivers/test-servo.cpp
@@ -30,6 +30,7 @@
 #include <string>
 
 using namespace std;
+using namespace Boardcore;
 using namespace DeathStackBoard;
 
 int servoMenu();
@@ -51,7 +52,7 @@ float perlin2d(float x, float y, float freq, int depth);
 
 int servoChoice;
 ServoInterface* servo;
-PWMChannel channel;
+TimerUtils::Channel channel;
 
 constexpr int WIGGLE_STEPS = 5;
 
@@ -77,8 +78,6 @@ static int hashh[] = {
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     servoChoice = servoMenu();
 
     switch (servoChoice)
@@ -266,15 +265,17 @@ void servoBreakIn()
 
     waitUserInput();
 
-    uint64_t start = TimestampTimer::getTimestamp();
+    uint64_t start = TimestampTimer::getInstance().getTimestamp();
 
-    while (TimestampTimer::getTimestamp() - start < minutes * 60 * 1000000)
+    while (TimestampTimer::getInstance().getTimestamp() - start <
+           minutes * 60 * 1000000)
     {
-        uint64_t start2 = TimestampTimer::getTimestamp();
+        uint64_t start2 = TimestampTimer::getInstance().getTimestamp();
         float counter   = 0;
 
         // 10 seconds
-        while (TimestampTimer::getTimestamp() - start2 < 10 * 1000000)
+        while (TimestampTimer::getInstance().getTimestamp() - start2 <
+               10 * 1000000)
         {
             double angolo =
                 servo->MIN_POS + abs(perlin2d(counter, 0, .075, 10)) *
diff --git a/src/tests/eigen-test.cpp b/src/tests/eigen-test.cpp
index 7a3ebb4d0..52cedb086 100644
--- a/src/tests/eigen-test.cpp
+++ b/src/tests/eigen-test.cpp
@@ -20,7 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <miosix.h>
 
 #include <Eigen/Dense>
diff --git a/src/tests/hardware_in_the_loop/test-HIL+ADA+Aerobrake/test-HIL+ADA+Aerobrake.cpp b/src/tests/hardware_in_the_loop/test-HIL+ADA+Aerobrake/test-HIL+ADA+Aerobrake.cpp
index d57fd42a4..132d3426b 100644
--- a/src/tests/hardware_in_the_loop/test-HIL+ADA+Aerobrake/test-HIL+ADA+Aerobrake.cpp
+++ b/src/tests/hardware_in_the_loop/test-HIL+ADA+Aerobrake/test-HIL+ADA+Aerobrake.cpp
@@ -22,7 +22,6 @@
 
 #define EIGEN_RUNTIME_NO_MALLOC  // enable eigen malloc usage assert
 
-#include <Common.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 
@@ -86,8 +85,6 @@ int main()
     // crash if eigen dynamically allocates memory
     Eigen::internal::set_is_malloc_allowed(false);
 
-    TimestampTimer::enableTimestampTimer();
-
     // Definition of the flight phases manager
     HILFlightPhasesManager *flightPhasesManager =
         HILFlightPhasesManager::getInstance();
@@ -184,7 +181,7 @@ int main()
 
     /*-------------- Events --------------*/
 
-    EventCounter counter{*sEventBroker};
+    EventCounter counter{sEventBroker};
     counter.subscribe(TOPIC_FLIGHT_EVENTS);
 
     counter.subscribe(TOPIC_ADA);
@@ -224,7 +221,7 @@ int main()
 
     matlab->start();
     ada_controller->start();
-    sEventBroker->start();
+    sEventBroker.start();
     scheduler.start();  // started only the scheduler instead of the SM
 
     /*---------- Normal execution --------*/
diff --git a/src/tests/hardware_in_the_loop/test-HIL+ADA+AerobrakeController+nas/test-HIL+ADA+AerobrakeController+nas.cpp b/src/tests/hardware_in_the_loop/test-HIL+ADA+AerobrakeController+nas/test-HIL+ADA+AerobrakeController+nas.cpp
index 51bb28c8b..03f914046 100644
--- a/src/tests/hardware_in_the_loop/test-HIL+ADA+AerobrakeController+nas/test-HIL+ADA+AerobrakeController+nas.cpp
+++ b/src/tests/hardware_in_the_loop/test-HIL+ADA+AerobrakeController+nas/test-HIL+ADA+AerobrakeController+nas.cpp
@@ -22,7 +22,6 @@
 
 #define EIGEN_RUNTIME_NO_MALLOC  // enable eigen malloc usage assert
 
-#include <Common.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 #include <events/utils/EventCounter.h>
@@ -80,8 +79,6 @@ int main()
 
     // crash if eigen dynamically allocates memory
     Eigen::internal::set_is_malloc_allowed(false);
-    TimestampTimer::enableTimestampTimer();
-
     // Definition of the flight phases manager
     HILFlightPhasesManager *flightPhasesManager =
         HILFlightPhasesManager::getInstance();
@@ -170,7 +167,7 @@ int main()
 
     /*-------------- Events --------------*/
 
-    EventCounter counter{*sEventBroker};
+    EventCounter counter{sEventBroker};
     counter.subscribe(TOPIC_FLIGHT_EVENTS);
     counter.subscribe(TOPIC_ADA);
     counter.subscribe(TOPIC_NAS);
@@ -214,7 +211,7 @@ int main()
     ada_controller->start();
     nas_controller.start();
     airbrakeController.start();
-    sEventBroker->start();
+    sEventBroker.start();
     scheduler.start();  // started only the scheduler instead of the SM
 
     /*---------- Normal execution --------*/
diff --git a/src/tests/hardware_in_the_loop/test-HIL+ADA/test-HIL+ADA.cpp b/src/tests/hardware_in_the_loop/test-HIL+ADA/test-HIL+ADA.cpp
index 276a1ccd5..26f8a4381 100644
--- a/src/tests/hardware_in_the_loop/test-HIL+ADA/test-HIL+ADA.cpp
+++ b/src/tests/hardware_in_the_loop/test-HIL+ADA/test-HIL+ADA.cpp
@@ -22,16 +22,15 @@
 
 #define EIGEN_RUNTIME_NO_MALLOC  // enable eigen malloc usage assert
 
-#include <Common.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
 
 #include <algorithm>
+#include <catch2/catch.hpp>
 #include <cmath>
 #include <iostream>
 #include <random>
 #include <sstream>
-#include <catch2/catch.hpp>
 
 #include "TimestampTimer.h"
 #include "miosix.h"
@@ -91,8 +90,6 @@ int main()
     // crash if eigen dynamically allocates memory
     Eigen::internal::set_is_malloc_allowed(false);
 
-    TimestampTimer::enableTimestampTimer();
-
     // Definition of the flight phases manager
     HILFlightPhasesManager *flightPhasesManager =
         HILFlightPhasesManager::getInstance();
@@ -208,7 +205,7 @@ int main()
 
     /*-------------- Events --------------*/
 
-    EventCounter counter{*sEventBroker};
+    EventCounter counter{sEventBroker};
     counter.subscribe({TOPIC_FLIGHT_EVENTS});
 
     counter.subscribe({TOPIC_ADA});
@@ -248,7 +245,7 @@ int main()
 
     matlab->start();
     ada_controller->start();
-    sEventBroker->start();
+    sEventBroker.start();
     scheduler.start();  // started only the scheduler instead of the SM
 
     /*---------- Normal execution --------*/
diff --git a/src/tests/hardware_in_the_loop/test-HIL+Aerobrake/test-HIL+Aerobrake.cpp b/src/tests/hardware_in_the_loop/test-HIL+Aerobrake/test-HIL+Aerobrake.cpp
index 8f250978b..cf757034e 100644
--- a/src/tests/hardware_in_the_loop/test-HIL+Aerobrake/test-HIL+Aerobrake.cpp
+++ b/src/tests/hardware_in_the_loop/test-HIL+Aerobrake/test-HIL+Aerobrake.cpp
@@ -20,7 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <events/EventBroker.h>
 
 #include "TimestampTimer.h"
@@ -73,8 +72,6 @@ int main()
 {
     isSimulationRunning = true;
 
-    TimestampTimer::enableTimestampTimer();
-
     // Definition of the flight phases manager
     HILFlightPhasesManager *flightPhasesManager =
         HILFlightPhasesManager::getInstance();
diff --git a/src/tests/hardware_in_the_loop/test-HIL/test-HIL.cpp b/src/tests/hardware_in_the_loop/test-HIL/test-HIL.cpp
index 0658ee791..65825262c 100644
--- a/src/tests/hardware_in_the_loop/test-HIL/test-HIL.cpp
+++ b/src/tests/hardware_in_the_loop/test-HIL/test-HIL.cpp
@@ -20,7 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <events/EventBroker.h>
 
 #include "TimestampTimer.h"
@@ -61,8 +60,6 @@ int main()
 {
     isSimulationRunning = true;
 
-    TimestampTimer::enableTimestampTimer();
-
     // Definition of the flight phases manager
     HILFlightPhasesManager *flightPhasesManager =
         HILFlightPhasesManager::getInstance();
diff --git a/src/tests/hardware_in_the_loop/test-SerialInterface/test-SerialInterface.cpp b/src/tests/hardware_in_the_loop/test-SerialInterface/test-SerialInterface.cpp
index 62cf5a6e3..80f8dace6 100644
--- a/src/tests/hardware_in_the_loop/test-SerialInterface/test-SerialInterface.cpp
+++ b/src/tests/hardware_in_the_loop/test-SerialInterface/test-SerialInterface.cpp
@@ -20,8 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
-
 #include "hardware_in_the_loop/HILConfig.h"
 #include "hardware_in_the_loop/simulator_communication/SerialInterface.h"
 #include "math/Vec3.h"
diff --git a/src/tests/mock_sensors/test-mock-sensors.cpp b/src/tests/mock_sensors/test-mock-sensors.cpp
index d21fa7b4e..2181291ea 100644
--- a/src/tests/mock_sensors/test-mock-sensors.cpp
+++ b/src/tests/mock_sensors/test-mock-sensors.cpp
@@ -20,15 +20,12 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <mocksensors/MockSensors.h>
 
 using namespace DeathStackBoard;
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     MockGPS gps;
     MockPressureSensor p_sensor;
     MockIMU imu;
@@ -55,7 +52,7 @@ int main()
         p_sensor.sample();
         PressureData pressure = p_sensor.getLastSample();
         TRACE("PRESSURE SAMPLE: \n");
-        TRACE("pressure = %f \n\n", pressure.press);
+        TRACE("pressure = %f \n\n", pressure.pressure);
 
         imu.sample();
         MockIMUData imu_data = imu.getLastSample();
diff --git a/src/tests/ram_test/ramtest.cpp b/src/tests/ram_test/ramtest.cpp
index d8e0e9862..312252ed9 100644
--- a/src/tests/ram_test/ramtest.cpp
+++ b/src/tests/ram_test/ramtest.cpp
@@ -1,19 +1,19 @@
- /***************************************************************************
-  *   Copyright (C) 2012 by Terraneo Federico                               *
-  *                                                                         *
-  *   This program is free software; you can redistribute it and/or modify  *
-  *   it under the terms of the GNU General Public License as published by  *
-  *   the Free Software Foundation; either version 2 of the License, or     *
-  *   (at your option) any later version.                                   *
-  *                                                                         *
-  *   This program is distributed in the hope that it will be useful,       *
-  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
-  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
-  *   GNU General Public License for more details.                          *
-  *                                                                         *
-  *   You should have received a copy of the GNU General Public License     *
-  *   along with this program; if not, see <http://www.gnu.org/licenses/>   *
-  ***************************************************************************/
+/***************************************************************************
+ *   Copyright (C) 2012 by Terraneo Federico                               *
+ *                                                                         *
+ *   This program is free software; you can redistribute it and/or modify  *
+ *   it under the terms of the GNU General Public License as published by  *
+ *   the Free Software Foundation; either version 2 of the License, or     *
+ *   (at your option) any later version.                                   *
+ *                                                                         *
+ *   This program is distributed in the hope that it will be useful,       *
+ *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
+ *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
+ *   GNU General Public License for more details.                          *
+ *                                                                         *
+ *   You should have received a copy of the GNU General Public License     *
+ *   along with this program; if not, see <http://www.gnu.org/licenses/>   *
+ ***************************************************************************/
 
 // RAM testing code
 // Useful to test the external RAM of a board.
@@ -22,64 +22,78 @@
 #include <stdlib.h>
 #include <string.h>
 #include <unistd.h>
+
 #include "sha1.h"
 
-const unsigned int ramBase=0xd0000000; //Tune this to the right value
-const unsigned int ramSize=8*1024*1024;     //Tune this to the right value
+const unsigned int ramBase = 0xd0000000;       // Tune this to the right value
+const unsigned int ramSize = 8 * 1024 * 1024;  // Tune this to the right value
 
 bool shaCmp(unsigned int a[5], unsigned int b[5])
 {
-    if(memcmp(a,b,20)==0) return false;
+    if (memcmp(a, b, 20) == 0)
+        return false;
     iprintf("Mismatch\n");
-    for(int i=0;i<5;i++) iprintf("%04x",a[i]); iprintf("\n");
-    for(int i=0;i<5;i++) iprintf("%04x",b[i]); iprintf("\n");
+    for (int i = 0; i < 5; i++)
+        iprintf("%04x", a[i]);
+    iprintf("\n");
+    for (int i = 0; i < 5; i++)
+        iprintf("%04x", b[i]);
+    iprintf("\n");
     return true;
 }
 
-template<typename T> bool ramTest()
+template <typename T>
+bool ramTest()
 {
     SHA1 sha;
     sha.Reset();
-    srand(0x7ad3c099*sizeof(T)); //Just to shuffle initialization between tests
-    for(unsigned int i=ramBase;i<ramBase+ramSize;i+=sizeof(T))
+    srand(0x7ad3c099 *
+          sizeof(T));  // Just to shuffle initialization between tests
+    for (unsigned int i = ramBase; i < ramBase + ramSize; i += sizeof(T))
     {
-        T *p=reinterpret_cast<T*>(i);
-        T v=static_cast<T>(rand());
-        *p=v;
-        sha.Input(reinterpret_cast<const unsigned char*>(&v),sizeof(T));
+        T *p = reinterpret_cast<T *>(i);
+        T v  = static_cast<T>(rand());
+        *p   = v;
+        sha.Input(reinterpret_cast<const unsigned char *>(&v), sizeof(T));
     }
     unsigned int a[5];
     sha.Result(a);
-    sleep(10); //To check SDRAM retention ability
+    sleep(10);  // To check SDRAM retention ability
     sha.Reset();
-    for(unsigned int i=ramBase;i<ramBase+ramSize;i+=sizeof(T))
+    for (unsigned int i = ramBase; i < ramBase + ramSize; i += sizeof(T))
     {
-        T *p=reinterpret_cast<T*>(i);
-        T v=*p;
-        sha.Input(reinterpret_cast<const unsigned char*>(&v),sizeof(T));
+        T *p = reinterpret_cast<T *>(i);
+        T v  = *p;
+        sha.Input(reinterpret_cast<const unsigned char *>(&v), sizeof(T));
     }
     unsigned int b[5];
     sha.Result(b);
-    return shaCmp(a,b);
+    return shaCmp(a, b);
 }
 
 int main()
 {
     printf("\nBEFORE YOU START:\n");
-    printf("1. Have you compiled with the right linker script (e.g. 2m+256k_rom)?\n");
-    printf("2. Have you set RamBase and RamSize correctly in this entrypoint?\n");
+    printf(
+        "1. Have you compiled with the right linker script (e.g. "
+        "2m+256k_rom)?\n");
+    printf(
+        "2. Have you set RamBase and RamSize correctly in this entrypoint?\n");
     printf("3. Have you enable the RAM (aka compile with -D__ENABLE_XRAM)?\n");
     printf("Press enter to start...");
     getchar();
 
-    for(;;)
+    for (;;)
     {
         iprintf("RAM test\nTesting word size transfers\n");
-        if(ramTest<unsigned int>()) return 1;
+        if (ramTest<unsigned int>())
+            return 1;
         iprintf("Testing halfword size transfers\n");
-        if(ramTest<unsigned short>()) return 1;
+        if (ramTest<unsigned short>())
+            return 1;
         iprintf("Testing byte size transfers\n");
-        if(ramTest<unsigned char>()) return 1;
+        if (ramTest<unsigned char>())
+            return 1;
         iprintf("Ok\n");
     }
 }
\ No newline at end of file
diff --git a/src/tests/test-ada-dpl-simulation.cpp b/src/tests/test-ada-dpl-simulation.cpp
index fb0342458..e3763db59 100644
--- a/src/tests/test-ada-dpl-simulation.cpp
+++ b/src/tests/test-ada-dpl-simulation.cpp
@@ -66,7 +66,8 @@ public:
             }
         }
 
-        return PressureData{TimestampTimer::getTimestamp(), press};
+        return PressureData{TimestampTimer::getInstance().getTimestamp(),
+                            press};
     }
 
     void signalLiftoff() { before_liftoff = false; }
@@ -95,8 +96,6 @@ public:
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     MockPressureSensor baro;
     MockGPSSensor gps;
 
@@ -111,8 +110,8 @@ int main()
     DeploymentController dpl_controller;
     PinHandler pin_handler;
 
-    sEventBroker->start();
-    EventCounter counter{*sEventBroker};
+    sEventBroker.start();
+    EventCounter counter{sEventBroker};
     counter.subscribe(TOPIC_ADA);
     counter.subscribe(TOPIC_FLIGHT_EVENTS);
 
@@ -129,7 +128,7 @@ int main()
     Thread::sleep(1000);
 
     // Enter ADA calibration state
-    sEventBroker->post({EV_CALIBRATE_ADA}, TOPIC_ADA);
+    sEventBroker.post({EV_CALIBRATE_ADA}, TOPIC_ADA);
     Thread::sleep(100);
 
     // Send baro calibration samples for ADA
@@ -164,7 +163,7 @@ int main()
 
     TRACE("Sending EV_LIFTOFF ... \n");
     // Send liftoff event
-    sEventBroker->post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
     baro.signalLiftoff();
 
     bool first_apogee_detection       = true;
@@ -185,7 +184,7 @@ int main()
             first_apogee_detection = false;
 
             TRACE("Triggering nosecone ejection ... \n\n");
-            sEventBroker->post({EV_NC_OPEN}, TOPIC_DPL);
+            sEventBroker.post({EV_NC_OPEN}, TOPIC_DPL);
         }
 
         if (ada_controller.getStatus().dpl_altitude_reached &&
@@ -195,7 +194,7 @@ int main()
             first_dpl_altitude_detection = false;
 
             TRACE("Triggering cutting sequence ... \n\n");
-            sEventBroker->post({EV_CUT_DROGUE}, TOPIC_DPL);
+            sEventBroker.post({EV_CUT_DROGUE}, TOPIC_DPL);
         }
     }
 
diff --git a/src/tests/test-fmm-interactive.cpp b/src/tests/test-fmm-interactive.cpp
index 7ed81fb54..19d488fde 100644
--- a/src/tests/test-fmm-interactive.cpp
+++ b/src/tests/test-fmm-interactive.cpp
@@ -36,12 +36,12 @@ void printEvent(uint8_t event, uint8_t topic)
 }
 int main()
 {
-    sEventBroker->start();
+    sEventBroker.start();
     FMMController* fmm = new FMMController();
     fmm->start();
 
     EventSniffer* sniffer =
-        new EventSniffer(*sEventBroker, TOPIC_LIST, printEvent);
+        new EventSniffer(sEventBroker, TOPIC_LIST, printEvent);
     UNUSED(sniffer);  // The sniffer's handler will be called by evBroker
 
     printf("\nOk\n");
@@ -53,11 +53,11 @@ int main()
     {
         printf("Choose an event\n");
         printf("ID:\n");
-        scanf("%hhu", &(ev.sig));
+        scanf("%hhu", &(ev.code));
         printf("TOPIC:\n");
         scanf("%d", &topic);
 
-        sEventBroker->post(ev, topic);
+        sEventBroker.post(ev, topic);
     }
 
     return 0;
diff --git a/src/tests/test-kalman-hitl.cpp b/src/tests/test-kalman-hitl.cpp
index f534a48f4..c9954f919 100644
--- a/src/tests/test-kalman-hitl.cpp
+++ b/src/tests/test-kalman-hitl.cpp
@@ -20,7 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include <Common.h>
 #include <EventClasses.h>
 #include <events/EventBroker.h>
 #include <events/Events.h>
@@ -49,7 +48,7 @@ int main()
     }
 
     // Start event broker and ada
-    sEventBroker->start();
+    sEventBroker.start();
     ada.start();
 
     // Read serial
@@ -99,15 +98,15 @@ void handleCommands(std::string line)
     // }
     else if (command == "EV_TC_RESET_CALIBRATION")
     {
-        sEventBroker->post({EV_TC_RESET_CALIBRATION}, TOPIC_ADA);
+        sEventBroker.post({EV_TC_RESET_CALIBRATION}, TOPIC_ADA);
     }
     else if (command == "EV_LIFTOFF")
     {
-        sEventBroker->post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
+        sEventBroker.post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
     }
     else if (command == "EV_APOGEE")
     {
-        sEventBroker->post({EV_APOGEE}, TOPIC_FLIGHT_EVENTS);
+        sEventBroker.post({EV_APOGEE}, TOPIC_FLIGHT_EVENTS);
     }
     else if (command == "EV_SET_DPL_ALTITUDE")
     {
@@ -115,11 +114,11 @@ void handleCommands(std::string line)
         DeploymentAltitudeEvent ev;
         ev.dplAltitude = alt;
         ev.sig         = EV_TC_SET_DPL_ALTITUDE;
-        sEventBroker->post(ev, TOPIC_TC);
+        sEventBroker.post(ev, TOPIC_TC);
     }
     else if (command == "EV_DPL_ALTITUDE")
     {
-        sEventBroker->post({EV_DPL_ALTITUDE}, TOPIC_FLIGHT_EVENTS);
+        sEventBroker.post({EV_DPL_ALTITUDE}, TOPIC_FLIGHT_EVENTS);
     }
     else
     {
diff --git a/src/tests/test-logproxy.cpp b/src/tests/test-logproxy.cpp
index 754109d69..d19b0d029 100644
--- a/src/tests/test-logproxy.cpp
+++ b/src/tests/test-logproxy.cpp
@@ -19,7 +19,6 @@
  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
  * THE SOFTWARE.
  */
-#include <Common.h>
 #include <LoggerService/LoggerService.h>
 
 using namespace miosix;
diff --git a/src/tests/test-pinhandler.cpp b/src/tests/test-pinhandler.cpp
index 93d116ed1..ee9b069c7 100644
--- a/src/tests/test-pinhandler.cpp
+++ b/src/tests/test-pinhandler.cpp
@@ -20,7 +20,6 @@
  * THE SOFTWARE.
  */
 
-#include "Common.h"
 #include "PinHandler/PinHandler.h"
 
 using namespace Boardcore;
@@ -29,8 +28,6 @@ using namespace DeathStackBoard;
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
     PinHandler pin_handler;
 
     if (!pin_handler.start())
diff --git a/src/tests/test-sensormanager.cpp b/src/tests/test-sensormanager.cpp
index e2e90c5f6..b2f9e2f20 100644
--- a/src/tests/test-sensormanager.cpp
+++ b/src/tests/test-sensormanager.cpp
@@ -21,7 +21,6 @@
  */
 
 #include "ADA/ADAController.h"
-#include "Common.h"
 #include "LoggerService/LoggerService.h"
 #include "Radio/TMTCManager.h"
 #include "SensorManager/SensorManager.h"
@@ -34,9 +33,7 @@ using namespace DeathStackBoard;
 
 int main()
 {
-    TimestampTimer::enableTimestampTimer();
-
-    sEventBroker->start();
+    sEventBroker.start();
 
     Stats s;
     SensorManager mgr;
@@ -58,7 +55,7 @@ int main()
 
     printf("CPU: %f%%, min: %f max: %f\n", s.getStats().mean,
            s.getStats().minValue, s.getStats().maxValue);
-    LoggerService::getInstance()->stop();
+    LoggerService::getInstance().stop();
     printf("End\n");
 
     for (;;)
diff --git a/src/tests/test-sm+tmtc.cpp b/src/tests/test-sm+tmtc.cpp
index 9024a013b..6726bb8fb 100644
--- a/src/tests/test-sm+tmtc.cpp
+++ b/src/tests/test-sm+tmtc.cpp
@@ -27,7 +27,6 @@
 #include <interfaces-impl/hwmapping.h>
 
 #include "ADA/ADAController.h"
-#include "Common.h"
 #include "LoggerService/LoggerService.h"
 #include "SensorManager/SensorManager.h"
 #include "diagnostic/CpuMeter.h"
@@ -50,7 +49,7 @@ int main()
     // ada.start();
     // try
     // {
-    //     LoggerService::getInstance()->start();
+    //     LoggerService::getInstance().start();
     // }
     // catch (const std::exception& e)
     // {
@@ -65,10 +64,10 @@ int main()
     // }
     // led1::high();
 
-    sEventBroker->start();
+    sEventBroker.start();
     mgr.start();
 
-    sEventBroker->post({EV_TC_START_SENSOR_LOGGING}, TOPIC_TC);
+    sEventBroker.post({EV_TC_START_SENSOR_LOGGING}, TOPIC_TC);
 
     printf("Wait for calibration to complete.\n");
 
@@ -80,7 +79,7 @@ int main()
 
     TMTCManager* tmtc = new TMTCManager();
     tmtc->start();
-    sEventBroker->start();
+    sEventBroker.start();
 
     Thread::sleep(1000);
 
@@ -94,7 +93,7 @@ int main()
 
     Thread::sleep(100);
 
-    sEventBroker->post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
 
     for (;;)
     {
diff --git a/src/tests/test-tmtc.cpp b/src/tests/test-tmtc.cpp
index b7eedc555..e46f383e4 100644
--- a/src/tests/test-tmtc.cpp
+++ b/src/tests/test-tmtc.cpp
@@ -41,10 +41,10 @@ int main()
 
     TMTCController* tmtc = new TMTCController();
     tmtc->start();
-    sEventBroker->start();
+    sEventBroker.start();
 
     EventSniffer* sniffer =
-        new EventSniffer(*sEventBroker, TOPIC_LIST, onEventReceived);
+        new EventSniffer(sEventBroker, TOPIC_LIST, onEventReceived);
 
     Thread::sleep(1000);
 
@@ -54,7 +54,7 @@ int main()
 
     Thread::sleep(100);
 
-    sEventBroker->post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
+    sEventBroker.post({EV_LIFTOFF}, TOPIC_FLIGHT_EVENTS);
 
     printf("Press close to reboot...\n");
     while (inputs::btn_close::value())
-- 
GitLab