diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json
index b03da947bb50aa0ccca1a19367ce32dcec19a1b8..895903d9393dbc530e59f77112078e50f5c70426 100644
--- a/.vscode/c_cpp_properties.json
+++ b/.vscode/c_cpp_properties.json
@@ -339,6 +339,29 @@
                 "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM7_stm32f7/stm32f767zi_compute_unit"
             ]
         },
+        {
+            "name": "stm32f767zi_gemini_gs",
+            "cStandard": "c11",
+            "cppStandard": "c++14",
+            "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++",
+            "defines": [
+                "{defaultDefines}",
+                "_MIOSIX_BOARDNAME=stm32f767zi_gemini_gs",
+                "_BOARD_STM32F767ZI_GEMINI_GS",
+                "_ARCH_CORTEXM7_STM32F7",
+                "STM32F769xx",
+                "HSE_VALUE=25000000",
+                "SYSCLK_FREQ_216MHz=216000000",
+                "__ENABLE_XRAM",
+                "V_DDA_VOLTAGE=3.3f"
+            ],
+            "includePath": [
+                "${defaultIncludePaths}",
+                "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM7_stm32f7/common",
+                "${workspaceFolder}/libs/miosix-kernel/miosix/arch/cortexM7_stm32f7/stm32f767zi_gemini_gs",
+                "${workspaceFolder}/libs/miosix-kernel/miosix/config/arch/cortexM7_stm32f7/stm32f767zi_gemini_gs"
+            ]
+        },
         {
             "name": "stm32f756zg_nucleo",
             "cStandard": "c11",
diff --git a/.vscode/settings.json b/.vscode/settings.json
index 66dd1b5820d9d5c4a599602b87f23eac419e33df..fa393981b857a5dbcae6300ee78bf8cd29a623cb 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -154,6 +154,7 @@
                 "cyaw",
                 "DATABUS",
                 "datasheet",
+                "Davide",
                 "deleteme",
                 "DMEIE",
                 "Doxyfile",
@@ -274,6 +275,7 @@
                 "Riccardo",
                 "RQCP",
                 "RXCRCR",
+                "Rssi",
                 "RXIRQ",
                 "RXNE",
                 "RXNEIE",
diff --git a/CMakeLists.txt b/CMakeLists.txt
index fd08e56e359e567de9880b2f34f3493ed2d14e29..7610a2b91bfdfebbaca1893b38a71723d219680c 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -57,13 +57,25 @@ sbs_target(runcam-settings stm32f407vg_stm32f4discovery)
 add_executable(sdcard-benchmark src/entrypoints/sdcard-benchmark.cpp)
 sbs_target(sdcard-benchmark stm32f429zi_skyward_death_stack_x)
 
-add_executable(sx1278fsk-serial src/entrypoints/sx1278-serial.cpp)
-target_compile_definitions(sx1278fsk-serial PRIVATE SX1278_IS_FSK)
-sbs_target(sx1278fsk-serial stm32f429zi_skyward_groundstation_v2)
+add_executable(sx1278fsk-ra01-serial src/entrypoints/sx1278-serial.cpp)
+target_compile_definitions(sx1278fsk-ra01-serial PRIVATE SX1278_IS_FSK)
+sbs_target(sx1278fsk-ra01-serial stm32f429zi_skyward_groundstation_v2)
 
-add_executable(sx1278lora-serial src/entrypoints/sx1278-serial.cpp)
-target_compile_definitions(sx1278lora-serial PRIVATE SX1278_IS_LORA)
-sbs_target(sx1278lora-serial stm32f429zi_skyward_groundstation_v2)
+add_executable(sx1278lora-ra01-serial src/entrypoints/sx1278-serial.cpp)
+target_compile_definitions(sx1278lora-ra01-serial PRIVATE SX1278_IS_LORA)
+sbs_target(sx1278lora-ra01-serial stm32f429zi_skyward_groundstation_v2)
+
+add_executable(sx1278fsk-skyward433-serial src/entrypoints/sx1278-serial.cpp)
+target_compile_definitions(sx1278fsk-skyward433-serial PRIVATE SX1278_IS_FSK SX1278_IS_SKYWARD433)
+sbs_target(sx1278fsk-skyward433-serial stm32f767zi_gemini_gs)
+
+add_executable(sx1278lora-skyward433-serial src/entrypoints/sx1278-serial.cpp)
+target_compile_definitions(sx1278lora-skyward433-serial PRIVATE SX1278_IS_LORA SX1278_IS_SKYWARD433)
+sbs_target(sx1278lora-skyward433-serial stm32f429zi_skyward_groundstation_v2)
+
+add_executable(sx1278fsk-ebyterig-serial src/entrypoints/sx1278-serial.cpp)
+target_compile_definitions(sx1278fsk-ebyterig-serial PRIVATE SX1278_IS_FSK)
+sbs_target(sx1278fsk-ebyterig-serial stm32f429zi_skyward_rig)
 
 #-----------------------------------------------------------------------------#
 #                                    Tests                                    #
@@ -280,25 +292,22 @@ sbs_target(test-fsm stm32f429zi_stm32f4discovery)
 add_executable(test-sx1278fsk-bidir src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp)
 sbs_target(test-sx1278fsk-bidir stm32f429zi_skyward_groundstation_v2)
 
-add_executable(test-sx1278fsk-tx src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp)
+add_executable(test-sx1278fsk-tx src/tests/radio/sx1278/test-sx1278-bench-serial.cpp)
 target_compile_definitions(test-sx1278fsk-tx PRIVATE DISABLE_RX)
 sbs_target(test-sx1278fsk-tx stm32f429zi_skyward_groundstation_v2)
 
-add_executable(test-sx1278fsk-rx src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp)
+add_executable(test-sx1278fsk-rx src/tests/radio/sx1278/test-sx1278-bench-serial.cpp)
 target_compile_definitions(test-sx1278fsk-rx PRIVATE DISABLE_TX)
 sbs_target(test-sx1278fsk-rx stm32f429zi_skyward_groundstation_v2)
 
-add_executable(test-sx1278fsk-gui src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp)
-sbs_target(test-sx1278fsk-gui stm32f429zi_skyward_groundstation_v2)
+add_executable(test-sx1278fsk-gui-tx src/tests/radio/sx1278/test-sx1278-bench-gui.cpp)
+target_compile_definitions(test-sx1278fsk-gui-tx PRIVATE DISABLE_RX)
+sbs_target(test-sx1278fsk-gui-tx stm32f429zi_skyward_groundstation_v2)
 
-add_executable(test-sx1278fsk-gui-rx src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp)
+add_executable(test-sx1278fsk-gui-rx src/tests/radio/sx1278/test-sx1278-bench-gui.cpp)
 target_compile_definitions(test-sx1278fsk-gui-rx PRIVATE DISABLE_TX)
 sbs_target(test-sx1278fsk-gui-rx stm32f429zi_skyward_groundstation_v2)
 
-add_executable(test-sx1278fsk-gui-tx src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp)
-target_compile_definitions(test-sx1278fsk-gui-tx PRIVATE DISABLE_RX)
-sbs_target(test-sx1278fsk-gui-tx stm32f429zi_skyward_groundstation_v2)
-
 add_executable(test-sx1278fsk-mavlink src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp)
 sbs_target(test-sx1278fsk-mavlink stm32f429zi_skyward_groundstation_v2)
 
@@ -311,14 +320,30 @@ sbs_target(test-sx1278lora-bidir stm32f429zi_skyward_groundstation_v2)
 add_executable(test-sx1278lora-mavlink src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp)
 sbs_target(test-sx1278lora-mavlink stm32f429zi_skyward_groundstation_v2)
 
-add_executable(test-sx1278lora-rx src/tests/radio/sx1278/lora/test-sx1278-simple.cpp)
-target_compile_definitions(test-sx1278lora-rx PRIVATE ENABLE_RX)
-sbs_target(test-sx1278lora-rx stm32f429zi_skyward_groundstation_v2)
+add_executable(test-sx1278lora-simple-rx src/tests/radio/sx1278/lora/test-sx1278-simple.cpp)
+target_compile_definitions(test-sx1278lora-simple-rx PRIVATE ENABLE_RX)
+sbs_target(test-sx1278lora-simple-rx stm32f429zi_skyward_groundstation_v2)
 
-add_executable(test-sx1278lora-tx src/tests/radio/sx1278/lora/test-sx1278-simple.cpp)
-target_compile_definitions(test-sx1278lora-tx PRIVATE ENABLE_TX)
+add_executable(test-sx1278lora-simple-tx src/tests/radio/sx1278/lora/test-sx1278-simple.cpp)
+target_compile_definitions(test-sx1278lora-simple-tx PRIVATE ENABLE_TX)
+sbs_target(test-sx1278lora-simple-tx stm32f429zi_skyward_groundstation_v2)
+
+add_executable(test-sx1278lora-tx src/tests/radio/sx1278/test-sx1278-bench-serial.cpp)
+target_compile_definitions(test-sx1278lora-tx PRIVATE DISABLE_RX SX1278_IS_LORA)
 sbs_target(test-sx1278lora-tx stm32f429zi_skyward_groundstation_v2)
 
+add_executable(test-sx1278lora-rx src/tests/radio/sx1278/test-sx1278-bench-serial.cpp)
+target_compile_definitions(test-sx1278lora-rx PRIVATE DISABLE_TX SX1278_IS_LORA)
+sbs_target(test-sx1278lora-rx stm32f429zi_skyward_groundstation_v2)
+
+add_executable(test-sx1278lora-gui-rx src/tests/radio/sx1278/test-sx1278-bench-gui.cpp)
+target_compile_definitions(test-sx1278lora-gui-rx PRIVATE DISABLE_TX SX1278_IS_LORA)
+sbs_target(test-sx1278lora-gui-rx stm32f429zi_skyward_groundstation_v2)
+
+add_executable(test-sx1278lora-gui-tx src/tests/radio/sx1278/test-sx1278-bench-gui.cpp)
+target_compile_definitions(test-sx1278lora-gui-tx PRIVATE DISABLE_RX SX1278_IS_LORA)
+sbs_target(test-sx1278lora-gui-tx stm32f429zi_skyward_groundstation_v2)
+
 #-----------------------------------------------------------------------------#
 #                               Tests - Sensors                               #
 #-----------------------------------------------------------------------------#
diff --git a/cmake/boardcore.cmake b/cmake/boardcore.cmake
index 435e99a41e20199bf39d6353ba9e1dfc8fe970a2..2b621f0ac78ea8c67b4056aaf1b1a20575d8efcd 100644
--- a/cmake/boardcore.cmake
+++ b/cmake/boardcore.cmake
@@ -76,7 +76,6 @@ foreach(OPT_BOARD ${BOARDS})
         ${SBS_BASE}/src/shared/radio/SX1278/SX1278Fsk.cpp
         ${SBS_BASE}/src/shared/radio/SX1278/SX1278Lora.cpp
         ${SBS_BASE}/src/shared/radio/SX1278/SX1278Common.cpp
-        ${SBS_BASE}/src/shared/radio/SX1278/Ebyte.cpp
 
         # Scheduler
         ${SBS_BASE}/src/shared/scheduler/TaskScheduler.cpp
diff --git a/src/entrypoints/sx1278-serial.cpp b/src/entrypoints/sx1278-serial.cpp
index 72fdc096eb46ba30099744d763b85097c24a50a7..ae0e6f41ae36a2b43fec40d02a6cbc7232e1d1d5 100644
--- a/src/entrypoints/sx1278-serial.cpp
+++ b/src/entrypoints/sx1278-serial.cpp
@@ -24,13 +24,12 @@
 #include <filesystem/console/console_device.h>
 
 // SX1278 includes
-#include <radio/SX1278/Ebyte.h>
+#include <radio/SX1278/SX1278Frontends.h>
 #include <radio/SX1278/SX1278Fsk.h>
 #include <radio/SX1278/SX1278Lora.h>
 
 #include <thread>
 
-using namespace Boardcore;
 using namespace miosix;
 
 // Uncomment the following line to enable Lora mode
@@ -42,6 +41,8 @@ using namespace miosix;
 
 // Uncomment the following line to enable Ebyte module
 // #define SX1278_IS_EBYTE
+// Uncomment the following line to ebable Skyward433 module
+// #define SX1278_IS_SKYWARD433
 
 using cs   = peripherals::ra01::pc13::cs;
 using dio0 = peripherals::ra01::pc13::dio0;
@@ -60,42 +61,125 @@ using rxen = Gpio<GPIOD_BASE, 4>;
 #define SX1278_SPI SPI4
 
 #define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
-#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl
 #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
 
+#elif defined _BOARD_STM32F429ZI_SKYWARD_RIG
+#include "interfaces-impl/hwmapping.h"
+
+#define SX1278_IS_EBYTE
+
+using cs   = radio::cs;
+using dio0 = radio::dio0;
+using dio1 = radio::dio1;
+using dio3 = radio::dio3;
+
+using sck  = radio::sck;
+using miso = radio::miso;
+using mosi = radio::mosi;
+
+using txen                         = radio::txEn;
+using rxen                         = radio::rxEn;
+
+#define SX1278_SPI SPI4
+
+#define SX1278_IRQ_DIO0 EXTI5_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI12_IRQHandlerImpl
+#define SX1278_IRQ_DIO3 EXTI13_IRQHandlerImpl
+
+#elif defined _BOARD_STM32F767ZI_GEMINI_GS
+#include "interfaces-impl/hwmapping.h"
+
+// #define SX1278_IS_SKYWARD433
+// #define SX1278_IS_EBYTE
+
+// Comment to use SX1278_2
+// #define SX1278_1
+
+#ifdef SX1278_1
+using cs   = miosix::radio1::cs;
+using dio0 = miosix::radio1::dio0;
+using dio1 = miosix::radio1::dio1;
+using dio3 = miosix::radio1::dio3;
+
+using sck  = miosix::radio1::spi::sck;
+using miso = miosix::radio1::spi::miso;
+using mosi = miosix::radio1::spi::mosi;
+
+using txen = miosix::radio1::txen;
+using rxen = miosix::radio1::rxen;
+
+#define SX1278_NRST
+using rst  = miosix::radio1::nrst;
+
+#define SX1278_SPI MIOSIX_RADIO1_SPI
+
+#define SX1278_IRQ_DIO0 MIOSIX_RADIO1_DIO0_IRQ
+#define SX1278_IRQ_DIO1 MIOSIX_RADIO1_DIO1_IRQ
+#define SX1278_IRQ_DIO3 MIOSIX_RADIO1_DIO3_IRQ
+#else
+using cs   = miosix::radio2::cs;
+using dio0 = miosix::radio2::dio0;
+using dio1 = miosix::radio2::dio1;
+using dio3 = miosix::radio2::dio3;
+
+using sck  = miosix::radio2::spi::sck;
+using miso = miosix::radio2::spi::miso;
+using mosi = miosix::radio2::spi::mosi;
+
+using txen = miosix::radio2::txen;
+using rxen = miosix::radio2::rxen;
+
+#define SX1278_NRST
+using rst  = miosix::radio2::nrst;
+
+#define SX1278_SPI MIOSIX_RADIO2_SPI
+
+#define SX1278_IRQ_DIO0 MIOSIX_RADIO2_DIO0_IRQ
+#define SX1278_IRQ_DIO1 MIOSIX_RADIO2_DIO1_IRQ
+#define SX1278_IRQ_DIO3 MIOSIX_RADIO2_DIO3_IRQ
+#endif
+
 #else
 #error "Target not supported"
 #endif
 
 #ifdef SX1278_IS_LORA
-static constexpr size_t SX1278_MTU = SX1278Lora::MTU;
-SX1278Lora *sx1278                 = nullptr;
+static constexpr size_t SX1278_MTU = Boardcore::SX1278Lora::MTU;
+Boardcore::SX1278Lora *sx1278      = nullptr;
 #else
-static constexpr size_t SX1278_MTU = SX1278Fsk::MTU;
-SX1278Fsk *sx1278                  = nullptr;
+static constexpr size_t SX1278_MTU = Boardcore::SX1278Fsk::MTU;
+Boardcore::SX1278Fsk *sx1278       = nullptr;
 #endif
 
+volatile int dio0_cnt = 0;
+volatile int dio1_cnt = 0;
+volatile int dio3_cnt = 0;
+
 #ifdef SX1278_IRQ_DIO0
 void __attribute__((used)) SX1278_IRQ_DIO0()
 {
+    dio0_cnt++;
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278::Dio::DIO0);
+        sx1278->handleDioIRQ();
 }
 #endif
 
 #ifdef SX1278_IRQ_DIO1
 void __attribute__((used)) SX1278_IRQ_DIO1()
 {
+    dio1_cnt++;
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278::Dio::DIO1);
+        sx1278->handleDioIRQ();
 }
 #endif
 
 #ifdef SX1278_IRQ_DIO3
 void __attribute__((used)) SX1278_IRQ_DIO3()
 {
+    dio3_cnt++;
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278::Dio::DIO3);
+        sx1278->handleDioIRQ();
 }
 #endif
 
@@ -108,22 +192,9 @@ void initBoard()
     txen::low();
 #endif
 
-#ifdef SX1278_IRQ_DIO0
-    GpioPin dio0_pin = dio0::getPin();
-    enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-#endif
-
-#ifdef SX1278_IRQ_DIO1
-    GpioPin dio1_pin = dio1::getPin();
-    enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-#endif
-
-#ifdef SX1278_IRQ_DIO3
-    GpioPin dio3_pin = dio3::getPin();
-    enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
+#ifdef SX1278_NRST
+    rst::mode(miosix::Mode::OUTPUT);
+    rst::high();
 #endif
 }
 
@@ -155,36 +226,38 @@ void sendLoop()
     }
 }
 
+Boardcore::SPIBus sx1278_bus(SX1278_SPI);
+
 int main()
 {
     initBoard();
 
-    // Generic SPI configuration
-    SPIBusConfig spi_config;
-    spi_config.clockDivider = SPI::ClockDivider::DIV_64;
-    spi_config.mode         = SPI::Mode::MODE_0;
-    spi_config.bitOrder     = SPI::Order::MSB_FIRST;
-    spi_config.byteOrder    = SPI::Order::MSB_FIRST;
-    spi_config.writeBit     = SPI::WriteBit::INVERTED;
-
-    SPIBus bus(SX1278_SPI);
-    GpioPin cs = cs::getPin();
-
-    SPISlave spi(bus, cs, spi_config);
+#if defined SX1278_IS_EBYTE
+    printf("[sx1278] Confuring Ebyte frontend...\n");
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+        new Boardcore::EbyteFrontend(txen::getPin(), rxen::getPin()));
+#elif defined SX1278_IS_SKYWARD433
+    printf("[sx1278] Confuring Skyward 433 frontend...\n");
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+              new Boardcore::Skyward433Frontend());
+#else
+    printf("[sx1278] Confuring RA01 frontend...\n");
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+         new Boardcore::RA01Frontend());
+#endif
 
 #ifdef SX1278_IS_LORA
     // Run default configuration
-    SX1278Lora::Config config;
-    SX1278Lora::Error err;
+    Boardcore::SX1278Lora::Config config;
+    Boardcore::SX1278Lora::Error err;
 
-#ifdef SX1278_IS_EBYTE
-    sx1278 = new EbyteLora(spi, txen::getPin(), rxen::getPin());
-#else
-    sx1278 = new SX1278Lora(spi);
-#endif
+    sx1278 = new Boardcore::SX1278Lora(sx1278_bus, cs::getPin(), dio0::getPin(),
+                                       dio1::getPin(), dio3::getPin(),
+                                       Boardcore::SPI::ClockDivider::DIV_64,
+                                       std::move(frontend));
 
-    printf("\n[sx1278] Configuring sx1278...\n");
-    if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE)
+    printf("\n[sx1278] Configuring sx1278 lora...\n");
+    if ((err = sx1278->init(config)) != Boardcore::SX1278Lora::Error::NONE)
     {
         printf("[sx1278] sx1278->init error\n");
         return -1;
@@ -193,21 +266,23 @@ int main()
     printf("\n[sx1278] Initialization complete!\n");
 #else
     // Run default configuration
-    SX1278Fsk::Config config;
-    SX1278Fsk::Error err;
+    Boardcore::SX1278Fsk::Config config;
+    Boardcore::SX1278Fsk::Error err;
 
-#ifdef SX1278_IS_EBYTE
-    sx1278 = new EbyteFsk(spi, txen::getPin(), rxen::getPin());
-#else
-    sx1278 = new SX1278Fsk(spi);
-#endif
+    config.freq_rf    = 868000000;
+    config.enable_crc = false;
+
+    sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), dio0::getPin(),
+                                            dio1::getPin(), dio3::getPin(),
+                                            Boardcore::SPI::ClockDivider::DIV_256,
+                                            std::move(frontend));
 
-    printf("\n[sx1278] Configuring sx1278...\n");
-    if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE)
+    printf("\n[sx1278] Configuring sx1278 fsk...\n");
+    if ((err = sx1278->init(config)) != Boardcore::SX1278Fsk::Error::NONE)
     {
-                         // FIXME: Why does clang-format put this line up here?
+              // FIXME: Why does clang-format put this line up here?
         printf("[sx1278] sx1278->init error\n");
-        return -1;
+        return false;
     }
 
     printf("\n[sx1278] Initialization complete!\n");
