diff --git a/.gitmodules b/.gitmodules
index 2feb5db9c4e6092157ecf5e5952238de43495a42..4b247f8f18e5f99c046589be7cdaee61758bd7a5 100644
--- a/.gitmodules
+++ b/.gitmodules
@@ -1,4 +1,3 @@
 [submodule "skyward-boardcore"]
 	path = skyward-boardcore
-	url = ../skyward-boardcore.git
-	branch = testing
+	url = ../skyward-boardcore
diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json
index eccea156a6e4cf52a47b20238d1ed5d4e4c14944..512ea6a7a9f53b53be3d93c1168d5582d2433a66 100755
--- a/.vscode/c_cpp_properties.json
+++ b/.vscode/c_cpp_properties.json
@@ -24,6 +24,8 @@
                 "${workspaceFolder}/skyward-boardcore/libs/mavlink_skyward_lib",
                 "${workspaceFolder}/skyward-boardcore/libs/fmt/include",
                 "${workspaceFolder}/skyward-boardcore/libs/eigen",
+                "${workspaceFolder}/skyward-boardcore/libs/tscpp",
+                "${workspaceFolder}/skyward-boardcore/libs/mavlink_skyward_lib",
                 "${workspaceFolder}/skyward-boardcore/libs",
                 "${workspaceFolder}/skyward-boardcore/src/shared",
                 "${workspaceFolder}/skyward-boardcore/src/tests",
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 2c14beeea49abadc2b0f0cbe0775e8211deb642e..264915607deeceab7578db5e76bd1c557b0a75c6 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -26,7 +26,7 @@ include(skyward-boardcore/cmake/sbs.cmake)
 #                                   Project                                   #
 #-----------------------------------------------------------------------------#
 
-project(SkywardOnBoardSoftware)
+project(SkywardParafoilTest)
 
 #-----------------------------------------------------------------------------#
 #                                Main Computer                                #
@@ -41,3 +41,20 @@ target_include_directories(catch-tests-main PRIVATE ${OBSW_INCLUDE_DIRS})
 target_compile_definitions(catch-tests-main PRIVATE USE_MOCK_PERIPHERALS)
 sbs_target(catch-tests-main stm32f429zi_skyward_death_stack_x)
 sbs_catch_test(catch-tests-main)
+
+#-----------------------------------------------------------------------------#
+#                              Parafoil Computer                              #
+#-----------------------------------------------------------------------------#
+
+add_executable(parafoil-entry
+	src/entrypoints/Parafoil/parafoil-entry.cpp
+	${PARAFOIL_COMPUTER}
+)
+target_include_directories(parafoil-entry PRIVATE ${OBSW_INCLUDE_DIRS})
+sbs_target(parafoil-entry stm32f429zi_stm32f4discovery)
+
+add_executable(parafoil-test-bme280 src/tests/Parafoil/parafoil-test-bme280.cpp)
+sbs_target(parafoil-test-bme280 stm32f429zi_stm32f4discovery)
+
+add_executable(parafoil-test-ublox-uart src/tests/Parafoil/parafoil-test-ublox-uart.cpp)
+sbs_target(parafoil-test-ublox-uart stm32f429zi_stm32f4discovery)
diff --git a/README.md b/README.md
index b6ceca0eeae5eb437857181f337d3ef71e827b78..24ee354611215ab1c013c46679c0a00d87059d45 100644
--- a/README.md
+++ b/README.md
@@ -1,6 +1,6 @@
-# Pyxis On-Board Software [![pipeline status](https://git.skywarder.eu/scs/pyxis/obsw/badges/master/pipeline.svg)](https://git.skywarder.eu/scs/pyxis/obsw/commits/master)
+# Parafoil test On-Board Software [![pipeline status](https://git.skywarder.eu/scs/pyxis/obsw/badges/master/pipeline.svg)](https://git.skywarder.eu/scs/pyxis/obsw/commits/master)
 
-*On Board software for Pyxis*
+*On Board software for Parafoil tests*
 
 To clone, use `git clone --recurse-submodules git@git.skywarder.eu:scs/pyxis/obsw.git`.
 
diff --git a/cmake/dependencies.cmake b/cmake/dependencies.cmake
index ee5705d965d19aa3eac56cc1d8eaef029fdff9ca..ece8b80ec8667ee683bdc97aa84e311f3e825773 100644
--- a/cmake/dependencies.cmake
+++ b/cmake/dependencies.cmake
@@ -28,3 +28,13 @@ set(MAIN_COMPUTER
     src/boards/Main/Actuators/Actuators.cpp
     src/boards/Main/Deployment/DeploymentController.cpp
 )
+
+set(PARAFOIL_COMPUTER
+    src/boards/Parafoil/Main/Sensors.cpp
+    src/boards/Parafoil/Main/Radio.cpp
+    src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp
+    src/boards/Parafoil/Wing/WingServo.cpp
+    src/boards/Parafoil/Wing/WingAlgorithm.cpp
+    src/boards/Parafoil/Wing/WingController.cpp
+    src/boards/Parafoil/FlightModeManager/FMMController.cpp
+)
\ No newline at end of file
diff --git a/data/ParafoilTestDev/UMLMavlink.dia b/data/ParafoilTestDev/UMLMavlink.dia
new file mode 100644
index 0000000000000000000000000000000000000000..91d826341f788f0f8060e481f3e3f2fc5232f174
Binary files /dev/null and b/data/ParafoilTestDev/UMLMavlink.dia differ
diff --git a/data/ParafoilTestDev/UMLWingControlDiagram.dia b/data/ParafoilTestDev/UMLWingControlDiagram.dia
new file mode 100644
index 0000000000000000000000000000000000000000..b0e6eef0408c9501493cff203294678c28eba077
Binary files /dev/null and b/data/ParafoilTestDev/UMLWingControlDiagram.dia differ
diff --git a/data/ParafoilTestDev/UMLWingControlDiagram.png b/data/ParafoilTestDev/UMLWingControlDiagram.png
new file mode 100644
index 0000000000000000000000000000000000000000..8b359ce213df23faa91d2edf019a88d27d35ad02
Binary files /dev/null and b/data/ParafoilTestDev/UMLWingControlDiagram.png differ
diff --git a/skyward-boardcore b/skyward-boardcore
index c6824c3b2e8e51fc17c3ed5ce5cc1bbbfcd8d860..024dd05e052b036bdab58ef7ec93c58b1bf8a858 160000
--- a/skyward-boardcore
+++ b/skyward-boardcore
@@ -1 +1 @@
-Subproject commit c6824c3b2e8e51fc17c3ed5ce5cc1bbbfcd8d860
+Subproject commit 024dd05e052b036bdab58ef7ec93c58b1bf8a858
diff --git a/src Lynx/boards/DeathStack/ApogeeDetectionAlgorithm/ADAData.h b/src Lynx/boards/DeathStack/ApogeeDetectionAlgorithm/ADAData.h
index 8da1446e981442ee8fd5f0b27302cb107a5c33d5..f4cde44500c894fe9f9eba759f5d505df27bfa48 100644
--- a/src Lynx/boards/DeathStack/ApogeeDetectionAlgorithm/ADAData.h	
+++ b/src Lynx/boards/DeathStack/ApogeeDetectionAlgorithm/ADAData.h	
@@ -29,6 +29,8 @@
 
 #include <ostream>
 
+#include <ostream>
+
 namespace DeathStackBoard
 {
 
diff --git a/src Lynx/boards/DeathStack/Main/Radio.cpp b/src Lynx/boards/DeathStack/Main/Radio.cpp
index d33ab6c3e615933ef42441c96ed52584b9ef4315..ef4aa4e3ab22fb38996ec1ec196c4c7828397ec5 100644
--- a/src Lynx/boards/DeathStack/Main/Radio.cpp	
+++ b/src Lynx/boards/DeathStack/Main/Radio.cpp	
@@ -38,7 +38,7 @@ using namespace std::placeholders;
 using namespace Boardcore;
 
 // Xbee ATTN interrupt
-void __attribute__((used)) EXTI10_IRQHandlerImpl()
+void __attribute__((used)) EXTI4_15_IRQHandlerImpl()
 {
     using namespace DeathStackBoard;
 
diff --git a/src Lynx/boards/DeathStack/configs/NASConfig.h b/src Lynx/boards/DeathStack/configs/NASConfig.h
index 1421402f5f6b5ad53be4e43487be29d161feee93..658fa7b25bd2e523d37b3de0bf78d06db292e62d 100644
--- a/src Lynx/boards/DeathStack/configs/NASConfig.h	
+++ b/src Lynx/boards/DeathStack/configs/NASConfig.h	
@@ -26,6 +26,8 @@
 
 #include "Eigen/Dense"
 
+#include "Eigen/Dense"
+
 namespace DeathStackBoard
 {
 
diff --git a/src Lynx/boards/DeathStack/common/Algorithm.h b/src Lynx/boards/common/Algorithm.h
similarity index 100%
rename from src Lynx/boards/DeathStack/common/Algorithm.h
rename to src Lynx/boards/common/Algorithm.h
diff --git a/src Lynx/boards/DeathStack/common/CanInterfaces.h b/src Lynx/boards/common/CanInterfaces.h
similarity index 100%
rename from src Lynx/boards/DeathStack/common/CanInterfaces.h
rename to src Lynx/boards/common/CanInterfaces.h
diff --git a/src Lynx/boards/DeathStack/common/ServoInterface.h b/src Lynx/boards/common/ServoInterface.h
similarity index 100%
rename from src Lynx/boards/DeathStack/common/ServoInterface.h
rename to src Lynx/boards/common/ServoInterface.h
diff --git a/src Lynx/boards/DeathStack/common/SystemData.h b/src Lynx/boards/common/SystemData.h
similarity index 100%
rename from src Lynx/boards/DeathStack/common/SystemData.h
rename to src Lynx/boards/common/SystemData.h
diff --git a/src Lynx/boards/DeathStack/common/events/EventStrings.cpp b/src Lynx/boards/common/events/EventStrings.cpp
similarity index 100%
rename from src Lynx/boards/DeathStack/common/events/EventStrings.cpp
rename to src Lynx/boards/common/events/EventStrings.cpp
diff --git a/src Lynx/boards/DeathStack/common/events/Events.h b/src Lynx/boards/common/events/Events.h
similarity index 98%
rename from src Lynx/boards/DeathStack/common/events/Events.h
rename to src Lynx/boards/common/events/Events.h
index 6a1b48996f54941cd274e533e5add533f0602736..2d993e6dc1563af7b81ac7a8ae4e2e90608839c0 100644
--- a/src Lynx/boards/DeathStack/common/events/Events.h	
+++ b/src Lynx/boards/common/events/Events.h	
@@ -99,6 +99,7 @@ enum Events : uint8_t
     EV_TC_STOP_SENSOR_TM,
     EV_TC_TEST_ABK,
     EV_TC_TEST_MODE,
+    EV_TC_EXIT_TEST_MODE,
     EV_TEST_ABK,
     EV_TEST_TIMEOUT,
     EV_TIMEOUT_END_MISSION,
@@ -164,6 +165,7 @@ const std::vector<uint8_t> EVENT_LIST{
     EV_TC_STOP_SENSOR_TM,
     EV_TC_TEST_ABK,
     EV_TC_TEST_MODE,
+    EV_TC_EXIT_TEST_MODE,
     EV_TEST_ABK,
     EV_TEST_TIMEOUT,
     EV_TIMEOUT_END_MISSION,
diff --git a/src Lynx/boards/DeathStack/common/events/Topics.h b/src Lynx/boards/common/events/Topics.h
similarity index 100%
rename from src Lynx/boards/DeathStack/common/events/Topics.h
rename to src Lynx/boards/common/events/Topics.h
diff --git a/src Lynx/entrypoints/deserializer/logdecoder.cpp b/src Lynx/entrypoints/deserializer/logdecoder.cpp
index 5ce4f3554848fb097f9e2d5d468356c3a5f00b2f..84badf247a5c047bec0c1dff98117039d22ae1a6 100644
--- a/src Lynx/entrypoints/deserializer/logdecoder.cpp	
+++ b/src Lynx/entrypoints/deserializer/logdecoder.cpp	
@@ -34,10 +34,6 @@
 #include <stdexcept>
 #include <string>
 
-// TODO: add here include files of serialized classes
-
-#include "LogTypes.h"
-
 using namespace std;
 using namespace tscpp;
 
diff --git a/src Lynx/hardware_in_the_loop/HIL_sensors/HILSensorsData.h b/src Lynx/hardware_in_the_loop/HIL_sensors/HILSensorsData.h
index 9e0655c79c35c40927b41ee004d2c84aa0ece0a9..27036157c56b9bebd750dd8c8d6bc1b854a90d41 100644
--- a/src Lynx/hardware_in_the_loop/HIL_sensors/HILSensorsData.h	
+++ b/src Lynx/hardware_in_the_loop/HIL_sensors/HILSensorsData.h	
@@ -35,8 +35,8 @@ struct HILAccelData : public AccelerometerData
 
     void print(std::ostream& os) const
     {
-        os << accel_timestamp << "," << accel_x << "," << accel_y << ","
-           << accel_z << "\n";
+        os << accelerationTimestamp << "," << accelerationX << ","
+           << accelerationY << "," << accelerationZ << "\n";
     }
 };
 
@@ -53,8 +53,8 @@ struct HILGyroscopeData : public GyroscopeData
 
     void print(std::ostream& os) const
     {
-        os << gyro_timestamp << "," << gyro_x << "," << gyro_y << "," << gyro_z
-           << "\n";
+        os << angularVelocityTimestamp << "," << angularVelocityX << ","
+           << angularVelocityY << "," << angularVelocityZ << "\n";
     }
 };
 
@@ -71,8 +71,8 @@ struct HILMagnetometerData : public MagnetometerData
 
     void print(std::ostream& os) const
     {
-        os << mag_timestamp << "," << mag_x << "," << mag_y << "," << mag_z
-           << "\n";
+        os << magneticFieldTimestamp << "," << magneticFieldX << ","
+           << magneticFieldY << "," << magneticFieldZ << "\n";
     }
 };
 
@@ -88,10 +88,12 @@ struct HILImuData : public HILAccelData,
 
     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";
     }
 };
 
@@ -114,10 +116,10 @@ struct HILGpsData : public GPSData
 
     void print(std::ostream& os) const
     {
-        os << gps_timestamp << "," << longitude << "," << latitude << ","
-           << height << "," << velocity_north << "," << velocity_east << ","
-           << velocity_down << "," << speed << "," << track << ","
-           << (int)num_satellites << "," << (int)fix << "\n";
+        os << gpsTimestamp << "," << longitude << "," << latitude << ","
+           << height << "," << velocityNorth << "," << velocityEast << ","
+           << velocityDown << "," << speed << "," << track << ","
+           << (int)satellites << "," << (int)fix << "\n";
     }
 };
 
@@ -131,6 +133,6 @@ struct HILBaroData : public PressureData
 
     void print(std::ostream& os) const
     {
-        os << press_timestamp << "," << press << "\n";
+        os << pressureTimestamp << "," << pressure << "\n";
     }
 };
diff --git a/src/boards/Payload/Main/Radio.h b/src/boards/Parafoil/Configs/MavlinkConfig.h
similarity index 67%
rename from src/boards/Payload/Main/Radio.h
rename to src/boards/Parafoil/Configs/MavlinkConfig.h
index ae67a56c66e4802cee4947d27e5ba89237592502..e502577174def3bdf58537a3f30fea993c1ef2d9 100644
--- a/src/boards/Payload/Main/Radio.h
+++ b/src/boards/Parafoil/Configs/MavlinkConfig.h
@@ -1,5 +1,5 @@
 /* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Erbetta
+ * Authors: Luca Conterio
  *
  * Permission is hereby granted, free of charge, to any person obtaining a copy
  * of this software and associated documentation files (the "Software"), to deal
@@ -19,34 +19,20 @@
  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
  * THE SOFTWARE.
  */
-
 #pragma once
 