diff --git a/src/shared/radio/SX1278/Ebyte.h b/src/shared/radio/SX1278/Ebyte.h
deleted file mode 100644
index c7e22a5d7330a6545c8ca8992b5d3cb8b3163b02..0000000000000000000000000000000000000000
--- a/src/shared/radio/SX1278/Ebyte.h
+++ /dev/null
@@ -1,87 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Davide Mor
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <miosix.h>
-
-#include "SX1278Fsk.h"
-#include "SX1278Lora.h"
-
-namespace Boardcore
-{
-
-/**
- * @brief Specialized SX1278 driver for the E32 400M30S module
- */
-class EbyteFsk : public SX1278Fsk
-{
-public:
-    EbyteFsk(SPISlave slave, miosix::GpioPin tx_enable,
-             miosix::GpioPin rx_enable)
-        : SX1278Fsk(slave), tx_enable(tx_enable), rx_enable(rx_enable)
-    {
-        // Make sure both the frontends are disabled!
-        tx_enable.low();
-        rx_enable.low();
-    }
-
-    [[nodiscard]] Error configure(const Config &config) override;
-
-private:
-    void enableRxFrontend() override;
-    void disableRxFrontend() override;
-    void enableTxFrontend() override;
-    void disableTxFrontend() override;
-
-    miosix::GpioPin tx_enable;
-    miosix::GpioPin rx_enable;
-};
-
-/**
- * @brief Specialized SX1278 driver for the E32 400M30S module
- */
-class EbyteLora : public SX1278Lora
-{
-public:
-    EbyteLora(SPISlave slave, miosix::GpioPin tx_enable,
-              miosix::GpioPin rx_enable)
-        : SX1278Lora(slave), tx_enable(tx_enable), rx_enable(rx_enable)
-    {
-        // Make sure both the frontends are disabled!
-        tx_enable.low();
-        rx_enable.low();
-    }
-
-    [[nodiscard]] Error configure(const Config &config) override;
-
-private:
-    void enableRxFrontend() override;
-    void disableRxFrontend() override;
-    void enableTxFrontend() override;
-    void disableTxFrontend() override;
-
-    miosix::GpioPin tx_enable;
-    miosix::GpioPin rx_enable;
-};
-
-}  // namespace Boardcore
diff --git a/src/shared/radio/SX1278/SX1278Common.cpp b/src/shared/radio/SX1278/SX1278Common.cpp
index 08b03a30126972efbd0e50c0ec75541a6fe6500d..a4cc12d11b023225a5504b94801a93956e9772fb 100644
--- a/src/shared/radio/SX1278/SX1278Common.cpp
+++ b/src/shared/radio/SX1278/SX1278Common.cpp
@@ -30,9 +30,9 @@ namespace Boardcore
 namespace SX1278
 {
 
-void SX1278Common::handleDioIRQ(Dio dio)
+void SX1278Common::handleDioIRQ()
 {
-    if (state.waiting_dio_mask.test(dio) && state.irq_wait_thread)
+    if (state.irq_wait_thread)
     {
         state.irq_wait_thread->IRQwakeup();
         if (state.irq_wait_thread->IRQgetPriority() >
@@ -45,73 +45,70 @@ void SX1278Common::handleDioIRQ(Dio dio)
     }
 }
 
+void SX1278Common::enableIrqs()
+{
+    enableExternalInterrupt(dio0, InterruptTrigger::RISING_EDGE);
+    enableExternalInterrupt(dio1, InterruptTrigger::RISING_EDGE);
+    enableExternalInterrupt(dio3, InterruptTrigger::RISING_EDGE);
+}
+
+void SX1278Common::disableIrqs()
+{
+    disableExternalInterrupt(dio0);
+    disableExternalInterrupt(dio1);
+    disableExternalInterrupt(dio3);
+}
+
 void SX1278Common::setDefaultMode(Mode mode, DioMapping mapping,
+                                  InterruptTrigger dio1_trigger,
                                   bool tx_frontend, bool rx_frontend)
 {
-    mutex.lock();
-    enterMode(mode, mapping, tx_frontend, rx_frontend);
-    mutex.unlock();
+    miosix::Lock<miosix::FastMutex> lock(mutex);
+    enterMode(mode, mapping, dio1_trigger, tx_frontend, rx_frontend);
 }
 
-void SX1278Common::waitForIrq(LockMode &_guard, IrqFlags irq, bool unlock)
+ISX1278::IrqFlags SX1278Common::waitForIrq(LockMode &guard, IrqFlags set_irq,
+                                           IrqFlags reset_irq, bool unlock)
 {
-    // Take a reference to a _guard to MAKE SURE that the mutex is locked, but
-    // otherwise don't do anything with it
-    (void)_guard;
-
-    // Convert the IRQ mask into a DIO mask
-    DioMask waiting_dio_mask =
-        getDioMaskFromIrqFlags(irq, state.mode, state.mapping);
+    IrqFlags ret_irq = 0;
 
     do
     {
         // An interrupt could occur and read from this variables
         {
-            miosix::FastInterruptDisableLock dLock;
-            state.waiting_dio_mask = waiting_dio_mask;
-            state.irq_wait_thread  = miosix::Thread::IRQgetCurrentThread();
+            miosix::FastInterruptDisableLock lock;
+            state.irq_wait_thread = miosix::Thread::IRQgetCurrentThread();
         }
 
         // Check that this hasn't already happened
-        if (checkForIrqAndReset(irq))
-        {
-            return;
-        }
-
-        if (unlock)
+        if ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) != 0)
         {
-            mutex.unlock();
+            break;
         }
 
+        if (!waitForIrqInner(guard, unlock))
         {
-            miosix::FastInterruptDisableLock dLock;
-            while (state.irq_wait_thread)
-            {
-                miosix::Thread::IRQwait();
-                {
-                    miosix::FastInterruptEnableLock eLock(dLock);
-                    miosix::Thread::yield();
-                }
-            }
+            // TODO: Something bad happened, do something!
         }
 
-        // Regain ownership of the lock
-        if (unlock)
-        {
-            mutex.lock();
-        }
+        // TODO: Check state of the device, and reset if needed!
 
         // Protect against sporadic IRQs
-    } while (!checkForIrqAndReset(irq));
+    } while ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) == 0);
+
+    return ret_irq;
 }
 
-bool SX1278Common::waitForIrqBusy(LockMode &_guard, IrqFlags irq, int timeout)
+ISX1278::IrqFlags SX1278Common::waitForIrqBusy(LockMode &_guard,
+                                               IrqFlags set_irq,
+                                               IrqFlags reset_irq, int timeout)
 {
     // Take a reference to a _guard to MAKE SURE that the mutex is locked, but
     // otherwise don't do anything with it
     (void)_guard;
 
-    long long start = miosix::getTick();
+    long long start  = miosix::getTick();
+    IrqFlags ret_irq = 0;
 
     while ((miosix::getTick() - start) < timeout)
     {
@@ -121,44 +118,81 @@ bool SX1278Common::waitForIrqBusy(LockMode &_guard, IrqFlags irq, int timeout)
         // Tight loop on IRQ register
         for (unsigned int i = 0; i < 1000 / DELAY; i++)
         {
-            if (checkForIrqAndReset(irq))
+            // Check if some of the interrupts triggered
+            if ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) != 0)
             {
-                return true;
+                return ret_irq;
             }
 
             miosix::delayUs(DELAY);
         }
     }
 
-    return false;
+    return 0;
 }
 
-bool SX1278Common::checkForIrqAndReset(IrqFlags irq)
+bool SX1278Common::waitForIrqInner(LockMode &_guard, bool unlock)
 {
-    IrqFlags cur_irq = getIrqFlags();
-    if (cur_irq & irq)
+    // Take a reference to a _guard to MAKE SURE that the mutex is locked, but
+    // otherwise don't do anything with it
+    (void)_guard;
+
+    // Release the lock for others to take
+    if (unlock)
     {
-        // Reset all of the interrupts we have detected
-        resetIrqFlags(cur_irq & irq);
+        mutex.unlock();
+    }
 
-        return true;
+    int start                      = miosix::getTick();
+    miosix::TimedWaitResult result = miosix::TimedWaitResult::NoTimeout;
+
+    {
+        miosix::FastInterruptDisableLock lock;
+        while (state.irq_wait_thread &&
+               result == miosix::TimedWaitResult::NoTimeout)
+        {
+            result = miosix::Thread::IRQenableIrqAndTimedWaitMs(
+                lock, start + IRQ_TIMEOUT);
+        }
     }
-    else
+
+    // Regain ownership of the lock
+    if (unlock)
+    {
+        mutex.lock();
+    }
+
+    // Check that we didn't have a timeout
+    return result == miosix::TimedWaitResult::NoTimeout;
+}
+
+ISX1278::IrqFlags SX1278Common::checkForIrqAndReset(IrqFlags set_irq,
+                                                    IrqFlags reset_irq)
+{
+    IrqFlags cur_irq = getIrqFlags();
+    if (cur_irq & set_irq)
     {
-        return false;
+        // Reset all of the interrupts we have detected
+        resetIrqFlags(cur_irq & set_irq);
     }
+
+    return (cur_irq & set_irq) | (~cur_irq & reset_irq);
 }
 
+ISX1278Frontend &SX1278Common::getFrontend() { return *frontend; }
+
+SPISlave &SX1278Common::getSpiSlave() { return slave; }
+
 SX1278Common::DeviceState SX1278Common::lockMode(Mode mode, DioMapping mapping,
+                                                 InterruptTrigger dio1_trigger,
                                                  bool tx_frontend,
                                                  bool rx_frontend)
 {
     // Store previous state
     DeviceState old_state = state;
 
-    enterMode(mode, mapping, tx_frontend, rx_frontend);
-    state.irq_wait_thread  = nullptr;
-    state.waiting_dio_mask = DioMask();
+    enterMode(mode, mapping, dio1_trigger, tx_frontend, rx_frontend);
+    state.irq_wait_thread = nullptr;
 
     return old_state;
 }
@@ -166,10 +200,9 @@ SX1278Common::DeviceState SX1278Common::lockMode(Mode mode, DioMapping mapping,
 void SX1278Common::unlockMode(DeviceState old_state)
 {
     // Do this copy manually, we want stuff to be copied in a specific order
-    state.irq_wait_thread  = old_state.irq_wait_thread;
-    state.waiting_dio_mask = old_state.waiting_dio_mask;
-    enterMode(old_state.mode, old_state.mapping, old_state.is_tx_frontend_on,
-              old_state.is_rx_frontend_on);
+    state.irq_wait_thread = old_state.irq_wait_thread;
+    enterMode(old_state.mode, old_state.mapping, old_state.dio1_trigger,
+              old_state.is_tx_frontend_on, old_state.is_rx_frontend_on);
 }
 
 void SX1278Common::lock() { mutex.lock(); }
@@ -177,6 +210,7 @@ void SX1278Common::lock() { mutex.lock(); }
 void SX1278Common::unlock() { mutex.unlock(); }
 
 void SX1278Common::enterMode(Mode mode, DioMapping mapping,
+                             InterruptTrigger dio1_trigger,
                              bool set_tx_frontend_on, bool set_rx_frontend_on)
 {
     // disable - enable in order to avoid having both RX/TX frontends active at
@@ -185,35 +219,41 @@ void SX1278Common::enterMode(Mode mode, DioMapping mapping,
     // First disable all of the frontend if necessary
     if (set_tx_frontend_on != state.is_tx_frontend_on && !set_tx_frontend_on)
     {
-        disableTxFrontend();
+        getFrontend().disableTx();
     }
 
     if (set_rx_frontend_on != state.is_rx_frontend_on && !set_rx_frontend_on)
     {
-        disableRxFrontend();
+        getFrontend().disableRx();
     }
 
     // Then enable the newly requested ones
     if (set_tx_frontend_on != state.is_tx_frontend_on && set_tx_frontend_on)
     {
-        enableTxFrontend();
+        getFrontend().enableTx();
     }
 
     if (set_rx_frontend_on != state.is_rx_frontend_on && set_rx_frontend_on)
     {
-        enableRxFrontend();
+        getFrontend().enableRx();
     }
 
     state.is_tx_frontend_on = set_tx_frontend_on;
     state.is_rx_frontend_on = set_rx_frontend_on;
 
-    // Check if necessary
     if (mode != state.mode)
     {
         setMode(mode);
         state.mode = mode;
     }
 
+    // Change DIO1 interrupt kind
+    if (dio1_trigger != state.dio1_trigger)
+    {
+        changeInterruptTrigger(dio1, dio1_trigger);
+        state.dio1_trigger = dio1_trigger;
+    }
+
     // Finally setup DIO mapping
     if (mapping != state.mapping)
     {
diff --git a/src/shared/radio/SX1278/SX1278Common.h b/src/shared/radio/SX1278/SX1278Common.h
index 0fee45b8cec93663327b98368a6d2a4581a9485c..30122331fc437aecd57faf5f37de482862e9c2c8 100644
--- a/src/shared/radio/SX1278/SX1278Common.h
+++ b/src/shared/radio/SX1278/SX1278Common.h
@@ -22,10 +22,14 @@
 
 #pragma once
 
+#include <drivers/interrupt/external_interrupts.h>
 #include <drivers/spi/SPIDriver.h>
 #include <miosix.h>
 #include <radio/Transceiver.h>
 
+#include <cmath>
+#include <memory>
+
 #include "SX1278Defs.h"
 
 namespace Boardcore
@@ -34,25 +38,6 @@ namespace Boardcore
 namespace SX1278
 {
 
-/**
- * @brief Represents a set of Dio
- */
-class DioMask
-{
-public:
-    DioMask() : mask(0) {}
-
-    bool test(Dio dio) const
-    {
-        return (mask & (1 << static_cast<int>(dio))) != 0;
-    }
-    void set(Dio dio) { mask |= (1 << static_cast<int>(dio)); }
-    void reset(Dio dio) { mask &= ~(1 << static_cast<int>(dio)); }
-
-private:
-    uint8_t mask;
-};
-
 using DioMapping = RegDioMapping::Mapping;
 
 /**
@@ -60,6 +45,24 @@ using DioMapping = RegDioMapping::Mapping;
  */
 class ISX1278 : public Transceiver
 {
+public:
+    /**
+     * @brief Get the RSSI in dBm, during last packet receive.
+     */
+    virtual float getLastRxRssi() = 0;
+
+    /**
+     * @brief Get the frequency error index in Hz, during last packet receive
+     * (NaN if not available).
+     */
+    virtual float getLastRxFei() { return std::nanf(""); }
+
+    /**
+     * @brief Get the signal to noise ratio, during last packet receive (NaN if
+     * not available).
+     */
+    virtual float getLastRxSnr() { return std::nanf(""); }
+
 protected:
     /*
      * Stuff used internally by SX1278Common
@@ -73,14 +76,28 @@ protected:
 
     virtual IrqFlags getIrqFlags()             = 0;
     virtual void resetIrqFlags(IrqFlags flags) = 0;
+};
 
-    virtual DioMask getDioMaskFromIrqFlags(IrqFlags flags, Mode mode,
-                                           DioMapping mapping) = 0;
+/**
+ * @brief Shared interface between all SX1278 frontends
+ */
+class ISX1278Frontend
+{
+public:
+    /**
+     * @brief Is this frontend connected to PA_BOOST or RFO_LF/_HF?
+     */
+    virtual bool isOnPaBoost() = 0;
 
-    virtual void enableRxFrontend()  = 0;
-    virtual void disableRxFrontend() = 0;
-    virtual void enableTxFrontend()  = 0;
-    virtual void disableTxFrontend() = 0;
+    /**
+     * @brief What is the maximum power supported by this frontend?
+     */
+    virtual int maxInPower() = 0;
+
+    virtual void enableRx()  = 0;
+    virtual void disableRx() = 0;
+    virtual void enableTx()  = 0;
+    virtual void disableTx() = 0;
 };
 
 class SX1278Common : public ISX1278
@@ -94,24 +111,35 @@ private:
         DioMapping mapping = DioMapping();
         // Thread waiting listening for interrupts
         miosix::Thread *irq_wait_thread = nullptr;
-        // What DIOs are we waiting on
-        DioMask waiting_dio_mask = DioMask();
         // True if the RX frontend is enabled
         bool is_rx_frontend_on = false;
         // True if the TX frontend is enabled
         bool is_tx_frontend_on = false;
+        // Mode of trigger for dio1
+        InterruptTrigger dio1_trigger = InterruptTrigger::RISING_EDGE;
     };
 
-public:
-    using Dio = SX1278::Dio;
+    // This is reasonably the maximum we should wait for an interrupt
+    static constexpr int IRQ_TIMEOUT = 100;
 
+public:
     /**
      * @brief Handle generic DIO irq.
      */
-    void handleDioIRQ(Dio dio);
+    void handleDioIRQ();
 
 protected:
-    explicit SX1278Common(SPISlave slave) : slave(slave) {}
+    explicit SX1278Common(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0,
+                          miosix::GpioPin dio1, miosix::GpioPin dio3,
+                          SPI::ClockDivider clock_divider,
+                          std::unique_ptr<ISX1278Frontend> frontend)
+        : slave(SPISlave(bus, cs, getSpiBusConfig(clock_divider))), dio0(dio0),
+          dio1(dio1), dio3(dio3), frontend(std::move(frontend))
+    {
+        enableIrqs();
+    }
+
+    ~SX1278Common() { disableIrqs(); }
 
     /**
      * @brief RAII scoped bus lock guard.
@@ -134,13 +162,14 @@ protected:
     {
     public:
         LockMode(SX1278Common &driver, Lock &lock, Mode mode,
-                 DioMapping mapping, bool set_tx_frontend_on = false,
+                 DioMapping mapping, InterruptTrigger dio1_trigger,
+                 bool set_tx_frontend_on = false,
                  bool set_rx_frontend_on = false)
             : driver(driver), lock(lock)
         {
             // cppcheck-suppress useInitializationList
-            old_state = driver.lockMode(mode, mapping, set_tx_frontend_on,
-                                        set_rx_frontend_on);
+            old_state = driver.lockMode(mode, mapping, dio1_trigger,
+                                        set_tx_frontend_on, set_rx_frontend_on);
         }
 
         ~LockMode() { driver.unlockMode(old_state); }
@@ -156,44 +185,65 @@ protected:
      *
      * WARNING: This will lock the mutex.
      */
-    void setDefaultMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on,
+    void setDefaultMode(Mode mode, DioMapping mapping,
+                        InterruptTrigger dio1_trigger, bool set_tx_frontend_on,
                         bool set_rx_frontend_on);
 
     /**
      * @brief Wait for generic irq.
      */
-    void waitForIrq(LockMode &guard, IrqFlags irq, bool unlock = false);
+    IrqFlags waitForIrq(LockMode &guard, IrqFlags set_irq, IrqFlags reset_irq,
+                        bool unlock = false);
 
     /**
      * @brief Busy waits for an interrupt by polling the irq register.
      *
      * USE ONLY DURING INITIALIZATION! BAD THINGS *HAVE* HAPPENED DUE TO THIS!
      */
-    bool waitForIrqBusy(LockMode &guard, IrqFlags irq, int timeout);
+    IrqFlags waitForIrqBusy(LockMode &guard, IrqFlags set_irq,
+                            IrqFlags reset_irq, int timeout);
 
     /**
-     * @brief Returns if an interrupt happened, and clears it if it did.
+     * @brief Returns a mask containing triggered interrupts.
+     *
+     * NOTE: This function checks both set irqs (rising edge), and reset irqs
+     * (falling edge). But it only resets set interrupts.
+     *
+     * @param set_irq Mask containing set (rising edge) interrupts.
+     * @param reset_irq Mask containing reset (falling edge) interrupts.
+     * @return Mask containing all triggered interrupts (both rising and
+     * falling)
      */
-    bool checkForIrqAndReset(IrqFlags irq);
+    IrqFlags checkForIrqAndReset(IrqFlags set_irq, IrqFlags reset_irq);
 
-    /**
-     * @brief The actual SPISlave, used by child classes.
-     */
-    SPISlave slave;
+    ISX1278Frontend &getFrontend();
+
+    SPISlave &getSpiSlave();
 
 private:
-    DeviceState lockMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on,
+    void enableIrqs();
+    void disableIrqs();
+
+    bool waitForIrqInner(LockMode &guard, bool unlock);
+
+    DeviceState lockMode(Mode mode, DioMapping mapping,
+                         InterruptTrigger dio1_trigger, bool set_tx_frontend_on,
                          bool set_rx_frontend_on);
     void unlockMode(DeviceState old_state);
 
     void lock();
     void unlock();
 
-    void enterMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on,
-                   bool set_rx_frontend_on);
+    void enterMode(Mode mode, DioMapping mapping, InterruptTrigger dio1_trigger,
+                   bool set_tx_frontend_on, bool set_rx_frontend_on);
 
     miosix::FastMutex mutex;
     DeviceState state;
+    SPISlave slave;
+    miosix::GpioPin dio0;
+    miosix::GpioPin dio1;
+    miosix::GpioPin dio3;
+    std::unique_ptr<ISX1278Frontend> frontend;
 };
 
 }  // namespace SX1278
diff --git a/src/shared/radio/SX1278/SX1278Defs.h b/src/shared/radio/SX1278/SX1278Defs.h
index e524279a806bd3685b2825f2393401a1ab2f4681..1398b00dbc417c1864d26d9578c0ae797ad5e075 100644
--- a/src/shared/radio/SX1278/SX1278Defs.h
+++ b/src/shared/radio/SX1278/SX1278Defs.h
@@ -22,6 +22,8 @@
 
 #pragma once
 
+#include <drivers/spi/SPIBusInterface.h>
+
 #include <cstdint>
 
 namespace Boardcore
@@ -40,6 +42,25 @@ constexpr int FXOSC = 32000000;
  */
 constexpr float FSTEP = 61.03515625;
 
+inline SPIBusConfig getSpiBusConfig(SPI::ClockDivider clock_divider)
+{
+    SPIBusConfig bus_config = {};
+    bus_config.clockDivider = clock_divider;
+    bus_config.mode         = SPI::Mode::MODE_0;
+    bus_config.bitOrder     = SPI::Order::MSB_FIRST;
+    bus_config.byteOrder    = SPI::Order::MSB_FIRST;
+    bus_config.writeBit     = SPI::WriteBit::INVERTED;
+    bus_config.csHoldTimeUs = 3;
+
+    return bus_config;
+}
+
+constexpr int MIN_FREQ_DEV = 0;
+constexpr int MAX_FREQ_DEV = 0x3fff * FSTEP;
+
+constexpr int MIN_FREQ_RF = 0;
+constexpr int MAX_FREQ_RF = 0xffffff * FSTEP;
+
 /**
  * @brief Represents a DIO..
  */
@@ -121,20 +142,12 @@ constexpr int FIFO_LEN = 64;
 namespace RegOpMode
 {
 
-enum LongRangeMode
-{
-    LONG_RANGE_MODE_FSK  = 0 << 7,
-    LONG_RANGE_MODE_LORA = 1 << 7
-};
-
 enum ModulationType
 {
     MODULATION_TYPE_FSK = 0 << 6,
     MODULATION_TYPE_OOK = 1 << 6,
 };
 
-constexpr uint8_t LOW_FREQUENCY_MODE_ON = 1 << 3;
-
 enum Mode
 {
     MODE_SLEEP = 0b000,
@@ -145,94 +158,197 @@ enum Mode
     MODE_RX    = 0b101,
 };
 
+inline constexpr uint8_t make(Mode mode, bool low_frequency_mode_on,
+                              ModulationType modulation_type)
+{
+    return mode | (low_frequency_mode_on ? (1 << 3) : 0) |
+           (modulation_type << 5);
+}
+
 }  // namespace RegOpMode
 
 namespace RegPaConfig
 {
-constexpr uint8_t PA_SELECT_BOOST = 1 << 7;
+
+inline constexpr uint8_t make(uint8_t output_power, uint8_t max_power,
+                              bool pa_select)
+{
+    return (output_power & 0b1111) | ((max_power & 0b111) << 4) |
+           (pa_select ? 1 << 7 : 0);
 }
 
+}  // namespace RegPaConfig
+
 namespace RegPaRamp
 {
 enum ModulationShaping
 {
-    MODULATION_SHAPING_NONE            = 0b00 << 5,
-    MODULATION_SHAPING_GAUSSIAN_BT_1_0 = 0b01 << 5,
-    MODULATION_SHAPING_GAUSSIAN_BT_0_5 = 0b10 << 5,
-    MODULATION_SHAPING_GAUSSIAN_BT_0_3 = 0b11 << 5,
+    MODULATION_SHAPING_NONE            = 0b00,
+    MODULATION_SHAPING_GAUSSIAN_BT_1_0 = 0b01,
+    MODULATION_SHAPING_GAUSSIAN_BT_0_5 = 0b10,
+    MODULATION_SHAPING_GAUSSIAN_BT_0_3 = 0b11,
+};
+
+enum PaRamp
+{
+    PA_RAMP_MS_3_4 = 0b0000,
+    PA_RAMP_MS_2   = 0b0001,
+    PA_RAMP_MS_1   = 0b0010,
+    PA_RAMP_US_500 = 0b0011,
+    PA_RAMP_US_250 = 0b0100,
+    PA_RAMP_US_125 = 0b0101,
+    PA_RAMP_US_100 = 0b0110,
+    PA_RAMP_US_62  = 0b0111,
+    PA_RAMP_US_50  = 0b1000,
+    PA_RAMP_US_40  = 0b1001,
+    PA_RAMP_US_31  = 0b1010,
+    PA_RAMP_US_25  = 0b1011,
+    PA_RAMP_US_20  = 0b1100,
+    PA_RAMP_US_15  = 0b1101,
+    PA_RAMP_US_12  = 0b1110,
+    PA_RAMP_US_10  = 0b1111,
 };
+
+inline constexpr uint8_t make(PaRamp pa_ramp,
+                              ModulationShaping modulation_shaping)
+{
+    return pa_ramp | (modulation_shaping << 5);
 }
 
+}  // namespace RegPaRamp
+
 namespace RegOcp
 {
-constexpr uint8_t OCP_ON = 1 << 5;
+
+inline constexpr uint8_t make(uint8_t ocp_trim, bool ocp_on)
+{
+    return (ocp_trim & 0b11111) | (ocp_on ? 1 << 5 : 0);
 }
 
+}  // namespace RegOcp
+
 namespace RegRxConfig
 {
-constexpr uint8_t RESTART_RX_ON_COLLISION      = 1 << 7;
-constexpr uint8_t RESTART_RX_WITHOUT_PILL_LOCK = 1 << 6;
-constexpr uint8_t RESTART_RX_WITH_PILL_LOCK    = 1 << 5;
-constexpr uint8_t AFC_AUTO_ON                  = 1 << 4;
-constexpr uint8_t AGC_AUTO_ON                  = 1 << 3;
 
-constexpr uint8_t RX_TRIGGER_RSSI_INTERRUPT  = 0b001;
-constexpr uint8_t RX_TRIGGER_PREAMBLE_DETECT = 0b110;
+inline constexpr uint8_t make(bool rx_trigger_rssi_interrupt,
+                              bool rx_trigger_preable_detect, bool agc_auto_on,
+                              bool afc_auto_on, bool restart_rx_with_pll_lock,
+                              bool restart_rx_without_pll_lock,
+                              bool restart_rx_on_collision)
+{
+    return (rx_trigger_rssi_interrupt ? 0b001 : 0) |
+           (rx_trigger_preable_detect ? 0b110 : 0) |
+           (agc_auto_on ? 1 << 3 : 0) | (afc_auto_on ? 1 << 4 : 0) |
+           (restart_rx_with_pll_lock ? 1 << 5 : 0) |
+           (restart_rx_without_pll_lock ? 1 << 6 : 0) |
+           (restart_rx_on_collision ? 1 << 7 : 0);
+}
+
 }  // namespace RegRxConfig
 
+namespace RegRxBw
+{
+
+enum RxBw
+{
+    HZ_2600   = 0b10111,
+    HZ_3100   = 0b01111,
+    HZ_3900   = 0b00111,
+    HZ_5200   = 0b10110,
+    HZ_6300   = 0b01110,
+    HZ_7800   = 0b00110,
+    HZ_10400  = 0b10101,
+    HZ_12500  = 0b01101,
+    HZ_15600  = 0b00101,
+    HZ_20800  = 0b10100,
+    HZ_25000  = 0b01100,
+    HZ_31300  = 0b00100,
+    HZ_41700  = 0b10011,
+    HZ_50000  = 0b01011,
+    HZ_62500  = 0b00011,
+    HZ_83300  = 0b10010,
+    HZ_100000 = 0b01010,
+    HZ_125000 = 0b00010,
+    HZ_166700 = 0b10001,
+    HZ_200000 = 0b01001,
+    HZ_250000 = 0b00001,
+};
+
+inline constexpr uint8_t make(RxBw rx_bw) { return rx_bw; }
+
+}  // namespace RegRxBw
+
+namespace RegAfcBw
+{
+
+using RxBwAfc = Boardcore::SX1278::Fsk::RegRxBw::RxBw;
+
+inline constexpr uint8_t make(RxBwAfc rx_bw_afc) { return rx_bw_afc; }
+
+}  // namespace RegAfcBw
+
 namespace RegPreambleDetector
 {
-constexpr uint8_t PREAMBLE_DETECTOR_ON = 1 << 7;
 
-enum PreambleDetectorSize
+enum Size
 {
-    PREAMBLE_DETECTOR_SIZE_1_BYTE  = 0b00 << 5,
-    PREAMBLE_DETECTOR_SIZE_2_BYTES = 0b01 << 5,
-    PREAMBLE_DETECTOR_SIZE_3_BYTES = 0b10 << 5,
+    PREAMBLE_DETECTOR_SIZE_1_BYTE  = 0b00,
+    PREAMBLE_DETECTOR_SIZE_2_BYTES = 0b01,
+    PREAMBLE_DETECTOR_SIZE_3_BYTES = 0b10,
 };
+
+inline constexpr uint8_t make(int tol, Size size, bool on)
+{
+    return (tol & 0b11111) | (size << 5) | (on ? 1 << 7 : 0);
+}
+
 }  // namespace RegPreambleDetector
 
 namespace RegSyncConfig
 {
 enum AutoRestartRxMode
 {
-    AUTO_RESTART_RX_MODE_OFF                  = 0b00 << 6,
-    AUTO_RESTART_RX_MODE_ON_WITHOUT_PILL_LOCK = 0b01 << 6,
-    AUTO_RESTART_RX_MODE_ON_WITH_PILL_LOCK    = 0b10 << 6,
+    AUTO_RESTART_RX_MODE_OFF                  = 0b00,
+    AUTO_RESTART_RX_MODE_ON_WITHOUT_PILL_LOCK = 0b01,
+    AUTO_RESTART_RX_MODE_ON_WITH_PILL_LOCK    = 0b10,
 };
 
 enum PreamblePolarity
 {
-    PREAMBLE_POLARITY_AA = 0 << 5,
-    PREAMBLE_POLARITY_55 = 1 << 5,
+    PREAMBLE_POLARITY_AA = 0,
+    PREAMBLE_POLARITY_55 = 1,
 };
 
-constexpr uint8_t SYNC_ON = 1 << 4;
+inline constexpr uint8_t make(int size, bool on,
+                              PreamblePolarity preamble_polarity,
+                              AutoRestartRxMode auto_restart_rx_mode)
+{
+    return ((size - 1) & 0b111) | (on ? 1 << 4 : 0) | (preamble_polarity << 5) |
+           (auto_restart_rx_mode << 6);
+}
+
 }  // namespace RegSyncConfig
 
 namespace RegPacketConfig1
 {
 enum PacketFormat
 {
-    PACKET_FORMAT_FIXED_LENGTH    = 0 << 7,
-    PACKET_FORMAT_VARIABLE_LENGTH = 1 << 7,
+    PACKET_FORMAT_FIXED_LENGTH    = 0,
+    PACKET_FORMAT_VARIABLE_LENGTH = 1,
 };
 
 enum DcFree
 {
-    DC_FREE_NONE       = 0b00 << 5,
-    DC_FREE_MANCHESTER = 0b01 << 5,
-    DC_FREE_WHITENING  = 0b10 << 5,
+    DC_FREE_NONE       = 0b00,
+    DC_FREE_MANCHESTER = 0b01,
+    DC_FREE_WHITENING  = 0b10,
 };
 
-constexpr uint8_t CRC_ON             = 1 << 4;
-constexpr uint8_t CRC_AUTO_CLEAR_OFF = 1 << 3;
-
 enum AddressFiltering
 {
-    ADDRESS_FILTERING_NONE                    = 0b00 << 1,
-    ADDRESS_FILTERING_MATCH_NODE              = 0b01 << 1,
-    ADDRESS_FILTERING_MATCH_NODE_OR_BROADCAST = 0b10 << 1,
+    ADDRESS_FILTERING_NONE                    = 0b00,
+    ADDRESS_FILTERING_MATCH_NODE              = 0b01,
+    ADDRESS_FILTERING_MATCH_NODE_OR_BROADCAST = 0b10,
 };
 
 enum CrcWhiteningType
@@ -240,29 +356,52 @@ enum CrcWhiteningType
     CRC_WHITENING_TYPE_CCITT_CRC = 0,
     CRC_WHITENING_TYPE_IBM_CRC   = 1,
 };
+
+inline constexpr uint8_t make(CrcWhiteningType crc_whitening_type,
+                              AddressFiltering address_filtering,
+                              bool crc_auto_clear_off, bool crc_on,
+                              DcFree dc_free, PacketFormat packet_format)
+{
+    return crc_whitening_type | (address_filtering << 1) |
+           (crc_auto_clear_off ? 1 << 3 : 0) | (crc_on ? 1 << 4 : 0) |
+           (dc_free << 5) | (packet_format << 7);
+}
+
 }  // namespace RegPacketConfig1
 
 namespace RegPacketConfig2
 {
 enum DataMode
 {
-    DATA_MODE_CONTINUOS = 0 << 6,
-    DATA_MODE_PACKET    = 1 << 6
+    DATA_MODE_CONTINUOS = 0,
+    DATA_MODE_PACKET    = 1
 };
 
-constexpr uint8_t IO_HOME_ON = 1 << 5;
-constexpr uint8_t BEACON_ON  = 1 << 4;
+inline constexpr uint8_t make(bool beacon_on, bool io_home_power_frame,
+                              bool io_home_on, DataMode data_mode)
+{
+    return (beacon_on ? 1 << 3 : 0) | (io_home_power_frame ? 1 << 4 : 0) |
+           (io_home_on ? 1 << 5 : 0) | (data_mode << 6);
+}
+
 }  // namespace RegPacketConfig2
 
 namespace RegFifoThresh
 {
 enum TxStartCondition
 {
-    TX_START_CONDITION_FIFO_LEVEL     = 0 << 7,
-    TX_START_CONDITION_FIFO_NOT_EMPTY = 1 << 7,
+    TX_START_CONDITION_FIFO_LEVEL     = 0,
+    TX_START_CONDITION_FIFO_NOT_EMPTY = 1,
 };
+
+inline constexpr uint8_t make(int fifo_threshold,
+                              TxStartCondition tx_start_condition)
+{
+    return (fifo_threshold & 0b111111) | (tx_start_condition << 7);
 }
 
+}  // namespace RegFifoThresh
+
 namespace RegIrqFlags
 {
 
@@ -295,22 +434,10 @@ enum PaDac
     PA_DAC_DEFAULT_VALUE = 0x04,
     PA_DAC_PA_BOOST      = 0x07
 };
-}
 
-namespace RegImageCal
-{
-constexpr uint8_t AUTO_IMAGE_CAL_ON = 0x80;
+inline constexpr uint8_t make(PaDac pa_dac) { return pa_dac | (0x10 << 3); }
 
-enum TempTreshold
-{
-    TEMP_TRESHOLD_5DEG  = 0x00,
-    TEMP_TRESHOLD_10DEG = 0x02,
-    TEMP_TRESHOLD_15DEG = 0x04,
-    TEMP_TRESHOLD_20DEG = 0x06,
-};
-
-constexpr uint8_t TEMP_MONITOR_OFF = 0x01;
-}  // namespace RegImageCal
+}  // namespace RegPaDac
 
 enum Registers
 {
@@ -413,134 +540,6 @@ enum Registers
     REG_AGC_PILL     = 0x70,
 };
 
-static constexpr int DIO_MAPPINGS[6][8][4] =
-    {[0] =
-         {
-             [RegOpMode::MODE_SLEEP] = {0, 0, 0, 0},
-             [RegOpMode::MODE_STDBY] = {0, 0, 0, RegIrqFlags::LOW_BAT},
-             [RegOpMode::MODE_FSTX]  = {0, 0, 0, RegIrqFlags::LOW_BAT},
-             [RegOpMode::MODE_TX]    = {RegIrqFlags::PACKET_SENT, 0, 0,
-                                        RegIrqFlags::LOW_BAT},
-             [RegOpMode::MODE_FSRX]  = {0, 0, 0, RegIrqFlags::LOW_BAT},
-             [RegOpMode::MODE_RX] =
-                 {RegIrqFlags::PAYLOAD_READY, RegIrqFlags::CRC_OK, 0,
-                  RegIrqFlags::LOW_BAT},
-         },
-     [1] =
-         {
-             [RegOpMode::MODE_SLEEP] = {RegIrqFlags::FIFO_LEVEL,
-                                        RegIrqFlags::FIFO_EMPTY,
-                                        RegIrqFlags::FIFO_FULL, 0},
-             [RegOpMode::MODE_STDBY] = {RegIrqFlags::FIFO_LEVEL,
-                                        RegIrqFlags::FIFO_EMPTY,
-                                        RegIrqFlags::FIFO_FULL, 0},
-             [RegOpMode::MODE_FSTX] =
-                 {RegIrqFlags::FIFO_LEVEL, RegIrqFlags::FIFO_EMPTY,
-                  RegIrqFlags::FIFO_FULL, 0},
-             [RegOpMode::MODE_TX] = {RegIrqFlags::FIFO_LEVEL,
-                                     RegIrqFlags::FIFO_EMPTY,
-                                     RegIrqFlags::FIFO_FULL, 0},
-             [RegOpMode::MODE_FSRX] =
-                 {RegIrqFlags::FIFO_LEVEL, RegIrqFlags::FIFO_EMPTY,
-                  RegIrqFlags::FIFO_FULL, 0},
-             [RegOpMode::MODE_RX] = {RegIrqFlags::FIFO_LEVEL,
-                                     RegIrqFlags::FIFO_EMPTY,
-                                     RegIrqFlags::FIFO_FULL, 0},
-         },
-     [2] =
-         {
-             [RegOpMode::MODE_SLEEP] =
-                 {RegIrqFlags::FIFO_FULL, 0, RegIrqFlags::FIFO_FULL,
-                  RegIrqFlags::FIFO_FULL},
-             [RegOpMode::MODE_STDBY] =
-                 {RegIrqFlags::FIFO_FULL, 0, RegIrqFlags::FIFO_FULL,
-                  RegIrqFlags::FIFO_FULL},
-             [RegOpMode::MODE_FSTX] = {RegIrqFlags::FIFO_FULL, 0,
-                                       RegIrqFlags::FIFO_FULL,
-                                       RegIrqFlags::FIFO_FULL},
-             [RegOpMode::MODE_TX] =
-                 {RegIrqFlags::FIFO_FULL, 0, RegIrqFlags::FIFO_FULL,
-                  RegIrqFlags::FIFO_FULL},
-             [RegOpMode::MODE_FSRX] = {RegIrqFlags::FIFO_FULL, 0,
-                                       RegIrqFlags::FIFO_FULL,
-                                       RegIrqFlags::FIFO_FULL},
-             [RegOpMode::MODE_RX] =
-                 {RegIrqFlags::FIFO_FULL, RegIrqFlags::RX_READY,
-                  RegIrqFlags::TIMEOUT, RegIrqFlags::SYNC_ADDRESS_MATCH},
-         },
-     [3] =
-         {
-             [RegOpMode::MODE_SLEEP] =
-                 {
-                     RegIrqFlags::FIFO_EMPTY,
-                     0,
-                     RegIrqFlags::FIFO_EMPTY,
-                     RegIrqFlags::FIFO_EMPTY,
-                 },
-             [RegOpMode::MODE_STDBY] =
-                 {
-                     RegIrqFlags::FIFO_EMPTY,
-                     0,
-                     RegIrqFlags::FIFO_EMPTY,
-                     RegIrqFlags::FIFO_EMPTY,
-                 },
-             [RegOpMode::MODE_FSTX] =
-                 {
-                     RegIrqFlags::FIFO_EMPTY,
-                     0,
-                     RegIrqFlags::FIFO_EMPTY,
-                     RegIrqFlags::FIFO_EMPTY,
-                 },
-             [RegOpMode::MODE_TX] =
-                 {
-                     RegIrqFlags::FIFO_EMPTY,
-                     RegIrqFlags::TX_READY,
-                     RegIrqFlags::FIFO_EMPTY,
-                     RegIrqFlags::FIFO_EMPTY,
-                 },
-             [RegOpMode::MODE_FSRX] =
-                 {
-                     RegIrqFlags::FIFO_EMPTY,
-                     0,
-                     RegIrqFlags::FIFO_EMPTY,
-                     RegIrqFlags::FIFO_EMPTY,
-                 },
-             [RegOpMode::MODE_RX] =
-                 {
-                     RegIrqFlags::FIFO_EMPTY,
-                     0,
-                     RegIrqFlags::FIFO_EMPTY,
-                     RegIrqFlags::FIFO_EMPTY,
-                 },
-         },
-     [4] =
-         {
-             [RegOpMode::MODE_SLEEP] = {0, 0, 0, 0},
-             [RegOpMode::MODE_STDBY] = {RegIrqFlags::LOW_BAT, 0, 0, 0},
-             [RegOpMode::MODE_FSTX]  = {RegIrqFlags::LOW_BAT,
-                                        RegIrqFlags::PILL_LOCK, 0, 0},
-             [RegOpMode::MODE_TX]    = {RegIrqFlags::LOW_BAT,
-                                        RegIrqFlags::PILL_LOCK, 0, 0},
-             [RegOpMode::MODE_FSRX]  = {RegIrqFlags::LOW_BAT,
-                                        RegIrqFlags::PILL_LOCK, 0, 0},
-             [RegOpMode::MODE_RX] =
-                 {RegIrqFlags::LOW_BAT, RegIrqFlags::PILL_LOCK,
-                  RegIrqFlags::TIMEOUT,
-                  RegIrqFlags::RSSI | RegIrqFlags::PREAMBLE_DETECT},
-         },
-     [5] = {
-         [RegOpMode::MODE_SLEEP] = {0, 0, 0, 0},
-         [RegOpMode::MODE_STDBY] = {0, 0, 0, RegIrqFlags::MODE_READY},
-         [RegOpMode::MODE_FSTX]  = {0, RegIrqFlags::PILL_LOCK, 0,
-                                    RegIrqFlags::MODE_READY},
-
-         [RegOpMode::MODE_TX]   = {0, RegIrqFlags::PILL_LOCK, 0,
-                                   RegIrqFlags::MODE_READY},
-         [RegOpMode::MODE_FSRX] = {0, RegIrqFlags::PILL_LOCK, 0,
-                                   RegIrqFlags::MODE_READY},
-         [RegOpMode::MODE_RX]   = {0, RegIrqFlags::PILL_LOCK, 0,
-                                   RegIrqFlags::MODE_READY},
-     }};
 }  // namespace Fsk
 
 /**
@@ -803,18 +802,6 @@ enum Registers
     REG_AGC_PILL     = 0x70,
 };
 
-static constexpr int DIO_MAPPINGS[6][4] = {
-    [0] = {RegIrqFlags::RX_DONE, RegIrqFlags::TX_DONE, RegIrqFlags::CAD_DONE,
-           0},
-    [1] = {RegIrqFlags::RX_TIMEOUT, RegIrqFlags::FHSS_CHANGE_CHANNEL,
-           RegIrqFlags::CAD_DETECTED, 0},
-    [2] = {RegIrqFlags::FHSS_CHANGE_CHANNEL, RegIrqFlags::FHSS_CHANGE_CHANNEL,
-           RegIrqFlags::FHSS_CHANGE_CHANNEL, 0},
-    [3] = {RegIrqFlags::CAD_DONE, RegIrqFlags::VALID_HEADER,
-           RegIrqFlags::PAYLOAD_CRC_ERROR, 0},
-    [4] = {RegIrqFlags::CAD_DETECTED, 0, 0, 0},
-    [5] = {0, 0, 0, 0}};
-
 }  // namespace Lora
 
 }  // namespace SX1278
diff --git a/src/shared/radio/SX1278/SX1278Frontends.h b/src/shared/radio/SX1278/SX1278Frontends.h
new file mode 100644
index 0000000000000000000000000000000000000000..41c90f858589049d12cf18312908bbe9a7b9cefc
--- /dev/null
+++ b/src/shared/radio/SX1278/SX1278Frontends.h
@@ -0,0 +1,81 @@
+/* Copyright (c) 2023 Skyward Experimental Rocketry
+ * Author: Davide Mor
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <miosix.h>
+
+#include "SX1278Common.h"
+
+namespace Boardcore
+{
+
+class EbyteFrontend : public SX1278::ISX1278Frontend
+{
+public:
+    EbyteFrontend(miosix::GpioPin tx_enable, miosix::GpioPin rx_enable)
+        : tx_enable(tx_enable), rx_enable(rx_enable)
+    {
+    }
+
+    bool isOnPaBoost() override { return true; }
+    int maxInPower() override { return 15; }
+
+    void enableRx() override { rx_enable.high(); }
+    void disableRx() override { rx_enable.low(); }
+    void enableTx() override { tx_enable.high(); }
+    void disableTx() override { tx_enable.low(); }
+
+private:
+    miosix::GpioPin tx_enable;
+    miosix::GpioPin rx_enable;
+};
+
+class RA01Frontend : public SX1278::ISX1278Frontend
+{
+public:
+    RA01Frontend() {}
+
+    bool isOnPaBoost() override { return true; }
+    int maxInPower() override { return 17; }
+
+    void enableRx() override {}
+    void disableRx() override {}
+    void enableTx() override {}
+    void disableTx() override {}
+};
+
+class Skyward433Frontend : public SX1278::ISX1278Frontend
+{
+public:
+    Skyward433Frontend() {}
+
+    bool isOnPaBoost() override { return false; }
+    int maxInPower() override { return 15; }
+
+    void enableRx() override {}
+    void disableRx() override {}
+    void enableTx() override {}
+    void disableTx() override {}
+};
+
+}  // namespace Boardcore
\ No newline at end of file
diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp
index dcf556af72627a216de1873475a10872f3db0e65..ddd8668755e944e4baf892189052e9d0d2d21183 100644
--- a/src/shared/radio/SX1278/SX1278Fsk.cpp
+++ b/src/shared/radio/SX1278/SX1278Fsk.cpp
@@ -25,6 +25,7 @@
 #include <kernel/scheduler/scheduler.h>
 #include <utils/Debug.h>
 
+#include <cassert>
 #include <cmath>
 
 namespace Boardcore
@@ -35,17 +36,6 @@ using namespace SX1278::Fsk;
 
 long long now() { return miosix::getTick() * 1000 / miosix::TICK_FREQ; }
 
-// Default values for registers
-constexpr uint8_t REG_OP_MODE_DEFAULT = RegOpMode::LONG_RANGE_MODE_FSK |
-                                        RegOpMode::MODULATION_TYPE_FSK |
-                                        RegOpMode::LOW_FREQUENCY_MODE_ON;
-
-constexpr uint8_t REG_SYNC_CONFIG_DEFAULT =
-    RegSyncConfig::AUTO_RESTART_RX_MODE_OFF |
-    RegSyncConfig::PREAMBLE_POLARITY_55 | RegSyncConfig::SYNC_ON;
-
-constexpr uint8_t REG_IMAGE_CAL_DEFAULT = RegImageCal::TEMP_TRESHOLD_10DEG;
-
 // Enable:
 // - PayloadReady, PacketSent on DIO0 (mode 00)
 // - FifoLevel on DIO1 (mode 00)
@@ -57,7 +47,6 @@ SX1278Fsk::Error SX1278Fsk::init(const Config &config)
     // First probe for the device
     if (!checkVersion())
     {
-        TRACE("[sx1278] Wrong chipid\n");
         return Error::BAD_VALUE;
     }
 
@@ -71,73 +60,192 @@ SX1278Fsk::Error SX1278Fsk::init(const Config &config)
 bool SX1278Fsk::checkVersion()
 {
     Lock guard(*this);
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
 
-    return spi.readRegister(REG_VERSION) == 0x12;
+    uint8_t version = spi.readRegister(REG_VERSION);
+    TRACE("[sx1278] Chip id: %d\n", version);
+
+    return version == 0x12;
 }
 
 SX1278Fsk::Error SX1278Fsk::configure(const Config &config)
 {
-    // First cycle the device to bring it into Fsk mode (can only be changed in
-    // sleep)
-    setDefaultMode(RegOpMode::MODE_SLEEP, DEFAULT_MAPPING, false, false);
-    // Make sure the device remains in standby and not in sleep
-    setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, false, false);
+    // Check that the configuration is actually valid
+    bool pa_boost = getFrontend().isOnPaBoost();
+    int min_power = pa_boost ? 2 : 0;
+    int max_power = getFrontend().maxInPower();
+
+    assert(config.power >= min_power && config.power <= max_power &&
+           "[sx1278] Configured power invalid for given frontend!");
+    assert(((config.ocp >= 0 && config.ocp <= 120) ||
+            (config.ocp >= 130 && config.ocp <= 240)) &&
+           "[sx1278] Invalid ocp!");
+    assert(config.freq_dev >= MIN_FREQ_DEV && config.freq_dev <= MAX_FREQ_DEV &&
+           "[sx1278] Invalid freq_dev!");
+    assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
+           "[sx1278] Invalid freq_rf");
+
+    // First make sure the device is in fsk and in standby
+    enterFskMode();
+
+    // Set default mode to standby, that way we reset the fifo every time we
+    // enter receive
+    setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
+                   InterruptTrigger::RISING_EDGE, false, false);
+    miosix::Thread::sleep(1);
 
     // Lock the bus
     Lock guard(*this);
-    LockMode guard_mode(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING);
+    LockMode guard_mode(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
+                        InterruptTrigger::RISING_EDGE);
+
+    // This code is unreliable so it got commented out, the datasheet states
+    // that this triggers during a successful state transition, but for some
+    // reason, this isn't always the case, and can lead to random failures of
+    // the driver initialization. Removing it has no side effects, so that is
+    // what was done.
+    // if (!waitForIrqBusy(guard_mode, RegIrqFlags::MODE_READY, 0, 1000))
+    //     return Error::IRQ_TIMEOUT;
+
+    int bitrate = config.bitrate;
+    int freq_dev =
+        std::max(std::min(config.freq_dev, MAX_FREQ_DEV), MIN_FREQ_DEV);
+    int freq_rf = std::max(std::min(config.freq_rf, MAX_FREQ_RF), MIN_FREQ_RF);
+    RegRxBw::RxBw rx_bw      = static_cast<RegRxBw::RxBw>(config.rx_bw);
+    RegAfcBw::RxBwAfc afc_bw = static_cast<RegAfcBw::RxBwAfc>(config.afc_bw);
+    int ocp   = config.ocp <= 120 ? std::max(std::min(config.ocp, 120), 0)
+                                  : std::max(std::min(config.ocp, 240), 130);
+    int power = std::max(std::min(config.power, max_power), min_power);
+    RegPaRamp::ModulationShaping shaping =
+        static_cast<RegPaRamp::ModulationShaping>(config.shaping);
+    RegPacketConfig1::DcFree dc_free =
+        static_cast<RegPacketConfig1::DcFree>(config.dc_free);
+
+    crc_enabled = config.enable_crc;
 
-    if (!waitForIrqBusy(guard_mode, RegIrqFlags::MODE_READY, 1000))
-        return Error::IRQ_TIMEOUT;
+    {
+        SPITransaction spi(getSpiSlave());
 
-    setBitrate(config.bitrate);
-    setFreqDev(config.freq_dev);
-    setFreqRF(config.freq_rf);
+        // Setup bitrate
+        uint16_t bitrate_raw = FXOSC / bitrate;
+        spi.writeRegister16(REG_BITRATE_MSB, bitrate_raw);
 
-    setRxBw(config.rx_bw);
-    setAfcBw(config.afc_bw);
+        // Setup frequency deviation
+        uint16_t freq_dev_raw = freq_dev / FSTEP;
+        spi.writeRegister16(REG_FDEV_MSB, freq_dev_raw & 0x3fff);
 
-    setOcp(config.ocp);
+        // Setup base frequency
+        uint32_t freq_rf_raw = freq_rf / FSTEP;
+        spi.writeRegister24(REG_FRF_MSB, freq_rf_raw);
 
-    uint8_t sync_word[2] = {0x12, 0xad};
-    setSyncWord(sync_word, 2);
-    setPreambleLen(2);
-    setPa(config.power, config.pa_boost);
-    setShaping(config.shaping);
+        // Setup RX bandwidth
+        spi.writeRegister(REG_RX_BW, RegRxBw::make(rx_bw));
 
-    // Setup generic parameters
-    {
-        SPITransaction spi(slave);
+        // Setup afc bandwidth
+        spi.writeRegister(REG_AFC_BW, RegAfcBw::make(afc_bw));
+
+        // Setup reg over-current protection
+        if (config.ocp == 0)
+        {
+            spi.writeRegister(REG_OCP, RegOcp::make(0, false));
+        }
+        else if (ocp <= 120)
+        {
+            spi.writeRegister(REG_OCP, RegOcp::make((ocp - 45) / 5, true));
+        }
+        else
+        {
+            spi.writeRegister(REG_OCP, RegOcp::make((ocp + 30) / 10, true));
+        }
+
+        // Setup sync word
+        spi.writeRegister(
+            REG_SYNC_CONFIG,
+            RegSyncConfig::make(2, true, RegSyncConfig::PREAMBLE_POLARITY_55,
+                                RegSyncConfig::AUTO_RESTART_RX_MODE_OFF));
+        spi.writeRegister(REG_SYNC_VALUE_1, 0x12);
+        spi.writeRegister(REG_SYNC_VALUE_2, 0xad);
+
+        // Set preamble length
+        spi.writeRegister16(REG_PREAMBLE_MSB, 2);
+
+        // Setup shaping
+        spi.writeRegister(REG_PA_RAMP,
+                          RegPaRamp::make(RegPaRamp::PA_RAMP_US_40, shaping));
+
+        // Setup power amplifier
+        // [2, 17] or 20 if PA_BOOST
+        // [0, 15] if !PA_BOOST
+        const int MAX_POWER = 0b111;
+        if (!pa_boost)
+        {
+            // Don't use power amplifier boost
+            spi.writeRegister(REG_PA_CONFIG,
+                              RegPaConfig::make(power, MAX_POWER, false));
+            spi.writeRegister(REG_PA_DAC,
+                              RegPaDac::make(RegPaDac::PA_DAC_DEFAULT_VALUE));
+        }
+        else if (power != 20)
+        {
+            // Run power amplifier boost but not at full power
+            spi.writeRegister(REG_PA_CONFIG,
+                              RegPaConfig::make(power - 2, MAX_POWER, true));
+            spi.writeRegister(REG_PA_DAC,
+                              RegPaDac::make(RegPaDac::PA_DAC_PA_BOOST));
+        }
+        else
+        {
+            // Run power amplifier boost at full power
+            spi.writeRegister(REG_PA_CONFIG,
+                              RegPaConfig::make(0b1111, MAX_POWER, true));
+            spi.writeRegister(REG_PA_DAC,
+                              RegPaDac::make(RegPaDac::PA_DAC_PA_BOOST));
+        }
+
+        // Setup other registers
+
+        spi.writeRegister(
+            REG_RX_CONFIG,
+            RegRxConfig::make(true, true, true, true, false, false, false));
 
-        spi.writeRegister(REG_RX_CONFIG,
-                          RegRxConfig::AFC_AUTO_ON | RegRxConfig::AGC_AUTO_ON |
-                              RegRxConfig::RX_TRIGGER_PREAMBLE_DETECT |
-                              RegRxConfig::RX_TRIGGER_RSSI_INTERRUPT);
         spi.writeRegister(REG_RSSI_THRESH, 0xff);
+
         spi.writeRegister(
             REG_PREAMBLE_DETECT,
-            RegPreambleDetector::PREAMBLE_DETECTOR_ON |
-                RegPreambleDetector::PREAMBLE_DETECTOR_SIZE_2_BYTES | 0x0a);
+            RegPreambleDetector::make(
+                0x0a, RegPreambleDetector::PREAMBLE_DETECTOR_SIZE_2_BYTES,
+                true));
+
         spi.writeRegister(REG_RX_TIMEOUT_1, 0x00);
         spi.writeRegister(REG_RX_TIMEOUT_2, 0x00);
         spi.writeRegister(REG_RX_TIMEOUT_3, 0x00);
-        spi.writeRegister(REG_PACKET_CONFIG_1,
-                          RegPacketConfig1::PACKET_FORMAT_VARIABLE_LENGTH |
-                              static_cast<uint8_t>(config.dc_free) |
-                              RegPacketConfig1::CRC_ON |
-                              RegPacketConfig1::ADDRESS_FILTERING_NONE |
-                              RegPacketConfig1::CRC_WHITENING_TYPE_CCITT_CRC);
-        spi.writeRegister(REG_PACKET_CONFIG_2,
-                          RegPacketConfig2::DATA_MODE_PACKET);
+
+        spi.writeRegister(
+            REG_PACKET_CONFIG_1,
+            RegPacketConfig1::make(
+                RegPacketConfig1::CRC_WHITENING_TYPE_CCITT_CRC,
+                RegPacketConfig1::ADDRESS_FILTERING_NONE, true, crc_enabled,
+                dc_free, RegPacketConfig1::PACKET_FORMAT_VARIABLE_LENGTH));
+
+        spi.writeRegister(
+            REG_PACKET_CONFIG_2,
+            RegPacketConfig2::make(false, false, false,
+                                   RegPacketConfig2::DATA_MODE_PACKET));
+
+        // Set maximum payload length
+        spi.writeRegister(REG_PACKET_PAYLOAD_LENGTH, MTU);
+
+        // Setup threshold to half of the fifo
         spi.writeRegister(
             REG_FIFO_THRESH,
-            RegFifoThresh::TX_START_CONDITION_FIFO_NOT_EMPTY | 0x0f);
+            RegFifoThresh::make(
+                FIFO_LEN / 2,
+                RegFifoThresh::TX_START_CONDITION_FIFO_NOT_EMPTY));
+
         spi.writeRegister(REG_NODE_ADRS, 0x00);
         spi.writeRegister(REG_BROADCAST_ADRS, 0x00);
     }
 
-    // imageCalibrate();
     return Error::NONE;
 }
 
@@ -145,33 +253,81 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
 {
     Lock guard(*this);
     LockMode guard_mode(*this, guard, RegOpMode::MODE_RX, DEFAULT_MAPPING,
-                        false, true);
+                        InterruptTrigger::RISING_EDGE, false, true);
+
+    // Save the packet locally, we always want to read it all
+    uint8_t tmp_pkt[MTU];
 
     uint8_t len = 0;
+    bool crc_ok;
+    IrqFlags flags = 0;
+
     do
     {
-        // Special wait for payload ready
-        waitForIrq(guard_mode, RegIrqFlags::PAYLOAD_READY, true);
+        crc_ok = false;
+
+        uint8_t cur_len = 0;
+
+        // Special wait for fifo level/payload ready, release the lock at this
+        // stage
+        flags = waitForIrq(guard_mode,
+                           RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY,
+                           0, true);
+        if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
+        {
+            crc_ok = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
+        }
+
+        // Record RSSI here, it's where it is the most accurate
         last_rx_rssi = getRssi();
 
+        // Now first packet bit
         {
-            SPITransaction spi(slave);
+            SPITransaction spi(getSpiSlave());
             len = spi.readRegister(REG_FIFO);
-            if (len > max_len)
-                return -1;
 
-            spi.readRegisters(REG_FIFO, pkt, len);
+            int read_size = std::min((int)len, FIFO_LEN / 2);
+            // Skip 0 sized read
+            if (read_size != 0)
+                spi.readRegisters(REG_FIFO, &tmp_pkt[cur_len], read_size);
+
+            cur_len += read_size;
+        }
+
+        // Then read the other chunks
+        while (cur_len < len)
+        {
+            flags = waitForIrq(
+                guard_mode,
+                RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY, 0);
+            if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
+            {
+                crc_ok = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
+            }
+
+            SPITransaction spi(getSpiSlave());
+
+            int read_size = std::min((int)(len - cur_len), FIFO_LEN / 2);
+            spi.readRegisters(REG_FIFO, &tmp_pkt[cur_len], read_size);
+
+            cur_len += read_size;
         }
 
         // For some reason this sometimes happen?
     } while (len == 0);
 
+    if (len > max_len || (!crc_ok && crc_enabled))
+    {
+        return -1;
+    }
+
+    // Finally copy the packet to the destination
+    memcpy(pkt, tmp_pkt, len);
     return len;
 }
 
 bool SX1278Fsk::send(uint8_t *pkt, size_t len)
 {
-    // Packets longer than FIFO_LEN (-1 for the len byte) are not supported
     if (len > MTU)
         return false;
 
@@ -180,20 +336,42 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len)
     rateLimitTx();
 
     Lock guard(*this);
-    LockMode guard_mode(*this, guard, RegOpMode::MODE_TX, DEFAULT_MAPPING, true,
-                        false);
+    LockMode guard_mode(*this, guard, RegOpMode::MODE_TX, DEFAULT_MAPPING,
+                        InterruptTrigger::FALLING_EDGE, true, false);
 
-    waitForIrq(guard_mode, RegIrqFlags::TX_READY);
+    waitForIrq(guard_mode, RegIrqFlags::TX_READY, 0);
 
+    // Send first segment
     {
-        SPITransaction spi(slave);
+        SPITransaction spi(getSpiSlave());
 
         spi.writeRegister(REG_FIFO, static_cast<uint8_t>(len));
-        spi.writeRegisters(REG_FIFO, pkt, len);
+
+        int write_size = std::min((int)len, FIFO_LEN - 1);
+        spi.writeRegisters(REG_FIFO, pkt, write_size);
+
+        pkt += write_size;
+        len -= write_size;
     }
 
+    // Then send the rest using fifo control
+    while (len > 0)
+    {
+        // Wait for FIFO_LEVEL to go down
+        waitForIrq(guard_mode, 0, RegIrqFlags::FIFO_LEVEL);
+
+        SPITransaction spi(getSpiSlave());
+
+        int write_size = std::min((int)len, FIFO_LEN / 2);
+        spi.writeRegisters(REG_FIFO, pkt, write_size);
+
+        pkt += write_size;
+        len -= write_size;
+    }
+
+    // Finally wait for packet sent
     // Wait for packet sent
-    waitForIrq(guard_mode, RegIrqFlags::PACKET_SENT);
+    waitForIrq(guard_mode, RegIrqFlags::PACKET_SENT, 0);
 
     last_tx = now();
     return true;
@@ -213,6 +391,24 @@ float SX1278Fsk::getCurRssi()
     return getRssi();
 }
 
+void SX1278Fsk::enterFskMode()
+{
+    Lock guard(*this);
+    SPITransaction spi(getSpiSlave());
+
+    // First enter Fsk sleep
+    spi.writeRegister(REG_OP_MODE,
+                      RegOpMode::make(RegOpMode::MODE_SLEEP, true,
+                                      RegOpMode::MODULATION_TYPE_FSK));
+    miosix::Thread::sleep(1);
+
+    // Then transition to standby
+    spi.writeRegister(REG_OP_MODE,
+                      RegOpMode::make(RegOpMode::MODE_STDBY, true,
+                                      RegOpMode::MODULATION_TYPE_FSK));
+    miosix::Thread::sleep(1);
+}
+
 void SX1278Fsk::rateLimitTx()
 {
     const long long RATE_LIMIT = 2;
@@ -224,50 +420,10 @@ void SX1278Fsk::rateLimitTx()
     }
 }
 
-void SX1278Fsk::imageCalibrate()
-{
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_IMAGE_CAL, REG_IMAGE_CAL_DEFAULT | (1 << 6));
-
-    // Wait for calibration complete by polling on running register
-    while (spi.readRegister(REG_IMAGE_CAL) & (1 << 5))
-        miosix::delayUs(10);
-}
-
-DioMask SX1278Fsk::getDioMaskFromIrqFlags(IrqFlags flags, Mode mode,
-                                          DioMapping mapping)
-{
-    DioMask dio_mask;
-
-    if (DIO_MAPPINGS[0][mode][mapping.getMapping(Dio::DIO0)] & flags)
-        dio_mask.set(Dio::DIO0);
-
-    if (DIO_MAPPINGS[1][mode][mapping.getMapping(Dio::DIO1)] & flags)
-        dio_mask.set(Dio::DIO1);
-
-    if (DIO_MAPPINGS[2][mode][mapping.getMapping(Dio::DIO2)] & flags)
-        dio_mask.set(Dio::DIO2);
-
-    if (DIO_MAPPINGS[3][mode][mapping.getMapping(Dio::DIO3)] & flags)
-        dio_mask.set(Dio::DIO3);
-
-    if (DIO_MAPPINGS[4][mode][mapping.getMapping(Dio::DIO4)] & flags)
-        dio_mask.set(Dio::DIO4);
-
-    if (DIO_MAPPINGS[5][mode][mapping.getMapping(Dio::DIO5)] & flags)
-        dio_mask.set(Dio::DIO5);
-
-    return dio_mask;
-}
-
 ISX1278::IrqFlags SX1278Fsk::getIrqFlags()
 {
-    SPITransaction spi(slave);
-
-    uint8_t flags_msb = spi.readRegister(REG_IRQ_FLAGS_1);
-    uint8_t flags_lsb = spi.readRegister(REG_IRQ_FLAGS_2);
-
-    return (flags_msb << 8 | flags_lsb);
+    SPITransaction spi(getSpiSlave());
+    return spi.readRegister16(REG_IRQ_FLAGS_1);
 }
 
 void SX1278Fsk::resetIrqFlags(IrqFlags flags)
@@ -279,244 +435,39 @@ void SX1278Fsk::resetIrqFlags(IrqFlags flags)
 
     if (flags != 0)
     {
-        SPITransaction spi(slave);
-        spi.writeRegister(REG_IRQ_FLAGS_1, flags >> 8);
-        spi.writeRegister(REG_IRQ_FLAGS_2, flags);
+        SPITransaction spi(getSpiSlave());
+        spi.writeRegister16(REG_IRQ_FLAGS_1, flags);
     }
 }
 
 float SX1278Fsk::getRssi()
 {
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
 
-    return static_cast<float>(spi.readRegister(REG_RSSI_VALUE)) * -0.5f;
+    uint8_t rssi_raw = spi.readRegister(REG_RSSI_VALUE);
+    return static_cast<float>(rssi_raw) * -0.5f;
 }
 
 float SX1278Fsk::getFei()
 {
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
 
-    // Order of read is important!!
-    uint8_t fei_msb = spi.readRegister(REG_FEI_MSB);
-    uint8_t fei_lsb = spi.readRegister(REG_FEI_LSB);
-
-    uint16_t fei = (static_cast<uint16_t>(fei_msb) << 8) |
-                   (static_cast<uint16_t>(fei_lsb));
-
-    return static_cast<float>(fei) * FSTEP;
+    uint16_t fei_raw = spi.readRegister16(REG_FEI_MSB);
+    return static_cast<float>(fei_raw) * FSTEP;
 }
 
 void SX1278Fsk::setMode(Mode mode)
 {
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_OP_MODE, REG_OP_MODE_DEFAULT | mode);
+    SPITransaction spi(getSpiSlave());
+    spi.writeRegister(REG_OP_MODE,
+                      RegOpMode::make(static_cast<RegOpMode::Mode>(mode), true,
+                                      RegOpMode::MODULATION_TYPE_FSK));
 }
 
 void SX1278Fsk::setMapping(SX1278::DioMapping mapping)
 {
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_DIO_MAPPING_1, mapping.raw >> 8);
-    spi.writeRegister(REG_DIO_MAPPING_2, mapping.raw);
-}
-
-void SX1278Fsk::setBitrate(int bitrate)
-{
-    uint16_t val = FXOSC / bitrate;
-
-    // Update values
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_BITRATE_MSB, val >> 8);
-    spi.writeRegister(REG_BITRATE_LSB, val);
-}
-
-void SX1278Fsk::setFreqDev(int freq_dev)
-{
-    uint16_t val = freq_dev / FSTEP;
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_FDEV_MSB, (val >> 8) & 0x3f);
-    spi.writeRegister(REG_FDEV_LSB, val);
-}
-
-void SX1278Fsk::setFreqRF(int freq_rf)
-{
-    uint32_t val = freq_rf / FSTEP;
-
-    // Update values
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_FRF_MSB, val >> 16);
-    spi.writeRegister(REG_FRF_MID, val >> 8);
-    spi.writeRegister(REG_FRF_LSB, val);
-}
-
-void SX1278Fsk::setOcp(int ocp)
-{
-    SPITransaction spi(slave);
-    if (ocp == 0)
-    {
-        spi.writeRegister(REG_OCP, 0);
-    }
-    else if (ocp <= 120)
-    {
-        uint8_t raw = (ocp - 45) / 5;
-        spi.writeRegister(REG_OCP, RegOcp::OCP_ON | raw);
-    }
-    else
-    {
-        uint8_t raw = (ocp + 30) / 10;
-        spi.writeRegister(REG_OCP, RegOcp::OCP_ON | raw);
-    }
-}
-
-void SX1278Fsk::setSyncWord(uint8_t value[], int size)
-{
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_SYNC_CONFIG, REG_SYNC_CONFIG_DEFAULT | size);
-
-    for (int i = 0; i < size; i++)
-    {
-        spi.writeRegister(REG_SYNC_VALUE_1 + i, value[i]);
-    }
-}
-
-void SX1278Fsk::setRxBw(RxBw rx_bw)
-{
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_RX_BW, static_cast<uint8_t>(rx_bw));
-}
-
-void SX1278Fsk::setAfcBw(RxBw afc_bw)
-{
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_AFC_BW, static_cast<uint8_t>(afc_bw));
-}
-
-void SX1278Fsk::setPreambleLen(int len)
-{
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_PREAMBLE_MSB, len >> 8);
-    spi.writeRegister(REG_PREAMBLE_LSB, len);
-}
-
-void SX1278Fsk::setPa(int power, bool pa_boost)
-{
-    // [2, 17] or 20 if PA_BOOST
-    // [0, 15] if !PA_BOOST
-
-    const uint8_t MAX_POWER = 0b111;
-
-    SPITransaction spi(slave);
-
-    if (!pa_boost)
-    {
-        // Don't use power amplifier boost
-        power = power - MAX_POWER + 15;
-        spi.writeRegister(REG_PA_CONFIG, MAX_POWER << 4 | power);
-        spi.writeRegister(REG_PA_DAC,
-                          RegPaDac::PA_DAC_DEFAULT_VALUE | 0x10 << 3);
-    }
-    else if (power != 20)
-    {
-        // Run power amplifier boost but not at full power
-        power = power - 2;
-        spi.writeRegister(REG_PA_CONFIG, MAX_POWER << 4 | power |
-                                             RegPaConfig::PA_SELECT_BOOST);
-        spi.writeRegister(REG_PA_DAC, RegPaDac::PA_DAC_PA_BOOST | 0x10 << 3);
-    }
-    // RA01 modules aren't capable of this, disable it to avoid damaging them
-    // else
-    // {
-    //     // Run power amplifier boost at full power
-    //     power = 15;
-    //     spi.writeRegister(REG_PA_CONFIG, MAX_POWER << 4 | power |
-    //                                          RegPaConfig::PA_SELECT_BOOST);
-    //     spi.writeRegister(REG_PA_DAC, RegPaDac::PA_DAC_PA_BOOST | 0x10 << 3);
-    // }
-}
-
-void SX1278Fsk::setShaping(Shaping shaping)
-{
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_PA_RAMP, static_cast<uint8_t>(shaping) | 0x09);
-}
-
-void SX1278Fsk::debugDumpRegisters()
-{
-    Lock guard(*this);
-    struct RegDef
-    {
-        const char *name;
-        int addr;
-    };
-
-    const RegDef defs[] = {
-        RegDef{"REG_OP_MODE", REG_OP_MODE},
-        RegDef{"REG_BITRATE_MSB", REG_BITRATE_MSB},
-        RegDef{"REG_BITRATE_LSB", REG_BITRATE_LSB},
-        RegDef{"REG_FDEV_MSB", REG_FDEV_MSB},
-        RegDef{"REG_FDEV_LSB", REG_FDEV_LSB},
-        RegDef{"REG_FRF_MSB", REG_FRF_MSB}, RegDef{"REG_FRF_MID", REG_FRF_MID},
-        RegDef{"REG_FRF_LSB", REG_FRF_LSB},
-        RegDef{"REG_PA_CONFIG", REG_PA_CONFIG},
-        RegDef{"REG_PA_RAMP", REG_PA_RAMP}, RegDef{"REG_OCP", REG_OCP},
-        RegDef{"REG_LNA", REG_LNA}, RegDef{"REG_RX_CONFIG", REG_RX_CONFIG},
-        RegDef{"REG_RSSI_CONFIG", REG_RSSI_CONFIG},
-        RegDef{"REG_RSSI_COLLISION", REG_RSSI_COLLISION},
-        RegDef{"REG_RSSI_THRESH", REG_RSSI_THRESH},
-        // RegDef { "REG_RSSI_VALUE", REG_RSSI_VALUE },
-        RegDef{"REG_RX_BW", REG_RX_BW}, RegDef{"REG_AFC_BW", REG_AFC_BW},
-        RegDef{"REG_OOK_PEAK", REG_OOK_PEAK},
-        RegDef{"REG_OOK_FIX", REG_OOK_FIX}, RegDef{"REG_OOK_AVG", REG_OOK_AVG},
-        RegDef{"REG_AFC_FEI", REG_AFC_FEI}, RegDef{"REG_AFC_MSB", REG_AFC_MSB},
-        RegDef{"REG_AFC_LSB", REG_AFC_LSB}, RegDef{"REG_FEI_MSB", REG_FEI_MSB},
-        RegDef{"REG_FEI_LSB", REG_FEI_LSB},
-        RegDef{"REG_PREAMBLE_DETECT", REG_PREAMBLE_DETECT},
-        RegDef{"REG_RX_TIMEOUT_1", REG_RX_TIMEOUT_1},
-        RegDef{"REG_RX_TIMEOUT_2", REG_RX_TIMEOUT_2},
-        RegDef{"REG_RX_TIMEOUT_3", REG_RX_TIMEOUT_3},
-        RegDef{"REG_RX_DELAY", REG_RX_DELAY}, RegDef{"REG_OSC", REG_OSC},
-        RegDef{"REG_PREAMBLE_MSB", REG_PREAMBLE_MSB},
-        RegDef{"REG_PREAMBLE_LSB", REG_PREAMBLE_LSB},
-        RegDef{"REG_SYNC_CONFIG", REG_SYNC_CONFIG},
-        RegDef{"REG_SYNC_VALUE_1", REG_SYNC_VALUE_1},
-        RegDef{"REG_SYNC_VALUE_2", REG_SYNC_VALUE_2},
-        RegDef{"REG_SYNC_VALUE_3", REG_SYNC_VALUE_3},
-        RegDef{"REG_SYNC_VALUE_4", REG_SYNC_VALUE_4},
-        RegDef{"REG_SYNC_VALUE_5", REG_SYNC_VALUE_5},
-        RegDef{"REG_SYNC_VALUE_6", REG_SYNC_VALUE_6},
-        RegDef{"REG_SYNC_VALUE_7", REG_SYNC_VALUE_7},
-        RegDef{"REG_SYNC_VALUE_8", REG_SYNC_VALUE_8},
-        RegDef{"REG_PACKET_CONFIG_1", REG_PACKET_CONFIG_1},
-        RegDef{"REG_PACKET_CONFIG_2", REG_PACKET_CONFIG_2},
-        RegDef{"REG_PACKET_PAYLOAD_LENGTH", REG_PACKET_PAYLOAD_LENGTH},
-        RegDef{"REG_NODE_ADRS", REG_NODE_ADRS},
-        RegDef{"REG_BROADCAST_ADRS", REG_BROADCAST_ADRS},
-        RegDef{"REG_FIFO_THRESH", REG_FIFO_THRESH},
-        RegDef{"REG_SEQ_CONFIG_1", REG_SEQ_CONFIG_1},
-        RegDef{"REG_SEQ_CONFIG_2", REG_SEQ_CONFIG_2},
-        RegDef{"REG_TIMER_RESOL", REG_TIMER_RESOL},
-        RegDef{"REG_TIMER_1_COEF", REG_TIMER_1_COEF},
-        RegDef{"REG_TIMER_2_COEF", REG_TIMER_2_COEF},
-        RegDef{"REG_IMAGE_CAL", REG_IMAGE_CAL},
-        // RegDef { "REG_TEMP", REG_TEMP },
-        RegDef{"REG_LOW_BAT", REG_LOW_BAT},
-        // RegDef { "REG_IRQ_FLAGS_1", REG_IRQ_FLAGS_1 },
-        // RegDef { "REG_IRQ_FLAGS_2", REG_IRQ_FLAGS_2 },
-        RegDef{"REG_DIO_MAPPING_1", REG_DIO_MAPPING_1},
-        RegDef{"REG_DIO_MAPPING_2", REG_DIO_MAPPING_2},
-        RegDef{"REG_VERSION", REG_VERSION}, RegDef{NULL, 0}};
-
-    SPITransaction spi(slave);
-
-    int i = 0;
-    while (defs[i].name)
-    {
-        auto name = defs[i].name;
-        auto addr = defs[i].addr;
-
-        LOG_DEBUG(logger, "%s: 0x%x\n", name, spi.readRegister(addr));
-
-        i++;
-    }
+    SPITransaction spi(getSpiSlave());
+    spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw);
 }
 
 }  // namespace Boardcore
diff --git a/src/shared/radio/SX1278/SX1278Fsk.h b/src/shared/radio/SX1278/SX1278Fsk.h
index 300780978ceec32e8b776012ffdaaf798d63b613..b67f6c202eb45fa1a5425d4cf2b4424d011b1b53 100644
--- a/src/shared/radio/SX1278/SX1278Fsk.h
+++ b/src/shared/radio/SX1278/SX1278Fsk.h
@@ -41,59 +41,71 @@ public:
     /**
      * @brief Maximum transmittable unit of this driver.
      */