-//#include <TelemetriesTelecommands/Mavlink.h>
-#include <drivers/Xbee/Xbee.h>
-
-namespace PayloadBoard
-{
-
-class Radio
+namespace ParafoilTestDev
 {
-public:
-    // TMTCController* tmtc_manager;
-    // TmRepository* tm_repo;
-    Boardcore::Xbee::Xbee* xbee;
-    // MavDriver* mav_driver;
-
-    Radio(Boardcore::SPIBusInterface& xbee_bus_);
-    ~Radio();
-
-    bool start();
-
-    void logStatus();
 
-private:
-    void onXbeeFrameReceived(Boardcore::Xbee::APIFrame& frame);
+    /* Mavlink Driver queue settings */
+    static constexpr unsigned int MAV_OUT_QUEUE_LEN   = 10;
+    static constexpr unsigned int MAV_PKT_SIZE        = 255;
+    static constexpr size_t MAV_OUT_BUFFER_MAX_AGE    = 200;
 
-    Boardcore::SPIBusInterface& xbee_bus;
-};
+    //These two values are taken as is 
+    static const unsigned int TMTC_MAV_SYSID  = 171;
+    static const unsigned int TMTC_MAV_COMPID = 96;
 
-}  // namespace PayloadBoard
+    /* Min guaranteed sleep time after each packet sent (milliseconds) */
+    static const uint16_t SLEEP_AFTER_SEND = 0;
+}
diff --git a/src/boards/Parafoil/Configs/RadioConfig.h b/src/boards/Parafoil/Configs/RadioConfig.h
new file mode 100644
index 0000000000000000000000000000000000000000..ca9beaf91a5f632216fb3fe8a8948071968a6a62
--- /dev/null
+++ b/src/boards/Parafoil/Configs/RadioConfig.h
@@ -0,0 +1,39 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <stdint.h>
+
+namespace ParafoilTestDev
+{
+
+// TODO update with the correct values
+static const uint32_t HR_GROUND_UPDATE_PERIOD = 62;  // Milliseconds
+static const uint32_t HR_FLIGHT_UPDATE_PERIOD = 10;
+static const uint32_t LR_UPDATE_PERIOD        = 100;  // Milliseconds
+
+// TODO define the correct ids for task scheduler
+static const uint8_t RADIO_HR_ID = 200;
+static const uint8_t RADIO_LR_ID = 201;
+
+}  // namespace ParafoilTestDev
\ No newline at end of file
diff --git a/src/boards/Parafoil/Configs/SensorsConfig.h b/src/boards/Parafoil/Configs/SensorsConfig.h
new file mode 100644
index 0000000000000000000000000000000000000000..ce12d431d18dd930dde72264259d13d2a157be43
--- /dev/null
+++ b/src/boards/Parafoil/Configs/SensorsConfig.h
@@ -0,0 +1,64 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+/**
+ * This class specifies the sensors constants that the sensor manager
+ * needs to know about every device. For example the sample time is
+ * essential to understand how much time a sensor should wait before
+ * another sample.
+ */
+
+#pragma once
+
+#include <sensors/UbloxGPS/UbloxGPS.h>
+#include <sensors/MPU9250/MPU9250.h>
+#include <sensors/BME280/BME280.h>
+
+using namespace Boardcore;
+
+namespace ParafoilTestDev
+{
+    //SPI pinouts
+    static miosix::GpioPin SCK(GPIOA_BASE, 5);
+	static miosix::GpioPin MISO(GPIOB_BASE, 4);
+	static miosix::GpioPin MOSI(GPIOA_BASE, 7);
+
+    //GPS settings
+    //static miosix::GpioPin GPS_CS(GPIOG_BASE, 3);
+    static miosix::GpioPin GPS_TX(GPIOA_BASE, 2);
+    static miosix::GpioPin GPS_RX(GPIOA_BASE, 3);
+    static constexpr unsigned int GPS_SAMPLE_RATE       = 25;
+    static constexpr unsigned int GPS_SAMPLE_PERIOD     = 1000 / GPS_SAMPLE_RATE;
+    
+
+    //IMU MPU9250 settings
+    static miosix::GpioPin IMU_CS(GPIOB_BASE, 2);
+    static const MPU9250::MPU9250GyroFSR IMU_GYRO_SCALE       = MPU9250::GYRO_FSR_500DPS;
+    static const MPU9250::MPU9250AccelFSR IMU_ACCEL_SCALE     = MPU9250::ACCEL_FSR_16G;
+    static constexpr unsigned short IMU_SAMPLE_RATE     = 500;
+    static constexpr unsigned int   IMU_SAMPLE_PERIOD   = 1000 / IMU_SAMPLE_RATE;
+
+    //Barometer BME280 settings
+    static miosix::GpioPin PRESS_CS(GPIOC_BASE, 11);   
+    static const BME280::StandbyTime PRESS_SAMPLE_RATE        = BME280::STB_TIME_0_5;
+    static constexpr unsigned int PRESS_SAMPLE_PERIOD   = 20; 
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Configs/XbeeConfig.h b/src/boards/Parafoil/Configs/XbeeConfig.h
new file mode 100644
index 0000000000000000000000000000000000000000..a5bb0275441c98c0432d0b393a2e502ac356437d
--- /dev/null
+++ b/src/boards/Parafoil/Configs/XbeeConfig.h
@@ -0,0 +1,42 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#pragma once
+
+#include <radio/Xbee/Xbee.h>
+
+using namespace Boardcore;
+
+namespace ParafoilTestDev
+{
+    //TODO change the pins to something correct
+    static miosix::GpioPin XBEE_CS(GPIOC_BASE, 1);
+    static miosix::GpioPin XBEE_ATTN(GPIOF_BASE, 10); //Interrupt pin (THE SAME AS THE RADIO.CPP)
+    static miosix::GpioPin XBEE_RESET(GPIOC_BASE, 5);
+
+    static miosix::GpioPin XBEE_SCK(GPIOE_BASE, 2);
+	static miosix::GpioPin XBEE_MISO(GPIOE_BASE, 5);
+	static miosix::GpioPin XBEE_MOSI(GPIOE_BASE, 6);
+
+    //Data rate
+    static const bool XBEE_80KBPS_DATA_RATE = true;
+    static const int XBEE_TIMEOUT           = 5000; //5 seconds
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/FlightModeManager/FMM.scxml b/src/boards/Parafoil/FlightModeManager/FMM.scxml
new file mode 100644
index 0000000000000000000000000000000000000000..0b59b8518e37d96999c2566e824e6696398ee509
--- /dev/null
+++ b/src/boards/Parafoil/FlightModeManager/FMM.scxml
@@ -0,0 +1,10 @@
+<scxml version="1.0" xmlns="http://www.w3.org/2005/07/scxml" initial="OnGround">
+    <state id="OnGround">
+        <transition event="FMM.EV_LIFTOFF" target="FlyingState"></transition>
+        <transition event="FMM.EV_TC_TEST_MODE" target="DebugState"></transition>
+    </state>
+    <state id="Flying"></state>
+    <state id="Debug">
+        <transition event="FMM.EV_TC_EXIT_TEST_MODE" target="OnGround"></transition>
+    </state>
+</scxml>
\ No newline at end of file
diff --git a/src/boards/Parafoil/FlightModeManager/FMMController.cpp b/src/boards/Parafoil/FlightModeManager/FMMController.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b40951fdbcf5d7f563d662d6693aa2b6e2b25b79
--- /dev/null
+++ b/src/boards/Parafoil/FlightModeManager/FMMController.cpp
@@ -0,0 +1,157 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Authors: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "FMMController.h"
+
+#include <miosix.h>
+
+#include <events/EventBroker.h>
+#include <common/events/Events.h>
+
+namespace ParafoilTestDev
+{
+    FMMController::FMMController() : FSM(&FMMController::state_on_ground)
+    {
+        memset(&status, 0, sizeof(FMMControllerStatus));
+        sEventBroker.subscribe(this, TOPIC_FMM);
+        sEventBroker.subscribe(this, TOPIC_TMTC);
+    }
+
+    FMMController::~FMMController()
+    {
+        sEventBroker.unsubscribe(this);
+    }
+
+    void FMMController::state_on_ground(const Event& ev)
+    {
+        switch (ev.code)
+        {
+            case EV_ENTRY:
+            {
+                // ...
+
+                logStatus(ON_GROUND);
+
+                LOG_DEBUG(logger, "[FMM] entering state on_ground\n");
+                break;
+            }
+            case EV_EXIT:
+            {
+                // ...
+
+                LOG_DEBUG(logger, "[FMM] exiting state on_ground\n");
+                break;
+            }
+            case EV_LIFTOFF:
+            {
+                transition(&FMMController::state_flying);
+                break;
+            }
+            case EV_TC_TEST_MODE:
+            {
+                transition(&FMMController::state_debug);
+                break;
+            }
+            default:
+            {
+                break;
+            }
+        }
+    }
+
+
+    void FMMController::state_flying(const Event& ev)
+    {
+        switch (ev.code)
+        {
+            case EV_ENTRY:
+            {
+                // ...
+
+                logStatus(FLYING_STATE);
+
+                LOG_DEBUG(logger, "[FMM] entering state flying\n");
+                break;
+            }
+            case EV_EXIT:
+            {
+                // ...
+
+                LOG_DEBUG(logger, "[FMM] exiting state flying\n");
+                break;
+            }
+
+            default:
+            {
+                break;
+            }
+        }
+    }
+
+
+    void FMMController::state_debug(const Event& ev)
+    {
+        switch (ev.code)
+        {
+            case EV_ENTRY:
+            {
+                // ...
+
+                logStatus(DEBUG_STATE);
+
+                LOG_DEBUG(logger, "[FMM] entering state debug\n");
+                break;
+            }
+            case EV_EXIT:
+            {
+                // ...
+
+                LOG_DEBUG(logger, "[FMM] exiting state debug\n");
+                break;
+            }
+            case EV_TC_EXIT_TEST_MODE:
+            {
+                transition(&FMMController::state_on_ground);
+                break;
+            }
+            default:
+            {
+                break;
+            }
+        }
+    }
+
+    /* --- LOGGER --- */
+
+    void FMMController::logStatus(FMMControllerState state)
+    {
+        status.state = state;
+        logStatus();
+    }
+
+    void FMMController::logStatus()
+    {
+        status.timestamp = miosix::getTick();
+        SDlogger -> log(status);
+    }
+
+}  // namespace ParafoilTestDev
diff --git a/src/boards/Parafoil/FlightModeManager/FMMController.h b/src/boards/Parafoil/FlightModeManager/FMMController.h
new file mode 100644
index 0000000000000000000000000000000000000000..f185f945251284cdb491b78ef9220d77d64ade34
--- /dev/null
+++ b/src/boards/Parafoil/FlightModeManager/FMMController.h
@@ -0,0 +1,56 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Authors: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include "FMMData.h"
+#include <events/FSM.h>
+#include <diagnostic/PrintLogger.h>
+
+using namespace Boardcore;
+
+namespace ParafoilTestDev
+{
+    /**
+     * @brief FMM state machine
+     */
+    class FMMController : public FSM<FMMController>
+    {
+    public:
+        FMMController();
+        ~FMMController();
+
+        void state_on_ground(const Event& ev);
+        void state_flying(const Event& ev);
+        void state_debug(const Event& ev);
+
+    private:
+        FMMControllerStatus status;
+        PrintLogger logger = Logging::getLogger("FMM");
+        Logger* SDlogger = &Logger::getInstance();
+
+        /* --- LOGGER --- */
+
+        void logStatus(FMMControllerState state);
+        void logStatus();
+    };
+}  // namespace ParafoilTestDev
diff --git a/src/boards/Payload/configs/WingConfig.h b/src/boards/Parafoil/FlightModeManager/FMMData.h
similarity index 57%
rename from src/boards/Payload/configs/WingConfig.h
rename to src/boards/Parafoil/FlightModeManager/FMMData.h
index 18e2f1361573f29fa2b4cba0af4fd5fc5a50a1b8..a57776517897806ccd734d693a9a8472e9e1b4f5 100644
--- a/src/boards/Payload/configs/WingConfig.h
+++ b/src/boards/Parafoil/FlightModeManager/FMMData.h
@@ -1,5 +1,5 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Conterio
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Authors: Matteo Pignataro
  *
  * Permission is hereby granted, free of charge, to any person obtaining a copy
  * of this software and associated documentation files (the "Software"), to deal
@@ -22,30 +22,41 @@
 
 #pragma once
 
-#include <drivers/timer/PWM.h>
-#include <drivers/timer/TimestampTimer.h>
-#include <utils/Constants.h>
+#include <stdint.h>
 
-namespace PayloadBoard
-{
+#include <iostream>
+#include <string>
 
-namespace WingConfigs
+namespace ParafoilTestDev
 {
 
-static TIM_TypeDef* const WING_SERVO_1_TIMER = TIM8;
-static constexpr Boardcore::TimerUtils::Channel WING_SERVO_1_PWM_CH =
-    Boardcore::TimerUtils::Channel::CHANNEL_2;
-
-static const TIM_TypeDef* WING_SERVO_2_TIMER = TIM4;
-static constexpr Boardcore::TimerUtils::Channel WING_SERVO_2_PWM_CH =
-    Boardcore::TimerUtils::Channel::CHANNEL_1;
+/**
+ * Enum defining the possibile FSM states.
+ */
+enum FMMControllerState : uint8_t
+{
+    ON_GROUND = 0,
+    FLYING_STATE,
+    DEBUG_STATE,
+};
 
-// Wing servo configs
-static constexpr float WING_SERVO_MAX_POS = 180.0;  // deg
-static constexpr float WING_SERVO_MIN_POS = 0.0;    // deg
+/**
+ * Structure defining the overall controller status.
+ */
+struct FMMControllerStatus
+{
+    long long timestamp;
+    FMMControllerState state;
 
-static constexpr float WING_SERVO_WIGGLE_AMPLITUDE = 20.0;  // deg
+    static std::string header()
+    {
+        return "timestamp,state\n";
+    }
 
-}  // namespace WingConfigs
+    void print(std::ostream& os) const
+    {
+        os << timestamp << "," << (int)state << "\n";
+    }
+};
 
-}  // namespace PayloadBoard
+}  // namespace ParafoilTestDev
diff --git a/src/boards/Parafoil/Main/Radio.cpp b/src/boards/Parafoil/Main/Radio.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..dcee160220bb15a941cb617a306d64e6fdaf9b7e
--- /dev/null
+++ b/src/boards/Parafoil/Main/Radio.cpp
@@ -0,0 +1,294 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include <Parafoil/Configs/RadioConfig.h>
+#include <Parafoil/Configs/XbeeConfig.h>
+#include <Parafoil/Main/Radio.h>
+#include <Parafoil/ParafoilTest.h>
+#include <Parafoil/TelemetriesTelecommands/TMRepository.h>
+#include <common/events/Topics.h>
+#include <drivers/interrupt/external_interrupts.h>
+#include <drivers/spi/SPIDriver.h>
+#include <radio/Xbee/ATCommands.h>
+
+using std::bind;
+using namespace std::placeholders;
+using namespace Boardcore;
+
+// Xbee ATTN interrupt
+/**
+ * @brief We must define the interrupt handler. This calls
+ * the message handler which is: handleMavlinkMessage
+ */
+void __attribute__((used)) EXTI10_IRQHandlerImpl()
+{
+    using namespace ParafoilTestDev;
+
+    /*if (ParafoilTest::getInstance().radio->xbee != nullptr)
+    {
+        ParafoilTest::getInstance().radio->xbee->handleATTNInterrupt();
+    }*/
+    if (ParafoilTest::getInstance().radio->module != nullptr)
+    {
+        ParafoilTest::getInstance().radio->module->handleDioIRQ();
+    }
+}
+
+namespace ParafoilTestDev
+{
+/**
+ * PUBLIC METHODS
+ */
+Radio::Radio(SPIBusInterface& xbee_bus, TaskScheduler* scheduler)
+    : xbee_bus(xbee_bus)
+{
+    // Create a SPI configuration object
+    SPIBusConfig config{};
+
+    // Set the internal scheduler
+    this->scheduler = scheduler;
+
+    // Set the internal telemetry status to low rate
+    this->HRtelemetry = false;
+
+    // Add a clock divider config
+    config.clockDivider = SPI::ClockDivider::DIV_16;
+
+    // Instantiate the xbee object
+    /*xbee = new Xbee::Xbee(xbee_bus, config,
+                          XBEE_CS,
+                          XBEE_ATTN,
+                          XBEE_RESET);*/
+    module = new SX1278(xbee_bus, XBEE_CS);
+
+    // Create the mavlink driver
+    mav_driver =
+        new MavDriver(module, bind(&Radio::handleMavlinkMessage, this, _1, _2),
+                      SLEEP_AFTER_SEND, MAV_OUT_BUFFER_MAX_AGE);
+    init();
+}
+
+Radio::~Radio()
+{
+    // TODO destruct
+}
+
+void Radio::handleMavlinkMessage(MavDriver* driver,
+                                 const mavlink_message_t& msg)
+{
+    // log status
+    ParafoilTest::getInstance().radio->logStatus();
+
+    LOG_DEBUG(logger, "Message received!");
+
+    // acknowledge
+    sendAck(msg);
+
+    // handle TC
+    switch (msg.msgid)
+    {
+        case MAVLINK_MSG_ID_NOARG_TC:  // basic command
+        {
+            LOG_DEBUG(logger, "Received NOARG command");
+            uint8_t commandId = mavlink_msg_noarg_tc_get_command_id(&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);
+            else
+                LOG_WARN(logger, "Unknown NOARG command {:d}", commandId);
+
+            switch (commandId)
+            {
+                case MAV_CMD_BOARD_RESET:
+                    SDlogger->stop();
+                    LOG_INFO(logger, "Received command BOARD_RESET");
+                    miosix::reboot();
+                    break;
+                case MAV_CMD_CLOSE_LOG:
+                    SDlogger->stop();
+                    sendTelemetry(MAV_LOGGER_TM_ID);
+                    LOG_INFO(logger, "Received command CLOSE_LOG");
+                    break;
+                case MAV_CMD_START_LOGGING:
+                    ParafoilTest::getInstance().startSDlogger();
+                    sendTelemetry(MAV_LOGGER_TM_ID);
+                    LOG_INFO(logger, "Received command START_LOG");
+                    break;
+                default:
+                    break;
+            }
+            break;
+        }
+        case MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC:  // tm request
+        {
+            uint8_t tmId = mavlink_msg_telemetry_request_tc_get_board_id(&msg);
+            LOG_DEBUG(logger, "Received TM request : id = {:d}", tmId);
+
+            // send corresponding telemetry or NACK
+            sendTelemetry(tmId);
+
+            break;
+        }
+        /*case MAVLINK_MSG_ID_SET_WING_ALGORITHM_TC: //Set the algorithm to be
+           executed uint8_t algorithm =
+           mavlink_msg_set_wing_algorithm_tc_get_algorithm(&msg);
+            LOG_DEBUG(logger, "Received Algorithm to be executed: algorithm =
+           {:d}", algorithm);
+
+            //TODO set the algorithm
+
+            break;*/
+        case MAVLINK_MSG_ID_RAW_EVENT_TC:  // post a raw event
+        {
+            LOG_DEBUG(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));
+            break;
+        }
+        case MAVLINK_MSG_ID_PING_TC:
+        {
+            LOG_DEBUG(logger, "Ping received");
+            break;
+        }
+        default:
+        {
+            LOG_DEBUG(logger, "Received message is not of a known type");
+            break;
+        }
+    }
+}
+
+bool Radio::sendTelemetry(const uint8_t tm_id)
+{
+    // Enqueue the message
+    bool result =
+        mav_driver->enqueueMsg(TMRepository::getInstance().packTM(tm_id));
+    // TODO log the operation
+    return result;
+}
+
+void Radio::sendHRTelemetry()
+{
+    // I send this telemetry if and only if the status is
+    // in high rate telemetry
+    if (HRtelemetry)
+    {
+        // sendTelemetry(MAV_HR_TM_ID);
+        // TEST ONLY
+        sendTelemetry(MAV_SENSORS_TM_ID);
+    }
+}
+
+void Radio::sendLRTelemetry()
+{
+    // I send this telemetry if and only if the status is
+    // in low rate telemetry
+    sendTelemetry(MAV_LR_TM_ID);
+}
+
+void Radio::sendAck(const mavlink_message_t& msg)
+{
+    mavlink_message_t ackMsg;
+    // Pack the ack message based on the received message
+    mavlink_msg_ack_tm_pack(TMTC_MAV_SYSID, TMTC_MAV_COMPID, &ackMsg, msg.msgid,
+                            msg.seq);
+
+    // Put the message in the queue
+    mav_driver->enqueueMsg(ackMsg);
+    // TODO log the thing
+}
+
+void Radio::toggleHRTelemetry()
+{
+    // Lock the kernel to avoid context switch during this toggle
+    miosix::PauseKernelLock kLock;
+    TaskScheduler::function_t HRfunction([=]() { sendHRTelemetry(); });
+    HRtelemetry = !HRtelemetry;
+
+    if (HRtelemetry)
+    {
+        // If we switched to hr telemetry on flight i change the period
+        scheduler->removeTask(RADIO_HR_ID);
+        // Add the same task with a faster period
+        scheduler->addTask(HRfunction, HR_FLIGHT_UPDATE_PERIOD, RADIO_HR_ID);
+    }
+    else
+    {
+        // If we switched to hr telemetry on ground i change the period
+        scheduler->removeTask(RADIO_HR_ID);
+        // Add the same task with a slower period
+        scheduler->addTask(HRfunction, HR_GROUND_UPDATE_PERIOD, RADIO_HR_ID);
+    }
+}
+
+bool Radio::start()
+{
+    // Start the mavlink driver
+    bool result = mav_driver->start();
+
+    // Start the scheduler
+    // result &= scheduler -> start();
+
+    return result;
+}
+
+void Radio::logStatus()
+{
+    // TODO log
+}
+
+/**
+ * PRIVATE METHODS
+ */
+void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
+{
+    // Log the thing
+}
+
+void Radio::init()
+{
+    // Create the lambdas to be called
+    TaskScheduler::function_t HRfunction([=]() { sendHRTelemetry(); });
+    TaskScheduler::function_t LRfunction([=]() { sendLRTelemetry(); });
+
+    // Set the HR telemetry TODO remove this TEST ONLY
+    HRtelemetry = true;
+
+    // Register the LR and HR tasks in the scheduler
+    scheduler->addTask(HRfunction, HR_GROUND_UPDATE_PERIOD, RADIO_HR_ID);
+    scheduler->addTask(LRfunction, LR_UPDATE_PERIOD, RADIO_LR_ID);
+
+    // Set the frame receive callback
+    // module -> setOnFrameReceivedListener(
+    // bind(&Radio::onXbeeFrameReceived, this, _1));
+
+    // Set the data rate
+    // Xbee::setDataRate(*xbee, XBEE_80KBPS_DATA_RATE, XBEE_TIMEOUT);
+
+    // Enable external interrupt on F10 pin
+    enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::FALLING_EDGE);
+}
+}  // namespace ParafoilTestDev
\ No newline at end of file
diff --git a/src/boards/Parafoil/Main/Radio.h b/src/boards/Parafoil/Main/Radio.h
new file mode 100644
index 0000000000000000000000000000000000000000..2bb6dc05369bfb25f1c8d1f2d851844a325f388a
--- /dev/null
+++ b/src/boards/Parafoil/Main/Radio.h
@@ -0,0 +1,185 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#pragma once
+
+#include <Parafoil/TelemetriesTelecommands/Mavlink.h>
+#include <radio/Xbee/Xbee.h>
+#include <radio/SX1278/SX1278.h>
+#include <scheduler/TaskScheduler.h>
+#include <common/events/Events.h>
+
+/**
+ * @brief This class represents the radio module. It allows the communications
+ * between the xbee radio module and the on board software. The main tasks are about
+ * sending automatic updates to ground based on the current state (High rate telemetry
+ * or Low rate telemetry) and handle the messages from the ground station.
+ * To handle the various messages there is an apposit callback method and,
+ * to pack the optional reply data we use the TMRepository singleton. 
+ */
+namespace ParafoilTestDev
+{
+    class Radio
+    {
+    public:
+        /**
+         * @brief The xbee module driver
+         */
+        //Xbee::Xbee* xbee;
+        SX1278* module;
+
+        /**
+         * @brief Construct a new Radio object
+         * 
+         * @param xbee_bus The Xbee SPI bus
+         */
+        Radio(SPIBusInterface& xbee_bus, TaskScheduler* scheduler);
+
+        /**
+         * @brief Destroy the Radio object
+         */
+        ~Radio();
+
+        /**
+         * @brief Method called when a mavlink message is received
+         * 
+         * @param msg The parsed message
+         */
+        void handleMavlinkMessage(MavDriver* driver, const mavlink_message_t& msg);
+
+        /**
+         * @brief This method is used to add in send queue
+         * the requested message. It is necessary to call the 
+         * TMrepository to process the actual packet.
+         * 
+         * @param tm_id The requested message id
+         * @return boolean that indicates the operation's result
+         */
+        bool sendTelemetry(const uint8_t tm_id);
+
+        /**
+         * @brief Method automatically called by the task
+         * scheduler that sends the high rate telemetry
+         */
+        void sendHRTelemetry();
+
+        /**
+         * @brief Method automatically called by the task
+         * scheduler that sends the high rate telemetry
+         */
+        void sendLRTelemetry();
+
+        /**
+         * @brief Every time a message is received we send
+         * an ack message to tell the ground station that we
+         * received the message
+         * 
+         * @param msg The message received that we need to ack
+         */
+        void sendAck(const mavlink_message_t& msg);
+
+        /**
+         * @brief Method to change the telemetry rate
+         */
+        void toggleHRTelemetry();
+
+        bool start();
+
+        void logStatus();
+
+    private:
+
+        //1 to 1 corrispondence of every message to its event
+        const std::map<uint8_t, uint8_t> tcMap = {
+        {MAV_CMD_ARM, EV_TC_ARM},
+        {MAV_CMD_DISARM, EV_TC_DISARM},
+
+        {MAV_CMD_FORCE_INIT, EV_TC_FORCE_INIT},
+        {MAV_CMD_FORCE_LAUNCH, EV_TC_LAUNCH},
+
+        {MAV_CMD_NOSECONE_OPEN, EV_TC_NC_OPEN},
+        {MAV_CMD_DPL_RESET_SERVO, EV_TC_DPL_RESET_SERVO},
+        {MAV_CMD_DPL_WIGGLE_SERVO, EV_TC_DPL_WIGGLE_SERVO},
+        {MAV_CMD_CUT_DROGUE, EV_TC_CUT_DROGUE},
+
+        {MAV_CMD_ARB_RESET_SERVO, EV_TC_ABK_RESET_SERVO},
+        {MAV_CMD_ARB_WIGGLE_SERVO, EV_TC_ABK_WIGGLE_SERVO},
+        {MAV_CMD_DISABLE_AEROBRAKES, EV_TC_ABK_DISABLE},
+        {MAV_CMD_TEST_AEROBRAKES, EV_TC_TEST_ABK},
+
+        {MAV_CMD_CALIBRATE_ALGOS, EV_TC_CALIBRATE_ALGOS},
+        {MAV_CMD_CALIBRATE_SENSORS, EV_TC_CALIBRATE_SENSORS},
+
+        {MAV_CMD_SERIAL_TM, EV_TC_SERIAL_TM},
+        {MAV_CMD_RADIO_TM, EV_TC_RADIO_TM},
+
+        {MAV_CMD_START_LOGGING, EV_TC_START_LOG},
+        {MAV_CMD_CLOSE_LOG, EV_TC_CLOSE_LOG},
+
+        {MAV_CMD_TEST_MODE, EV_TC_TEST_MODE},
+        {MAV_CMD_BOARD_RESET, EV_TC_RESET_BOARD},
+        {MAV_CMD_END_MISSION, EV_TC_END_MISSION}};
+
+        /**
+         * @brief The mavlink driver
+         */
+        MavDriver* mav_driver;
+
+        /**
+         * @brief SPI bus
+         */
+        SPIBusInterface& xbee_bus;
+
+        /**
+         * @brief Main task scheduler
+         */
+        TaskScheduler* scheduler;
+
+        /**
+         * @brief high rate telemetry status.
+         * false -> LR telemetry
+         * true  -> HR telemetry
+         */
+        bool HRtelemetry;
+
+        /**
+         * @brief Logger
+         */
+        PrintLogger logger = Logging::getLogger("Radio");
+
+        /**
+         * @brief SD logger (pre started because of the ParafoilTest.h main class)
+         */
+        Logger* SDlogger = &Logger::getInstance();
+
+        /**
+         * @brief Radio frame received callback method.
+         * It's used for logging purposes
+         */
+        void onXbeeFrameReceived(Xbee::APIFrame& frame);
+
+        /**
+         * @brief Method to initialize all the variables and objects
+         * and to register the HR and LR tasks into the task scheduler
+         */
+        void init();
+    };
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Main/Sensors.cpp b/src/boards/Parafoil/Main/Sensors.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..1f3f57de810b60871091532dafa2be7409007f75
--- /dev/null
+++ b/src/boards/Parafoil/Main/Sensors.cpp
@@ -0,0 +1,178 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "Sensors.h"
+
+#include <Parafoil/Configs/SensorsConfig.h>
+#include <Parafoil/TelemetriesTelecommands/TMRepository.h>
+#include <sensors/SensorInfo.h>
+
+using std::bind;
+using namespace Boardcore;
+
+namespace ParafoilTestDev
+{
+/**
+ * PRIVATE METHODS
+ */
+void Sensors::MPU9250init()
+{
+    SPIBusConfig spiConfig{};
+    spiConfig.clockDivider = SPI::ClockDivider::DIV_64;
+    spiConfig.mode         = SPI::Mode::MODE_3;
+    // I create first a new SPISlave with all the settings
+    SPISlave slave{spiInterface, IMU_CS, spiConfig};
+
+    // Instantiate the object
+    imu_mpu9250 = new MPU9250(slave, IMU_SAMPLE_RATE, IMU_GYRO_SCALE,
+                              IMU_ACCEL_SCALE, SPI::ClockDivider::DIV_16);
+
+    // Bind the information
+    SensorInfo info("MPU9250", IMU_SAMPLE_PERIOD,
+                    bind(&Sensors::MPU9250Callback, this), true);
+
+    // Insert the sensor in the common map
+    sensors_map.emplace(std::make_pair(imu_mpu9250, info));
+
+    // Log the results
+    LOG_INFO(log, "IMU MPU9250 Setup done!");
+}
+
+void Sensors::MPU9250Callback()
+{
+    // Log the sample
+    MPU9250Data d = imu_mpu9250->getLastSample();
+    logger->log(imu_mpu9250->getLastSample());
+    LOG_DEBUG(log, "{:.2f} {:.2f} {:.2f}", d.accelerationX, d.accelerationY,
+              d.accelerationZ);
+
+    // Update the radio repository
+    TMRepository::getInstance().update(d);
+}
+
+void Sensors::UbloxGPSinit()
+{
+    // Instantiate the object TODO set the sample rate and stuff
+    gps_ublox = new UbloxGPS(38400, GPS_SAMPLE_RATE, 2, "gps", 38400);
+
+    // Starting GPS thread
+    gps_ublox->start();
+
+    // Bind the information with the callback method
+    SensorInfo info("UbloxGPS", GPS_SAMPLE_PERIOD,
+                    bind(&Sensors::UbloxGPSCallback, this), true);
+
+    // Insert the sensor in the common map
+    sensors_map.emplace(std::make_pair(gps_ublox, info));
+
+    // Log the result
+    LOG_INFO(log, "Ublox GPS Setup done!");
+}
+
+void Sensors::UbloxGPSCallback()
+{
+    // Log the sample
+    UbloxGPSData d = gps_ublox->getLastSample();
+    logger->log(gps_ublox->getLastSample());
+    if (d.fix)
+    {
+        LOG_DEBUG(log, "{:.2f} {:.2f}", d.latitude, d.longitude);
+    }
+
+    // Update the radio repository
+    TMRepository::getInstance().update(d);
+}
+
+void Sensors::BME280init()
+{
+    // I first create a SPI slave needed to instantiate the sensor
+    SPISlave slave(spiInterface, PRESS_CS, SPIBusConfig{});
+
+    slave.config.clockDivider = SPI::ClockDivider::DIV_16;
+
+    auto config = BME280::BME280_CONFIG_ALL_ENABLED;
+    config.bits.oversamplingPressure = BME280::OVERSAMPLING_4;
+
+    // Instantiate the object
+    press_bme280 = new BME280(slave, config);
+
+    // Set the standby time
+    press_bme280->setStandbyTime(PRESS_SAMPLE_RATE);
+
+    // Bind the information with the callback method
+    SensorInfo info("BME280", PRESS_SAMPLE_PERIOD,
+                    bind(&Sensors::BME280Callback, this), true);
+    // Insert the sensor in the common map
+    sensors_map.emplace(std::make_pair(press_bme280, info));
+
+    // Log the result
+    LOG_INFO(log, "BME280 Setup done!");
+}
+
+void Sensors::BME280Callback()
+{
+    // Log the sample
+    BME280Data d = press_bme280->getLastSample();
+    logger->log(press_bme280->getLastSample());
+    LOG_DEBUG(log, "{:.2f} {:.2f} {:.2f}", d.pressure, d.temperature,
+              d.humidity);
+
+    // Update the radio repository
+    TMRepository::getInstance().update(d);
+}
+
+/**
+ * PUBLIC METHODS
+ */
+Sensors::Sensors(SPIBusInterface& spi, TaskScheduler* scheduler)
+    : spiInterface(spi)
+{
+    // Take the SD logger singleton
+    logger = &Logger::getInstance();
+
+    // Sensor init
+    MPU9250init();
+    UbloxGPSinit();
+    BME280init();
+
+    // Sensor manager instance
+    // At this point sensors_map contains all the initialized sensors
+    manager = new SensorManager(sensors_map, scheduler);
+}
+
+Sensors::~Sensors()
+{
+    // Delete the sensors
+    delete (imu_mpu9250);
+    delete (gps_ublox);
+    delete (press_bme280);
+
+    // Sensor manager stop and delete
+    manager->stop();
+    delete manager;
+}
+
+bool Sensors::start() { return manager->start(); }
+
+void Sensors::calibrate() {}
+
+}  // namespace ParafoilTestDev
\ No newline at end of file
diff --git a/src/boards/Parafoil/Main/Sensors.h b/src/boards/Parafoil/Main/Sensors.h
new file mode 100644
index 0000000000000000000000000000000000000000..8f6fd5b5806afde85993de692ee21eec07c31f7b
--- /dev/null
+++ b/src/boards/Parafoil/Main/Sensors.h
@@ -0,0 +1,127 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#pragma once
+
+#include <sensors/SensorManager.h>
+#include <sensors/MPU9250/MPU9250.h>
+#include <sensors/UbloxGPS/UbloxGPS.h>
+#include <sensors/BME280/BME280.h>
+
+using namespace Boardcore;
+
+/**
+ * This class memorizes all the sensors instances.
+ * Every instance is initialized by the constructor. Also every
+ * sensor has its own status
+ */
+namespace ParafoilTestDev
+{
+    class Sensors
+    {
+    private:
+        
+        /**
+         * @brief Sensor manager object
+         */
+        SensorManager* manager;
+        
+        /**
+         * @brief Sensor map that contains every sensor istance
+         * that needs to be sampled by the sensor manager
+         */
+        SensorManager::SensorMap_t sensors_map;
+
+        /**
+         * @brief SPI interface passed via constructor
+         */
+        SPIBusInterface& spiInterface;
+
+        /**
+         * @brief Sensors serial logger
+         */
+        PrintLogger log = Logging::getLogger("sensors");
+
+        /**
+         * @brief SD logger singleton
+         */
+        Logger* logger;
+
+        /**
+         * @brief The MPU9250 IMU init function and
+         * sample callback
+         */
+        void MPU9250init();
+        void MPU9250Callback();
+
+        /**
+         * @brief GPS init function and sample callback
+         */
+        void UbloxGPSinit();
+        void UbloxGPSCallback();
+
+        /**
+         * @brief Barometer BME280 init function and sample callback
+         */
+        void BME280init();
+        void BME280Callback();
+
+    public:
+
+        /**
+         * @brief MPU9250IMU
+         */
+        MPU9250* imu_mpu9250;
+
+        /**
+         * @brief GPS
+         */
+        UbloxGPS* gps_ublox;
+
+        /**
+         * @brief Barometer
+         */
+        BME280* press_bme280;
+
+        /**
+         * @brief Constructor
+         * @param The spi interface used for the sensors
+         * @param The task scheduler
+         */
+        Sensors(SPIBusInterface& spi, TaskScheduler* scheduler);
+
+        /**
+         * @brief Deconstructor
+         */
+        ~Sensors();
+
+        /**
+         * @brief Starts the sensor manager to sample data
+         * @return boolean that indicates operation's result
+         */
+        bool start();
+
+        /**
+         * @brief Calibrates the sensors that need to
+         */
+        void calibrate();
+    };
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/ParafoilTest.h b/src/boards/Parafoil/ParafoilTest.h
new file mode 100644
index 0000000000000000000000000000000000000000..7482ef9a566ea4f1a9643b2cdb68ec264b3ba9f6
--- /dev/null
+++ b/src/boards/Parafoil/ParafoilTest.h
@@ -0,0 +1,242 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <Parafoil/FlightModeManager/FMMController.h>
+#include <Parafoil/Main/Radio.h>
+#include <Parafoil/Main/Sensors.h>
+#include <Parafoil/ParafoilTestStatus.h>
+#include <Parafoil/Wing/WingController.h>
+#include <drivers/spi/SPIDriver.h>
+#include <events/EventBroker.h>
+#include <miosix.h>
+
+using namespace Boardcore;
+
+/**
+ * This class is the main singleton that keeps all the project objects.
+ * It has all the instances and initializes all of them.
+ */
+namespace ParafoilTestDev
+{
+enum ThreadIds : uint8_t
+{
+    THID_ENTRYPOINT = THID_FIRST_AVAILABLE_ID,
+    THID_FMM_FSM,
+    THID_TMTC_FSM,
+    THID_STATS_FSM,
+    THID_ADA_FSM,
+    THID_NAS_FSM,
+    THID_TASK_SCHEDULER
+};
+
+enum TaskIDs : uint8_t
+{
+    TASK_SCHEDULER_STATS_ID = 0,
+    TASK_SENSORS_6_MS_ID    = 1,
+    TASK_SENSORS_15_MS_ID   = 2,
+    TASK_SENSORS_20_MS_ID   = 3,
+    TASK_SENSORS_24_MS_ID   = 4,
+    TASK_SENSORS_40_MS_ID   = 5,
+    TASK_SENSORS_1000_MS_ID = 6,
+    TASK_ADA_ID             = 7,
+    TASK_NAS_ID             = 9
+};
+
+class ParafoilTest : public Singleton<ParafoilTest>
+{
+    friend class Singleton<ParafoilTest>;
+
+public:
+    /**
+     * @brief Event broker
+     */
+    EventBroker* broker;
+
+    /**
+     * @brief Sensors collection
+     */
+    Sensors* sensors;
+
+    /**
+     * @brief Wing algorithm controller
+     */
+    WingController* wingController;
+
+    /**
+     * @brief Radio that manages the interaction between
+     * the xbee module and mavlink
+     */
+    Radio* radio;
+
+    /**
+     * @brief Main FSM
+     */
+    FMMController* FMM;
+
+    /**
+     * @brief Task scheduler
+     */
+    TaskScheduler* scheduler;
+
+    /**
+     * @brief Start method
+     */
+    void start()
+    {
+        // Start the broker
+        if (!broker->start())
+        {
+            LOG_ERR(log, "Error starting EventBroker");
+            status.setError(&ParafoilTestStatus::eventBroker);
+        }
+
+        // Start the sensors sampling
+        if (!sensors->start())
+        {
+            LOG_ERR(log, "Error starting sensors");
+            status.setError(&ParafoilTestStatus::sensors);
+        }
+
+        // Start the main FSM
+        /*if(!FMM -> start())
+        {
+            LOG_ERR(log, "Error starting the main FSM");
+            status.setError(&ParafoilTestStatus::FMM);
+        }*/
+
+        // Start the radio
+        if (!radio->start())
+        {
+            LOG_ERR(log, "Error starting the radio");
+            status.setError(&ParafoilTestStatus::radio);
+        }
+
+        // After all the initializations i log the status
+        SDlogger->log(status);
+
+        // If all is ok i can send the signal to the FSMs
+        if (status.parafoil_test != OK)
+        {
+            LOG_ERR(log, "Initialization failed");
+            // TODO add event to inibit the state machines
+        }
+        else
+        {
+            LOG_INFO(log, "Initialization ok");
+            // TODO add event to start the state machines
+        }
+    }
+
+    /**
+     * @brief Method to start the SDlogger singleton
+     */
+    void startSDlogger()
+    {
+        try
+        {
+            SDlogger->start();
+            // Log in serial
+            LOG_INFO(log, "SDlogger started");
+        }
+        catch (const std::runtime_error& error)
+        {
+            LOG_ERR(log, "SD SDlogger init error");
+            status.setError(&ParafoilTestStatus::logger);
+        }
+        // Log the status
+        SDlogger->log(SDlogger->getLoggerStats());
+    }
+
+private:
+    /**
+     * @brief SDlogger in debug mode
+     */
+    PrintLogger log = Logging::getLogger("ParafoilTest");
+
+    /**
+     * @brief SDlogger singleton for SD
+     */
+    Logger* SDlogger;
+
+    /**
+     * @brief Status memory
+     */
+    ParafoilTestStatus status{};
+
+    /**
+     * @brief Constructor
+     */
+    ParafoilTest()
+    {
+        // Take the singleton instance of SD logger
+        SDlogger = &Logger::getInstance();
+
+        // Start the logging
+        startSDlogger();
+
+        // Store the broker
+        broker = &sEventBroker;
+
+        // Create the task scheduler
+        scheduler = new TaskScheduler();
+        addSchedulerStatsTask();
+
+        // Create the sensors
+        SPIBusInterface* spiInterface1 = new SPIBus(SPI1);
+        sensors                        = new Sensors(*spiInterface1, scheduler);
+
+        // Create the wing controller
+        // wingController = new WingController(scheduler);
+
+        // Create the main FSM
+        // FMM = new FMMController();
+
+        // Create a new radio
+        SPIBusInterface* spiInterface4 = new SPIBus(SPI4);
+        radio                          = new Radio(*spiInterface4, scheduler);
+    }
+
+    void addSchedulerStatsTask()
+    {
+        // add lambda to log scheduler tasks statistics
+        scheduler->addTask(
+            [&]()
+            {
+                std::vector<Boardcore::TaskStatsResult> scheduler_stats =
+                    scheduler->getTaskStats();
+
+                for (TaskStatsResult stat : scheduler_stats)
+                {
+                    SDlogger->log(stat);
+                }
+
+                Boardcore::StackLogger::getInstance().updateStack(
+                    THID_TASK_SCHEDULER);
+            },
+            1000,  // 1 hz
+            TASK_SCHEDULER_STATS_ID, Boardcore::TaskScheduler::Policy::SKIP,
+            miosix::getTick());
+    }
+};
+}  // namespace ParafoilTestDev
\ No newline at end of file
diff --git a/src/boards/Parafoil/ParafoilTestStatus.h b/src/boards/Parafoil/ParafoilTestStatus.h
new file mode 100644
index 0000000000000000000000000000000000000000..005deebd8c231cc9683305353c807acf5d95333f
--- /dev/null
+++ b/src/boards/Parafoil/ParafoilTestStatus.h
@@ -0,0 +1,75 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */ 
+
+/**
+ * This class is used to keep track of various main class
+ * initialization errors.
+ */
+
+#pragma once
+
+#include <string>
+#include <ostream>
+
+namespace ParafoilTestDev
+{
+    enum ParafoilTestComponentStatus
+    {
+        ERROR   = 0,
+        OK      = 1
+    };
+
+    struct ParafoilTestStatus
+    {
+        //If there is an error, this uint8_t reports it(OR)
+        uint8_t parafoil_test = OK;
+
+        //Specific errors
+        uint8_t logger          = OK;
+        uint8_t eventBroker     = OK;
+        uint8_t sensors         = OK;
+        uint8_t FMM             = OK;
+        uint8_t radio           = OK;
+
+        /**
+         * @brief Method to set a specific component in an error state
+         */
+        void setError(uint8_t ParafoilTestStatus::*component)
+        {
+            //Put the passed component to error state
+            this->*component  = ERROR;
+            //Logic OR
+            parafoil_test       = ERROR;
+        }
+
+
+        static std::string header()
+        {
+            return "logger, eventBorker, sensors, radio\n";
+        }
+
+        void print(std::ostream& os)
+        {
+            os << (int)logger << "," << (int)eventBroker << "," << (int)sensors << "," << (int)radio << "\n";
+        }
+    };
+}
\ No newline at end of file
diff --git a/src/boards/Payload/Main/Bus.h b/src/boards/Parafoil/TelemetriesTelecommands/Mavlink.h
similarity index 70%
rename from src/boards/Payload/Main/Bus.h
rename to src/boards/Parafoil/TelemetriesTelecommands/Mavlink.h
index 7a865c15058949465ad35a2441e6c90986dae777..59f1fd075610c24e7ce7c34cf08a760b5f385491 100644
--- a/src/boards/Payload/Main/Bus.h
+++ b/src/boards/Parafoil/TelemetriesTelecommands/Mavlink.h
@@ -22,16 +22,20 @@
 
 #pragma once
 
-#include <drivers/spi/SPIBus.h>
-#include <miosix.h>
+// Ignore warnings as these are auto-generated headers made with third party
+// tools
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wcast-align"
+#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
+#include <mavlink_lib/lynx/mavlink.h>
+#pragma GCC diagnostic pop
 
-namespace PayloadBoard
-{
+#include <radio/MavlinkDriver/MavlinkDriver.h>
+#include <Parafoil/Configs/MavlinkConfig.h>
 
-struct Bus
-{
-    Boardcore::SPIBusInterface* spi1 = new Boardcore::SPIBus(SPI1);
-    Boardcore::SPIBusInterface* spi2 = new Boardcore::SPIBus(SPI2);
-};
+using namespace Boardcore;
 
-}  // namespace PayloadBoard
+namespace ParafoilTestDev
+{
+    using MavDriver = MavlinkDriver<MAV_PKT_SIZE, MAV_OUT_QUEUE_LEN>;
+}
diff --git a/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp b/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..8f73ce12c05d4960be03630676cf8b1621a4be8b
--- /dev/null
+++ b/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp
@@ -0,0 +1,135 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#include <Parafoil/TelemetriesTelecommands/TMRepository.h>
+
+namespace ParafoilTestDev
+{
+    /**
+     * PUBLIC METHODS 
+     */
+    mavlink_message_t TMRepository::packTM(uint8_t req_tm, uint8_t sys_id, uint8_t comp_id)
+    {
+        mavlink_message_t m;
+        mavlink_nack_tm_t nack_tm;
+
+        miosix::PauseKernelLock kLock;
+
+        switch (req_tm)
+        {
+            case MavTMList::MAV_SENSORS_TM_ID:
+                tm_repository.sensors_tm.timestamp = miosix::getTick();
+                mavlink_msg_sensors_tm_encode(sys_id, comp_id, &m, 
+                                            &(tm_repository.sensors_tm));
+                break;
+            /*case MavTMList::MAV_SYS_TM_ID:
+                tm_repository.sys_tm.timestamp = miosix::getTick();
+                mavlink_msg_sys_tm_encode(sys_id, comp_id, &m,
+                                        &(tm_repository.sys_tm));
+                break;
+            case MavTMList::MAV_FMM_TM_ID:
+                tm_repository.fmm_tm.timestamp = miosix::getTick();
+                mavlink_msg_fmm_tm_encode(sys_id, comp_id, &m,
+                                        &(tm_repository.fmm_tm));
+                break;
+            case MavTMList::MAV_LOGGER_TM_ID:
+                tm_repository.logger_tm.timestamp = miosix::getTick();
+                mavlink_msg_logger_tm_encode(sys_id, comp_id, &m,
+                                            &(tm_repository.logger_tm));
+                break;
+            case MavTMList::MAV_TMTC_TM_ID:
+                tm_repository.tmtc_tm.timestamp = miosix::getTick();
+                mavlink_msg_tmtc_tm_encode(sys_id, comp_id, &m,
+                                        &(tm_repository.tmtc_tm));
+                break;
+            case MavTMList::MAV_TASK_STATS_TM_ID:
+                tm_repository.task_stats_tm.timestamp = miosix::getTick();
+                mavlink_msg_task_stats_tm_encode(sys_id, comp_id, &m,
+                                                &(tm_repository.task_stats_tm));
+                break;
+            case MavTMList::MAV_GPS_TM_ID:
+                tm_repository.gps_tm.timestamp = miosix::getTick();
+                mavlink_msg_gps_tm_encode(sys_id, comp_id, &m,
+                                        &(tm_repository.gps_tm));
+                break;
+            case MavTMList::MAV_HR_TM_ID:
+                tm_repository.hr_tm.timestamp = miosix::getTick();
+                mavlink_msg_hr_tm_encode(sys_id, comp_id, &m,
+                                        &(tm_repository.hr_tm));
+                break;
+            case MavTMList::MAV_LR_TM_ID:
+                //tm_repository.tm_repository.lr_tm.timestamp = miosix::getTick();
+                mavlink_msg_lr_tm_encode(sys_id, comp_id, &m,
+                                        &(tm_repository.lr_tm));
+                break;*/
+            default:
+            {
+                LOG_DEBUG(logger, "Unknown telemetry id: %d", req_tm);
+                nack_tm.recv_msgid = 0;
+                nack_tm.seq_ack    = 0;
+                mavlink_msg_nack_tm_encode(sys_id, comp_id, &m, &nack_tm);
+                break;
+            }
+        }
+        return m;
+    }
+
+    //Implement all the update functions
+    void TMRepository::update(MPU9250Data data)
+    {
+        //Pause the kernel to avoid interructions during this fast operation
+        miosix::PauseKernelLock kLock;   
+        //Update only the sensors message TODO update all the things
+        tm_repository.sensors_tm.bmx160_acc_x = data.accelerationX;
+        tm_repository.sensors_tm.bmx160_acc_y = data.accelerationY;
+        tm_repository.sensors_tm.bmx160_acc_z = data.accelerationZ;
+
+        tm_repository.sensors_tm.bmx160_gyro_x = data.angularVelocityX;
+        tm_repository.sensors_tm.bmx160_gyro_y = data.angularVelocityY;
+        tm_repository.sensors_tm.bmx160_gyro_z = data.angularVelocityZ;
+
+        tm_repository.sensors_tm.bmx160_mag_x = data.magneticFieldX;
+        tm_repository.sensors_tm.bmx160_mag_y = data.magneticFieldY;
+        tm_repository.sensors_tm.bmx160_mag_z = data.magneticFieldZ;
+
+        tm_repository.sensors_tm.bmx160_temp = data.temperature;
+    }
+
+    void TMRepository::update(UbloxGPSData data)
+    {
+        //Pause the kernel to avoid interructions during this fast operation
+        miosix::PauseKernelLock kLock;   
+        //Update only the sensors message TODO update all the things
+        tm_repository.sensors_tm.gps_alt = data.height;
+        tm_repository.sensors_tm.gps_fix = data.fix;
+        tm_repository.sensors_tm.gps_lon = data.longitude;
+        tm_repository.sensors_tm.gps_lat = data.latitude;
+    }
+
+    void TMRepository::update(BME280Data data)
+    {
+        //Pause the kernel to avoid interructions during this fast operation
+        miosix::PauseKernelLock kLock;   
+        //Update only the sensors message TODO update all the things
+        tm_repository.sensors_tm.ms5803_press = data.pressure;
+        tm_repository.sensors_tm.ms5803_temp = data.temperature;
+    }
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.h b/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.h
new file mode 100644
index 0000000000000000000000000000000000000000..38eba7747f8e68de14ec96cec5d654d2a33da1b6
--- /dev/null
+++ b/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.h
@@ -0,0 +1,105 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#pragma once
+
+#include <Singleton.h>
+#include <sensors/MPU9250/MPU9250Data.h>
+#include <sensors/UbloxGPS/UbloxGPSData.h>
+#include <sensors/BME280/BME280Data.h>
+#include <Parafoil/TelemetriesTelecommands/Mavlink.h>
+
+/**
+ * @brief This class represents the collection of data that can
+ * be sent via radio communication. This refers to mavlink libriaries
+ * and structures created in the correct .xml file.
+ *
+ * It is necessary that this singleton class handles the structure update
+ * (when a message pack is requested).
+ * The pack method is the core of the class. It returns a mavlink_message
+ * with the message data(specified with the id) requested. 
+ */
+
+using namespace Boardcore;
+
+namespace ParafoilTestDev
+{
+    class TMRepository : public Singleton<TMRepository>
+    {
+        friend class Singleton<TMRepository>;
+
+    public:
+
+        /**
+         * @brief Retrieve a telemetry message in packed form.
+         *
+         * @param req_tm    required telemetry
+         * @param sys_id    system id to pack it with
+         * @param comp_id   component id to pack it with
+         * @return          packed mavlink struct of that telemetry or a NACK_TM if
+         *                  the telemetry id was not found.
+         */
+        mavlink_message_t packTM(uint8_t req_tm, uint8_t sys_id = TMTC_MAV_SYSID,
+                                uint8_t comp_id = TMTC_MAV_COMPID);
+
+        /**
+         * @brief Update functions
+         */
+        void update(MPU9250Data data);
+        void update(UbloxGPSData data);
+        void update(BME280Data data);
+
+    private:
+        /**
+         * @brief Struct containing all TMs in the form of mavlink messages.
+         */
+        struct TmRepository_t
+        {
+            mavlink_sys_tm_t sys_tm;
+            mavlink_pin_obs_tm_t pin_obs_tm;
+            mavlink_logger_tm_t logger_tm;
+            mavlink_fmm_tm_t fmm_tm;
+            mavlink_tmtc_tm_t tmtc_tm;
+            mavlink_task_stats_tm_t task_stats_tm;
+            mavlink_dpl_tm_t dpl_tm;
+            mavlink_ada_tm_t ada_tm;
+            mavlink_abk_tm_t abk_tm;
+            mavlink_nas_tm_t nas_tm;
+
+            mavlink_ms5803_tm_t digital_baro_tm;
+            mavlink_bmx160_tm_t bmx_tm;
+            mavlink_lis3mdl_tm_t lis3mdl_tm;
+            mavlink_adc_tm_t adc_tm;
+            mavlink_gps_tm_t gps_tm;
+
+            mavlink_hr_tm_t hr_tm;
+            mavlink_lr_tm_t lr_tm;
+            mavlink_windtunnel_tm_t wind_tm;
+            mavlink_sensors_tm_t sensors_tm;
+            mavlink_test_tm_t test_tm;
+        } tm_repository;
+
+        /**
+         * @brief Logger
+         */
+        PrintLogger logger = Logging::getLogger("TMRepository");
+    };
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Wing/WingAlgorithm.cpp b/src/boards/Parafoil/Wing/WingAlgorithm.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..38f120d2c10097ee46edfb939292190d18db392e
--- /dev/null
+++ b/src/boards/Parafoil/Wing/WingAlgorithm.cpp
@@ -0,0 +1,162 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include <Parafoil/Wing/WingAlgorithm.h>
+#include <drivers/timer/TimestampTimer.h>
+
+namespace ParafoilTestDev
+{
+    std::istream& operator>>(std::istream& input, WingAlgorithmData& data)
+    {
+        input >> data.timestamp;
+        input.ignore(1, ',');
+        input >> data.servo1Angle;
+        input.ignore(1, ',');
+        input >> data.servo2Angle;
+        return input;
+    }
+
+    /**
+     * PUBLIC METHODS
+     */
+    WingAlgorithm::WingAlgorithm(ServoInterface* servo1, ServoInterface* servo2, const char* filename)
+                 : parser(filename)
+    {
+        setServo(servo1, servo2);
+    }
+
+    WingAlgorithm::WingAlgorithm(const char* filename)
+                 : parser(filename){}
+
+    bool WingAlgorithm::init()
+    {
+        //Returns a std::vector which contains
+        //all the csv parsed with the data structure in mind
+        steps = parser.collect();
+        
+        //Return if the size collected is greater than 0
+        fileValid = steps.size() > 0;
+        return fileValid;
+    }
+
+    void WingAlgorithm::setServo(ServoInterface* servo1, ServoInterface* servo2)
+    {
+        if(servo1 != NULL)
+        {
+            this -> servo1 = servo1;
+        }
+        else
+        {
+            //In this case i create a standard servo from the wing config file
+            servo1 = new WingServo(WING_SERVO1_TIMER,
+                                   WING_SERVO1_PWM_CHANNEL,
+                                   WING_SERVO1_MIN_POSITION,
+                                   WING_SERVO1_MAX_POSITION,
+                                   WING_SERVO1_RESET_POSITION);
+        }
+
+        if(servo2 != NULL)
+        {
+            this -> servo2 = servo2;
+        }
+        else
+        {
+            //In this case i create a standard servo from the wing config file
+            servo2 = new WingServo(WING_SERVO2_TIMER,
+                                   WING_SERVO2_PWM_CHANNEL,
+                                   WING_SERVO2_MIN_POSITION,
+                                   WING_SERVO2_MAX_POSITION,
+                                   WING_SERVO2_RESET_POSITION);
+        }
+    }
+
+    void WingAlgorithm::addStep(WingAlgorithmData step)
+    {
+        //I do it if and only if the file is invalid, because 
+        //i don't want to mess up with the timestamp order
+        if(!fileValid)
+        {
+            //Add it to the std::vector at the end
+            steps.push_back(step);
+        }
+    }
+
+    void WingAlgorithm::begin()
+    {
+        running = true;
+        shouldReset = true;
+        //Set the current timestamp
+        timeStart = TimestampTimer::getInstance().getTimestamp();
+    }
+
+    void WingAlgorithm::end()
+    {
+        running = false;
+        //Set the offset timestamp to 0
+        timeStart = 0;
+    }
+
+    /**
+     * PROTECTED METHODS
+     */
+    void WingAlgorithm::step()
+    {
+        //Variable to remember what is the step that has to be done
+        static unsigned int stepIndex = 0;
+        uint64_t currentTimestamp = TimestampTimer::getInstance().getTimestamp();
+
+        if(shouldReset)
+        {
+            //If the algorithm has been stopped 
+            //i want to start from the beginning
+            stepIndex   = 0;
+            shouldReset = false;
+        }
+
+        if(stepIndex >= steps.size())
+        {
+            //End the procedure so it won't be executed
+            end();
+            //Set the index to 0 in case of another future execution
+            stepIndex = 0;
+            //Terminate here
+            return;
+        }
+
+        if(currentTimestamp - timeStart >= steps[stepIndex].timestamp)
+        {
+            //TODO log the action
+            //I need to execute the current step (if not null servos)
+            if(servo1 != NULL)
+            {
+                servo1->set(steps[stepIndex].servo1Angle);
+            }
+            if(servo2 != NULL)
+            {
+                servo2->set(steps[stepIndex].servo2Angle);
+            }
+
+            //finally increment the stepIndex
+            stepIndex++;
+        }
+    }
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Wing/WingAlgorithm.h b/src/boards/Parafoil/Wing/WingAlgorithm.h
new file mode 100644
index 0000000000000000000000000000000000000000..ad4aa33f33865543c2c4e969ebbdba5e8575ba78
--- /dev/null
+++ b/src/boards/Parafoil/Wing/WingAlgorithm.h
@@ -0,0 +1,145 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <utils/CSVReader/CSVReader.h>
+#include <common/Algorithm.h>
+#include <Parafoil/Wing/WingServo.h>
+
+/**
+ * @brief This class abstracts the concept of wing timestamp based
+ * algorithm. These algorithms are stored in files (formatted in csv).
+ * We use a CSV parser to properly parse the procedure and every step
+ * we check if it is time to advance and in case actuate teh step with
+ * the two servos.
+ * 
+ * Brief use case:
+ * WingServo servo1...
+ * WingServo servo2...
+ * 
+ * servo1.enable();
+ * servo2.enable();
+ * 
+ * WingAlgorithm algorithm(&servo1, &servo2, "Optional File")
+ * algorithm.init();
+ * 
+ * //In case of a non valid file/empty string you can add the steps
+ * algorithm.addStep(WingAlgorithmData{timestamp, angle1, angle2});
+ * 
+ * algorithm.begin();
+ * 
+ * algorithm.update()...
+ * 
+ * //End of algorithm
+ * 
+ * algorithm.begin();
+ * 
+ * algorithm.update()...
+ */
+
+using namespace Boardcore;
+
+namespace ParafoilTestDev
+{
+    struct WingAlgorithmData
+    {
+        uint64_t timestamp; //First timestamp is 0 (in microseconds)
+        float servo1Angle;  //degrees
+        float servo2Angle;  //degrees
+    };
+
+    class WingAlgorithm : public Algorithm
+    {
+    public:
+
+        /**
+         * @brief Construct a new Wing Algorithm object
+         * 
+         * @param servo1 The first servo
+         * @param servo2 The second servo
+         * @param filename The csv file where all the operations are stored
+         */
+        WingAlgorithm(ServoInterface* servo1, ServoInterface* servo2, const char* filename);
+
+        /**
+         * @brief Construct a new Wing Algorithm object
+         * 
+         * @param filename The csv file where all the operations are stored
+         */
+        WingAlgorithm(const char* filename);
+
+        /**
+         * @brief This method parses the file and stores it into a std::vector
+         * 
+         * @return true If the initialization finished correctly
+         * @return false If something went wrong
+         */
+        bool init() override;
+
+        /**
+         * @brief Set the Servos objects
+         * @param servo1 The first algorithm servo
+         * @param servo2 The second algorithm servo
+         */
+        void setServo(ServoInterface* servo1, ServoInterface* servo2);
+
+        /**
+         * @brief Adds manually the step in case of fast debug needs
+         * 
+         * @param step The data that describes a step(timestamp, servo1 angle, servo2 angle)
+         */
+        void addStep(WingAlgorithmData step);
+
+        /**
+         * @brief This sets the reference timestamp for the algorithm
+         */
+        void begin();
+
+        /**
+         * @brief This disables the algorithm
+         */
+        void end();
+
+    protected:
+        //Actuators
+        ServoInterface* servo1;
+        ServoInterface* servo2;
+        //Offset timestamp
+        uint64_t timeStart;
+        //Procedure
+        std::vector<WingAlgorithmData> steps;
+        //File parser
+        CSVParser<WingAlgorithmData> parser;
+        bool fileValid      = false;
+        //This boolean is used to understand when to reset
+        //the index where the algorithm has stopped.
+        //In case of end call, we want to be able to perform
+        //another time this algorithm starting from 0
+        bool shouldReset    = false;
+
+        /**
+         * @brief This method implements the algorithm step based on the current timestamp
+         */
+        void step() override;
+    };
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Wing/WingConfig.h b/src/boards/Parafoil/Wing/WingConfig.h
new file mode 100644
index 0000000000000000000000000000000000000000..213f00bf3b189ae3298a33b3291dfbc18707fb8e
--- /dev/null
+++ b/src/boards/Parafoil/Wing/WingConfig.h
@@ -0,0 +1,64 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */ 
+#pragma once
+
+#include <drivers/timer/PWM.h>
+
+using namespace Boardcore;
+
+/**
+ * @brief This class defines all the wing configs
+ * (E.g. Servos PWM channels, Servos max and min positions, etc..)
+ */
+namespace ParafoilTestDev
+{
+    /**
+     * ALGORITHM CONFIGURATION
+     */
+    static const uint32_t   WING_UPDATE_PERIOD = 10; //milliseconds
+    static const uint8_t    WING_CONTROLLER_ID = 100; //TODO define a correct ID
+
+    /**
+     * SERVOS CONFIGURATIONS
+     */
+
+    //16 bit, 45MHz, no DMA timer
+    static TIM_TypeDef* WING_SERVO1_TIMER = TIM13;
+    static TIM_TypeDef* WING_SERVO2_TIMER = TIM14;
+
+    static const TimerUtils::Channel WING_SERVO1_PWM_CHANNEL = TimerUtils::Channel::CHANNEL_1;
+    static const TimerUtils::Channel WING_SERVO2_PWM_CHANNEL = TimerUtils::Channel::CHANNEL_1;
+
+    //Servo dipendent variables
+    static const unsigned int WING_SERVO_MIN_PULSE = 1000;
+    static const unsigned int WING_SERVO_MAX_PULSE = 2500;
+    static const unsigned int WING_SERVO_FREQUENCY = 50;
+
+    static const float WING_SERVO1_MAX_POSITION = 180; //degrees
+    static const float WING_SERVO2_MAX_POSITION = 180; //degrees
+
+    static const float WING_SERVO1_MIN_POSITION = 0;   //degrees
+    static const float WING_SERVO2_MIN_POSITION = 0;   //degrees
+
+    static const float WING_SERVO1_RESET_POSITION = 90; //degrees
+    static const float WING_SERVO2_RESET_POSITION = 90; //degrees
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Wing/WingController.cpp b/src/boards/Parafoil/Wing/WingController.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a32ad0580b31d6ba75089e83a035cfc487adc015
--- /dev/null
+++ b/src/boards/Parafoil/Wing/WingController.cpp
@@ -0,0 +1,158 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#include <Parafoil/Wing/WingConfig.h>
+#include <Parafoil/Wing/WingController.h>
+
+namespace ParafoilTestDev
+{
+    /**
+     * PUBLIC METHODS
+     */
+    WingController::WingController(TaskScheduler* scheduler)
+    {
+        //Assign the task scheduler
+        this -> scheduler = scheduler;
+
+        //Set the current running state
+        this -> running = false;
+
+        //Set the current selected algorithm to 0
+        this -> selectedAlgorithm = 0;
+
+        //Initialize the servos, enable them,
+        //register the task into the task scheduler
+        init();
+    }
+
+    WingController::~WingController()
+    {
+        //Delete the servos
+        delete servo1;
+        delete servo2;
+    }
+
+    void WingController::addAlgorithm(const char* filename)
+    {
+        //Create the algorithm
+        WingAlgorithm* algorithm = new WingAlgorithm(servo1, servo2, filename);
+        
+        //Add the algorithm to the vector and init it
+        algorithms.push_back(algorithm);
+        //If init fails[Beacuse of inexistent file or stuff] doesn't matter
+        //Because the algorithm is empty and so it won't do anything
+        algorithms[algorithms.size() - 1] -> init();
+    }
+
+    void WingController::addAlgorithm(WingAlgorithm* algorithm)
+    {
+        //Ensure that the servos are correct
+        algorithm->setServo(servo1, servo2);
+
+        //Add the algorithm to the vector
+        algorithms.push_back(algorithm);
+    }
+
+    void WingController::selectAlgorithm(unsigned int index)
+    {
+        if(index >= 0 && index < algorithms.size())
+        {
+            selectedAlgorithm = index;
+        }
+        else
+        {
+            //I select the 0 algorithm
+            selectedAlgorithm = 0;
+        }
+    }
+
+    void WingController::start()
+    {
+        //If the selected algorithm is valid --> also the 
+        //algorithms array is not empty i start the whole thing
+        if(selectedAlgorithm >= 0 && selectedAlgorithm < algorithms.size())
+        {
+            //Set the boolean that enables the update method to true
+            running = true;
+
+            //Begin the selected algorithm
+            algorithms[selectedAlgorithm] -> begin();
+
+            //Also start the scheduler
+            scheduler -> start();
+        }
+    }
+
+    void WingController::stop()
+    {
+        //Set running to false so that the update method doesn't act
+        running = false;
+        //Stop the algorithm if selected
+        if(selectedAlgorithm >= 0 && selectedAlgorithm < algorithms.size())
+        {
+            algorithms[selectedAlgorithm] -> end();
+        }
+    }
+
+    void WingController::update()
+    {
+        //Check if the algorithm is running
+        if(!running)
+        {
+            return;
+        }
+
+        //If the selected algorithm is valid i can update it
+        if(selectedAlgorithm >= 0 && selectedAlgorithm < algorithms.size())
+        {
+            algorithms[selectedAlgorithm] -> update();
+        }
+    }
+
+    /**
+     * PRIVATE METHODS
+     */
+    void WingController::init()
+    {
+        //Instanciate the servos
+        servo1 = new WingServo(WING_SERVO1_TIMER,
+                               WING_SERVO1_PWM_CHANNEL,
+                               WING_SERVO1_MIN_POSITION,
+                               WING_SERVO1_MAX_POSITION,
+                               WING_SERVO1_RESET_POSITION);
+        
+        servo2 = new WingServo(WING_SERVO2_TIMER,
+                               WING_SERVO2_PWM_CHANNEL,
+                               WING_SERVO2_MIN_POSITION,
+                               WING_SERVO2_MAX_POSITION,
+                               WING_SERVO2_RESET_POSITION);
+        
+        //Enable servos
+        servo1 -> enable();
+        servo2 -> enable();
+
+        //Register the task
+        TaskScheduler::function_t updateFunction([=]() {update();});
+        
+        scheduler -> addTask(updateFunction, WING_UPDATE_PERIOD,
+                                             WING_CONTROLLER_ID);
+    }
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Wing/WingController.h b/src/boards/Parafoil/Wing/WingController.h
new file mode 100644
index 0000000000000000000000000000000000000000..1e9e0c488783b43a32a126edb7d59a21b73a0b16
--- /dev/null
+++ b/src/boards/Parafoil/Wing/WingController.h
@@ -0,0 +1,143 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#pragma once
+
+#include <Parafoil/Wing/WingAlgorithm.h>
+#include <scheduler/TaskScheduler.h>
+
+/**
+ * @brief This class allows the user to select the wing algorithm
+ * that has to be used during the tests. It also registers his 
+ * dedicated function in the task schduler in order to be
+ * executed every fixed period and to update the two servos position
+ * depending on the selected algorithm.
+ * 
+ * Use case example:
+ * controller = new WingController(scheduler);
+ * 
+ * controller.addAlgorithm("filename");
+ * OR
+ * controller.addAlgorithm(algorithm);
+ * 
+ * controller.selectAlgorithm(index);
+ * 
+ * controller.start();
+ * controller.stop();  //If you want to abort the execution
+ * controller.start(); //If you want to start again from the beginning
+ */
+
+using namespace Boardcore;
+
+namespace ParafoilTestDev
+{
+    class WingController
+    {
+    private:
+        /**
+         * @brief Servo actuators
+         */
+        ServoInterface* servo1;
+        ServoInterface* servo2;
+
+        /**
+         * @brief List of loaded algorithms (from SD or not)
+         */
+        std::vector<WingAlgorithm*> algorithms;
+
+        /**
+         * @brief The common task scheduler
+         */
+        TaskScheduler* scheduler;
+
+        /**
+         * @brief This attribute is modified by the mavlink radio section.
+         * The user using the Ground Station can select the pre-enumered algorithm to execute
+         */
+        unsigned int selectedAlgorithm;
+
+        /**
+         * @brief Internal running state
+         */
+        bool running;
+
+        /**
+         * @brief Initialization method. It registers the update method
+         * into the task scheduler
+         */
+        void init();
+
+    public:
+
+        /**
+         * @brief Construct a new Wing Controller object
+         * 
+         * @param scheduler The main used task scheduler
+         */
+        WingController(TaskScheduler* scheduler);
+
+        /**
+         * @brief Destroy the Wing Controller object.
+         * In particular destroys the servo instances 
+         */
+        ~WingController();
+
+        /**
+         * @brief Method to add the algorithm in the list
+         * 
+         * @param filename The SD file where to read the instructions
+         */
+        void addAlgorithm(const char* filename);
+
+        /**
+         * @brief Method to add the algorithm in the list
+         * 
+         * @param algorithm The algorithm with 
+         * all already done (e.g. steps already registered)
+         */
+        void addAlgorithm(WingAlgorithm* algorithm);
+
+        /**
+         * @brief Selects the algorithm if present.
+         * 
+         * @param index The algorithms vector index
+         */
+        void selectAlgorithm(unsigned int index);
+
+        /**
+         * @brief Sets the internal state running and
+         * starts the selected algorithm
+         */
+        void start();
+        
+        /**
+         * @brief Sets the internal state to stop and
+         * stops the selected algorithm
+         */
+        void stop();
+
+        /**
+         * @brief Method that is called every time period
+         * to update the internal wing servos states
+         */
+        void update();
+    };
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Wing/WingServo.cpp b/src/boards/Parafoil/Wing/WingServo.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..d10aabb4ebd544eeaf738c79ca9593d4dde7d533
--- /dev/null
+++ b/src/boards/Parafoil/Wing/WingServo.cpp
@@ -0,0 +1,75 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#include <Parafoil/Wing/WingServo.h>
+
+namespace ParafoilTestDev
+{
+    /**
+     * PUBLIC METHODS
+     */
+    WingServo::WingServo(TIM_TypeDef* timer, TimerUtils::Channel pwmChannel, float minPosition, float maxPosition)
+             :WingServo(timer, pwmChannel, minPosition, maxPosition, minPosition){}
+    
+    WingServo::WingServo(TIM_TypeDef* timer, TimerUtils::Channel pwmChannel, float minPosition, float maxPosition, float resetPosition)
+             :ServoInterface(minPosition, maxPosition, resetPosition)
+    {
+        servo = new Servo(timer, pwmChannel, WING_SERVO_MIN_PULSE
+                                           , WING_SERVO_MAX_PULSE
+                                           , WING_SERVO_FREQUENCY);
+    }
+
+    WingServo::~WingServo(){}
+
+    void WingServo::enable()
+    {
+        servo -> enable();
+        //Set the servo position to reset
+        setPosition(RESET_POS);
+    }
+
+    void WingServo::disable()
+    {
+        servo -> disable();
+    }
+
+    void WingServo::selfTest()
+    {
+        setPosition(MIN_POS);
+        miosix::Thread::sleep(1000);
+        setPosition(RESET_POS);
+        miosix::Thread::sleep(1000);
+        setPosition(MAX_POS);
+    }
+
+    /**
+     * PRIVATE METHODS
+     */
+    void WingServo::setPosition(float angle)
+    {
+        servo->setPosition(angle / 180);
+    }
+
+    float WingServo::preprocessPosition(float angle)
+    {
+        return angle;
+    }
+}
\ No newline at end of file
diff --git a/src/boards/Parafoil/Wing/WingServo.h b/src/boards/Parafoil/Wing/WingServo.h
new file mode 100644
index 0000000000000000000000000000000000000000..2711a3c4c3897c9ce727b0cf9738b907a817ccad
--- /dev/null
+++ b/src/boards/Parafoil/Wing/WingServo.h
@@ -0,0 +1,90 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#pragma once
+
+#include <common/ServoInterface.h>
+#include <drivers/servo/Servo.h>
+#include <Parafoil/Wing/WingConfig.h>
+
+using namespace Boardcore;
+
+namespace ParafoilTestDev
+{
+    class WingServo : public ServoInterface
+    {
+    public:
+
+        /**
+         * @brief Construct a new Wing Servo object
+         * It will use the min position as reset
+         * 
+         * @param timer The servo timer that needs to be used
+         * @param pwmChannel The servo pwm port used
+         * @param minPosition The min allowed servo position(degrees)
+         * @param maxPosition The max allowed servo position(degrees)
+         */
+        WingServo(TIM_TypeDef* timer, TimerUtils::Channel pwmChannel, float minPosition, float maxPosition);
+
+        /**
+         * @brief Construct a new Wing Servo object
+         * 
+         * @param timer The servo timer that needs to be used
+         * @param pwmChannel The servo pwm port used
+         * @param minPosition The min allowed servo position(degrees)
+         * @param maxPosition The max allowed servo position(degrees)
+         * @param resetPosition The position where the servo is when it resets(degrees)
+         */
+        WingServo(TIM_TypeDef* timer, TimerUtils::Channel pwmChannel, float minPosition, float maxPosition, float resetPosition);
+
+        /**
+         * @brief Destroy the Wing Servo object
+         */
+        ~WingServo();
+
+        void enable() override;
+
+        void disable() override;
+
+        /**
+         * @brief Execute a self test with the servo
+         */
+        void selfTest() override;
+
+    private:
+        Servo* servo;
+
+    protected:
+        /**
+         * @brief Set the servo position
+         * @param angle sevo position(degrees)
+         */
+        void setPosition(float angle) override;
+
+        /**
+         * @brief Method to convert the angle passed by the user to an
+         * useful angle for the servo interface
+         * @param angle The angle(degrees)
+         * @return float The converted angle
+         */
+        float preprocessPosition(float angle) override;
+    };
+}
\ No newline at end of file
diff --git a/src/boards/Payload/Main/Radio.cpp b/src/boards/Payload/Main/Radio.cpp
deleted file mode 100644
index 31a52fabfc12f861afa41933e8f414106987bf92..0000000000000000000000000000000000000000
--- a/src/boards/Payload/Main/Radio.cpp
+++ /dev/null
@@ -1,180 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-//#include <LoggerService/LoggerService.h>
-#include <Payload/Main/Radio.h>
-//#include <TelemetriesTelecommands/TCHandler.h>
-//#include <TelemetriesTelecommands/TMTCController.h>
-//#include <TelemetriesTelecommands/TmRepository.h>
-#include <drivers/Xbee/APIFramesLog.h>
-#include <drivers/Xbee/ATCommands.h>
-#include <drivers/interrupt/external_interrupts.h>
-#include <interfaces-impl/hwmapping.h>
-
-#include <functional>
-
-// using std::function;
-using std::bind;
-using namespace std::placeholders;
-using namespace Boardcore;
-
-// Xbee ATTN interrupt
-void __attribute__((used)) EXTI10_IRQHandlerImpl()
-{
-    using namespace PayloadBoard;
-
-    /*if (DeathStack::getInstance().radio->xbee != nullptr)
-    {
-        DeathStack::getInstance().radio->xbee->handleATTNInterrupt();
-    }*/
-}
-
-namespace PayloadBoard
-{
-
-Radio::Radio(SPIBusInterface& xbee_bus) : xbee_bus(xbee_bus)
-{
-    SPIBusConfig xbee_cfg{};
-
-    xbee_cfg.clockDivider = SPI::ClockDivider::DIV_16;
-
-    xbee = new Xbee::Xbee(xbee_bus, xbee_cfg, miosix::xbee::cs::getPin(),
-                          miosix::xbee::attn::getPin(),
-                          miosix::xbee::reset::getPin());
-    xbee->setOnFrameReceivedListener(
-        bind(&Radio::onXbeeFrameReceived, this, _1));
-
-    // Xbee::setDataRate(*xbee, XBEE_80KBPS_DATA_RATE, XBEE_TIMEOUT);
-
-    // mav_driver = new MavDriver(xbee, handleMavlinkMessage, SLEEP_AFTER_SEND,
-    //                           MAV_OUT_BUFFER_MAX_AGE);
-
-    // tmtc_manager = new TMTCController();
-
-    // tm_repo = TmRepository::getInstance();
-
-    enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::FALLING_EDGE);
-}
-
-Radio::~Radio()
-{
-    // tmtc_manager->stop();
-    // mav_driver->stop();
-
-    // delete tmtc_manager;
-    // delete mav_driver;
-    delete xbee;
-}
-
-bool Radio::start()
-{
-    // return mav_driver->start() && tmtc_manager->start();
-    return true;
-}
-
-void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
-{
-    // LoggerService& logger = *LoggerService::getInstance();
-
-    using namespace Xbee;
-    bool logged = false;
-    switch (frame.frameType)
-    {
-        case FTYPE_AT_COMMAND:
-        {
-            ATCommandFrameLog dest;
-            logged = ATCommandFrameLog::toFrameType(frame, &dest);
-            if (logged)
-            {
-                // logger.log(dest);
-            }
-            break;
-        }
-        case FTYPE_AT_COMMAND_RESPONSE:
-        {
-            ATCommandResponseFrameLog dest;
-            logged = ATCommandResponseFrameLog::toFrameType(frame, &dest);
-            if (logged)
-            {
-                // logger.log(dest);
-            }
-            break;
-        }
-        case FTYPE_MODEM_STATUS:
-        {
-            ModemStatusFrameLog dest;
-            logged = ModemStatusFrameLog::toFrameType(frame, &dest);
-            if (logged)
-            {
-                // logger.log(dest);
-            }
-            break;
-        }
-        case FTYPE_TX_REQUEST:
-        {
-            TXRequestFrameLog dest;
-            logged = TXRequestFrameLog::toFrameType(frame, &dest);
-            if (logged)
-            {
-                // logger.log(dest);
-            }
-            break;
-        }
-        case FTYPE_TX_STATUS:
-        {
-            TXStatusFrameLog dest;
-            logged = TXStatusFrameLog::toFrameType(frame, &dest);
-            if (logged)
-            {
-                // logger.log(dest);
-            }
-            break;
-        }
-        case FTYPE_RX_PACKET_FRAME:
-        {
-            RXPacketFrameLog dest;
-            logged = RXPacketFrameLog::toFrameType(frame, &dest);
-            if (logged)
-            {
-                // logger.log(dest);
-            }
-            break;
-        }
-    }
-
-    if (!logged)
-    {
-        APIFrameLog api;
-        APIFrameLog::fromAPIFrame(frame, &api);
-        // logger.log(api);
-    }
-}
-
-void Radio::logStatus()
-{
-    // 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
deleted file mode 100644
index 6460aefdda2ee0402f043790d5feee10052cd553..0000000000000000000000000000000000000000
--- a/src/boards/Payload/Main/Sensors.cpp
+++ /dev/null
@@ -1,499 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-//#include <ApogeeDetectionAlgorithm/ADAController.h>
-#include <Payload/PayloadBoard.h>
-//#include <LoggerService/LoggerService.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>
-
-#include <functional>
-#include <utility>
-
-using std::bind;
-using std::function;
-
-using namespace Boardcore;
-using namespace PayloadBoard::SensorConfigs;
-
-// BMX160 Watermark interrupt
-void __attribute__((used)) EXTI5_IRQHandlerImpl()
-{
-    using namespace PayloadBoard;
-
-    /*if (Payload::getInstance().sensors->imu_bmx160 != nullptr)
-    {
-        Payload::getInstance().ensors->imu_bmx160->IRQupdateTimestamp(
-            TimestampTimer::getInstance().getTimestamp());
-    }*/
-}
-
-namespace PayloadBoard
-{
-
-using namespace SensorConfigs;
-
-Sensors::Sensors(SPIBusInterface& spi1_bus, TaskScheduler* scheduler)
-    : spi1_bus(spi1_bus)
-{
-    // sensors are added to the map ordered by increasing period
-    ADS1118Init();
-    magLISinit();
-    imuBMXInit();
-    imuBMXWithCorrectionInit();
-    pressDigiInit();
-    pressPitotInit();
-    pressDPLVaneInit();
-    pressStaticInit();
-    gpsUbloxInit();
-    internalAdcInit();
-    batteryVoltageInit();
-
-    sensor_manager = new SensorManager(sensors_map, scheduler);
-}
-
-Sensors::~Sensors()
-{
-    delete imu_bmx160;
-    delete press_digital;
-    delete gps_ublox;
-    delete internal_adc;
-    delete battery_voltage;
-    delete adc_ads1118;
-    delete press_pitot;
-    delete press_dpl_vane;
-    delete press_static_port;
-    delete mag_lis3mdl;
-
-    sensor_manager->stop();
-    delete sensor_manager;
-}
-
-bool Sensors::start()
-{
-    GpioPin int_pin = miosix::sensors::bmx160::intr::getPin();
-    enableExternalInterrupt(int_pin.getPort(), int_pin.getNumber(),
-                            InterruptTrigger::FALLING_EDGE);
-
-    gps_ublox->start();
-
-    bool sm_start_result = sensor_manager->start();
-
-    // if not init ok, set failing sensors in sensors status
-    if (!sm_start_result)
-    {
-        updateSensorsStatus();
-    }
-
-    // LoggerService::getInstance().log(status);
-
-    return sm_start_result;
-}
-
-void Sensors::calibrate()
-{
-    imu_bmx160_with_correction->calibrate();
-    // LoggerService::getInstance().log(
-    //      imu_bmx160_with_correction->getGyroscopeBiases());
-
-    press_pitot->calibrate();
-
-    // use the digital barometer as a reference to compute the offset of the
-    // analog one (static ports sensor)
-    Stats press_digi_stats;
-    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().pressure);
-    }
-    press_static_port->setReferencePressure(press_digi_stats.getStats().mean);
-    press_static_port->calibrate();
-
-    // wait differential and static barometers calibration end
-    while (press_pitot->isCalibrating() && press_static_port->isCalibrating())
-    {
-        Thread::sleep(10);
-    }
-}
-
-void Sensors::internalAdcInit()
-{
-    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));
-    sensors_map.emplace(std::make_pair(internal_adc, info));
-
-    LOG_INFO(log, "InternalADC setup done!");
-}
-
-void Sensors::batteryVoltageInit()
-{
-    function<ADCData()> voltage_fun(
-        bind(&InternalADC::getVoltage, internal_adc, ADC_BATTERY_VOLTAGE));
-    battery_voltage =
-        new BatteryVoltageSensor(voltage_fun, BATTERY_VOLTAGE_COEFF);
-
-    SensorInfo info("BatterySensor", SAMPLE_PERIOD_INTERNAL_ADC,
-                    bind(&Sensors::batteryVoltageCallback, this));
-
-    sensors_map.emplace(std::make_pair(battery_voltage, info));
-
-    LOG_INFO(log, "Battery voltage sensor setup done!");
-}
-
-void Sensors::pressDigiInit()
-{
-    SPIBusConfig spi_cfg{};
-    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));
-
-    sensors_map.emplace(std::make_pair(press_digital, info));
-
-    LOG_INFO(log, "MS5803 pressure sensor setup done!");
-}
-
-void Sensors::ADS1118Init()
-{
-    SPIBusConfig spi_cfg = ADS1118::getDefaultSPIConfig();
-    spi_cfg.clockDivider = SPI::ClockDivider::DIV_64;
-
-    ADS1118::ADS1118Config ads1118Config = ADS1118::ADS1118_DEFAULT_CONFIG;
-    ads1118Config.bits.mode = ADS1118::ADS1118Mode::CONTIN_CONV_MODE;
-
-    adc_ads1118 = new ADS1118(spi1_bus, miosix::sensors::ads1118::cs::getPin(),
-                              ads1118Config, spi_cfg);
-
-    adc_ads1118->enableInput(ADC_CH_STATIC_PORT, ADC_DR_STATIC_PORT,
-                             ADC_PGA_STATIC_PORT);
-
-    adc_ads1118->enableInput(ADC_CH_PITOT_PORT, ADC_DR_PITOT_PORT,
-                             ADC_PGA_PITOT_PORT);
-    adc_ads1118->enableInput(ADC_CH_DPL_PORT, ADC_DR_DPL_PORT,
-                             ADC_PGA_DPL_PORT);
-
-    adc_ads1118->enableInput(ADC_CH_VREF, ADC_DR_VREF, ADC_PGA_VREF);
-
-    SensorInfo info("ADS1118", SAMPLE_PERIOD_ADC_ADS1118,
-                    bind(&Sensors::ADS1118Callback, this));
-    sensors_map.emplace(std::make_pair(adc_ads1118, info));
-
-    LOG_INFO(log, "ADS1118 setup done!");
-}
-
-void Sensors::pressPitotInit()
-{
-    function<ADCData()> voltage_fun(
-        bind(&ADS1118::getVoltage, adc_ads1118, ADC_CH_PITOT_PORT));
-    press_pitot = new SSCDRRN015PDA(voltage_fun, REFERENCE_VOLTAGE,
-                                    PRESS_PITOT_CALIB_SAMPLES_NUM);
-
-    SensorInfo info("DiffBarometer", SAMPLE_PERIOD_PRESS_PITOT,
-                    bind(&Sensors::pressPitotCallback, this));
-
-    sensors_map.emplace(std::make_pair(press_pitot, info));
-
-    LOG_INFO(log, "Diff pressure sensor setup done!");
-}
-
-void Sensors::pressDPLVaneInit()
-{
-    function<ADCData()> voltage_fun(
-        bind(&ADS1118::getVoltage, adc_ads1118, ADC_CH_DPL_PORT));
-    press_dpl_vane = new SSCDANN030PAA(voltage_fun, REFERENCE_VOLTAGE);
-
-    SensorInfo info("DeploymentBarometer", SAMPLE_PERIOD_PRESS_DPL,
-                    bind(&Sensors::pressDPLVaneCallback, this));
-
-    sensors_map.emplace(std::make_pair(press_dpl_vane, info));
-
-    LOG_INFO(log, "DPL pressure sensor setup done!");
-}
-
-void Sensors::pressStaticInit()
-{
-    function<ADCData()> voltage_fun(
-        bind(&ADS1118::getVoltage, adc_ads1118, ADC_CH_STATIC_PORT));
-    press_static_port = new MPXHZ6130A(voltage_fun, REFERENCE_VOLTAGE,
-                                       PRESS_STATIC_CALIB_SAMPLES_NUM,
-                                       PRESS_STATIC_MOVING_AVG_COEFF);
-
-    SensorInfo info("StaticPortsBarometer", SAMPLE_PERIOD_PRESS_STATIC,
-                    bind(&Sensors::pressStaticCallback, this));
-
-    sensors_map.emplace(std::make_pair(press_static_port, info));
-
-    LOG_INFO(log, "Static pressure sensor setup done!");
-}
-
-void Sensors::imuBMXInit()
-{
-    SPIBusConfig spi_cfg;
-    spi_cfg.clockDivider = SPI::ClockDivider::DIV_8;
-
-    BMX160Config bmx_config;
-    bmx_config.fifoMode      = BMX160Config::FifoMode::HEADER;
-    bmx_config.fifoWatermark = IMU_BMX_FIFO_WATERMARK;
-    bmx_config.fifoInterrupt = BMX160Config::FifoInterruptPin::PIN_INT1;
-
-    bmx_config.temperatureDivider = IMU_BMX_TEMP_DIVIDER;
-
-    bmx_config.accelerometerRange = IMU_BMX_ACC_FULLSCALE_ENUM;
-    bmx_config.gyroscopeRange     = IMU_BMX_GYRO_FULLSCALE_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.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));
-
-    sensors_map.emplace(std::make_pair(imu_bmx160, info));
-
-    LOG_INFO(log, "BMX160 Setup done!");
-}
-
-void Sensors::imuBMXWithCorrectionInit()
-{
-    // Read the correction parameters
-    BMX160CorrectionParameters correctionParameters =
-        BMX160WithCorrection::readCorrectionParametersFromFile(
-            BMX160_CORRECTION_PARAMETERS_FILE);
-
-    // Print the calibration parameters
-    TRACE("[Sensors] Current accelerometer bias vector\n");
-    TRACE("[Sensors] b = [    % 2.5f    % 2.5f    % 2.5f    ]\n",
-          correctionParameters.accelParams(0, 1),
-          correctionParameters.accelParams(1, 1),
-          correctionParameters.accelParams(2, 1));
-    TRACE("[Sensors] Matrix to be multiplied to the input vector\n");
-    TRACE("[Sensors]     |    % 2.5f    % 2.5f    % 2.5f    |\n",
-          correctionParameters.accelParams(0, 0), 0.f, 0.f);
-    TRACE("[Sensors] M = |    % 2.5f    % 2.5f    % 2.5f    |\n", 0.f,
-          correctionParameters.accelParams(1, 0), 0.f);
-    TRACE("[Sensors]     |    % 2.5f    % 2.5f    % 2.5f    |\n\n", 0.f, 0.f,
-          correctionParameters.accelParams(2, 0));
-    TRACE("[Sensors] Current magnetometer bias vector\n");
-    TRACE("[Sensors] b = [    % 2.5f    % 2.5f    % 2.5f    ]\n",
-          correctionParameters.magnetoParams(0, 1),
-          correctionParameters.magnetoParams(1, 1),
-          correctionParameters.magnetoParams(2, 1));
-    TRACE("[Sensors] Matrix to be multiplied to the input vector\n");
-    TRACE("[Sensors]     |    % 2.5f    % 2.5f    % 2.5f    |\n",
-          correctionParameters.magnetoParams(0, 0), 0.f, 0.f);
-    TRACE("[Sensors] M = |    % 2.5f    % 2.5f    % 2.5f    |\n", 0.f,
-          correctionParameters.magnetoParams(1, 0), 0.f);
-    TRACE("[Sensors]     |    % 2.5f    % 2.5f    % 2.5f    |\n\n", 0.f, 0.f,
-          correctionParameters.magnetoParams(2, 0));
-    TRACE(
-        "[Sensors] The current minimun number of gyroscope samples for "
-        "calibration is %d\n",
-        correctionParameters.minGyroSamplesForCalibration);
-
-    imu_bmx160_with_correction = new BMX160WithCorrection(
-        imu_bmx160, correctionParameters, BMX160_AXIS_ROTATION);
-
-    SensorInfo info("BMX160WithCorrection", SAMPLE_PERIOD_IMU_BMX,
-                    bind(&Sensors::imuBMXWithCorrectionCallback, this));
-
-    sensors_map.emplace(std::make_pair(imu_bmx160_with_correction, info));
-
-    LOG_INFO(log, "BMX160WithCorrection Setup done!");
-}
-
-void Sensors::magLISinit()
-{
-    SPIBusConfig busConfig;
-    busConfig.clockDivider = SPI::ClockDivider::DIV_32;
-
-    LIS3MDL::Config config;
-    config.odr                = MAG_LIS_ODR_ENUM;
-    config.scale              = MAG_LIS_FULLSCALE;
-    config.temperatureDivider = 1;
-
-    mag_lis3mdl = new LIS3MDL(spi1_bus, miosix::sensors::lis3mdl::cs::getPin(),
-                              busConfig, config);
-
-    SensorInfo info("LIS3MDL", SAMPLE_PERIOD_MAG_LIS,
-                    bind(&Sensors::magLISCallback, this));
-
-    sensors_map.emplace(std::make_pair(mag_lis3mdl, info));
-
-    LOG_INFO(log, "LIS3MDL Setup done!");
-}
-
-void Sensors::gpsUbloxInit()
-{
-    gps_ublox = new UbloxGPSSerial(GPS_BAUD_RATE, GPS_SAMPLE_RATE);
-
-    SensorInfo info("UbloxGPS", GPS_SAMPLE_PERIOD,
-                    bind(&Sensors::gpsUbloxCallback, this));
-
-    sensors_map.emplace(std::make_pair(gps_ublox, info));
-
-    LOG_INFO(log, "Ublox GPS Setup done!");
-}
-
-void Sensors::internalAdcCallback()
-{
-    // LoggerService::getInstance().log(internal_adc->getLastSample());
-}
-
-void Sensors::batteryVoltageCallback()
-{
-    static float v = battery_voltage->getLastSample().batVoltage;
-    if (v < BATTERY_MIN_SAFE_VOLTAGE)
-    {
-        battery_critical_counter++;
-        // every 30 seconds to avoid filling the log (if debug disabled)
-        if (battery_critical_counter % 30 == 0)
-        {
-            LOG_CRIT(log, "*** LOW BATTERY *** ---> Voltage = {:02f}", v);
-            battery_critical_counter = 0;
-        }
-    }
-
-    // LoggerService::getInstance().log(battery_voltage->getLastSample());
-}
-
-void Sensors::pressDigiCallback()
-{
-    // LoggerService::getInstance().log(press_digital->getLastSample());
-}
-
-void Sensors::ADS1118Callback()
-{
-    // LoggerService::getInstance().log(adc_ads1118->getLastSample());
-}
-
-void Sensors::pressPitotCallback()
-{
-    // SSCDRRN015PDAData d = press_pitot->getLastSample();
-    // LoggerService::getInstance().log(d);
-
-    /*ADAReferenceValues rv =
-        DeathStack::getInstance()
-            ->state_machines->ada_controller->getReferenceValues();
-
-    float rel_density = aeroutils::relDensity(
-        press_digital->getLastSample().pressure, rv.ref_pressure,
-    rv.ref_altitude, rv.ref_temperature); if (rel_density != 0.0f)
-    {
-        float airspeed = sqrtf(2 * fabs(d.pressure) / rel_density);
-
-        AirSpeedPitot
-    aspeed_data{TimestampTimer::getInstance().getTimestamp(), airspeed};
-        //LoggerService::getInstance().log(aspeed_data);
-    }*/
-}
-
-void Sensors::pressDPLVaneCallback()
-{
-    // LoggerService::getInstance().log(press_dpl_vane->getLastSample());
-}
-
-void Sensors::pressStaticCallback()
-{
-    // LoggerService::getInstance().log(press_static_port->getLastSample());
-}
-
-void Sensors::imuBMXCallback()
-{
-    // uint8_t fifo_size = imu_bmx160->getLastFifoSize();
-    // auto& fifo        = imu_bmx160->getLastFifo();
-
-    // LoggerService::getInstance().log(imu_bmx160->getTemperature());
-
-    // for (uint8_t i = 0; i < fifo_size; ++i)
-    // {
-    //     LoggerService::getInstance().log(fifo.at(i));
-    // }
-
-    // LoggerService::getInstance().log(imu_bmx160->getFifoStats());
-}
-
-void Sensors::imuBMXWithCorrectionCallback()
-{
-    // LoggerService::getInstance().log(
-    //    imu_bmx160_with_correction->getLastSample());
-}
-
-void Sensors::magLISCallback()
-{
-    // LoggerService::getInstance().log(mag_lis3mdl->getLastSample());
-}
-
-void Sensors::gpsUbloxCallback()
-{
-    // LoggerService::getInstance().log(gps_ublox->getLastSample());
-}
-
-void Sensors::updateSensorsStatus()
-{
-    SensorInfo info = sensor_manager->getSensorInfo(imu_bmx160);
-    if (!info.isInitialized)
-    {
-        status.bmx160 = SensorDriverStatus::DRIVER_ERROR;
-    }
-
-    info = sensor_manager->getSensorInfo(mag_lis3mdl);
-    if (!info.isInitialized)
-    {
-        status.lis3mdl = SensorDriverStatus::DRIVER_ERROR;
-    }
-
-    info = sensor_manager->getSensorInfo(gps_ublox);
-    if (!info.isInitialized)
-    {
-        status.gps = SensorDriverStatus::DRIVER_ERROR;
-    }
-
-    info = sensor_manager->getSensorInfo(internal_adc);
-    if (!info.isInitialized)
-    {
-        status.internal_adc = SensorDriverStatus::DRIVER_ERROR;
-    }
-
-    info = sensor_manager->getSensorInfo(adc_ads1118);
-    if (!info.isInitialized)
-    {
-        status.ads1118 = SensorDriverStatus::DRIVER_ERROR;
-    }
-}
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/Main/Sensors.h b/src/boards/Payload/Main/Sensors.h
deleted file mode 100644
index 98118dfa7f374401461dd1b7633be3ec1c6bb356..0000000000000000000000000000000000000000
--- a/src/boards/Payload/Main/Sensors.h
+++ /dev/null
@@ -1,128 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <Payload/Main/SensorsData.h>
-#include <diagnostic/PrintLogger.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>
-#include <sensors/analog/pressure/honeywell/SSCDANN030PAA.h>
-#include <sensors/analog/pressure/honeywell/SSCDRRN015PDA.h>
-
-#include <map>
-
-namespace PayloadBoard
-{
-
-/**
- * @brief Initializes all the sensors on the death stack
- *
- */
-class Sensors
-{
-public:
-    Boardcore::SensorManager* sensor_manager = nullptr;
-
-    Boardcore::InternalADC* internal_adc             = nullptr;
-    Boardcore::BatteryVoltageSensor* battery_voltage = nullptr;
-
-    Boardcore::MS5803* press_digital = nullptr;
-
-    Boardcore::ADS1118* adc_ads1118          = nullptr;
-    Boardcore::SSCDANN030PAA* press_dpl_vane = nullptr;
-    Boardcore::MPXHZ6130A* press_static_port = nullptr;
-    Boardcore::SSCDRRN015PDA* press_pitot    = nullptr;
-
-    Boardcore::BMX160* imu_bmx160                               = nullptr;
-    Boardcore::BMX160WithCorrection* imu_bmx160_with_correction = nullptr;
-    Boardcore::LIS3MDL* mag_lis3mdl                             = nullptr;
-    Boardcore::UbloxGPS* gps_ublox                              = nullptr;
-
-    Sensors(Boardcore::SPIBusInterface& spi1_bus_,
-            Boardcore::TaskScheduler* scheduler);
-
-    ~Sensors();
-
-    bool start();
-
-    void calibrate();
-
-private:
-    void internalAdcInit();
-    void internalAdcCallback();
-
-    void batteryVoltageInit();
-    void batteryVoltageCallback();
-
-    void pressDigiInit();
-    void pressDigiCallback();
-
-    void ADS1118Init();
-    void ADS1118Callback();
-
-    void pressPitotInit();
-    void pressPitotCallback();
-
-    void pressDPLVaneInit();
-    void pressDPLVaneCallback();
-
-    void pressStaticInit();
-    void pressStaticCallback();
-
-    void imuBMXInit();
-    void imuBMXCallback();
-
-    void imuBMXWithCorrectionInit();
-    void imuBMXWithCorrectionCallback();
-
-    void magLISinit();
-    void magLISCallback();
-
-    void gpsUbloxInit();
-    void gpsUbloxCallback();
-
-    void updateSensorsStatus();
-
-    Boardcore::SPIBusInterface& spi1_bus;
-
-    Boardcore::SensorManager::SensorMap_t sensors_map;
-
-    SensorsStatus status;
-
-    Boardcore::PrintLogger log = Boardcore::Logging::getLogger("sensors");
-
-    unsigned int battery_critical_counter = 0;
-};
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/Main/SensorsData.h b/src/boards/Payload/Main/SensorsData.h
deleted file mode 100644
index c86847fda874d5694e2ada2eb47aa338624f10f4..0000000000000000000000000000000000000000
--- a/src/boards/Payload/Main/SensorsData.h
+++ /dev/null
@@ -1,69 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-namespace PayloadBoard
-{
-
-struct AirSpeedPitot
-{
-    uint64_t timestamp;
-    float airspeed;
-
-    static std::string header() { return "timestamp,airspeed\n"; }
-
-    void print(std::ostream& os) const
-    {
-        os << timestamp << "," << airspeed << "\n";
-    }
-};
-
-enum SensorDriverStatus
-{
-    DRIVER_ERROR = 0,
-    DRIVER_OK    = 1
-};
-
-struct SensorsStatus
-{
-    uint8_t bmx160       = DRIVER_OK;
-    uint8_t ms5803       = DRIVER_OK;
-    uint8_t lis3mdl      = DRIVER_OK;
-    uint8_t gps          = DRIVER_OK;
-    uint8_t internal_adc = DRIVER_OK;
-    uint8_t ads1118      = DRIVER_OK;
-
-    static std::string header()
-    {
-        return "bmx160,ms5803,lis3mdl,gps,internal_adc,ads1118\n";
-    }
-
-    void print(std::ostream& os) const
-    {
-        os << (int)bmx160 << "," << (int)ms5803 << "," << (int)lis3mdl << ","
-           << (int)gps << "," << (int)internal_adc << "," << (int)ads1118
-           << "\n";
-    }
-};
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/PayloadBoard.h b/src/boards/Payload/PayloadBoard.h
deleted file mode 100644
index a8e87f1cf9abf58306e8b6950b57e4e25ac6d427..0000000000000000000000000000000000000000
--- a/src/boards/Payload/PayloadBoard.h
+++ /dev/null
@@ -1,237 +0,0 @@
-/* Copyright (c) 2019 Skyward Experimental Rocketry
- * Author: Alvise de'Faveri Tron
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <Payload/PayloadStatus.h>
-//#include <LoggerService/LoggerService.h>
-#include <Payload/Main/Actuators.h>
-#include <Payload/Main/Bus.h>
-#include <Payload/Main/Radio.h>
-#include <Payload/Main/Sensors.h>
-//#include <Payload/Main/StateMachines.h>
-#include <Payload/PinHandler/PinHandler.h>
-#include <System/StackLogger.h>
-#include <System/TaskID.h>
-#include <events/EventBroker.h>
-#include <events/EventData.h>
-#include <events/Events.h>
-#include <events/Topics.h>
-#include <events/utils/EventInjector.h>
-#include <events/utils/EventSniffer.h>
-
-#include <functional>
-#include <stdexcept>
-#include <vector>
-
-using std::bind;
-
-namespace PayloadBoard
-{
-
-// Add heres the events that you don't want to be TRACEd in
-// Payload.logEvent()
-static const std::vector<uint8_t> TRACE_EVENT_BLACKLIST{
-    EV_SEND_HR_TM, EV_SEND_LR_TM, EV_SEND_TEST_TM, EV_SEND_SENS_TM};
-/**
- * This file provides a simplified way to initialize and monitor all
- * the components of the Payload.
- */
-class Payload : public Boardcore::Singleton<Payload>
-{
-    friend class Boardcore::Singleton<Payload>;
-
-public:
-    // Shared Components
-    Boardcore::EventBroker* broker;
-    // LoggerService* logger;
-
-    Boardcore::EventSniffer* sniffer;
-
-    // StateMachines* state_machines;
-    Bus* bus;
-    Sensors* sensors;
-    Radio* radio;
-    Actuators* actuators;
-
-    PinHandler* pin_handler;
-
-    Boardcore::TaskScheduler* scheduler;
-
-    void start()
-    {
-        if (!broker->start())
-        {
-            LOG_ERR(log, "Error starting EventBroker");
-            status.setError(&PayloadStatus::ev_broker);
-        }
-
-        /*if (!radio->start())
-        {
-            LOG_ERR(log, "Error starting radio module");
-            status.setError(&PayloadStatus::radio);
-        }*/
-
-        if (!sensors->start())
-        {
-            LOG_ERR(log, "Error starting sensors");
-            status.setError(&PayloadStatus::sensors);
-        }
-
-        /*if (!state_machines->start())
-        {
-            LOG_ERR(log, "Error starting state machines");
-            status.setError(&PayloadStatus::state_machines);
-        }*/
-
-        if (!pin_handler->start())
-        {
-            LOG_ERR(log, "Error starting PinObserver");
-            status.setError(&PayloadStatus::pin_obs);
-        }
-
-#ifdef DEBUG
-        injector->start();
-#endif
-
-        // 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(Boardcore::Event{EV_INIT_ERROR},
-                              TOPIC_FLIGHT_EVENTS);
-        }
-        else
-        {
-            LOG_INFO(log, "Initalization ok");
-            sEventBroker.post(Boardcore::Event{EV_INIT_OK},
-                              TOPIC_FLIGHT_EVENTS);
-        }
-    }
-
-    /*void startLogger()
-    {
-        try
-        {
-            logger->start();
-            LOG_INFO(log, "Logger started");
-        }
-        catch (const std::runtime_error& re)
-        {
-            LOG_ERR(log, "SD Logger init error");
-            status.setError(&PayloadStatus::logger);
-        }
-
-        logger->log(logger->getLogger().getLoggerStats());
-    }*/
-
-private:
-    /**
-     * @brief Initialize Everything.
-     */
-    Payload()
-    {
-        /* Shared components */
-        // logger = Singleton<LoggerService>::getInstance();
-        // startLogger();
-
-        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(&Payload::logEvent, this, _1, _2));
-        }*/
-
-        scheduler = new Boardcore::TaskScheduler();
-
-        bus       = new Bus();
-        radio     = new Radio(*bus->spi2);
-        sensors   = new Sensors(*bus->spi1, scheduler);
-        actuators = new Actuators();
-
-        pin_handler = new PinHandler();
-
-#ifdef DEBUG
-        injector = new Boardcore::EventInjector();
-#endif
-
-        LOG_INFO(log, "Init finished");
-    }
-
-    /**
-     * @brief Helpers for debugging purposes.
-     */
-    /*void logEvent(uint8_t event, uint8_t topic)
-    {
-        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
-        // serial terminal
-        for (uint8_t bl_ev : TRACE_EVENT_BLACKLIST)
-        {
-            if (bl_ev == event)
-            {
-                return;
-            }
-        }
-        LOG_DEBUG(log, "{:s} on {:s}",
-getEventString(event), getTopicString(topic)); #endif
-    }*/
-
-    inline void postEvent(Boardcore::Event ev, uint8_t topic)
-    {
-        broker->post(ev, topic);
-    }
-
-    /*void addSchedulerStatsTask()
-    {
-        // add lambda to log scheduler tasks statistics
-        scheduler.add(
-            [&]() {
-                std::vector<TaskStatsResult> scheduler_stats =
-                    scheduler.getTaskStats();
-
-                for (TaskStatsResult stat : scheduler_stats)
-                {
-                    logger->log(stat);
-                }
-
-                StackLogger::getInstance().updateStack(THID_TASK_SCHEDULER);
-            },
-            1000,  // 1 hz
-            TASK_SCHEDULER_STATS_ID, miosix::getTick());
-    }*/
-
-    Boardcore::EventInjector* injector;
-    PayloadStatus status{};
-
-    Boardcore::PrintLogger log = Boardcore::Logging::getLogger("Payload");
-};
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/PayloadStatus.h b/src/boards/Payload/PayloadStatus.h
deleted file mode 100644
index c8e6e516f0f142a7daa4e45106591e0700e9c3f9..0000000000000000000000000000000000000000
--- a/src/boards/Payload/PayloadStatus.h
+++ /dev/null
@@ -1,75 +0,0 @@
-/* Copyright (c) 2019 Skyward Experimental Rocketry
- * Author: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <cstdint>
-#include <ostream>
-#include <string>
-
-namespace PayloadBoard
-{
-
-enum PayloadComponentStatus
-{
-    COMP_ERROR = 0,
-    COMP_OK    = 1
-};
-
-struct PayloadStatus
-{
-    // Logic OR of all components errors.
-    uint8_t payload_board = COMP_OK;
-
-    uint8_t logger         = COMP_OK;
-    uint8_t ev_broker      = COMP_OK;
-    uint8_t pin_obs        = COMP_OK;
-    uint8_t sensors        = COMP_OK;
-    uint8_t radio          = COMP_OK;
-    uint8_t state_machines = COMP_OK;
-
-    /**
-     * @brief Helper method to signal an error in the PayloadStatus struct.
-     *
-     * @param component_status Pointer to a member of PayloadStatus
-     * Eg: setError(&PayloadStatus::dpl)
-     */
-    void setError(uint8_t PayloadStatus::*component_status)
-    {
-        this->*component_status = COMP_ERROR;
-        payload_board           = COMP_ERROR;
-    }
-
-    static std::string header()
-    {
-        return "logger,ev_broker,pin_obs,sensors,radio,state_machines\n";
-    }
-
-    void print(std::ostream& os)
-    {
-        os << (int)logger << "," << (int)ev_broker << "," << (int)pin_obs << ","
-           << (int)sensors << "," << (int)radio << "," << (int)state_machines
-           << "\n";
-    }
-};
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/PinHandler/PinHandler.cpp b/src/boards/Payload/PinHandler/PinHandler.cpp
deleted file mode 100644
index 7fb6eedf2434818fc433b324a86fbf28f84f658b..0000000000000000000000000000000000000000
--- a/src/boards/Payload/PinHandler/PinHandler.cpp
+++ /dev/null
@@ -1,86 +0,0 @@
-/* Copyright (c) 2019-2021 Skyward Experimental Rocketry
- * Authors: Luca Erbetta, Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-//#include <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>
-
-#include <functional>
-
-using std::bind;
-using namespace Boardcore;
-
-namespace PayloadBoard
-{
-
-PinHandler::PinHandler()
-    : pin_obs(PIN_POLL_INTERVAL)  //, logger(LoggerService::getInstance())
-{
-    // Used for _1, _2. See std::bind cpp reference
-    using namespace std::placeholders;
-
-    // Noseconse pin callbacks registration
-    PinObserver::OnTransitionCallback nc_transition_cb =
-        bind(&PinHandler::onNCPinTransition, this, _1, _2);
-
-    PinObserver::OnStateChangeCallback nc_statechange_cb =
-        bind(&PinHandler::onNCPinStateChange, this, _1, _2, _3);
-
-    pin_obs.observePin(nosecone_pin.getPort(), nosecone_pin.getNumber(),
-                       TRIGGER_NC_DETACH_PIN, nc_transition_cb,
-                       THRESHOLD_NC_DETACH_PIN, nc_statechange_cb);
-}
-
-void PinHandler::onNCPinTransition(unsigned int p, unsigned char n)
-{
-    UNUSED(p);
-    UNUSED(n);
-    sEventBroker.post(Event{EV_NC_DETACHED}, TOPIC_FLIGHT_EVENTS);
-
-    LOG_INFO(log, "Nosecone detached!");
-
-    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)
-{
-    UNUSED(p);
-    UNUSED(n);
-
-    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);
-}
-
-}  // namespace PayloadBoard
\ No newline at end of file
diff --git a/src/boards/Payload/PinHandler/PinHandler.h b/src/boards/Payload/PinHandler/PinHandler.h
deleted file mode 100644
index c7abde008c3b48a9eb6da9507a880debe4efbdf9..0000000000000000000000000000000000000000
--- a/src/boards/Payload/PinHandler/PinHandler.h
+++ /dev/null
@@ -1,83 +0,0 @@
-/* Copyright (c) 2019-2021 Skyward Experimental Rocketry
- * Authors: Luca Erbetta, Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <Payload/PinHandler/PinHandlerData.h>
-#include <Payload/configs/PinHandlerConfig.h>
-#include <diagnostic/PrintLogger.h>
-#include <utils/PinObserver.h>
-
-namespace PayloadBoard
-{
-
-/**
- * @brief Forward dec.
- */
-// class LoggerService;
-
-/**
- * @brief This class contains the handlers for both the launch pin (umbilical)
- * and the nosecone detachment pin.
- *
- * It uses boardcore's PinObserver to bind these functions to the GPIO pins.
- * The handlers post an event on the EventBroker.
- */
-class PinHandler
-{
-public:
-    PinHandler();
-
-    /**
-     * @brief Starts the pin observer.
-     *
-     */
-    bool start() { return pin_obs.start(); }
-
-    /**
-     * @brief Stops the pin observer.
-     *
-     */
-    void stop() { pin_obs.stop(); }
-
-    /**
-     * @brief Function called by the pinobserver when a nosecone pin detachment
-     * is detected.
-     *
-     * @param p
-     * @param n
-     */
-    void onNCPinTransition(unsigned int p, unsigned char n);
-
-    void onNCPinStateChange(unsigned int p, unsigned char n, int state);
-
-private:
-    PinStatus status_pin_nosecone{ObservedPin::NOSECONE};
-
-    Boardcore::PinObserver pin_obs;
-
-    // LoggerService* logger;
-    Boardcore::PrintLogger log =
-        Boardcore::Logging::getLogger("deathstack.pinhandler");
-};
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/WingControl/WingServo.cpp b/src/boards/Payload/WingControl/WingServo.cpp
deleted file mode 100644
index 7146eafa4b3ff85579fe69c884381aa3a1347300..0000000000000000000000000000000000000000
--- a/src/boards/Payload/WingControl/WingServo.cpp
+++ /dev/null
@@ -1,71 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include <Payload/WingControl/WingServo.h>
-
-using namespace Boardcore;
-using namespace PayloadBoard::WingConfigs;
-
-namespace PayloadBoard
-{
-
-WingServo::WingServo(TIM_TypeDef* const timer, TimerUtils::Channel channel,
-                     float minPosition, float maxPosition)
-    : ServoInterface(minPosition, maxPosition),
-      servo(timer, channel, 50, 500, 2500)
-{
-}
-
-WingServo::~WingServo() {}
-
-void WingServo::enable() { servo.enable(); }
-
-void WingServo::disable() { servo.disable(); }
-
-void WingServo::selfTest()
-{
-    float base   = (MAX_POS + RESET_POS) / 2;
-    float maxpos = base + WING_SERVO_WIGGLE_AMPLITUDE / 2;
-    float minpos = base - WING_SERVO_WIGGLE_AMPLITUDE / 2;
-
-    set(base, true);
-
-    for (int i = 0; i < 3; i++)
-    {
-        miosix::Thread::sleep(500);
-        set(maxpos, true);
-        miosix::Thread::sleep(500);
-        set(minpos, true);
-    }
-
-    miosix::Thread::sleep(500);
-    reset();
-}
-
-void WingServo::setPosition(float angle)
-{
-    this->currentPosition = angle;
-    // map position to [0;1] interval for the servo driver
-    servo.setPosition180Deg(angle);
-}
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/configs/PinHandlerConfig.h b/src/boards/Payload/configs/PinHandlerConfig.h
deleted file mode 100644
index 1f00ffe75b791cd231ec71e955270169096ecd7a..0000000000000000000000000000000000000000
--- a/src/boards/Payload/configs/PinHandlerConfig.h
+++ /dev/null
@@ -1,58 +0,0 @@
-/* Copyright (c) 2019-2021 Skyward Experimental Rocketry
- * Authors: Luca Erbetta, Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <interfaces-impl/hwmapping.h>
-#include <miosix.h>
-#include <utils/PinObserver.h>
-
-namespace PayloadBoard
-{
-
-static const unsigned int PIN_POLL_INTERVAL = 10;  // ms
-
-// // Launch pin config
-// static const GpioPin launch_pin(miosix::inputs::lp_dtch::getPin());
-// static const PinObserver::Transition TRIGGER_LAUNCH_PIN =
-//     PinObserver::Transition::FALLING_EDGE;
-// // How many consecutive times the launch pin should be detected as detached
-// // before triggering a launch event.
-// static const unsigned int THRESHOLD_LAUNCH_PIN = 10;
-
-// Nosecone detach pin config
-static const GpioPin nosecone_pin(miosix::inputs::nc_dtch::getPin());
-static const Boardcore::PinObserver::Transition TRIGGER_NC_DETACH_PIN =
-    Boardcore::PinObserver::Transition::FALLING_EDGE;
-// How many consecutive times the nosecone pin should be detected as detached
-// before triggering a nosecone detach event.
-static const unsigned int THRESHOLD_NC_DETACH_PIN = 10;
-
-// // Dpl servo actuation pin config
-// static const GpioPin dpl_servo_pin(miosix::inputs::expulsion_in::getPin());
-// static const PinObserver::Transition TRIGGER_DPL_SERVO_PIN =
-//     PinObserver::Transition::RISING_EDGE;
-// // How many consecutive times the deployment servo pin should be detected as
-// // detached before triggering a nosecone detach event.
-// static const unsigned int THRESHOLD_DPL_SERVO_PIN = 10;
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/configs/SensorsConfig.h b/src/boards/Payload/configs/SensorsConfig.h
deleted file mode 100644
index e00655539ff0127eb6dc5926212a3d582c47382b..0000000000000000000000000000000000000000
--- a/src/boards/Payload/configs/SensorsConfig.h
+++ /dev/null
@@ -1,153 +0,0 @@
-/* Copyright (c) 2015-2021 Skyward Experimental Rocketry
- * Author: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <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>
-
-using miosix::Gpio;
-
-namespace PayloadBoard
-{
-
-namespace SensorConfigs
-{
-
-static constexpr float INTERNAL_ADC_VREF = 3.3;
-static constexpr Boardcore::InternalADC::Channel ADC_BATTERY_VOLTAGE =
-    Boardcore::InternalADC::Channel::CH5;
-
-static constexpr float BATTERY_VOLTAGE_COEFF    = 5.98;
-static constexpr float BATTERY_MIN_SAFE_VOLTAGE = 10.5;  // [V]
-
-static constexpr Boardcore::ADS1118::ADS1118Mux ADC_CH_STATIC_PORT =
-    Boardcore::ADS1118::MUX_AIN0_GND;
-static constexpr Boardcore::ADS1118::ADS1118Mux ADC_CH_PITOT_PORT =
-    Boardcore::ADS1118::MUX_AIN1_GND;
-static constexpr Boardcore::ADS1118::ADS1118Mux ADC_CH_DPL_PORT =
-    Boardcore::ADS1118::MUX_AIN2_GND;
-static constexpr Boardcore::ADS1118::ADS1118Mux ADC_CH_VREF =
-    Boardcore::ADS1118::MUX_AIN3_GND;
-
-static constexpr Boardcore::ADS1118::ADS1118DataRate ADC_DR_STATIC_PORT =
-    Boardcore::ADS1118::DR_860;
-static constexpr Boardcore::ADS1118::ADS1118DataRate ADC_DR_PITOT_PORT =
-    Boardcore::ADS1118::DR_860;
-static constexpr Boardcore::ADS1118::ADS1118DataRate ADC_DR_DPL_PORT =
-    Boardcore::ADS1118::DR_860;
-static constexpr Boardcore::ADS1118::ADS1118DataRate ADC_DR_VREF =
-    Boardcore::ADS1118::DR_860;
-
-static constexpr Boardcore::ADS1118::ADS1118Pga ADC_PGA_STATIC_PORT =
-    Boardcore::ADS1118::FSR_6_144;
-static constexpr Boardcore::ADS1118::ADS1118Pga ADC_PGA_PITOT_PORT =
-    Boardcore::ADS1118::FSR_6_144;
-static constexpr Boardcore::ADS1118::ADS1118Pga ADC_PGA_DPL_PORT =
-    Boardcore::ADS1118::FSR_6_144;
-static constexpr Boardcore::ADS1118::ADS1118Pga ADC_PGA_VREF =
-    Boardcore::ADS1118::FSR_6_144;
-
-// Sampling periods in milliseconds
-static constexpr unsigned int SAMPLE_PERIOD_INTERNAL_ADC =
-    1000;  // only for battery voltage
-static constexpr unsigned int SAMPLE_PERIOD_ADC_ADS1118 = 6;
-
-static constexpr unsigned int SAMPLE_PERIOD_PRESS_DIGITAL = 15;
-static constexpr unsigned int TEMP_DIVIDER_PRESS_DIGITAL  = 5;
-
-static constexpr unsigned int SAMPLE_PERIOD_PRESS_PITOT =
-    SAMPLE_PERIOD_ADC_ADS1118 * 4;
-static constexpr unsigned int SAMPLE_PERIOD_PRESS_DPL =
-    SAMPLE_PERIOD_ADC_ADS1118 * 4;
-static constexpr unsigned int SAMPLE_PERIOD_PRESS_STATIC =
-    SAMPLE_PERIOD_ADC_ADS1118 * 4;
-
-static constexpr unsigned int PRESS_PITOT_CALIB_SAMPLES_NUM  = 500;
-static constexpr unsigned int PRESS_STATIC_CALIB_SAMPLES_NUM = 500;
-static constexpr float PRESS_STATIC_MOVING_AVG_COEFF         = 0.95;
-
-static constexpr Boardcore::BMX160Config::AccelerometerRange
-    IMU_BMX_ACC_FULLSCALE_ENUM =
-        Boardcore::BMX160Config::AccelerometerRange::G_16;
-static constexpr Boardcore::BMX160Config::GyroscopeRange
-    IMU_BMX_GYRO_FULLSCALE_ENUM =
-        Boardcore::BMX160Config::GyroscopeRange::DEG_1000;
-
-static constexpr unsigned int IMU_BMX_ACC_GYRO_ODR = 1600;
-static constexpr Boardcore::BMX160Config::OutputDataRate
-    IMU_BMX_ACC_GYRO_ODR_ENUM =
-        Boardcore::BMX160Config::OutputDataRate::HZ_1600;
-static constexpr unsigned int IMU_BMX_MAG_ODR = 100;
-static constexpr Boardcore::BMX160Config::OutputDataRate IMU_BMX_MAG_ODR_ENUM =
-    Boardcore::BMX160Config::OutputDataRate::HZ_100;
-
-static constexpr unsigned int IMU_BMX_FIFO_HEADER_SIZE = 1;
-static constexpr unsigned int IMU_BMX_ACC_DATA_SIZE    = 6;
-static constexpr unsigned int IMU_BMX_GYRO_DATA_SIZE   = 6;
-static constexpr unsigned int IMU_BMX_MAG_DATA_SIZE    = 8;
-
-static constexpr unsigned int IMU_BMX_FIFO_WATERMARK = 80;
-
-// How many bytes go into the fifo each second
-static constexpr unsigned int IMU_BMX_FIFO_FILL_RATE =
-    IMU_BMX_ACC_GYRO_ODR * (IMU_BMX_FIFO_HEADER_SIZE + IMU_BMX_ACC_DATA_SIZE +
-                            IMU_BMX_GYRO_DATA_SIZE) +
-    IMU_BMX_MAG_ODR * (IMU_BMX_MAG_DATA_SIZE + IMU_BMX_FIFO_HEADER_SIZE);
-
-// How long does it take for the bmx fifo to fill up
-static constexpr unsigned int IMU_BMX_FIFO_FILL_TIME =
-    1024 * 1000 / IMU_BMX_FIFO_FILL_RATE;
-
-// Sample before the fifo is full, but slightly after the watermark level
-// (watermark + 30) ---> high slack due to scheduler imprecision,
-//                       avoid clearing the fifo before the interrupt
-static constexpr unsigned int SAMPLE_PERIOD_IMU_BMX =
-    IMU_BMX_FIFO_FILL_TIME * (IMU_BMX_FIFO_WATERMARK + 30) * 4 / 1024;
-
-static constexpr unsigned int IMU_BMX_TEMP_DIVIDER = 1;
-
-// IMU axis rotation
-static const Boardcore::AxisOrthoOrientation BMX160_AXIS_ROTATION = {
-    Boardcore::Direction::NEGATIVE_Z, Boardcore::Direction::POSITIVE_Y};
-
-static constexpr char BMX160_CORRECTION_PARAMETERS_FILE[30] =
-    "/sd/bmx160_params.csv";
-
-static constexpr unsigned int SAMPLE_PERIOD_MAG_LIS = 15;
-static constexpr Boardcore::LIS3MDL::ODR MAG_LIS_ODR_ENUM =
-    Boardcore::LIS3MDL::ODR_80_HZ;
-static constexpr Boardcore::LIS3MDL::FullScale MAG_LIS_FULLSCALE =
-    Boardcore::LIS3MDL::FS_4_GAUSS;
-
-static constexpr unsigned int GPS_SAMPLE_RATE   = 25;
-static constexpr unsigned int GPS_SAMPLE_PERIOD = 1000 / GPS_SAMPLE_RATE;
-static constexpr unsigned int GPS_BAUD_RATE     = 460800;
-
-static constexpr float REFERENCE_VOLTAGE = 5.0;
-}  // namespace SensorConfigs
-
-}  // namespace PayloadBoard
diff --git a/src/boards/Payload/WingControl/WingServo.h b/src/boards/common/Algorithm.h
similarity index 58%
rename from src/boards/Payload/WingControl/WingServo.h
rename to src/boards/common/Algorithm.h
index 19edecee750b8de098e7b359e46426e1fbe2ac19..7f8ace5e3da652e594dbeee7101a2ee39e8a9b83 100644
--- a/src/boards/Payload/WingControl/WingServo.h
+++ b/src/boards/common/Algorithm.h
@@ -1,4 +1,4 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
+/* Copyright (c) 2020 Skyward Experimental Rocketry
  * Author: Luca Conterio
  *
  * Permission is hereby granted, free of charge, to any person obtaining a copy
@@ -22,43 +22,44 @@
 
 #pragma once
 
-#include <Payload/configs/WingConfig.h>
-#include <common/ServoInterface.h>
-#include <drivers/servo/Servo.h>
-#include <miosix.h>
-
-namespace PayloadBoard
-{
-
-class WingServo : public ServoInterface
+class Algorithm
 {
-
 public:
-    WingServo(TIM_TypeDef* const timer, Boardcore::TimerUtils::Channel channel,
-              float minPosition = WingConfigs::WING_SERVO_MIN_POS,
-              float maxPosition = WingConfigs::WING_SERVO_MAX_POS);
-
-    virtual ~WingServo();
-
-    void enable() override;
+    /**
+     * @brief Initializes the Algorithm object, must be called as soon as the
+     * object is created.
+     * */
+    virtual bool init() = 0;
 
-    void disable() override;
+    /**
+     * @brief Starts the execution of the algorithm and set the running flag to
+     * true.
+     * */
+    void begin() { running = true; }
 
     /**
-     * @brief Perform wiggle around the middle point.
-     */
-    void selfTest() override;
+     * @brief Terminates the algorithm's execution and sets the running flag to
+     * false.
+     * */
+    void end() { running = false; }
 
-private:
-    Boardcore::Servo servo;
+    /**
+     * @brief Checks wether the algorithm is in a running state or not, and
+     * eventually calls the @see{step} routine.
+     * */
+    void update()
+    {
+        if (running)
+        {
+            step();
+        }
+    }
 
 protected:
     /**
-     * @brief Set servo position.
-     *
-     * @param angle servo position (in degrees)
+     * @brief The actual algorithm step.
      */
-    void setPosition(float angle) override;
-};
+    virtual void step() = 0;
 