-    static constexpr size_t MTU = SX1278::Fsk::FIFO_LEN - 1;
-
-    /**
-     * @brief Channel filter bandwidth.
-     */
-    enum class RxBw
-    {
-        HZ_2600   = (0b10 << 3) | 7,
-        HZ_3100   = (0b01 << 3) | 7,
-        HZ_3900   = 7,
-        HZ_5200   = (0b10 << 3) | 6,
-        HZ_6300   = (0b01 << 3) | 6,
-        HZ_7800   = 6,
-        HZ_10400  = (0b10 << 3) | 5,
-        HZ_12500  = (0b01 << 3) | 5,
-        HZ_15600  = 5,
-        HZ_20800  = (0b10 << 3) | 4,
-        HZ_25000  = (0b01 << 3) | 4,
-        HZ_31300  = 4,
-        HZ_41700  = (0b10 << 3) | 3,
-        HZ_50000  = (0b01 << 3) | 3,
-        HZ_62500  = 3,
-        HZ_83300  = (0b10 << 3) | 2,
-        HZ_100000 = (0b01 << 3) | 2,
-        HZ_125000 = 2,
-        HZ_166700 = (0b10 << 3) | 1,
-        HZ_200000 = (0b01 << 3) | 1,
-        HZ_250000 = 1,
-    };
-
-    enum class Shaping
-    {
-        NONE = SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_NONE,
-        GAUSSIAN_BT_1_0 =
-            SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_1_0,
-        GAUSSIAN_BT_0_5 =
-            SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_0_5,
-        GAUSSIAN_BT_0_3 =
-            SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_0_3,
-    };
-
-    enum class DcFree
-    {
-        NONE       = SX1278::Fsk::RegPacketConfig1::DC_FREE_NONE,
-        MANCHESTER = SX1278::Fsk::RegPacketConfig1::DC_FREE_MANCHESTER,
-        WHITENING  = SX1278::Fsk::RegPacketConfig1::DC_FREE_WHITENING
-    };
+    static constexpr size_t MTU = 255;
 
     /**
      * @brief Requested SX1278 configuration.
      */
     struct Config
     {
+        /**
+         * @brief Channel filter bandwidth.
+         */
+        enum class RxBw
+        {
+            HZ_2600   = SX1278::Fsk::RegRxBw::HZ_2600,
+            HZ_3100   = SX1278::Fsk::RegRxBw::HZ_3100,
+            HZ_3900   = SX1278::Fsk::RegRxBw::HZ_3900,
+            HZ_5200   = SX1278::Fsk::RegRxBw::HZ_5200,
+            HZ_6300   = SX1278::Fsk::RegRxBw::HZ_6300,
+            HZ_7800   = SX1278::Fsk::RegRxBw::HZ_7800,
+            HZ_10400  = SX1278::Fsk::RegRxBw::HZ_10400,
+            HZ_12500  = SX1278::Fsk::RegRxBw::HZ_12500,
+            HZ_15600  = SX1278::Fsk::RegRxBw::HZ_15600,
+            HZ_20800  = SX1278::Fsk::RegRxBw::HZ_20800,
+            HZ_25000  = SX1278::Fsk::RegRxBw::HZ_25000,
+            HZ_31300  = SX1278::Fsk::RegRxBw::HZ_31300,
+            HZ_41700  = SX1278::Fsk::RegRxBw::HZ_41700,
+            HZ_50000  = SX1278::Fsk::RegRxBw::HZ_50000,
+            HZ_62500  = SX1278::Fsk::RegRxBw::HZ_62500,
+            HZ_83300  = SX1278::Fsk::RegRxBw::HZ_83300,
+            HZ_100000 = SX1278::Fsk::RegRxBw::HZ_100000,
+            HZ_125000 = SX1278::Fsk::RegRxBw::HZ_125000,
+            HZ_166700 = SX1278::Fsk::RegRxBw::HZ_166700,
+            HZ_200000 = SX1278::Fsk::RegRxBw::HZ_200000,
+            HZ_250000 = SX1278::Fsk::RegRxBw::HZ_250000,
+        };
+
+        /**
+         * @brief Output modulation shaping.
+         */
+        enum class Shaping
+        {
+            NONE = SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_NONE,
+            GAUSSIAN_BT_1_0 =
+                SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_1_0,
+            GAUSSIAN_BT_0_5 =
+                SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_0_5,
+            GAUSSIAN_BT_0_3 =
+                SX1278::Fsk::RegPaRamp::MODULATION_SHAPING_GAUSSIAN_BT_0_3,
+        };
+
+        /**
+         * @brief Dc free encoding.
+         *
+         * @warning Setting this to NONE heightens the probability of long
+         * sequences of 0s, reducing reliability.
+         *
+         * @warning MANCHESTER might be slightly more reliable, but halves the
+         * bitrate.
+         */
+        enum class DcFree
+        {
+            NONE       = SX1278::Fsk::RegPacketConfig1::DC_FREE_NONE,
+            MANCHESTER = SX1278::Fsk::RegPacketConfig1::DC_FREE_MANCHESTER,
+            WHITENING  = SX1278::Fsk::RegPacketConfig1::DC_FREE_WHITENING
+        };
+
         int freq_rf  = 434000000;        //< RF Frequency in Hz.
         int freq_dev = 50000;            //< Frequency deviation in Hz.
         int bitrate  = 48000;            //< Bitrate in b/s.
@@ -101,12 +113,12 @@ public:
         RxBw afc_bw  = RxBw::HZ_125000;  //< Afc filter bandwidth.
         int ocp =
             120;  //< Over current protection limit in mA (0 for no limit).
-        int power = 10;  //< Output power in dB (Between +2 and +17, or +20 for
+        int power = 13;  //< Output power in dB (Between +2 and +17, or +20 for
                          // full power).
-        bool pa_boost   = true;  //< Enable output on PA_BOOST.
         Shaping shaping = Shaping::GAUSSIAN_BT_1_0;  //< Shaping applied to
                                                      // the modulation stream.
-        DcFree dc_free = DcFree::WHITENING;  //< Dc free encoding scheme.
+        DcFree dc_free  = DcFree::WHITENING;  //< Dc free encoding scheme.
+        bool enable_crc = true;  //< Enable hardware CRC calculation/checking
     };
 
     /**
@@ -122,11 +134,16 @@ public:
 
     /**
      * @brief Construct a new SX1278
-     *
-     * @param bus SPI bus used.
-     * @param cs Chip select pin.
      */
-    explicit SX1278Fsk(SPISlave slave) : SX1278Common(slave) {}
+    explicit SX1278Fsk(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0,
+                       miosix::GpioPin dio1, miosix::GpioPin dio3,
+                       SPI::ClockDivider clock_divider,
+                       std::unique_ptr<SX1278::ISX1278Frontend> frontend)
+        : SX1278Common(bus, cs, dio0, dio1, dio3, clock_divider,
+                       std::move(frontend)),
+          crc_enabled(false)
+    {
+    }
 
     /**
      * @brief Setup the device.
@@ -148,7 +165,7 @@ public:
      *
      * @param pkt       Buffer to store the received packet into.
      * @param pkt_len   Maximum length of the received data.
-     * @return          Size of the data received or -1 if failure
+     * @return          Size of the data received or -1 on failure
      */
     ssize_t receive(uint8_t *pkt, size_t max_len) override;
 
@@ -171,32 +188,17 @@ public:
     /**
      * @brief Get the RSSI in dBm, during last packet receive.
      */
-    float getLastRxRssi();
+    float getLastRxRssi() override;
 
     /**
      * @brief Get the frequency error index in Hz, during last packet receive.
      */
-    float getLastRxFei();
-
-    /**
-     * @brief Dump all registers via TRACE.
-     */
-    void debugDumpRegisters();
-
-protected:
-    // Stuff to work with various front-ends
-    virtual void enableRxFrontend() override {}
-    virtual void disableRxFrontend() override {}
-    virtual void enableTxFrontend() override {}
-    virtual void disableTxFrontend() override {}
+    float getLastRxFei() override;
 
 private:
-    void rateLimitTx();
-
-    void imageCalibrate();
+    void enterFskMode();
 
-    SX1278::DioMask getDioMaskFromIrqFlags(IrqFlags flags, Mode mode,
-                                           SX1278::DioMapping mapping) override;
+    void rateLimitTx();
 
     IrqFlags getIrqFlags() override;
     void resetIrqFlags(IrqFlags flags) override;
@@ -207,17 +209,7 @@ private:
     void setMode(Mode mode) override;
     void setMapping(SX1278::DioMapping mapping) override;
 
-    void setBitrate(int bitrate);
-    void setFreqDev(int freq_dev);
-    void setFreqRF(int freq_rf);
-    void setOcp(int ocp);
-    void setSyncWord(uint8_t value[], int size);
-    void setRxBw(RxBw rx_bw);
-    void setAfcBw(RxBw afc_bw);
-    void setPreambleLen(int len);
-    void setPa(int power, bool pa_boost);
-    void setShaping(Shaping shaping);
-
+    bool crc_enabled;
     long long last_tx  = 0;
     float last_rx_rssi = 0.0f;
     PrintLogger logger = Logging::getLogger("sx1278");
diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp
index 08162a5ac1e9b13dd5ba4638628197e86b4280bd..6062b50b231dbd2437207dbedd5a04c19fb04db4 100644
--- a/src/shared/radio/SX1278/SX1278Lora.cpp
+++ b/src/shared/radio/SX1278/SX1278Lora.cpp
@@ -149,22 +149,40 @@ SX1278Lora::Error SX1278Lora::init(const Config &config)
 bool SX1278Lora::checkVersion()
 {
     Lock guard(*this);
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
 
-    return spi.readRegister(REG_VERSION) == 0x12;
+    uint8_t version = spi.readRegister(REG_VERSION);
+    TRACE("[sx1278] Chip id: %d\n", version);
+
+    return version == 0x12;
 }
 
 SX1278Lora::Error SX1278Lora::configure(const Config &config)
 {
-    // First cycle the device to bring it into LoRa mode (can only be changed in
-    // sleep)
-    setDefaultMode(RegOpMode::MODE_SLEEP, DEFAULT_MAPPING, false, false);
-    // Make sure the device remains in standby and not in sleep
-    setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, false, false);
+    // Check that the configuration is actually valid
+    bool pa_boost = getFrontend().isOnPaBoost();
+    int min_power = pa_boost ? 2 : 0;
+    int max_power = getFrontend().maxInPower();
+
+    assert(config.power >= min_power && config.power <= max_power &&
+           "[sx1278] Configured power invalid for given frontend!");
+    assert(((config.ocp >= 0 && config.ocp <= 120) ||
+            (config.ocp >= 130 && config.ocp <= 240)) &&
+           "[sx1278] Invalid ocp!");
+    assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
+           "[sx1278] Invalid freq_rf");
+
+    // First make sure the device is in lora mode and in standby
+    enterLoraMode();
+
+    // Then make sure the device remains in standby and not in sleep
+    setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
+                   InterruptTrigger::RISING_EDGE, false, false);
 
     // Lock the bus
     Lock guard(*this);
-    LockMode mode_guard(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING);
+    LockMode mode_guard(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
+                        InterruptTrigger::RISING_EDGE);
 
     RegModemConfig1::Bw bw = static_cast<RegModemConfig1::Bw>(config.bandwidth);
     RegModemConfig1::Cr cr =
@@ -172,10 +190,10 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
     RegModemConfig2::Sf sf =
         static_cast<RegModemConfig2::Sf>(config.spreading_factor);
 
-    int freq_rf   = config.freq_rf;
-    int ocp       = config.ocp;
-    int power     = config.power;
-    bool pa_boost = config.pa_boost;
+    int freq_rf = std::max(std::min(config.freq_rf, MAX_FREQ_RF), MIN_FREQ_RF);
+    int ocp     = config.ocp <= 120 ? std::max(std::min(config.ocp, 120), 0)
+                                    : std::max(std::min(config.ocp, 240), 130);
+    int power   = std::max(std::min(config.power, max_power), min_power);
 
     bool low_data_rate_optimize = config.low_data_rate_optimize;
 
@@ -187,8 +205,10 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
     ErrataRegistersValues errata_values =
         ErrataRegistersValues::calculate(bw, freq_rf);
 
+    crc_enabled = config.enable_crc;
+
     {
-        SPITransaction spi(slave);
+        SPITransaction spi(getSpiSlave());
 
         // Setup FIFO sections
         spi.writeRegister(REG_FIFO_TX_BASE_ADDR, FIFO_TX_BASE_ADDR);
@@ -197,10 +217,7 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
 
         // Setup frequency
         uint32_t freq_rf_raw = errata_values.freq_rf / FSTEP;
-
-        spi.writeRegister(REG_FRF_MSB, freq_rf_raw >> 16);
-        spi.writeRegister(REG_FRF_MID, freq_rf_raw >> 8);
-        spi.writeRegister(REG_FRF_LSB, freq_rf_raw);
+        spi.writeRegister24(REG_FRF_MSB, freq_rf_raw);
 
         // Setup reg power amplifier
         const int MAX_POWER = 0b111;
@@ -244,7 +261,7 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
         spi.writeRegister(REG_MODEM_CONFIG_1,
                           RegModemConfig1::make(false, cr, bw));
         spi.writeRegister(REG_MODEM_CONFIG_2,
-                          RegModemConfig2::make(false, false, sf));
+                          RegModemConfig2::make(crc_enabled, false, sf));
         spi.writeRegister(REG_MODEM_CONFIG_3,
                           RegModemConfig3::make(true, low_data_rate_optimize));
 