-}  // namespace PayloadBoard
+    bool running = false;
+};
diff --git a/src/boards/common/ServoInterface.h b/src/boards/common/ServoInterface.h
new file mode 100644
index 0000000000000000000000000000000000000000..e549b35b1ef7830b493dee17f8936636e392c2f5
--- /dev/null
+++ b/src/boards/common/ServoInterface.h
@@ -0,0 +1,154 @@
+/* Copyright (c) 2021 Skyward Experimental Rocketry
+ * Author: Vincenzo Santomarco
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+/**
+ * @brief Class for interfacing with 180° servo motors, works in degrees.
+ *
+ * This class provides all the methods for enabling/disabling servo
+ * communication as well as methods for testing it (like reset, setMaxPosition
+ * and selftest).
+ * The function set(float) is used to send data to the servo and calls, in
+ * sequence, the preprocessPosition() and the setPosition() functions. This
+ * function must not be overridden and all the logic of preprocessing and
+ * sending position to the actual servo must be implemented via those two
+ * methods.
+ * */
+class ServoInterface
+{
+public:
+    /**
+     * @brief Class constructor.
+     *
+     * @param minPosition The minimum position possible for the Servo
+     * @param maxPosition The maximum position possible for the Servo
+     */
+    ServoInterface(float minPosition, float maxPosition)
+        : MIN_POS(minPosition), MAX_POS(maxPosition), RESET_POS(minPosition)
+    {
+    }
+
+    /**
+     * @brief Class constructor.
+     *
+     * @param minPosition The minimum position possible for the Servo
+     * @param maxPosition The maximum position possible for the Servo
+     * @param resetPosition The reset position for the Servo
+     */
+    ServoInterface(float minPosition, float maxPosition, float resetPosition)
+        : MIN_POS(minPosition), MAX_POS(maxPosition), RESET_POS(resetPosition)
+    {
+    }
+
+    virtual ~ServoInterface() {}
+
+    /**
+     * @brief Enables the communication with the servo and sets it to its reset
+     * position.
+     */
+    virtual void enable() = 0;
+
+    /**
+     * @brief Disables the communication with the servo.
+     */
+    virtual void disable() = 0;
+
+    /**
+     * @brief Sends the given input to the Servo.
+     *
+     * Before sending data the input is preprocessed in order to have a physical
+     * consistent position to send to the servo. Do not override this method,
+     * but use @see{setPosition} and @see{preprocessPosition}.
+     *
+     * @param angle The input to be sent to the Servo
+     */
+    void set(float angle, bool preprocess = false)
+    {
+        if (angle > MAX_POS)
+        {
+            angle = MAX_POS;
+        }
+        else if (angle < MIN_POS)
+        {
+            angle = MIN_POS;
+        }
+
+        if (preprocess)
+        {
+            setPosition(preprocessPosition(angle));
+        }
+        else
+        {
+            setPosition(angle);
+        }
+    }
+
+    /**
+     * @brief Sends the Servo the highest input possible
+     */
+    void setMaxPosition() { setPosition(MAX_POS); }
+
+    /**
+     * @brief Sends the Servo the lowest input possible
+     */
+    void setMinPosition() { setPosition(MIN_POS); }
+
+    /**
+     * @brief Sets servo to its reset position
+     */
+    void reset() { setPosition(RESET_POS); }
+
+    /**
+     * @return current actuator position (in degrees)
+     */
+    float getCurrentPosition() { return currentPosition; }
+
+    virtual void selfTest() = 0;
+
+    const float MIN_POS   = 0;
+    const float MAX_POS   = 0;
+    const float RESET_POS = 0;
+
+protected:
+    /**
+     * @brief Sends the data to the servo.
+     *
+     * @param angle Data to be sent to servo.
+     */
+    virtual void setPosition(float angle) = 0;
+
+    /**
+     * @brief Applies any transformation needed to the data before actually
+     * sending it to the servo.
+     *
+     * @param angle Non normalized input position.
+     *
+     * @returns Normalized input position.
+     */
+    virtual float preprocessPosition(float angle) { return angle; };
+
+    /**
+     * @brief Actuator's current position.
+     */
+    float currentPosition = 0;
+};
diff --git a/src/boards/Payload/PinHandler/PinHandlerData.h b/src/boards/common/SystemData.h
similarity index 57%
rename from src/boards/Payload/PinHandler/PinHandlerData.h
rename to src/boards/common/SystemData.h
index b794ba55d007e9244b0a6f2e628a8f34c2bdb1a2..f4253d251ab7fdc2eb187777d529c1eea0074de1 100644
--- a/src/boards/Payload/PinHandler/PinHandlerData.h
+++ b/src/boards/common/SystemData.h
@@ -1,5 +1,5 @@
-/* Copyright (c) 2019-2021 Skyward Experimental Rocketry
- * Authors: Luca Erbetta, Luca Conterio
+/* Copyright (c) 2019 Skyward Experimental Rocketry
+ * Author: Luca Erbetta
  *
  * Permission is hereby granted, free of charge, to any person obtaining a copy
  * of this software and associated documentation files (the "Software"), to deal
@@ -22,45 +22,30 @@
 
 #pragma once
 
-#include <cstdint>
 #include <ostream>
+#include <string>
 
-namespace PayloadBoard
+struct SystemData
 {
+    long long timestamp  = 0;
+    float cpu_usage      = 0.0f;
+    float cpu_usage_min  = 0.0f;
+    float cpu_usage_max  = 0.0f;
+    float cpu_usage_mean = 0.0f;
 
-enum class ObservedPin : uint8_t
-{
-    NOSECONE = 0
-};
-
-/**
- * @brief Struct represeting the status of an observed pin.
- *
- */
-struct PinStatus
-{
-    ObservedPin pin;
-
-    uint64_t last_state_change     = 0;  // Last time the pin changed state
-    uint8_t state                  = 0;  // Current state of the pin
-    unsigned int num_state_changes = 0;
-
-    uint64_t last_detection_time = 0;  // When a transition is detected
-
-    PinStatus(){};
-    PinStatus(ObservedPin pin) : pin(pin) {}
+    float free_heap     = 0.0f;
+    float min_free_heap = 0.0f;
 
     static std::string header()
     {
-        return "pin,last_state_change,state,num_state_changes,last_detection_"
-               "time\n";
+        return "timestamp,cpu_usage,cpu_usage_min,cpu_usage_max,cpu_usage_mean,"
+               "free_heap,min_free_heap\n";
     }
 
     void print(std::ostream& os) const
     {
-        os << (int)pin << "," << last_state_change << "," << (int)state << ","
-           << num_state_changes << "," << last_detection_time << "\n";
+        os << timestamp << "," << cpu_usage << "," << cpu_usage_min << ","
+           << cpu_usage_max << "," << cpu_usage_mean << "," << free_heap << ","
+           << min_free_heap << "\n";
     }
 };