@@ -277,24 +294,27 @@ ssize_t SX1278Lora::receive(uint8_t *pkt, size_t max_len)
 {
     Lock guard(*this);
 
-    SPITransaction spi(slave);
+    // Use continuous because it doesn't go into timeout (and you cannot
+    // disable it...)
+    LockMode mode_guard(*this, guard, RegOpMode::MODE_RXCONTINUOUS,
+                        DioMapping(0, 0, 0, 0, 0, 0),
+                        InterruptTrigger::RISING_EDGE, false, true);
 
-    do
-    {
-        // Use continuous because it doesn't go into timeout (and you cannot
-        // disable it...)
-        LockMode mode_guard(*this, guard, RegOpMode::MODE_RXCONTINUOUS,
-                            DioMapping(0, 0, 0, 0, 0, 0), false, true);
+    waitForIrq(mode_guard, RegIrqFlags::RX_DONE, 0, true);
 
-        waitForIrq(mode_guard, RegIrqFlags::RX_DONE, true);
-    } while (checkForIrqAndReset(RegIrqFlags::PAYLOAD_CRC_ERROR));
+    uint8_t len;
+    {
+        SPITransaction spi(getSpiSlave());
+        len = spi.readRegister(REG_RX_NB_BYTES);
+    }
 
-    uint8_t len = spi.readRegister(REG_RX_NB_BYTES);
-    if (len > max_len)
+    if (len > max_len ||
+        (crc_enabled &&
+         checkForIrqAndReset(RegIrqFlags::PAYLOAD_CRC_ERROR, 0) != 0))
         return -1;
 
+    // Finally read the contents of the fifo
     readFifo(FIFO_RX_BASE_ADDR, pkt, len);
-
     return len;
 }
 
@@ -305,18 +325,21 @@ bool SX1278Lora::send(uint8_t *pkt, size_t len)
 
     Lock guard(*this);
 
-    SPITransaction spi(slave);
+    {
+        SPITransaction spi(getSpiSlave());
 
-    spi.writeRegister(REG_PAYLOAD_LENGTH, len);
-    writeFifo(FIFO_TX_BASE_ADDR, pkt, len);
+        spi.writeRegister(REG_PAYLOAD_LENGTH, len);
+        writeFifo(FIFO_TX_BASE_ADDR, pkt, len);
+    }
 
     {
         // Now enter in mode TX to send the packet
         LockMode mode_guard(*this, guard, RegOpMode::MODE_TX,
-                            DioMapping(1, 0, 0, 0, 0, 0), true, false);
+                            DioMapping(1, 0, 0, 0, 0, 0),
+                            InterruptTrigger::RISING_EDGE, true, false);
 
         // Wait for the transmission to end
-        waitForIrq(mode_guard, RegIrqFlags::TX_DONE);
+        waitForIrq(mode_guard, RegIrqFlags::TX_DONE, 0);
     }
 
     return true;
@@ -327,7 +350,7 @@ float SX1278Lora::getLastRxRssi()
     float rssi;
     {
         Lock guard(*this);
-        SPITransaction spi(slave);
+        SPITransaction spi(getSpiSlave());
         rssi =
             static_cast<float>(spi.readRegister(REG_PKT_RSSI_VALUE)) - 164.0f;
     }
@@ -343,70 +366,58 @@ float SX1278Lora::getLastRxRssi()
 float SX1278Lora::getLastRxSnr()
 {
     Lock guard(*this);
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
     return static_cast<float>(
                static_cast<int8_t>(spi.readRegister(REG_PKT_SNR_VALUE))) /
            4.0f;
 }
 
+void SX1278Lora::enterLoraMode()
+{
+    Lock guard(*this);
+    SPITransaction spi(getSpiSlave());
+
+    // First enter LoRa sleep
+    spi.writeRegister(REG_OP_MODE,
+                      RegOpMode::make(RegOpMode::MODE_SLEEP, true, false));
+    miosix::Thread::sleep(1);
+
+    // Then transition to standby
+    spi.writeRegister(REG_OP_MODE,
+                      RegOpMode::make(RegOpMode::MODE_STDBY, true, false));
+    miosix::Thread::sleep(1);
+}
+
 void SX1278Lora::readFifo(uint8_t addr, uint8_t *dst, uint8_t size)
 {
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
     spi.writeRegister(REG_FIFO_ADDR_PTR, addr);
     spi.readRegisters(REG_FIFO, dst, size);
 }
 
 void SX1278Lora::writeFifo(uint8_t addr, uint8_t *src, uint8_t size)
 {
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
     spi.writeRegister(REG_FIFO_ADDR_PTR, addr);
     spi.writeRegisters(REG_FIFO, src, size);
 }
 
-SX1278::DioMask SX1278Lora::getDioMaskFromIrqFlags(IrqFlags flags, Mode _mode,
-                                                   SX1278::DioMapping mapping)
-{
-    // In LoRa the mode doesn't matter for IRQs
-    (void)_mode;
-    DioMask dio_mask;
-
-    if (DIO_MAPPINGS[0][mapping.getMapping(Dio::DIO0)] & flags)
-        dio_mask.set(Dio::DIO0);
-
-    if (DIO_MAPPINGS[1][mapping.getMapping(Dio::DIO1)] & flags)
-        dio_mask.set(Dio::DIO1);
-
-    if (DIO_MAPPINGS[2][mapping.getMapping(Dio::DIO2)] & flags)
-        dio_mask.set(Dio::DIO2);
-
-    if (DIO_MAPPINGS[3][mapping.getMapping(Dio::DIO3)] & flags)
-        dio_mask.set(Dio::DIO3);
-
-    if (DIO_MAPPINGS[4][mapping.getMapping(Dio::DIO4)] & flags)
-        dio_mask.set(Dio::DIO4);
-
-    if (DIO_MAPPINGS[5][mapping.getMapping(Dio::DIO5)] & flags)
-        dio_mask.set(Dio::DIO5);
-
-    return dio_mask;
-}
-
 ISX1278::IrqFlags SX1278Lora::getIrqFlags()
 {
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
     return spi.readRegister(REG_IRQ_FLAGS);
 }
 
 void SX1278Lora::resetIrqFlags(IrqFlags flags)
 {
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
     // Register is write clear
     spi.writeRegister(REG_IRQ_FLAGS, flags);
 }
 
 void SX1278Lora::setMode(ISX1278::Mode mode)
 {
-    SPITransaction spi(slave);
+    SPITransaction spi(getSpiSlave());
 
     spi.writeRegister(
         REG_OP_MODE,
@@ -415,9 +426,8 @@ void SX1278Lora::setMode(ISX1278::Mode mode)
 
 void SX1278Lora::setMapping(SX1278::DioMapping mapping)
 {
-    SPITransaction spi(slave);
-    spi.writeRegister(REG_DIO_MAPPING_1, mapping.raw >> 8);
-    spi.writeRegister(REG_DIO_MAPPING_2, mapping.raw);
+    SPITransaction spi(getSpiSlave());
+    spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw);
 }
 
 }  // namespace Boardcore
diff --git a/src/shared/radio/SX1278/SX1278Lora.h b/src/shared/radio/SX1278/SX1278Lora.h
index 3d129fac0406f4ec2218ab1006140e5e4171a2ee..c30bdf41f72962659748fca95b292272d6ca32b8 100644
--- a/src/shared/radio/SX1278/SX1278Lora.h
+++ b/src/shared/radio/SX1278/SX1278Lora.h
@@ -102,10 +102,10 @@ public:
         int ocp =
             120;  //< Over current protection limit in mA (0 for no limit).
         int power =
-            15;  //< Output power in dB (between +2 and +17 with pa_boost = on,
+            13;  //< Output power in dB (between +2 and +17 with pa_boost = on,
                  // and between +0 and +14 with pa_boost = off, +20 for +20dBm
                  // max power ignoring pa_boost).
-        bool pa_boost = true;  //< Enable output on PA_BOOST.
+        bool enable_crc = true;  //< Enable hardware CRC calculation/checking
 
         /**
          * @brief Calculates effective and usable bitrate.
@@ -133,7 +133,18 @@ public:
         IRQ_TIMEOUT,  //< Timeout on IRQ register.
     };
 
-    explicit SX1278Lora(SPISlave slave) : SX1278Common(slave) {}
+    /**
+     * @brief Construct a new SX1278
+     */
+    explicit SX1278Lora(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0,
+                        miosix::GpioPin dio1, miosix::GpioPin dio3,
+                        SPI::ClockDivider clock_divider,
+                        std::unique_ptr<SX1278::ISX1278Frontend> frontend)
+        : SX1278Common(bus, cs, dio0, dio1, dio3, clock_divider,
+                       std::move(frontend)),
+          crc_enabled(false)
+    {
+    }
 
     /**
      * @brief Setup the device.
@@ -173,27 +184,19 @@ public:
     /**
      * @brief Get the RSSI in dBm, during last packet receive.
      */
-    float getLastRxRssi();
+    float getLastRxRssi() override;
 
     /**
      * @brief Get the RSSI in dBm, during last packet receive.
      */
-    float getLastRxSnr();
-
-protected:
-    // Stuff to work with various front-ends
-    virtual void enableRxFrontend() override {}
-    virtual void disableRxFrontend() override {}
-    virtual void enableTxFrontend() override {}
-    virtual void disableTxFrontend() override {}
+    float getLastRxSnr() override;
 
 private:
+    void enterLoraMode();
+
     void readFifo(uint8_t addr, uint8_t *dst, uint8_t size);
     void writeFifo(uint8_t addr, uint8_t *src, uint8_t size);
 
-    SX1278::DioMask getDioMaskFromIrqFlags(IrqFlags flags, Mode mode,
-                                           SX1278::DioMapping mapping) override;
-
     IrqFlags getIrqFlags() override;
     void resetIrqFlags(IrqFlags flags) override;
 
@@ -201,6 +204,8 @@ private:
     void setMapping(SX1278::DioMapping mapping) override;
 
     void setFreqRF(int freq_rf);
+
+    bool crc_enabled;
 };
 
 }  // namespace Boardcore
diff --git a/src/tests/radio/sx1278/fsk/common.h b/src/tests/radio/sx1278/fsk/common.h
index d95cacd0aa3f0b79eaa3463cf821c2572b8b9146..9106da46ad3c3560e58dbe53b732dc132a9ad6c7 100644
--- a/src/tests/radio/sx1278/fsk/common.h
+++ b/src/tests/radio/sx1278/fsk/common.h
@@ -32,56 +32,58 @@ static const char *stringFromErr(Boardcore::SX1278Fsk::Error err)
             return "Error::BAD_VALUE";
         case Boardcore::SX1278Fsk::Error::BAD_VERSION:
             return "Error::BAD_VERSION";
+        case Boardcore::SX1278Fsk::Error::IRQ_TIMEOUT:
+            return "Error::IRQ_TIMEOUT";
         default:
             return "<unknown>";
     }
 }
 
-static const char *stringFromRxBw(Boardcore::SX1278Fsk::RxBw rx_bw)
+static const char *stringFromRxBw(Boardcore::SX1278Fsk::Config::RxBw rx_bw)
 {
     switch (rx_bw)
     {
-        case Boardcore::SX1278Fsk::RxBw::HZ_2600:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_2600:
             return "RxBw::HZ_2600";
-        case Boardcore::SX1278Fsk::RxBw::HZ_3100:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_3100:
             return "RxBw::HZ_3100";
-        case Boardcore::SX1278Fsk::RxBw::HZ_3900:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_3900:
             return "RxBw::HZ_3900";
-        case Boardcore::SX1278Fsk::RxBw::HZ_5200:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_5200:
             return "RxBw::HZ_5200";
-        case Boardcore::SX1278Fsk::RxBw::HZ_6300:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_6300:
             return "RxBw::HZ_6300";
-        case Boardcore::SX1278Fsk::RxBw::HZ_7800:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_7800:
             return "RxBw::HZ_7800";
-        case Boardcore::SX1278Fsk::RxBw::HZ_10400:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_10400:
             return "RxBw::HZ_10400";
-        case Boardcore::SX1278Fsk::RxBw::HZ_12500:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_12500:
             return "RxBw::HZ_12500";
-        case Boardcore::SX1278Fsk::RxBw::HZ_15600:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_15600:
             return "RxBw::HZ_15600";
-        case Boardcore::SX1278Fsk::RxBw::HZ_20800:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_20800:
             return "RxBw::HZ_20800";
-        case Boardcore::SX1278Fsk::RxBw::HZ_25000:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_25000:
             return "RxBw::HZ_25000";
-        case Boardcore::SX1278Fsk::RxBw::HZ_31300:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_31300:
             return "RxBw::HZ_31300";
-        case Boardcore::SX1278Fsk::RxBw::HZ_41700:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_41700:
             return "RxBw::HZ_41700";
-        case Boardcore::SX1278Fsk::RxBw::HZ_50000:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_50000:
             return "RxBw::HZ_50000";
-        case Boardcore::SX1278Fsk::RxBw::HZ_62500:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_62500:
             return "RxBw::HZ_62500";
-        case Boardcore::SX1278Fsk::RxBw::HZ_83300:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_83300:
             return "RxBw::HZ_83300";
-        case Boardcore::SX1278Fsk::RxBw::HZ_100000:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_100000:
             return "RxBw::HZ_100000";
-        case Boardcore::SX1278Fsk::RxBw::HZ_125000:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_125000:
             return "RxBw::HZ_125000";
-        case Boardcore::SX1278Fsk::RxBw::HZ_166700:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_166700:
             return "RxBw::HZ_166700";
-        case Boardcore::SX1278Fsk::RxBw::HZ_200000:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_200000:
             return "RxBw::HZ_200000";
-        case Boardcore::SX1278Fsk::RxBw::HZ_250000:
+        case Boardcore::SX1278Fsk::Config::RxBw::HZ_250000:
             return "RxBw::HZ_250000";
         default:
             return "<unknown>";
diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp
deleted file mode 100644
index 5ef25822fa303630a8d1de04d746440bd2808e49..0000000000000000000000000000000000000000
--- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-gui.cpp
+++ /dev/null
@@ -1,162 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Davide Mor
- *
- * 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/interrupt/external_interrupts.h>
-#include <radio/SX1278/SX1278Fsk.h>
-
-#include <thread>
-
-#include "common.h"
-#include "gui/GUI.h"
-
-// Include body of the test
-#include "test-sx1278-bench.cpp"
-
-using namespace Boardcore;
-using namespace miosix;
-using namespace mxgui;
-
-#if defined _BOARD_STM32F429ZI_SKYWARD_GS_V2
-#include "interfaces-impl/hwmapping.h"
-
-using cs   = peripherals::ra01::pc13::cs;
-using dio0 = peripherals::ra01::pc13::dio0;
-using dio1 = peripherals::ra01::pc13::dio1;
-using dio3 = peripherals::ra01::pc13::dio3;
-
-using sck  = interfaces::spi4::sck;
-using miso = interfaces::spi4::miso;
-using mosi = interfaces::spi4::mosi;
-
-#define SX1278_SPI SPI4
-
-#define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
-#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl
-#define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
-
-#else
-#error "Target not supported"
-#endif
-
-void __attribute__((used)) SX1278_IRQ_DIO0()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO0);
-}
-
-void __attribute__((used)) SX1278_IRQ_DIO1()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO1);
-}
-
-void __attribute__((used)) SX1278_IRQ_DIO3()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO3);
-}
-
-void initBoard()
-{
-    GpioPin dio0_pin = dio0::getPin();
-    GpioPin dio1_pin = dio1::getPin();
-    GpioPin dio3_pin = dio3::getPin();
-
-    enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-}
-
-GUI *gui = nullptr;
-
-void initGUI()
-{
-    // TODO: This should be in bsp
-    using GpioUserBtn = Gpio<GPIOA_BASE, 0>;
-    GpioUserBtn::mode(Mode::INPUT_PULL_DOWN);
-
-    gui = new GUI();
-
-    ButtonHandler::getInstance().registerButtonCallback(
-        GpioUserBtn::getPin(),
-        [](auto event) { gui->screen_manager.onButtonEvent(event); });
-}
-
-int main()
-{
-    initBoard();
-    initGUI();
-
-    SX1278Fsk::Config config = {
-        .freq_rf  = 422075000,
-        .freq_dev = 25000,
-        .bitrate  = 19200,
-        .rx_bw    = Boardcore::SX1278Fsk::RxBw::HZ_83300,
-        .afc_bw   = Boardcore::SX1278Fsk::RxBw::HZ_125000,
-        .ocp      = 120,
-        .power    = 17,
-        .shaping  = Boardcore::SX1278Fsk::Shaping::GAUSSIAN_BT_1_0,
-        .dc_free  = Boardcore::SX1278Fsk::DcFree::WHITENING};
-    SX1278Fsk::Error err;
-
-    SPIBus bus(SX1278_SPI);
-    GpioPin cs = cs::getPin();
-
-    SPIBusConfig spi_config = {};
-    spi_config.clockDivider = SPI::ClockDivider::DIV_64;
-    spi_config.mode         = SPI::Mode::MODE_0;
-    spi_config.bitOrder     = SPI::Order::MSB_FIRST;
-    spi_config.byteOrder    = SPI::Order::MSB_FIRST;
-    spi_config.writeBit     = SPI::WriteBit::INVERTED;
-
-    sx1278 = new SX1278Fsk(SPISlave(bus, cs, spi_config));
-
-    printf("\n[sx1278] Configuring sx1278...\n");
-    if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE)
-    {
-        gui->stats_screen.updateError(err);
-        printf("[sx1278] sx1278->init error: %s\n", stringFromErr(err));
-
-        while (1)
-            Thread::wait();
-    }
-
-    printConfig(config);
-    gui->stats_screen.updateReady();
-
-    // Initialize backgrounds threads
-    spawnThreads();
-
-    while (1)
-    {
-        StatsScreen::Data data = {
-            stats.txBitrate(), stats.rxBitrate(), stats.corrupted_count,
-            stats.sent_count,  stats.recv_count,  0.0f /* TODO: Packet loss */,
-            stats.rssi};
-
-        gui->stats_screen.updateStats(data);
-        Thread::sleep(100);
-    }
-}
diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp
deleted file mode 100644
index f56c8200bb5e93d799999b1c23a5af8b98a79b14..0000000000000000000000000000000000000000
--- a/src/tests/radio/sx1278/fsk/test-sx1278-bench-serial.cpp
+++ /dev/null
@@ -1,165 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Davide Mor
- *
- * 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/interrupt/external_interrupts.h>
-#include <radio/SX1278/SX1278Fsk.h>
-
-#include <thread>
-
-#include "common.h"
-
-// Include body of the test
-#include "test-sx1278-bench.cpp"
-
-using namespace Boardcore;
-using namespace miosix;
-
-#if defined _BOARD_STM32F429ZI_SKYWARD_GS_V2
-#include "interfaces-impl/hwmapping.h"
-
-using cs   = peripherals::ra01::pc13::cs;
-using dio0 = peripherals::ra01::pc13::dio0;
-using dio1 = peripherals::ra01::pc13::dio1;
-using dio3 = peripherals::ra01::pc13::dio3;
-
-using sck  = interfaces::spi4::sck;
-using miso = interfaces::spi4::miso;
-using mosi = interfaces::spi4::mosi;
-
-#define SX1278_SPI SPI4
-
-#define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
-#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl
-#define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
-
-#else
-#error "Target not supported"
-#endif
-
-volatile int dio0_cnt = 0;
-volatile int dio1_cnt = 0;
-volatile int dio3_cnt = 0;
-
-void __attribute__((used)) SX1278_IRQ_DIO0()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO0);
-
-    dio0_cnt++;
-}
-
-void __attribute__((used)) SX1278_IRQ_DIO1()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO1);
-
-    dio1_cnt++;
-}
-
-void __attribute__((used)) SX1278_IRQ_DIO3()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO3);
-
-    dio3_cnt++;
-}
-
-void initBoard()
-{
-    GpioPin dio0_pin = dio0::getPin();
-    GpioPin dio1_pin = dio1::getPin();
-    GpioPin dio3_pin = dio3::getPin();
-
-    enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-}
-
-int main()
-{
-    initBoard();
-
-    SX1278Fsk::Config config = {
-        .freq_rf  = 422075000,
-        .freq_dev = 25000,
-        .bitrate  = 19200,
-        .rx_bw    = Boardcore::SX1278Fsk::RxBw::HZ_83300,
-        .afc_bw   = Boardcore::SX1278Fsk::RxBw::HZ_125000,
-        .ocp      = 120,
-        .power    = 17,
-        .shaping  = Boardcore::SX1278Fsk::Shaping::GAUSSIAN_BT_1_0,
-        .dc_free  = Boardcore::SX1278Fsk::DcFree::WHITENING};
-    SX1278Fsk::Error err;
-
-    SPIBus bus(SX1278_SPI);
-    GpioPin cs = cs::getPin();
-
-    SPIBusConfig spi_config = {};
-    spi_config.clockDivider = SPI::ClockDivider::DIV_64;
-    spi_config.mode         = SPI::Mode::MODE_0;
-    spi_config.bitOrder     = SPI::Order::MSB_FIRST;
-    spi_config.byteOrder    = SPI::Order::MSB_FIRST;
-    spi_config.writeBit     = SPI::WriteBit::INVERTED;
-
-    sx1278 = new SX1278Fsk(SPISlave(bus, cs, spi_config));
-
-    printf("\n[sx1278] Configuring sx1278...\n");
-    if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE)
-    {
-        printf("[sx1278] sx1278->init error: %s\n", stringFromErr(err));
-        return -1;
-    }
-
-    printConfig(config);
-    printf("\n[sx1278] Initialization complete!\n");
-
-    // Initialize backgrounds threads
-    spawnThreads();
-
-    while (1)
-    {
-        printf(
-            "\n[sx1278] Stats:\n"
-            "Tx bitrate:        %.2f kb/s\n"
-            "Packet sent:       %d\n"
-            "Rx bitrate:        %.2f kb/s\n"
-            "Packet received:   %d\n"
-            "Corrupted packets: %d\n"
-            "Packet loss:       %.2f %%\n"
-            "RSSI:              %.2f dBm\n"
-            "FEI:               %.2f dBm\n"
-            "dio0:              %d\n"
-            "dio1:              %d\n"
-            "dio3:              %d\n",
-            static_cast<float>(stats.txBitrate()) / 1000.0f, stats.sent_count,
-            static_cast<float>(stats.rxBitrate()) / 1000.0f, stats.recv_count,
-            stats.corrupted_count, 0.0f /* TODO: Packet loss */, stats.rssi,
-            stats.fei, dio0_cnt, dio1_cnt, dio3_cnt);
-
-        miosix::Thread::sleep(2000);
-    }
-
-    return 0;
-}
diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp
index cb6180630a07edea2d0c5b08fa1da079abbde1b8..19de226e5b3e822e6759ef16a99acfb1e39e762d 100644
--- a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp
+++ b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp
@@ -22,7 +22,7 @@
 
 #include <drivers/interrupt/external_interrupts.h>
 #include <miosix.h>
-#include <radio/SX1278/Ebyte.h>
+#include <radio/SX1278/SX1278Frontends.h>
 #include <radio/SX1278/SX1278Fsk.h>
 
 #include <cstring>
@@ -51,7 +51,7 @@ using rxen = Gpio<GPIOD_BASE, 4>;
 #define SX1278_SPI SPI4
 
 #define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
-#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl
 #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
 
 #else
@@ -63,19 +63,19 @@ SX1278Fsk *sx1278 = nullptr;
 void __attribute__((used)) SX1278_IRQ_DIO0()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO0);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO1()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO1);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO3()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO3);
+        sx1278->handleDioIRQ();
 }
 
 void initBoard()
@@ -90,16 +90,16 @@ void initBoard()
     GpioPin dio3_pin = dio3::getPin();
 
     enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
+                            InterruptTrigger::RISING_FALLING_EDGE);
     enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
+                            InterruptTrigger::RISING_FALLING_EDGE);
     enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
+                            InterruptTrigger::RISING_FALLING_EDGE);
 }
 
 void recvLoop()
 {
-    char buf[64];
+    char buf[SX1278Fsk::MTU];
     while (1)
     {
         ssize_t res =
@@ -116,7 +116,7 @@ void recvLoop()
 
 void sendLoop(int interval, const char *data)
 {
-    char buf[64];
+    char buf[SX1278Fsk::MTU];
     strncpy(buf, data, sizeof(buf) - 1);
 
     while (1)
@@ -134,22 +134,16 @@ int main()
 
     // Run default configuration
     SX1278Fsk::Config config;
-    config.power = 2;
 
     SX1278Fsk::Error err;
 
     SPIBus bus(SX1278_SPI);
-    GpioPin cs = cs::getPin();
 
-    SPIBusConfig spi_config = {};
-    spi_config.clockDivider = SPI::ClockDivider::DIV_64;
-    spi_config.mode         = SPI::Mode::MODE_0;
-    spi_config.bitOrder     = SPI::Order::MSB_FIRST;
-    spi_config.byteOrder    = SPI::Order::MSB_FIRST;
-    spi_config.writeBit     = SPI::WriteBit::INVERTED;
+    std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend());
 
-    sx1278 = new EbyteFsk(SPISlave(bus, cs, spi_config), txen::getPin(),
-                          rxen::getPin());
+    sx1278 = new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(),
+                           dio3::getPin(), SPI::ClockDivider::DIV_64,
+                           std::move(frontend));
 
     printf("\n[sx1278] Configuring sx1278...\n");
     if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE)
@@ -162,8 +156,15 @@ int main()
 
     printf("\n[sx1278] Initialization complete!\n");
 
+    const char *msg =
+        "Very very very very very very very very very very very "
+        "very very very very very very very very very very very "
+        "very very very very very very very very very very very "
+        "very very very very very very very very very very very "
+        "long message";
+
     // Spawn all threads
-    std::thread send([]() { sendLoop(1000, "Sample radio message"); });
+    std::thread send([msg]() { sendLoop(3333, msg); });
     std::thread recv([]() { recvLoop(); });
 
     // sx1278->debugDumpRegisters();
diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp
index 6fb0a6173e02555ede22cf430c518f6620843611..2ea4330776a25051354534ef0c85aa25fe5b15ef 100644
--- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp
+++ b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp
@@ -21,7 +21,10 @@
  */
 
 #include <drivers/interrupt/external_interrupts.h>
+#include <drivers/timer/TimestampTimer.h>
+#include <radio/SX1278/SX1278Frontends.h>
 #include <radio/SX1278/SX1278Fsk.h>
+#include <utils/collections/CircularBuffer.h>
 
 #include <thread>
 
@@ -32,7 +35,7 @@
 #pragma GCC diagnostic push
 #pragma GCC diagnostic ignored "-Wcast-align"
 #pragma GCC diagnostic ignored "-Waddress-of-packed-member"
-#include <mavlink_lib/pyxis/mavlink.h>
+#include <mavlink_lib/gemini/mavlink.h>
 #pragma GCC diagnostic pop
 
 #include <radio/MavlinkDriver/MavlinkDriver.h>
@@ -40,12 +43,11 @@
 using namespace Boardcore;
 using namespace miosix;
 
-constexpr uint32_t RADIO_PKT_LENGTH     = 63;
+constexpr uint32_t RADIO_PKT_LENGTH     = SX1278Fsk::MTU;
 constexpr uint32_t RADIO_OUT_QUEUE_SIZE = 10;
 constexpr uint32_t RADIO_MAV_MSG_LENGTH = MAVLINK_MAX_DIALECT_PAYLOAD_SIZE;
-constexpr size_t MAV_OUT_BUFFER_MAX_AGE = 200;
+constexpr size_t MAV_OUT_BUFFER_MAX_AGE = 10;
 constexpr uint32_t FLIGHT_TM_PERIOD     = 250;
-constexpr uint32_t STATS_TM_PERIOD      = 2000;
 
 // Mavlink out buffer with 10 packets, 256 bytes each.
 using Mav =
@@ -66,9 +68,62 @@ using mosi = interfaces::spi4::mosi;
 #define SX1278_SPI SPI4
 
 #define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
-#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl
 #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
 
+#elif defined _BOARD_STM32F767ZI_GEMINI_GS
+#include "interfaces-impl/hwmapping.h"
+
+#define SX1278_IS_SKYWARD433
+// #define SX1278_IS_EBYTE
+
+// Comment to use SX1278_2
+#define SX1278_1
+
+#ifdef SX1278_1
+using cs   = miosix::radio1::cs;
+using dio0 = miosix::radio1::dio0;
+using dio1 = miosix::radio1::dio1;
+using dio3 = miosix::radio1::dio3;
+
+using sck  = miosix::radio1::spi::sck;
+using miso = miosix::radio1::spi::miso;
+using mosi = miosix::radio1::spi::mosi;
+
+using txen = miosix::radio1::txen;
+using rxen = miosix::radio1::rxen;
+
+#define SX1278_NRST
+using rst  = miosix::radio1::nrst;
+
+#define SX1278_SPI MIOSIX_RADIO1_SPI
+
+#define SX1278_IRQ_DIO0 MIOSIX_RADIO1_DIO0_IRQ
+#define SX1278_IRQ_DIO1 MIOSIX_RADIO1_DIO1_IRQ
+#define SX1278_IRQ_DIO3 MIOSIX_RADIO1_DIO3_IRQ
+#else
+using cs   = miosix::radio2::cs;
+using dio0 = miosix::radio2::dio0;
+using dio1 = miosix::radio2::dio1;
+using dio3 = miosix::radio2::dio3;
+
+using sck  = miosix::radio2::spi::sck;
+using miso = miosix::radio2::spi::miso;
+using mosi = miosix::radio2::spi::mosi;
+
+using txen = miosix::radio2::txen;
+using rxen = miosix::radio2::rxen;
+
+#define SX1278_NRST
+using rst  = miosix::radio2::nrst;
+
+#define SX1278_SPI MIOSIX_RADIO2_SPI
+
+#define SX1278_IRQ_DIO0 MIOSIX_RADIO2_DIO0_IRQ
+#define SX1278_IRQ_DIO1 MIOSIX_RADIO2_DIO1_IRQ
+#define SX1278_IRQ_DIO3 MIOSIX_RADIO2_DIO3_IRQ
+#endif
+
 #else
 #error "Target not supported"
 #endif
@@ -78,76 +133,79 @@ SX1278Fsk* sx1278 = nullptr;
 void __attribute__((used)) SX1278_IRQ_DIO0()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO0);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO1()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO1);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO3()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Fsk::Dio::DIO3);
+        sx1278->handleDioIRQ();
 }
 
-void initBoard()
+void initBoard() {}
+
+struct PendingAck
 {
-    GpioPin dio0_pin = dio0::getPin();
-    GpioPin dio1_pin = dio1::getPin();
-    GpioPin dio3_pin = dio3::getPin();
-
-    enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-}
+    int msgid;
+    int seq;
+};
+
+CircularBuffer<PendingAck, 10> pending_acks;
+FastMutex mutex;
 
 Mav* channel;
 
 void onReceive(Mav* channel, const mavlink_message_t& msg)
 {
-    // Prepare ack messages
-    mavlink_message_t ackMsg;
-    mavlink_msg_ack_tm_pack(1, 1, &ackMsg, msg.msgid, msg.seq);
-
-    // Send the ack back to the sender
-    channel->enqueueMsg(ackMsg);
+    if (msg.msgid != MAVLINK_MSG_ID_ACK_TM)
+    {
+        Lock<FastMutex> l(mutex);
+        pending_acks.put({msg.msgid, msg.seq});
+    }
 }
 
 void flightTmLoop()
 {
+    int i = 0;
+
     while (1)
     {
         long long start = miosix::getTick();
 
-        mavlink_message_t msg;
-        mavlink_rocket_flight_tm_t tm = {0};
-        mavlink_msg_rocket_flight_tm_encode(171, 96, &msg, &tm);
+        {
+            Lock<FastMutex> l(mutex);
+            while (!pending_acks.isEmpty())
+            {
+                PendingAck ack = pending_acks.pop();
 
-        channel->enqueueMsg(msg);
+                // Prepare ack message
+                mavlink_message_t msg;
+                mavlink_msg_ack_tm_pack(171, 96, &msg, ack.msgid, ack.seq);
 
-        Thread::sleepUntil(start + FLIGHT_TM_PERIOD);
-    }
-}
-
-void statsTmLoop()
-{
-    while (1)
-    {
-        long long start = miosix::getTick();
+                // Send the ack back to the sender
+                channel->enqueueMsg(msg);
+            }
+        }
 
         mavlink_message_t msg;
-        mavlink_rocket_stats_tm_t tm = {0};
-        mavlink_msg_rocket_stats_tm_encode(171, 96, &msg, &tm);
+        mavlink_rocket_flight_tm_t tm = {0};
+        tm.timestamp                  = TimestampTimer::getTimestamp();
+        tm.acc_x                      = i;
+        tm.acc_y                      = i * 2;
+        tm.acc_z                      = i * 3;
+
+        mavlink_msg_rocket_flight_tm_encode(171, 96, &msg, &tm);
 
         channel->enqueueMsg(msg);
 
-        Thread::sleepUntil(start + STATS_TM_PERIOD);
+        Thread::sleepUntil(start + FLIGHT_TM_PERIOD);
+        i += 1;
     }
 }
 
@@ -155,20 +213,27 @@ int main()
 {
     initBoard();
 
-    SX1278Fsk::Config config;
+    SX1278Fsk::Config config = {
+        .freq_rf    = 434000000,
+        .freq_dev   = 50000,
+        .bitrate    = 48000,
+        .rx_bw      = Boardcore::SX1278Fsk::Config::RxBw::HZ_125000,
+        .afc_bw     = Boardcore::SX1278Fsk::Config::RxBw::HZ_125000,
+        .ocp        = 120,
+        .power      = 13,
+        .shaping    = Boardcore::SX1278Fsk::Config::Shaping::GAUSSIAN_BT_1_0,
+        .dc_free    = Boardcore::SX1278Fsk::Config::DcFree::WHITENING,
+        .enable_crc = false};
+
     SX1278Fsk::Error err;
 
     SPIBus bus(SX1278_SPI);
-    GpioPin cs = cs::getPin();
 
-    SPIBusConfig spi_config;
-    spi_config.clockDivider = SPI::ClockDivider::DIV_64;
-    spi_config.mode         = SPI::Mode::MODE_0;
-    spi_config.bitOrder     = SPI::Order::MSB_FIRST;
-    spi_config.byteOrder    = SPI::Order::MSB_FIRST;
-    spi_config.writeBit     = SPI::WriteBit::INVERTED;
+    std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend());
 
-    sx1278 = new SX1278Fsk(SPISlave(bus, cs, spi_config));
+    sx1278 = new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(),
+                           dio3::getPin(), SPI::ClockDivider::DIV_64,
+                           std::move(frontend));
 
     printf("\n[sx1278] Configuring sx1278...\n");
     if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE)
@@ -184,11 +249,7 @@ int main()
     channel = new Mav(sx1278, &onReceive, 0, MAV_OUT_BUFFER_MAX_AGE);
     channel->start();
 
-    std::thread flight_tm_loop([]() { flightTmLoop(); });
-    std::thread stats_tm_loop([]() { statsTmLoop(); });
-
-    while (1)
-        Thread::wait();
+    flightTmLoop();
 
     return 0;
 }
diff --git a/src/tests/radio/sx1278/fsk/gui/GUI.h b/src/tests/radio/sx1278/gui/GUI.h
similarity index 82%
rename from src/tests/radio/sx1278/fsk/gui/GUI.h
rename to src/tests/radio/sx1278/gui/GUI.h
index bd4544a4e595f265e2553cfe75127064f51416d2..9f317e8dfa9a0f0113d3b703d90a3eec1f5a49a3 100644
--- a/src/tests/radio/sx1278/fsk/gui/GUI.h
+++ b/src/tests/radio/sx1278/gui/GUI.h
@@ -39,6 +39,16 @@ std::string format_link_speed(size_t value)
         return fmt::format("{} b/s", value);
 }
 
+std::string format_frequency(size_t value)
+{
+    if (value > 1000000)
+        return fmt::format("{:.2f} MHz", static_cast<float>(value) / 1000000);
+    else if (value > 1000)
+        return fmt::format("{:.2f} kHz", static_cast<float>(value) / 1000);
+    else
+        return fmt::format("{} Hz", value);
+}
+
 class StatsScreen
 {
 public:
@@ -49,8 +59,9 @@ public:
         int corrupted_count;
         int sent_count;
         int recv_count;
-        float packet_loss;
         float rssi;
+        float fei;
+        float snr;
     };
 
     StatsScreen()
@@ -72,42 +83,27 @@ public:
         rx_data.setCell(&lbl_rx_bitrate, 0, 0);
         rx_data.setCell(&lbl_recv_count, 1, 0);
         rx_data.setCell(&lbl_corrupted_count, 2, 0);
-        rx_data.setCell(&lbl_packet_loss, 3, 0);
 
         rx_data.setCell(&rx_bitrate, 0, 1);
         rx_data.setCell(&recv_count, 1, 1);
         rx_data.setCell(&corrupted_count, 2, 1);
-        rx_data.setCell(&packet_loss, 3, 1);
 
         lbl_misc_data.setTextColor(mxgui::blue);
         misc_data.setCell(&lbl_rssi, 0, 0);
+        misc_data.setCell(&lbl_fei, 1, 0);
+        misc_data.setCell(&lbl_snr, 2, 0);
+
         misc_data.setCell(&rssi, 0, 1);
+        misc_data.setCell(&fei, 1, 1);
+        misc_data.setCell(&snr, 2, 1);
 
         root.addView(&status, 0.1);
         root.addView(&lbl_tx_data, 0.1);
         root.addView(&tx_data, 0.4);
         root.addView(&lbl_rx_data, 0.1);
-        root.addView(&rx_data, 0.8);
+        root.addView(&rx_data, 0.6);
         root.addView(&lbl_misc_data, 0.1);
-        root.addView(&misc_data, 0.2);
-    }
-
-    void updateError(Boardcore::SX1278Fsk::Error value)
-    {
-        switch (value)
-        {
-            case Boardcore::SX1278Fsk::Error::BAD_VALUE:
-                status.setBackgroundColor(mxgui::red);
-                status.setText("BAD VALUE");
-                break;
-            case Boardcore::SX1278Fsk::Error::BAD_VERSION:
-                status.setBackgroundColor(mxgui::red);
-                status.setText("BAD VERSION");
-                break;
-
-            default:
-                break;
-        }
+        root.addView(&misc_data, 0.6);
     }
 
     void updateReady()
@@ -124,18 +120,18 @@ public:
         rx_bitrate.setText(format_link_speed(stats.rx_bitrate));
         recv_count.setText(fmt::format("{}", stats.recv_count));
         corrupted_count.setText(fmt::format("{}", stats.corrupted_count));
-        packet_loss.setText(
-            fmt::format("{:.2f} %", stats.packet_loss * 100.0f));
 
         rssi.setText(fmt::format("{} dBm", stats.rssi));
+        fei.setText(format_frequency(stats.fei));
+        snr.setText(fmt::format("{}", stats.snr));
     }
 
     Boardcore::VerticalLayout root{10};
     Boardcore::TextView status{"LOADING"};
 
     Boardcore::GridLayout tx_data{2, 2};
-    Boardcore::GridLayout rx_data{4, 2};
-    Boardcore::GridLayout misc_data{1, 2};
+    Boardcore::GridLayout rx_data{3, 2};
+    Boardcore::GridLayout misc_data{3, 2};
 
     Boardcore::TextView lbl_tx_data{"Tx data"};
     Boardcore::TextView lbl_rx_data{"Rx data"};
@@ -146,16 +142,18 @@ public:
     Boardcore::TextView lbl_rx_bitrate{"Rx bitrate:"};
     Boardcore::TextView lbl_recv_count{"Packets received:"};
     Boardcore::TextView lbl_corrupted_count{"Corrupted packets:"};
-    Boardcore::TextView lbl_packet_loss{"Packet loss:"};
     Boardcore::TextView lbl_rssi{"RSSI:"};
+    Boardcore::TextView lbl_fei{"FEI:"};
+    Boardcore::TextView lbl_snr{"SNR:"};
 
     Boardcore::TextView tx_bitrate{"0.00 b/s"};
     Boardcore::TextView rx_bitrate{"0.00 b/s"};
     Boardcore::TextView corrupted_count{"0"};
     Boardcore::TextView recv_count{"0"};
     Boardcore::TextView sent_count{"0"};
-    Boardcore::TextView packet_loss{"0 %"};
     Boardcore::TextView rssi{"0 dBm"};
+    Boardcore::TextView fei{"0 Hz"};
+    Boardcore::TextView snr{"0"};
 };
 
 class GUI
diff --git a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp
index b2d66e80b9b621fed25d7bd56e9a6904731b75ae..a08f009cb9c699e49e0bf0df69217d6d5a3056c2 100644
--- a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp
+++ b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp
@@ -22,7 +22,7 @@
 
 #include <drivers/interrupt/external_interrupts.h>
 #include <miosix.h>
-#include <radio/SX1278/Ebyte.h>
+#include <radio/SX1278/SX1278Frontends.h>
 #include <radio/SX1278/SX1278Lora.h>
 
 #include <cstring>
@@ -54,7 +54,7 @@ using rxen = Gpio<GPIOD_BASE, 4>;
 #define SX1278_SPI SPI4
 
 #define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
-#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl
 #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
 
 #else
@@ -66,19 +66,19 @@ SX1278Lora *sx1278 = nullptr;
 void __attribute__((used)) SX1278_IRQ_DIO0()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO0);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO1()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO1);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO3()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO3);
+        sx1278->handleDioIRQ();
 }
 
 void initBoard()
@@ -89,17 +89,6 @@ void initBoard()
     rxen::low();
     txen::low();
 #endif
-
-    GpioPin dio0_pin = dio0::getPin();
-    GpioPin dio1_pin = dio1::getPin();
-    GpioPin dio3_pin = dio3::getPin();
-
-    enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
 }
 
 bool isByteBuf(uint8_t *buf, ssize_t len)
@@ -157,7 +146,7 @@ void recvLoop()
 
 void sendLoop(int interval, const char *data)
 {
-    char buf[64];
+    char buf[SX1278Lora::MTU];
     strncpy(buf, data, sizeof(buf) - 1);
 
     while (1)
@@ -174,42 +163,44 @@ int main()
     initBoard();
 
     SX1278Lora::Config config = {};
-    config.pa_boost           = true;
     config.power              = 10;
     config.ocp                = 0;
-    config.coding_rate        = SX1278Lora::Config::Cr::CR_4;
-    config.spreading_factor   = SX1278Lora::Config::Sf::SF_12;
+    config.coding_rate        = SX1278Lora::Config::Cr::CR_2;
+    config.spreading_factor   = SX1278Lora::Config::Sf::SF_8;
 
     SX1278Lora::Error err;
 
     SPIBus bus(SX1278_SPI);
-    GpioPin cs = cs::getPin();
-
-    SPIBusConfig spi_config = {};
-    spi_config.clockDivider = SPI::ClockDivider::DIV_64;
-    spi_config.mode         = SPI::Mode::MODE_0;
-    spi_config.bitOrder     = SPI::Order::MSB_FIRST;
-    spi_config.byteOrder    = SPI::Order::MSB_FIRST;
-    spi_config.writeBit     = SPI::WriteBit::INVERTED;
 
 #ifdef IS_EBYTE
-    sx1278 = new EbyteLora(SPISlave(bus, cs, spi_config), txen::getPin(),
-                           rxen::getPin());
+    std::unique_ptr<SX1278::ISX1278Frontend> frontend(
+        new EbyteFrontend(txen::getPin(), rxen::getPin()));
 #else
-    sx1278 = new SX1278Lora(SPISlave(bus, cs, spi_config));
+    std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend());
 #endif
 
+    sx1278 = new SX1278Lora(bus, cs::getPin(), dio0::getPin(), dio1::getPin(),
+                            dio3::getPin(), SPI::ClockDivider::DIV_64,
+                            std::move(frontend));
+
     printf("\n[sx1278] Configuring sx1278...\n");
     if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE)
     {
-        printf("[sx1278] sx1278->init error: %s\n", "TODO");
+        printf("[sx1278] sx1278->init error\n");
         return -1;
     }
 
     printf("\n[sx1278] Initialization complete!\n");
 
+    const char *msg =
+        "Very very very very very very very very very very very "
+        "very very very very very very very very very very very "
+        "very very very very very very very very very very very "
+        "very very very very very very very very very very very "
+        "long message";
+
     // Spawn all threads
-    std::thread send([]() { sendLoop(3333, "Sample radio message"); });
+    std::thread send([msg]() { sendLoop(3333, msg); });
     std::thread recv([]() { recvLoop(); });
 
     // sx1278->debugDumpRegisters();
diff --git a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp
index 65d31267144a7ba27052abb6321c4d55b14b7e49..4bf32e6ba58c3719140a1e7a6d38e3071b434ce7 100644
--- a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp
+++ b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp
@@ -21,6 +21,7 @@
  */
 
 #include <drivers/interrupt/external_interrupts.h>