-
-}  // namespace PayloadBoard
diff --git a/src/boards/common/events/EventStrings.cpp b/src/boards/common/events/EventStrings.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..c08a9b86dff2f7077c33390aa9040816b92750e9
--- /dev/null
+++ b/src/boards/common/events/EventStrings.cpp
@@ -0,0 +1,124 @@
+/* Copyright (c) 2018-2020 Skyward Experimental Rocketry
+ * Authors: Luca Erbetta, Alvise de'Faveri Tron
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+/*
+ ******************************************************************************
+ *                  THIS FILE IS AUTOGENERATED. DO NOT EDIT.                  *
+ ******************************************************************************
+ */
+
+// Autogen date: 2021-09-08 23:46:23.104837
+
+#include <map>
+
+using std::map;
+
+#include "Events.h"
+#include "Topics.h"
+
+using namespace Boardcore;
+
+string getEventString(uint8_t event)
+{
+    static const map<uint8_t, string> event_string_map{
+        {EV_ADA_APOGEE_DETECTED, "EV_ADA_APOGEE_DETECTED"},
+        {EV_ADA_DISABLE_ABK, "EV_ADA_DISABLE_ABK"},
+        {EV_ADA_DPL_ALT_DETECTED, "EV_ADA_DPL_ALT_DETECTED"},
+        {EV_ADA_READY, "EV_ADA_READY"},
+        {EV_APOGEE, "EV_APOGEE"},
+        {EV_ARMED, "EV_ARMED"},
+        {EV_CALIBRATE, "EV_CALIBRATE"},
+        {EV_CALIBRATE_ADA, "EV_CALIBRATE_ADA"},
+        {EV_CALIBRATE_NAS, "EV_CALIBRATE_NAS"},
+        {EV_CALIBRATION_OK, "EV_CALIBRATION_OK"},
+        {EV_CUTTING_TIMEOUT, "EV_CUTTING_TIMEOUT"},
+        {EV_CUT_DROGUE, "EV_CUT_DROGUE"},
+        {EV_DISABLE_ABK, "EV_DISABLE_ABK"},
+        {EV_DISARMED, "EV_DISARMED"},
+        {EV_DPL_ALTITUDE, "EV_DPL_ALTITUDE"},
+        {EV_INIT_ERROR, "EV_INIT_ERROR"},
+        {EV_INIT_OK, "EV_INIT_OK"},
+        {EV_LANDED, "EV_LANDED"},
+        {EV_LIFTOFF, "EV_LIFTOFF"},
+        {EV_NAS_READY, "EV_NAS_READY"},
+        {EV_NC_DETACHED, "EV_NC_DETACHED"},
+        {EV_NC_OPEN, "EV_NC_OPEN"},
+        {EV_NC_OPEN_TIMEOUT, "EV_NC_OPEN_TIMEOUT"},
+        {EV_RESET_SERVO, "EV_RESET_SERVO"},
+        {EV_SEND_HR_TM, "EV_SEND_HR_TM"},
+        {EV_SEND_HR_TM_OVER_SERIAL, "EV_SEND_HR_TM_OVER_SERIAL"},
+        {EV_SEND_LR_TM, "EV_SEND_LR_TM"},
+        {EV_SEND_SENS_TM, "EV_SEND_SENS_TM"},
+        {EV_SEND_TEST_TM, "EV_SEND_TEST_TM"},
+        {EV_SENSORS_READY, "EV_SENSORS_READY"},
+        {EV_SHADOW_MODE_TIMEOUT, "EV_SHADOW_MODE_TIMEOUT"},
+        {EV_STATS_TIMEOUT, "EV_STATS_TIMEOUT"},
+        {EV_TC_ABK_DISABLE, "EV_TC_ABK_DISABLE"},
+        {EV_TC_ABK_RESET_SERVO, "EV_TC_ABK_RESET_SERVO"},
+        {EV_TC_ABK_WIGGLE_SERVO, "EV_TC_ABK_WIGGLE_SERVO"},
+        {EV_TC_ARM, "EV_TC_ARM"},
+        {EV_TC_CALIBRATE_ALGOS, "EV_TC_CALIBRATE_ALGOS"},
+        {EV_TC_CALIBRATE_SENSORS, "EV_TC_CALIBRATE_SENSORS"},
+        {EV_TC_CLOSE_LOG, "EV_TC_CLOSE_LOG"},
+        {EV_TC_CUT_DROGUE, "EV_TC_CUT_DROGUE"},
+        {EV_TC_DISARM, "EV_TC_DISARM"},
+        {EV_TC_DPL_RESET_SERVO, "EV_TC_DPL_RESET_SERVO"},
+        {EV_TC_DPL_WIGGLE_SERVO, "EV_TC_DPL_WIGGLE_SERVO"},
+        {EV_TC_END_MISSION, "EV_TC_END_MISSION"},
+        {EV_TC_FORCE_INIT, "EV_TC_FORCE_INIT"},
+        {EV_TC_LAUNCH, "EV_TC_LAUNCH"},
+        {EV_TC_NC_OPEN, "EV_TC_NC_OPEN"},
+        {EV_TC_RADIO_TM, "EV_TC_RADIO_TM"},
+        {EV_TC_RESET_BOARD, "EV_TC_RESET_BOARD"},
+        {EV_TC_SERIAL_TM, "EV_TC_SERIAL_TM"},
+        {EV_TC_START_SENSOR_TM, "EV_TC_START_SENSOR_TM"},
+        {EV_TC_START_LOG, "EV_TC_START_LOG"},
+        {EV_TC_STOP_SENSOR_TM, "EV_TC_STOP_SENSOR_TM"},
+        {EV_TC_TEST_ABK, "EV_TC_TEST_ABK"},
+        {EV_TC_TEST_MODE, "EV_TC_TEST_MODE"},
+        {EV_TEST_ABK, "EV_TEST_ABK"},
+        {EV_TEST_TIMEOUT, "EV_TEST_TIMEOUT"},
+        {EV_TIMEOUT_END_MISSION, "EV_TIMEOUT_END_MISSION"},
+        {EV_TIMEOUT_PRESS_STABILIZATION, "EV_TIMEOUT_PRESS_STABILIZATION"},
+        {EV_TIMEOUT_SHADOW_MODE, "EV_TIMEOUT_SHADOW_MODE"},
+        {EV_UMBILICAL_DETACHED, "EV_UMBILICAL_DETACHED"},
+        {EV_WIGGLE_SERVO, "EV_WIGGLE_SERVO"},
+    };
+    auto it = event_string_map.find(event);
+    return it == event_string_map.end() ? "EV_UNKNOWN" : it->second;
+}
+
+string getTopicString(uint8_t topic)
+{
+    static const map<uint8_t, string> topic_string_map{
+        {TOPIC_ABK, "TOPIC_ABK"},
+        {TOPIC_ADA, "TOPIC_ADA"},
+        {TOPIC_DPL, "TOPIC_DPL"},
+        {TOPIC_FLIGHT_EVENTS, "TOPIC_FLIGHT_EVENTS"},
+        {TOPIC_FMM, "TOPIC_FMM"},
+        {TOPIC_NAS, "TOPIC_NAS"},
+        {TOPIC_STATS, "TOPIC_STATS"},
+        {TOPIC_TMTC, "TOPIC_TMTC"},
+    };
+    auto it = topic_string_map.find(topic);
+    return it == topic_string_map.end() ? "TOPIC_UNKNOWN" : it->second;
+}
diff --git a/src/boards/common/events/Events.h b/src/boards/common/events/Events.h
new file mode 100644
index 0000000000000000000000000000000000000000..2d993e6dc1563af7b81ac7a8ae4e2e90608839c0
--- /dev/null
+++ b/src/boards/common/events/Events.h
@@ -0,0 +1,184 @@
+/* Copyright (c) 2018-2021 Skyward Experimental Rocketry
+ * Authors: Luca Erbetta, Alvise de'Faveri Tron
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+/*
+ ******************************************************************************
+ *                  THIS FILE IS AUTOGENERATED. DO NOT EDIT.                  *
+ ******************************************************************************
+ */
+
+// Autogen date: 2021-09-08 23:46:23.104837
+
+#pragma once
+
+#include <cstdint>
+#include <string>
+#include <vector>
+
+#include "Topics.h"
+#include "events/Event.h"
+#include "events/EventBroker.h"
+
+/**
+ * Definition of all events in the Board software.
+ * Refer to the Software Design Document.
+ */
+enum Events : uint8_t
+{
+    EV_ADA_APOGEE_DETECTED = Boardcore::EV_FIRST_SIGNAL,
+    EV_ADA_DISABLE_ABK,
+    EV_ADA_DPL_ALT_DETECTED,
+    EV_ADA_READY,
+    EV_APOGEE,
+    EV_ARMED,
+    EV_CALIBRATE,
+    EV_CALIBRATE_ADA,
+    EV_CALIBRATE_NAS,
+    EV_CALIBRATION_OK,
+    EV_CUTTING_TIMEOUT,
+    EV_CUT_DROGUE,
+    EV_DISABLE_ABK,
+    EV_DISARMED,
+    EV_DPL_ALTITUDE,
+    EV_INIT_ERROR,
+    EV_INIT_OK,
+    EV_LANDED,
+    EV_LIFTOFF,
+    EV_NAS_READY,
+    EV_NC_DETACHED,
+    EV_NC_OPEN,
+    EV_NC_OPEN_TIMEOUT,
+    EV_RESET_SERVO,
+    EV_SEND_HR_TM,
+    EV_SEND_HR_TM_OVER_SERIAL,
+    EV_SEND_LR_TM,
+    EV_SEND_SENS_TM,
+    EV_SEND_TEST_TM,
+    EV_SENSORS_READY,
+    EV_SHADOW_MODE_TIMEOUT,
+    EV_STATS_TIMEOUT,
+    EV_TC_ABK_DISABLE,
+    EV_TC_ABK_RESET_SERVO,
+    EV_TC_ABK_WIGGLE_SERVO,
+    EV_TC_ARM,
+    EV_TC_CALIBRATE_ALGOS,
+    EV_TC_CALIBRATE_SENSORS,
+    EV_TC_CLOSE_LOG,
+    EV_TC_CUT_DROGUE,
+    EV_TC_DISARM,
+    EV_TC_DPL_RESET_SERVO,
+    EV_TC_DPL_WIGGLE_SERVO,
+    EV_TC_END_MISSION,
+    EV_TC_FORCE_INIT,
+    EV_TC_LAUNCH,
+    EV_TC_NC_OPEN,
+    EV_TC_RADIO_TM,
+    EV_TC_RESET_BOARD,
+    EV_TC_SERIAL_TM,
+    EV_TC_START_SENSOR_TM,
+    EV_TC_START_LOG,
+    EV_TC_STOP_SENSOR_TM,
+    EV_TC_TEST_ABK,
+    EV_TC_TEST_MODE,
+    EV_TC_EXIT_TEST_MODE,
+    EV_TEST_ABK,
+    EV_TEST_TIMEOUT,
+    EV_TIMEOUT_END_MISSION,
+    EV_TIMEOUT_PRESS_STABILIZATION,
+    EV_TIMEOUT_SHADOW_MODE,
+    EV_UMBILICAL_DETACHED,
+    EV_WIGGLE_SERVO,
+};
+
+const std::vector<uint8_t> EVENT_LIST{
+    EV_ADA_APOGEE_DETECTED,
+    EV_ADA_DISABLE_ABK,
+    EV_ADA_DPL_ALT_DETECTED,
+    EV_ADA_READY,
+    EV_APOGEE,
+    EV_ARMED,
+    EV_CALIBRATE,
+    EV_CALIBRATE_ADA,
+    EV_CALIBRATE_NAS,
+    EV_CALIBRATION_OK,
+    EV_CUTTING_TIMEOUT,
+    EV_CUT_DROGUE,
+    EV_DISABLE_ABK,
+    EV_DISARMED,
+    EV_DPL_ALTITUDE,
+    EV_INIT_ERROR,
+    EV_INIT_OK,
+    EV_LANDED,
+    EV_LIFTOFF,
+    EV_NAS_READY,
+    EV_NC_DETACHED,
+    EV_NC_OPEN,
+    EV_NC_OPEN_TIMEOUT,
+    EV_RESET_SERVO,
+    EV_SEND_HR_TM,
+    EV_SEND_HR_TM_OVER_SERIAL,
+    EV_SEND_LR_TM,
+    EV_SEND_SENS_TM,
+    EV_SEND_TEST_TM,
+    EV_SENSORS_READY,
+    EV_SHADOW_MODE_TIMEOUT,
+    EV_STATS_TIMEOUT,
+    EV_TC_ABK_DISABLE,
+    EV_TC_ABK_RESET_SERVO,
+    EV_TC_ABK_WIGGLE_SERVO,
+    EV_TC_ARM,
+    EV_TC_CALIBRATE_ALGOS,
+    EV_TC_CALIBRATE_SENSORS,
+    EV_TC_CLOSE_LOG,
+    EV_TC_CUT_DROGUE,
+    EV_TC_DISARM,
+    EV_TC_DPL_RESET_SERVO,
+    EV_TC_DPL_WIGGLE_SERVO,
+    EV_TC_END_MISSION,
+    EV_TC_FORCE_INIT,
+    EV_TC_LAUNCH,
+    EV_TC_NC_OPEN,
+    EV_TC_RADIO_TM,
+    EV_TC_RESET_BOARD,
+    EV_TC_SERIAL_TM,
+    EV_TC_START_SENSOR_TM,
+    EV_TC_START_LOG,
+    EV_TC_STOP_SENSOR_TM,
+    EV_TC_TEST_ABK,
+    EV_TC_TEST_MODE,
+    EV_TC_EXIT_TEST_MODE,
+    EV_TEST_ABK,
+    EV_TEST_TIMEOUT,
+    EV_TIMEOUT_END_MISSION,
+    EV_TIMEOUT_PRESS_STABILIZATION,
+    EV_TIMEOUT_SHADOW_MODE,
+    EV_UMBILICAL_DETACHED,
+    EV_WIGGLE_SERVO,
+};
+
+/**
+ * @brief Returns the name of the provided event
+ *
+ * @param event
+ * @return string
+ */
+std::string getEventString(uint8_t event);
diff --git a/src/boards/common/events/Topics.h b/src/boards/common/events/Topics.h
new file mode 100644
index 0000000000000000000000000000000000000000..254e008f7c110ae90789e728454f5adf494bac59
--- /dev/null
+++ b/src/boards/common/events/Topics.h
@@ -0,0 +1,65 @@
+/* Copyright (c) 2018-2021 Skyward Experimental Rocketry
+ * Authors: Luca Erbetta, Alvise de'Faveri Tron
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+/*
+ ******************************************************************************
+ *                  THIS FILE IS AUTOGENERATED. DO NOT EDIT.                  *
+ ******************************************************************************
+ */
+
+// Autogen date: 2021-09-08 23:46:23.104837
+
+#pragma once
+
+#include <cstdint>
+#include <string>
+#include <vector>
+
+using std::string;
+
+/**
+ * Definition of various event topics to use in the EventBroker
+ */
+enum Topics : uint8_t
+{
+    TOPIC_ABK,
+    TOPIC_ADA,
+    TOPIC_DPL,
+    TOPIC_FLIGHT_EVENTS,
+    TOPIC_FMM,
+    TOPIC_NAS,
+    TOPIC_STATS,
+    TOPIC_TMTC,
+};
+
+const std::vector<uint8_t> TOPIC_LIST{
+    TOPIC_ABK, TOPIC_ADA, TOPIC_DPL,   TOPIC_FLIGHT_EVENTS,
+    TOPIC_FMM, TOPIC_NAS, TOPIC_STATS, TOPIC_TMTC,
+};
+
+/**
+ * @brief Returns the name of the provided event
+ *
+ * @param event
+ * @return string
+ */
+string getTopicString(uint8_t topic);
diff --git a/src/entrypoints/Parafoil/logdecoder/.gitignore b/src/entrypoints/Parafoil/logdecoder/.gitignore
new file mode 100644
index 0000000000000000000000000000000000000000..8217283873861e241c84835fc6bfaa1d15ba30e3
--- /dev/null
+++ b/src/entrypoints/Parafoil/logdecoder/.gitignore
@@ -0,0 +1,2 @@
+logdecoder
+logs/
\ No newline at end of file
diff --git a/src/entrypoints/Parafoil/logdecoder/LogTypes.h b/src/entrypoints/Parafoil/logdecoder/LogTypes.h
new file mode 100644
index 0000000000000000000000000000000000000000..9a2ca5f89444b350a67e8bfef3cdec003cb15b3e
--- /dev/null
+++ b/src/entrypoints/Parafoil/logdecoder/LogTypes.h
@@ -0,0 +1,163 @@
+/* Copyright (c) 2021 Skyward Experimental Rocketry
+ * Author: Luca Erbetta
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <sensors/ADS1118/ADS1118Data.h>
+#include <sensors/BME280/BME280Data.h>
+#include <sensors/BMX160/BMX160Data.h>
+#include <sensors/BMX160/BMX160WithCorrectionData.h>
+#include <sensors/LIS3MDL/LIS3MDLData.h>
+#include <sensors/MPU9250/MPU9250Data.h>
+#include <sensors/MS5803/MS5803Data.h>
+#include <sensors/UbloxGPS/UbloxGPSData.h>
+#include <sensors/analog/battery/BatteryVoltageSensorData.h>
+#include <sensors/analog/current/CurrentSensorData.h>
+#include <sensors/analog/pressure/MPXHZ6130A/MPXHZ6130AData.h>
+#include <sensors/analog/pressure/honeywell/SSCDANN030PAAData.h>
+#include <sensors/analog/pressure/honeywell/SSCDRRN015PDAData.h>
+
+#include <fstream>
+#include <iostream>
+
+#include "AirBrakes/AirBrakesData.h"
+#include "ApogeeDetectionAlgorithm/ADAData.h"
+//#include "AirBrakes/WindData.h"
+#include "DeathStackStatus.h"
+//#include "Deployment/DeploymentData.h"
+#include "FlightModeManager/FMMStatus.h"
+//#include "LogStats.h"
+#include <common/SystemData.h>
+
+#include "Main/SensorsData.h"
+#include "NavigationAttitudeSystem/NASData.h"
+#include "PinHandler/PinHandlerData.h"
+#include "diagnostic/PrintLoggerData.h"
+#include "diagnostic/StackData.h"
+#include "events/EventData.h"
+#include "radio/MavlinkDriver/MavlinkStatus.h"
+//#include "logger/Deserializer.h"
+#include <ParafoilTestStatus.h>
+#include <logger/Deserializer.h>
+#include <logger/LoggerStats.h>
+#include <scheduler/TaskSchedulerData.h>
+
+#include "../../hardware_in_the_loop/HIL_sensors/HILSensorsData.h"
+#include "FlightStatsRecorder/FSRData.h"
+#include "scheduler/TaskSchedulerData.h"
+
+// Serialized classes
+using std::ofstream;
+
+using namespace DeathStackBoard;
+using namespace Boardcore;
+using namespace ParafoilTestDev;
+
+template <typename T>
+void print(T& t, ostream& os)
+{
+    t.print(os);
+}
+
+template <typename T>
+void registerType(Deserializer& ds)
+{
+    ds.registerType<T>(print<T>, T::header());
+}
+
+void registerTypes(Deserializer& ds)
+{
+    // Disagnostic
+    registerType<TaskStatsResult>(ds);
+    registerType<LoggerStats>(ds);
+    registerType<StackData>(ds);
+    registerType<LoggingString>(ds);
+    registerType<SystemData>(ds);
+    registerType<ParafoilTestStatus>(ds);
+
+    // Sensors
+    registerType<CurrentSensorData>(ds);
+    registerType<BatteryVoltageSensorData>(ds);
+    registerType<UbloxGPSData>(ds);
+    registerType<BMX160Data>(ds);
+    registerType<BMX160WithCorrectionData>(ds);
+    registerType<BMX160GyroscopeCalibrationBiases>(ds);
+    registerType<BMX160Temperature>(ds);
+    registerType<BMX160FifoStats>(ds);
+    registerType<MS5803Data>(ds);
+    registerType<MPXHZ6130AData>(ds);
+    registerType<SSCDRRN015PDAData>(ds);
+    registerType<SSCDANN030PAAData>(ds);
+    registerType<LIS3MDLData>(ds);
+    registerType<ADS1118Data>(ds);
+    registerType<AirSpeedPitot>(ds);
+    registerType<MPU9250Data>(ds);
+    registerType<BME280Data>(ds);
+
+    // Statuses
+    registerType<AirBrakesControllerStatus>(ds);
+    registerType<DeathStackStatus>(ds);
+    registerType<SensorsStatus>(ds);
+    registerType<FMMStatus>(ds);
+    registerType<PinStatus>(ds);
+    // registerType<LogStats>(ds);
+    // registerType<DeploymentStatus>(ds);
+    registerType<ADAControllerStatus>(ds);
+
+    // Mavlink
+    registerType<MavlinkStatus>(ds);
+
+    // ADA
+    registerType<ADAKalmanState>(ds);
+    registerType<ADAData>(ds);
+    registerType<ADAReferenceValues>(ds);
+    registerType<TargetDeploymentAltitude>(ds);
+    registerType<ApogeeDetected>(ds);
+    registerType<DplAltitudeReached>(ds);
+
+    // NAS
+    registerType<NASStatus>(ds);
+    registerType<NASKalmanState>(ds);
+    registerType<NASReferenceValues>(ds);
+    registerType<NASTriadResult>(ds);
+    registerType<NASData>(ds);
+
+    // Airbrakes
+    registerType<AirBrakesData>(ds);
+    registerType<AirBrakesAlgorithmData>(ds);
+    registerType<AirBrakesChosenTrajectory>(ds);
+
+    // FlightStatsRecorder
+    registerType<LiftOffStats>(ds);
+    registerType<ApogeeStats>(ds);
+    registerType<DrogueDPLStats>(ds);
+    registerType<MainDPLStats>(ds);
+
+    // HIL
+    registerType<HILImuData>(ds);
+    registerType<HILGpsData>(ds);
+    registerType<HILBaroData>(ds);
+
+    // Others
+    registerType<EventData>(ds);
+    // registerType<WindData>(ds);
+}
diff --git a/src/entrypoints/Parafoil/logdecoder/Makefile b/src/entrypoints/Parafoil/logdecoder/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..8079bf6fe98d279787b4d79a6db84bcdd360dc9f
--- /dev/null
+++ b/src/entrypoints/Parafoil/logdecoder/Makefile
@@ -0,0 +1,21 @@
+BASE := ../../../
+BOARDCORE := $(BASE)skyward-boardcore/
+
+all:
+	g++ -std=c++17 -O2 -o logdecoder Parafoil-decoder.cpp \
+					$(BOARDCORE)libs/tscpp/tscpp/stream.cpp \
+					-DCOMPILE_FOR_X86 \
+					-I$(BOARDCORE)libs/tscpp/tscpp \
+					-I$(BASE)src/boards/ParafoilTest \
+					-I$(BASE)src/boards/DeathStack \
+	 				-I$(BASE)src \
+	 				-I$(BOARDCORE)src/shared \
+	 				-I$(BOARDCORE)src/tests \
+					-I$(BOARDCORE)libs \
+					-I$(BOARDCORE)libs/tscpp \
+					-I$(BOARDCORE)libs/eigen \
+					-I$(BOARDCORE)libs/mavlink_skyward_lib \
+					-I$(BOARDCORE)libs/miosix-kernel/miosix
+
+clean:
+	rm logdecoder
diff --git a/src/boards/Payload/Main/Actuators.h b/src/entrypoints/Parafoil/logdecoder/Parafoil-decoder.cpp
similarity index 85%
rename from src/boards/Payload/Main/Actuators.h
rename to src/entrypoints/Parafoil/logdecoder/Parafoil-decoder.cpp
index 9e69ce622720d4c975a3e721c364cf04d0b5fe89..4fdafbddad40077d6914574c9ac707b16905c8f3 100644
--- a/src/boards/Payload/Main/Actuators.h
+++ b/src/entrypoints/Parafoil/logdecoder/Parafoil-decoder.cpp
@@ -20,17 +20,5 @@
  * THE SOFTWARE.
  */
 