+#include <radio/SX1278/SX1278Frontends.h>
 #include <radio/SX1278/SX1278Lora.h>
 
 #include <thread>
@@ -38,7 +39,7 @@
 using namespace Boardcore;
 using namespace miosix;
 
-constexpr uint32_t RADIO_PKT_LENGTH     = 255;
+constexpr uint32_t RADIO_PKT_LENGTH     = SX1278Lora::MTU;
 constexpr uint32_t RADIO_OUT_QUEUE_SIZE = 10;
 constexpr uint32_t RADIO_MAV_MSG_LENGTH = MAVLINK_MAX_DIALECT_PAYLOAD_SIZE;
 constexpr size_t MAV_OUT_BUFFER_MAX_AGE = 0;
@@ -73,7 +74,7 @@ using rxen = Gpio<GPIOD_BASE, 4>;
 #define SX1278_SPI SPI4
 
 #define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
-#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl
 #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
 
 #else
@@ -85,19 +86,19 @@ SX1278Lora* sx1278 = nullptr;
 void __attribute__((used)) SX1278_IRQ_DIO0()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO0);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO1()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO1);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO3()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO3);
+        sx1278->handleDioIRQ();
 }
 
 void initBoard()
@@ -108,17 +109,6 @@ void initBoard()
     rxen::low();
     txen::low();
 #endif
-
-    GpioPin dio0_pin = dio0::getPin();
-    GpioPin dio1_pin = dio1::getPin();
-    GpioPin dio3_pin = dio3::getPin();
-
-    enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
 }
 
 Mav* channel;
@@ -181,7 +171,6 @@ int main()
     initBoard();
 
     SX1278Lora::Config config = {};
-    config.pa_boost           = true;
     config.power              = 15;
     config.ocp                = 0;
     config.coding_rate        = SX1278Lora::Config::Cr::CR_1;
@@ -193,26 +182,22 @@ int main()
     SX1278Lora::Error err;
 
     SPIBus bus(SX1278_SPI);
-    GpioPin cs = cs::getPin();
-
-    SPIBusConfig spi_config = {};
-    spi_config.clockDivider = SPI::ClockDivider::DIV_64;
-    spi_config.mode         = SPI::Mode::MODE_0;
-    spi_config.bitOrder     = SPI::Order::MSB_FIRST;
-    spi_config.byteOrder    = SPI::Order::MSB_FIRST;
-    spi_config.writeBit     = SPI::WriteBit::INVERTED;
 
 #ifdef IS_EBYTE
-    sx1278 = new EbyteLora(SPISlave(bus, cs, spi_config), txen::getPin(),
-                           rxen::getPin());
+    std::unique_ptr<SX1278::ISX1278Frontend> frontend(
+        new EbyteFrontend(txen::getPin(), rxen::getPin()));
 #else
-    sx1278 = new SX1278Lora(SPISlave(bus, cs, spi_config));
+    std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend());
 #endif
 
+    sx1278 = new SX1278Lora(bus, cs::getPin(), dio0::getPin(), dio1::getPin(),
+                            dio3::getPin(), SPI::ClockDivider::DIV_64,
+                            std::move(frontend));
+
     printf("\n[sx1278] Configuring sx1278...\n");
     if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE)
     {
-        printf("[sx1278] sx1278->init error: %s\n", "TODO");
+        printf("[sx1278] sx1278->init error\n");
         return -1;
     }
 
diff --git a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp
index 694c68daac00f13243d29d7f8b07c8d7c09e7278..2d4bdc75b62f457aa44bc77104d7c53df3ab1a5d 100644
--- a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp
+++ b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp
@@ -21,7 +21,7 @@
  */
 
 #include <drivers/interrupt/external_interrupts.h>
-#include <radio/SX1278/Ebyte.h>
+#include <radio/SX1278/SX1278Frontends.h>
 #include <radio/SX1278/SX1278Lora.h>
 
 using namespace Boardcore;
@@ -50,7 +50,7 @@ using rxen = Gpio<GPIOD_BASE, 4>;
 #define SX1278_SPI SPI4
 
 #define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
-#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl
 #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
 
 #else
@@ -62,19 +62,19 @@ SX1278Lora *sx1278 = nullptr;
 void __attribute__((used)) SX1278_IRQ_DIO0()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO0);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO1()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO1);
+        sx1278->handleDioIRQ();
 }
 
 void __attribute__((used)) SX1278_IRQ_DIO3()
 {
     if (sx1278)
-        sx1278->handleDioIRQ(SX1278Lora::Dio::DIO3);
+        sx1278->handleDioIRQ();
 }
 
 void initBoard()
@@ -85,17 +85,6 @@ void initBoard()
     rxen::low();
     txen::low();
 #endif
-
-    GpioPin dio0_pin = dio0::getPin();
-    GpioPin dio1_pin = dio1::getPin();
-    GpioPin dio3_pin = dio3::getPin();
-
-    enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
-    enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(),
-                            InterruptTrigger::RISING_EDGE);
 }
 
 int main()
@@ -104,7 +93,6 @@ int main()
     initBoard();
 
     SX1278Lora::Config config = {};
-    config.pa_boost           = true;
     config.power              = 10;
     config.ocp                = 0;
     config.coding_rate        = SX1278Lora::Config::Cr::CR_1;
@@ -113,26 +101,22 @@ int main()
     SX1278Lora::Error err;
 
     SPIBus bus(SX1278_SPI);
-    GpioPin cs = cs::getPin();
-
-    SPIBusConfig spi_config = {};
-    spi_config.clockDivider = SPI::ClockDivider::DIV_64;
-    spi_config.mode         = SPI::Mode::MODE_0;
-    spi_config.bitOrder     = SPI::Order::MSB_FIRST;
-    spi_config.byteOrder    = SPI::Order::MSB_FIRST;
-    spi_config.writeBit     = SPI::WriteBit::INVERTED;
 
 #ifdef IS_EBYTE
-    sx1278 = new EbyteLora(SPISlave(bus, cs, spi_config), txen::getPin(),
-                           rxen::getPin());
+    std::unique_ptr<SX1278::ISX1278Frontend> frontend(
+        new EbyteFrontend(txen::getPin(), rxen::getPin()));
 #else
-    sx1278 = new SX1278Lora(SPISlave(bus, cs, spi_config));
+    std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend());
 #endif
 
+    sx1278 = new SX1278Lora(bus, cs::getPin(), dio0::getPin(), dio1::getPin(),
+                            dio3::getPin(), SPI::ClockDivider::DIV_64,
+                            std::move(frontend));
+
     printf("\n[sx1278] Configuring sx1278...\n");
     if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE)
     {
-        printf("[sx1278] sx1278->init error: %s\n", "TODO");
+        printf("[sx1278] sx1278->init error\n");
         return -1;
     }
 
diff --git a/src/tests/radio/sx1278/sx1278-init.h b/src/tests/radio/sx1278/sx1278-init.h
new file mode 100644
index 0000000000000000000000000000000000000000..f304948729a401b0045b907b2d971592d5c03742
--- /dev/null
+++ b/src/tests/radio/sx1278/sx1278-init.h
@@ -0,0 +1,259 @@
+/* Copyright (c) 2023 Skyward Experimental Rocketry
+ * Author: Davide Mor
+ *
+ * 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/interrupt/external_interrupts.h>
+#include <miosix.h>
+
+// SX1278 includes
+#include <radio/SX1278/SX1278Frontends.h>
+#include <radio/SX1278/SX1278Fsk.h>
+#include <radio/SX1278/SX1278Lora.h>
+
+// Uncomment the following line to enable Lora mode
+// Or use SBS to define it for you
+// #define SX1278_IS_LORA
+
+#if defined _BOARD_STM32F429ZI_SKYWARD_GS_V2
+#include "interfaces-impl/hwmapping.h"
+
+// Uncomment the following line to enable Ebyte module
+// #define SX1278_IS_EBYTE
+// Uncomment the following line to ebable Skyward433 module
+// #define SX1278_IS_SKYWARD433
+
+using cs   = miosix::peripherals::ra01::pc13::cs;
+using dio0 = miosix::peripherals::ra01::pc13::dio0;
+using dio1 = miosix::peripherals::ra01::pc13::dio1;
+using dio3 = miosix::peripherals::ra01::pc13::dio3;
+
+using sck  = miosix::interfaces::spi4::sck;
+using miso = miosix::interfaces::spi4::miso;
+using mosi = miosix::interfaces::spi4::mosi;
+
+#ifdef SX1278_IS_EBYTE
+using txen = miosix::Gpio<GPIOE_BASE, 4>;
+using rxen = miosix::Gpio<GPIOD_BASE, 4>;
+#endif
+
+#define SX1278_SPI SPI4
+
+#define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl
+#define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl
+
+#elif defined _BOARD_STM32F429ZI_SKYWARD_RIG
+#include "interfaces-impl/hwmapping.h"
+
+#define SX1278_IS_EBYTE
+
+using cs   = miosix::radio::cs;
+using dio0 = miosix::radio::dio0;
+using dio1 = miosix::radio::dio1;
+using dio3 = miosix::radio::dio3;
+
+using sck  = miosix::radio::sck;
+using miso = miosix::radio::miso;
+using mosi = miosix::radio::mosi;
+
+using txen                         = miosix::radio::txEn;
+using rxen                         = miosix::radio::rxEn;
+
+#define SX1278_SPI SPI4
+
+#define SX1278_IRQ_DIO0 EXTI5_IRQHandlerImpl
+#define SX1278_IRQ_DIO1 EXTI12_IRQHandlerImpl
+#define SX1278_IRQ_DIO3 EXTI13_IRQHandlerImpl
+
+#elif defined _BOARD_STM32F767ZI_GEMINI_GS
+#include "interfaces-impl/hwmapping.h"
+
+#define SX1278_IS_SKYWARD433
+// #define SX1278_IS_EBYTE
+
+// Comment to use SX1278_2
+#define SX1278_1
+
+#ifdef SX1278_1
+using cs   = miosix::radio1::cs;
+using dio0 = miosix::radio1::dio0;
+using dio1 = miosix::radio1::dio1;
+using dio3 = miosix::radio1::dio3;
+
+using sck  = miosix::radio1::spi::sck;
+using miso = miosix::radio1::spi::miso;
+using mosi = miosix::radio1::spi::mosi;
+
+using txen = miosix::radio1::txen;
+using rxen = miosix::radio1::rxen;
+
+#define SX1278_NRST
+using rst  = miosix::radio1::nrst;
+
+#define SX1278_SPI MIOSIX_RADIO1_SPI
+
+#define SX1278_IRQ_DIO0 MIOSIX_RADIO1_DIO0_IRQ
+#define SX1278_IRQ_DIO1 MIOSIX_RADIO1_DIO1_IRQ
+#define SX1278_IRQ_DIO3 MIOSIX_RADIO1_DIO3_IRQ
+#else
+using cs   = miosix::radio2::cs;
+using dio0 = miosix::radio2::dio0;
+using dio1 = miosix::radio2::dio1;
+using dio3 = miosix::radio2::dio3;
+
+using sck  = miosix::radio2::spi::sck;
+using miso = miosix::radio2::spi::miso;
+using mosi = miosix::radio2::spi::mosi;
+
+using txen = miosix::radio2::txen;
+using rxen = miosix::radio2::rxen;
+
+#define SX1278_NRST
+using rst  = miosix::radio2::nrst;
+
+#define SX1278_SPI MIOSIX_RADIO2_SPI
+
+#define SX1278_IRQ_DIO0 MIOSIX_RADIO2_DIO0_IRQ
+#define SX1278_IRQ_DIO1 MIOSIX_RADIO2_DIO1_IRQ
+#define SX1278_IRQ_DIO3 MIOSIX_RADIO2_DIO3_IRQ
+#endif
+
+#else
+#error "Target not supported"
+#endif
+
+#ifdef SX1278_IS_LORA
+static constexpr size_t SX1278_MTU = Boardcore::SX1278Lora::MTU;
+Boardcore::SX1278Lora *sx1278      = nullptr;
+#else
+static constexpr size_t SX1278_MTU = Boardcore::SX1278Fsk::MTU;
+Boardcore::SX1278Fsk *sx1278       = nullptr;
+#endif
+
+volatile int dio0_cnt = 0;
+volatile int dio1_cnt = 0;
+volatile int dio3_cnt = 0;
+
+#ifdef SX1278_IRQ_DIO0
+void __attribute__((used)) SX1278_IRQ_DIO0()
+{
+    dio0_cnt++;
+    if (sx1278)
+        sx1278->handleDioIRQ();
+}
+#endif
+
+#ifdef SX1278_IRQ_DIO1
+void __attribute__((used)) SX1278_IRQ_DIO1()
+{
+    dio1_cnt++;
+    if (sx1278)
+        sx1278->handleDioIRQ();
+}
+#endif
+
+#ifdef SX1278_IRQ_DIO3
+void __attribute__((used)) SX1278_IRQ_DIO3()
+{
+    dio3_cnt++;
+    if (sx1278)
+        sx1278->handleDioIRQ();
+}
+#endif
+
+void initBoard()
+{
+#ifdef SX1278_IS_EBYTE
+    rxen::mode(miosix::Mode::OUTPUT);
+    txen::mode(miosix::Mode::OUTPUT);
+    rxen::low();
+    txen::low();
+#endif
+
+#ifdef SX1278_NRST
+    rst::mode(miosix::Mode::OUTPUT);
+    rst::high();
+#endif
+}
+
+Boardcore::SPIBus sx1278_bus(SX1278_SPI);
+
+bool initRadio()
+{
+    // Initialize frontend (if any)
+#if defined SX1278_IS_EBYTE
+    printf("[sx1278] Confuring Ebyte frontend...\n");
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+        new Boardcore::EbyteFrontend(txen::getPin(), rxen::getPin()));
+#elif defined SX1278_IS_SKYWARD433
+    printf("[sx1278] Confuring Skyward 433 frontend...\n");
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+              new Boardcore::Skyward433Frontend());
+#else
+    printf("[sx1278] Confuring RA01 frontend...\n");
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+         new Boardcore::RA01Frontend());
+#endif
+
+    // Initialize actual radio driver
+#ifdef SX1278_IS_LORA
+    // Run default configuration
+    Boardcore::SX1278Lora::Config config;
+    Boardcore::SX1278Lora::Error err;
+
+    sx1278 = new Boardcore::SX1278Lora(sx1278_bus, cs::getPin(), dio0::getPin(),
+                                       dio1::getPin(), dio3::getPin(),
+                                       Boardcore::SPI::ClockDivider::DIV_256,
+                                       std::move(frontend));
+
+    printf("\n[sx1278] Configuring sx1278 lora...\n");
+    if ((err = sx1278->init(config)) != Boardcore::SX1278Lora::Error::NONE)
+    {
+        printf("[sx1278] sx1278->init error\n");
+        return false;
+    }
+
+    printf("\n[sx1278] Initialization complete!\n");
+#else
+    // Run default configuration
+    Boardcore::SX1278Fsk::Config config;
+    Boardcore::SX1278Fsk::Error err;
+
+    sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), dio0::getPin(),
+                                            dio1::getPin(), dio3::getPin(),
+                                            Boardcore::SPI::ClockDivider::DIV_256,
+                                            std::move(frontend));
+
+    printf("\n[sx1278] Configuring sx1278 fsk...\n");
+    if ((err = sx1278->init(config)) != Boardcore::SX1278Fsk::Error::NONE)
+    {
+              // FIXME: Why does clang-format put this line up here?
+        printf("[sx1278] sx1278->init error\n");
+        return false;
+    }
+
+    printf("\n[sx1278] Initialization complete!\n");
+#endif
+
+    return true;
+}
diff --git a/src/shared/radio/SX1278/Ebyte.cpp b/src/tests/radio/sx1278/test-sx1278-bench-gui.cpp
similarity index 54%
rename from src/shared/radio/SX1278/Ebyte.cpp
rename to src/tests/radio/sx1278/test-sx1278-bench-gui.cpp
index 8ac662783c0eb1d26869326d19119b43cf81b819..c07aea5c2831cb31e640866d73d5775e3b78759e 100644
--- a/src/shared/radio/SX1278/Ebyte.cpp
+++ b/src/tests/radio/sx1278/test-sx1278-bench-gui.cpp
@@ -20,31 +20,51 @@
  * THE SOFTWARE.
  */
 
-#include "Ebyte.h"
+#include "gui/GUI.h"
 
-namespace Boardcore
-{
+// Include body of the test
+#include "test-sx1278-bench.cpp"
 
-EbyteFsk::Error EbyteFsk::configure(const Config& config)
-{
-    // TODO(davide.mor): Validate input parameters
-    return SX1278Fsk::configure(config);
-}
+using namespace mxgui;
 
-void EbyteFsk::enableRxFrontend() { rx_enable.high(); }
-void EbyteFsk::disableRxFrontend() { rx_enable.low(); }
-void EbyteFsk::enableTxFrontend() { tx_enable.high(); }
-void EbyteFsk::disableTxFrontend() { tx_enable.low(); }
+GUI *gui = nullptr;
 
-EbyteLora::Error EbyteLora::configure(const Config& config)
+void initGUI()
 {
-    // TODO(davide.mor): Validate input parameters
-    return SX1278Lora::configure(config);
+    using GpioUserBtn = Gpio<GPIOA_BASE, 0>;
+    GpioUserBtn::mode(Mode::INPUT_PULL_DOWN);
+
+    gui = new GUI();
+
+    ButtonHandler::getInstance().registerButtonCallback(
+        GpioUserBtn::getPin(),
+        [](auto event) { gui->screen_manager.onButtonEvent(event); });
 }
 
-void EbyteLora::enableRxFrontend() { rx_enable.high(); }
-void EbyteLora::disableRxFrontend() { rx_enable.low(); }
-void EbyteLora::enableTxFrontend() { tx_enable.high(); }
-void EbyteLora::disableTxFrontend() { tx_enable.low(); }
+int main()
+{
+    initBoard();
+    initGUI();
+    if (!initRadio())
+    {
+        while (1)
+            ;
+    }
+
+    // Set display to ready
+    gui->stats_screen.updateReady();
+
+    // Initialize backgrounds threads
+    spawnThreads();
 
-}  // namespace Boardcore
+    while (1)
+    {
+        StatsScreen::Data data = {
+            stats.txBitrate(), stats.rxBitrate(), stats.corrupted_count,
+            stats.sent_count,  stats.recv_count,  stats.rssi,
+            stats.fei,         stats.snr};
+
+        gui->stats_screen.updateStats(data);
+        Thread::sleep(100);
+    }
+}
diff --git a/src/tests/radio/sx1278/test-sx1278-bench-serial.cpp b/src/tests/radio/sx1278/test-sx1278-bench-serial.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..da250f7fe9a41c8f0e32429471d9a092515f69c6
--- /dev/null
+++ b/src/tests/radio/sx1278/test-sx1278-bench-serial.cpp
@@ -0,0 +1,65 @@
+/* Copyright (c) 2021 Skyward Experimental Rocketry
+ * Author: Davide Mor
+ *
+ * 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 the body of the test
+#include "test-sx1278-bench.cpp"
+
+int main()
+{
+    initBoard();
+    if (!initRadio())
+    {
+        while (1)
+            ;
+    }
+
+    // Initialize backgrounds threads
+    spawnThreads();
+
+    while (1)
+    {
+        printf(
+            "\n[sx1278] Stats:\n"
+            "Tx bitrate:        %.2f kb/s\n"
+            "Packet sent:       %d\n"
+            "Rx bitrate:        %.2f kb/s\n"
+            "Packet received:   %d\n"
+            "Corrupted packets: %d\n"
+            "RSSI:              %.2f dBm\n"
+            "FEI:               %.2f Hz\n"
+            "SNR:               %.2f\n"
+            "dio0:              %d\n"
+            "dio1:              %d\n"
+            "dio3:              %d\n",
+            static_cast<float>(stats.txBitrate()) / 1000.0f, stats.sent_count,
+            static_cast<float>(stats.rxBitrate()) / 1000.0f, stats.recv_count,
+            stats.corrupted_count, stats.rssi, stats.fei, stats.snr, dio0_cnt,
+            dio1_cnt, dio3_cnt);
+        dio0_cnt = 0;
+        dio1_cnt = 0;
+        dio3_cnt = 0;
+
+        miosix::Thread::sleep(2000);
+    }
+
+    return 0;
+}
diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bench.cpp b/src/tests/radio/sx1278/test-sx1278-bench.cpp
similarity index 89%
rename from src/tests/radio/sx1278/fsk/test-sx1278-bench.cpp
rename to src/tests/radio/sx1278/test-sx1278-bench.cpp
index 66e153a862d7c9c74f44fdd0ab51767c6795ff46..67d02cecb25bae77506ce10aeb8832d7ae819249 100644
--- a/src/tests/radio/sx1278/fsk/test-sx1278-bench.cpp
+++ b/src/tests/radio/sx1278/test-sx1278-bench.cpp
@@ -22,16 +22,15 @@
 
 #include <drivers/timer/TimestampTimer.h>
 #include <miosix.h>
-#include <radio/SX1278/SX1278Fsk.h>
 #include <utils/MovingAverage.h>
 
 #include <thread>
 
+#include "sx1278-init.h"
+
 using namespace Boardcore;
 using namespace miosix;
 
-SX1278Fsk *sx1278 = nullptr;
-
 // Simple xorshift RNG
 uint32_t xorshift32()
 {
@@ -48,7 +47,7 @@ uint32_t xorshift32()
 
 struct TestMsg
 {
-    static constexpr int WORD_COUNT = 14;
+    static constexpr int WORD_COUNT = 60;
 
     uint32_t payload[WORD_COUNT];
 
@@ -86,6 +85,7 @@ struct LinkStats
 
     float rssi = 0.0f;
     float fei  = 0.0f;
+    float snr  = 0.0f;
 
     uint64_t txBitrate()
     {
@@ -114,12 +114,13 @@ void recvLoop()
         TestMsg msg = {};
 
         sx1278->receive((uint8_t *)&msg, sizeof(msg));
-        if (true)
+        if (msg.validate())
         {
             stats.recv_count++;
 
             stats.rssi = sx1278->getLastRxRssi();
             stats.fei  = sx1278->getLastRxFei();
+            stats.snr  = sx1278->getLastRxSnr();
         }
         else
         {
@@ -165,4 +166,17 @@ void spawnThreads()
     std::thread send([]() { sendLoop(); });
     send.detach();
 #endif
+
+    // For now, I'll keep it here, just in case ...
+    /* std::thread watchdog([]() {
+        while(1) {
+            {
+                FastInterruptDisableLock dlock;
+                sx1278->handleDioIRQ();
+            }
+            Thread::sleep(2);
+        }
+    });
+    watchdog.detach();
+    //*/
 }