-#pragma once
-
-#include <Payload/WingControl/WingServo.h>
-
-namespace PayloadBoard
-{
-
-struct Actuators
-{
-    WingServo* left_servo;
-    WingServo* right_servo;
-};
-
-}  // namespace PayloadBoard
\ No newline at end of file
+#include "LogTypes.h"
+#include "entrypoints/deserializer/logdecoder.cpp"
diff --git a/src/entrypoints/Parafoil/parafoil-entry.cpp b/src/entrypoints/Parafoil/parafoil-entry.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b5abd84ee5983e44e1c5985507d7f3b97e156d7f
--- /dev/null
+++ b/src/entrypoints/Parafoil/parafoil-entry.cpp
@@ -0,0 +1,109 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#include <Parafoil/Configs/SensorsConfig.h>
+#include <Parafoil/Configs/XbeeConfig.h>
+#include <Parafoil/ParafoilTest.h>
+#include <common/SystemData.h>
+#include <diagnostic/CpuMeter.h>
+#include <miosix.h>
+
+using namespace miosix;
+using namespace ParafoilTestDev;
+using namespace Boardcore;
+
+void enablePin()
+{
+    // GPS_CS.mode(miosix::Mode::OUTPUT);
+    IMU_CS.mode(miosix::Mode::OUTPUT);
+    PRESS_CS.mode(miosix::Mode::OUTPUT);
+
+    SCK.mode(miosix::Mode::ALTERNATE);
+    MISO.mode(miosix::Mode::ALTERNATE);
+    MOSI.mode(miosix::Mode::ALTERNATE);
+    GPS_TX.mode(miosix::Mode::ALTERNATE);
+    GPS_RX.mode(miosix::Mode::ALTERNATE);
+
+    SCK.alternateFunction(5);
+    MISO.alternateFunction(5);
+    MOSI.alternateFunction(5);
+    GPS_TX.alternateFunction(7);
+    GPS_RX.alternateFunction(7);
+
+    XBEE_SCK.mode(miosix::Mode::ALTERNATE);
+    XBEE_SCK.alternateFunction(5);
+    XBEE_MISO.mode(miosix::Mode::ALTERNATE);
+    XBEE_MISO.alternateFunction(5);
+    XBEE_MOSI.mode(miosix::Mode::ALTERNATE);
+    XBEE_MOSI.alternateFunction(5);
+
+    XBEE_CS.mode(miosix::Mode::OUTPUT);
+    XBEE_CS.high();
+
+    XBEE_ATTN.mode(miosix::Mode::INPUT);
+
+    XBEE_RESET.mode(miosix::Mode::OUTPUT);
+
+    // GPS_CS.high();
+    IMU_CS.high();
+    PRESS_CS.high();
+}
+
+int main()
+{
+    Stats cpu_stat;
+    StatsResult cpu_stat_res;
+    SystemData system_data;
+
+    RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;  // Enable SPI1 bus
+    RCC->APB2ENR |= RCC_APB2ENR_SPI4EN;  // Enable SPI4 bus
+    enablePin();
+
+    // TODO integrate all the logging stuff
+    ParafoilTest::getInstance().start();
+
+    Logger* logger_service = &Logger::getInstance();
+
+    for (;;)
+    {
+        Thread::sleep(1000);
+        logger_service->log(logger_service->getLoggerStats());
+
+        StackLogger::getInstance().updateStack(THID_ENTRYPOINT);
+
+        system_data.timestamp = miosix::getTick();
+        system_data.cpu_usage = averageCpuUtilization();
+        cpu_stat.add(system_data.cpu_usage);
+
+        cpu_stat_res               = cpu_stat.getStats();
+        system_data.cpu_usage_min  = cpu_stat_res.minValue;
+        system_data.cpu_usage_max  = cpu_stat_res.maxValue;
+        system_data.cpu_usage_mean = cpu_stat_res.mean;
+
+        system_data.min_free_heap = MemoryProfiling::getAbsoluteFreeHeap();
+        system_data.free_heap     = MemoryProfiling::getCurrentFreeHeap();
+
+        logger_service->log(system_data);
+
+        StackLogger::getInstance().log();
+    }
+    return 0;
+}
diff --git a/src/tests/Parafoil/parafoil-test-bme280.cpp b/src/tests/Parafoil/parafoil-test-bme280.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a1e84acc8b9d9dbd179ca8a7f1c0e075d09c1ee6
--- /dev/null
+++ b/src/tests/Parafoil/parafoil-test-bme280.cpp
@@ -0,0 +1,107 @@
+/* Copyright (c) 2021 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include <drivers/spi/SPIDriver.h>
+#include <drivers/timer/TimestampTimer.h>
+#include <miosix.h>
+#include <sensors/BME280/BME280.h>
+#include <utils/Debug.h>
+
+using namespace miosix;
+using namespace Boardcore;
+
+GpioPin sckPin  = GpioPin(GPIOA_BASE, 5);
+GpioPin misoPin = GpioPin(GPIOB_BASE, 4);
+GpioPin mosiPin = GpioPin(GPIOA_BASE, 7);
+GpioPin csPin   = GpioPin(GPIOC_BASE, 11);
+
+void initBoard()
+{
+    // Alternate function configuration for SPI pins
+    sckPin.mode(miosix::Mode::ALTERNATE);
+    sckPin.alternateFunction(5);  // SPI function
+    mosiPin.mode(miosix::Mode::ALTERNATE);
+    mosiPin.alternateFunction(5);  // SPI function
+    misoPin.mode(miosix::Mode::ALTERNATE);
+    misoPin.alternateFunction(5);  // SPI function
+
+    // Chip select pin as output starting high
+    csPin.mode(miosix::Mode::OUTPUT);
+    csPin.high();
+}
+
+int main()
+{
+    // Enable SPI clock and set gpios
+    initBoard();
+
+    // SPI configuration setup
+    SPIBusConfig spiConfig;
+    spiConfig.clockDivider = SPI::ClockDivider::DIV_32;
+    spiConfig.mode         = SPI::Mode::MODE_0;
+    SPIBus spiBus(SPI1);
+    SPISlave spiSlave(spiBus, csPin, spiConfig);
+
+    // Device initialization
+    BME280 bme280(spiSlave);
+
+    bme280.init();
+
+    // In practice the self test reads the who am i reagister, this is already
+    // done in init()
+    if (!bme280.selfTest())
+    {
+        TRACE("Self test failed!\n");
+
+        return -1;
+    }
+
+    // Try forced mode
+    TRACE("Forced mode\n");
+    for (int i = 0; i < 10; i++)
+    {
+        bme280.setSensorMode(BME280::FORCED_MODE);
+
+        miosix::Thread::sleep(bme280.getMaxMeasurementTime());
+
+        bme280.sample();
+
+        TRACE("temp: %.2f DegC\tpress: %.2f hPa\thumid: %.2f %%RH\n",
+              bme280.getLastSample().temperature,
+              bme280.getLastSample().pressure, bme280.getLastSample().humidity);
+
+        miosix::Thread::sleep(1000);
+    }
+
+    TRACE("Normal mode\n");
+    bme280.setSensorMode(BME280::NORMAL_MODE);
+    while (true)
+    {
+        bme280.sample();
+
+        TRACE("temp: %.2f DegC\tpress: %.2f Pa\thumid: %.2f %%RH\n",
+              bme280.getLastSample().temperature,
+              bme280.getLastSample().pressure, bme280.getLastSample().humidity);
+
+        miosix::Thread::sleep(50);  // 25Hz
+    }
+}
diff --git a/src/tests/Parafoil/parafoil-test-ublox-uart.cpp b/src/tests/Parafoil/parafoil-test-ublox-uart.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..3a050565ba1c3d18d999cddb3fcd9b8eeec78bb3
--- /dev/null
+++ b/src/tests/Parafoil/parafoil-test-ublox-uart.cpp
@@ -0,0 +1,94 @@
+/* Copyright (c) 2021 Skyward Experimental Rocketry
+ * Authors: Davide Bonomini, Davide Mor, Alberto Nidasio, Damiano Amatruda
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include <drivers/timer/TimestampTimer.h>
+#include <sensors/UbloxGPS/UbloxGPS.h>
+#include <utils/Debug.h>
+
+using namespace miosix;
+using namespace Boardcore;
+
+#define RATE 4
+
+int main()
+{
+    (void)TimestampTimer::getInstance();
+
+    GpioPin tx(GPIOA_BASE, 2);
+    GpioPin rx(GPIOA_BASE, 3);
+
+    tx.mode(miosix::Mode::ALTERNATE);
+    tx.alternateFunction(7);
+    rx.mode(miosix::Mode::ALTERNATE);
+    rx.alternateFunction(7);
+
+    printf("Welcome to the ublox test\n");
+
+    // Keep GPS baud rate at default for easier testing
+    UbloxGPS gps(38400, RATE, 2, "gps", 38400);
+    UbloxGPSData dataGPS;
+    printf("Gps allocated\n");
+
+    // Init the gps
+    if (gps.init())
+    {
+        printf("Successful gps initialization\n");
+    }
+    else
+    {
+        printf("Failed gps initialization\n");
+    }
+
+    // Perform the selftest
+    if (gps.selfTest())
+    {
+        printf("Successful gps selftest\n");
+    }
+    else
+    {
+        printf("Failed gps selftest\n");
+    }
+
+    // Start the gps thread
+    gps.start();
+    printf("Gps started\n");
+
+    while (true)
+    {
+        // Give time to the thread
+        Thread::sleep(1000 / RATE);
+
+        // Sample
+        gps.sample();
+        dataGPS = gps.getLastSample();
+
+        // Print out the latest sample
+        TRACE(
+            "[gps] timestamp: % 4.3f, fix: %01d lat: % f lon: % f "
+            "height: %4.1f nsat: %2d speed: %3.2f velN: % 3.2f velE: % 3.2f "
+            "track %3.1f\n",
+            (float)dataGPS.gpsTimestamp / 1000000, dataGPS.fix,
+            dataGPS.latitude, dataGPS.longitude, dataGPS.height,
+            dataGPS.satellites, dataGPS.speed, dataGPS.velocityNorth,
+            dataGPS.velocityEast, dataGPS.track);
+    }
+}