diff --git a/CMakeLists.txt b/CMakeLists.txt
index aaba63944cb7e1096e7e70e16796acbfec10e304..3ebdcfe5784dbf7ac91520ebe138d826c0469aa8 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -71,7 +71,7 @@ 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)
+sbs_target(sx1278lora-skyward433-serial stm32f767zi_gemini_gs)
 
 add_executable(sx1278fsk-ebyterig-serial src/entrypoints/sx1278-serial.cpp)
 target_compile_definitions(sx1278fsk-ebyterig-serial PRIVATE SX1278_IS_FSK)
@@ -314,17 +314,15 @@ add_executable(test-sx1278fsk-gui-rx src/tests/radio/sx1278/test-sx1278-bench-gu
 target_compile_definitions(test-sx1278fsk-gui-rx PRIVATE DISABLE_TX)
 sbs_target(test-sx1278fsk-gui-rx stm32f429zi_skyward_groundstation_v2)
 
-add_executable(test-sx1278fsk-mavlink src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp)
+add_executable(test-sx1278fsk-mavlink src/tests/radio/sx1278/test-sx1278-mavlink.cpp)
+target_compile_definitions(test-sx1278fsk-mavlink PRIVATE SX1278_IS_FSK)
 sbs_target(test-sx1278fsk-mavlink stm32f429zi_skyward_groundstation_v2)
 
 # add_executable(test-mavlinkdriver src/tests/radio/test-mavlinkdriver.cpp)
 # sbs_target(test-mavlinkdriver stm32f407vg_stm32f4discovery)
 
 add_executable(test-sx1278lora-bidir src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp)
-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)
+sbs_target(test-sx1278lora-bidir stm32f767zi_gemini_gs)
 
 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)
@@ -340,7 +338,7 @@ 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)
+sbs_target(test-sx1278lora-rx stm32f767zi_gemini_gs)
 
 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)
@@ -350,6 +348,10 @@ add_executable(test-sx1278lora-gui-tx src/tests/radio/sx1278/test-sx1278-bench-g
 target_compile_definitions(test-sx1278lora-gui-tx PRIVATE DISABLE_RX SX1278_IS_LORA)
 sbs_target(test-sx1278lora-gui-tx stm32f429zi_skyward_groundstation_v2)
 
+add_executable(test-sx1278lora-mavlink src/tests/radio/sx1278/test-sx1278-mavlink.cpp)
+target_compile_definitions(test-sx1278lora-mavlink PRIVATE SX1278_IS_LORA)
+sbs_target(test-sx1278lora-mavlink stm32f429zi_skyward_groundstation_v2)
+
 #-----------------------------------------------------------------------------#
 #                               Tests - Sensors                               #
 #-----------------------------------------------------------------------------#
diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp
index 317d779c125ce2649aafed75006381518e009aee..43983114e1412fbec6f6f0f54383edfbd3b40265 100644
--- a/src/shared/radio/SX1278/SX1278Fsk.cpp
+++ b/src/shared/radio/SX1278/SX1278Fsk.cpp
@@ -34,6 +34,8 @@ namespace Boardcore
 using namespace SX1278;
 using namespace SX1278::Fsk;
 
+static constexpr uint16_t FSK_SYNC_VALUE = 0x12ad;
+
 long long now() { return miosix::getTick() * 1000 / miosix::TICK_FREQ; }
 
 // Enable:
@@ -82,8 +84,6 @@ bool SX1278Fsk::checkVersion()
     SPITransaction spi(getSpiSlave(guard));
 
     uint8_t version = spi.readRegister(REG_VERSION);
-    TRACE("[sx1278] Chip id: %d\n", version);
-
     return version == 0x12;
 }
 
@@ -130,6 +130,16 @@ void SX1278Fsk::reconfigure(Lock &guard)
     {
         SPITransaction spi(getSpiSlave(guard));
 
+        // This must be the first register to be configured, so if anything goes
+        // wrong past this point, we can detect it
+        spi.writeRegister16(REG_SYNC_VALUE_1, FSK_SYNC_VALUE);
+
+        // Setup sync word
+        spi.writeRegister(
+            REG_SYNC_CONFIG,
+            RegSyncConfig::make(2, true, RegSyncConfig::PREAMBLE_POLARITY_55,
+                                RegSyncConfig::AUTO_RESTART_RX_MODE_OFF));
+
         // Setup bitrate
         uint16_t bitrate_raw = FXOSC / bitrate;
         spi.writeRegister16(REG_BITRATE_MSB, bitrate_raw);
@@ -162,14 +172,6 @@ void SX1278Fsk::reconfigure(Lock &guard)
             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);
 
@@ -462,15 +464,13 @@ void SX1278Fsk::rateLimitTx()
 
 bool SX1278Fsk::checkDeviceFailure(Lock &guard)
 {
-    // This check will be performed sometimes when hte IRQ timeout ends
-    // In such cases the device will NEVER be in standby, even if we keep it at
-    // standby between operations. So, if the device IS in standby in that case,
-    // then something must have gone wrong
+    // Check that this register is the same as when we configured it, otherwise
+    // the device has failed.
 
     SPITransaction spi(getSpiSlave(guard));
-    uint8_t mode = spi.readRegister(REG_OP_MODE);
+    uint16_t sync_value = spi.readRegister16(REG_SYNC_VALUE_1);
 
-    return (mode & 0b111) == RegOpMode::Mode::MODE_STDBY;
+    return sync_value != FSK_SYNC_VALUE;
 }
 
 SX1278Fsk::IrqFlags SX1278Fsk::getIrqFlags(Lock &guard)
diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp
index 11ef83f232d3dca0cab612bf549a16204a2b6a33..e2bbd4a57a380dbf241eb5df758a9408cf647ba4 100644
--- a/src/shared/radio/SX1278/SX1278Lora.cpp
+++ b/src/shared/radio/SX1278/SX1278Lora.cpp
@@ -32,6 +32,8 @@ namespace Boardcore
 using namespace SX1278;
 using namespace SX1278::Lora;
 
+static constexpr uint8_t LORA_SYNC_VALUE = 0x69;
+
 static constexpr uint8_t MAX_PAYLOAD_LENGTH = 0xff;
 static constexpr uint8_t FIFO_TX_BASE_ADDR  = 0x00;
 static constexpr uint8_t FIFO_RX_BASE_ADDR  = 0x00;
@@ -135,7 +137,6 @@ SX1278Lora::Error SX1278Lora::init(const Config &config)
     // First probe for the device
     if (!checkVersion())
     {
-        TRACE("[sx1278] Wrong chipid\n");
         return Error::BAD_VALUE;
     }
 
@@ -169,8 +170,6 @@ bool SX1278Lora::checkVersion()
     SPITransaction spi(getSpiSlave(guard));
 
     uint8_t version = spi.readRegister(REG_VERSION);
-    TRACE("[sx1278] Chip id: %d\n", version);
-
     return version == 0x12;
 }
 
@@ -214,6 +213,10 @@ void SX1278Lora::reconfigure(Lock &guard)
     {
         SPITransaction spi(getSpiSlave(guard));
 
+        // This must be the first register to be configured, so if anything goes
+        // wrong past this point, we can detect it
+        spi.writeRegister(REG_SYNC_WORD, LORA_SYNC_VALUE);
+
         // Setup FIFO sections
         spi.writeRegister(REG_FIFO_TX_BASE_ADDR, FIFO_TX_BASE_ADDR);
         spi.writeRegister(REG_FIFO_RX_BASE_ADDR, FIFO_RX_BASE_ADDR);
@@ -275,9 +278,6 @@ void SX1278Lora::reconfigure(Lock &guard)
             RegDetectOptimize::make(0x03, errata_values.automatic_if_on));
         spi.writeRegister(REG_DETECTION_THRESHOLD, 0x0a);
 
-        // (just change it to something that isn't the default)
-        spi.writeRegister(REG_SYNC_WORD, 0x69);
-
         // Setup weird errata registers (see errata note)
         if (errata_values.reg_high_bw_optimize_1 != -1)
             spi.writeRegister(REG_HIGH_BW_OPTIMIZE_1,
@@ -420,7 +420,15 @@ void SX1278Lora::writeFifo(Lock &guard, uint8_t addr, uint8_t *src,
     spi.writeRegisters(REG_FIFO, src, size);
 }
 
-bool SX1278Lora::checkDeviceFailure(Lock &guard) { return false; }
+bool SX1278Lora::checkDeviceFailure(Lock &guard) { 
+    // Check that this register is the same as when we configured it, otherwise
+    // the device has failed.
+
+    SPITransaction spi(getSpiSlave(guard));
+    uint8_t sync_value = spi.readRegister(REG_SYNC_WORD);
+
+    return sync_value != LORA_SYNC_VALUE;
+}
 
 SX1278Common::IrqFlags SX1278Lora::getIrqFlags(Lock &guard)
 {
diff --git a/src/shared/radio/SX1278/SX1278Lora.h b/src/shared/radio/SX1278/SX1278Lora.h
index 9cf025218ad3911b4815ee9d03aeaaa47d7fbf36..2b3a197b6d9daf77c6449cf2ca35b7e34733f7ce 100644
--- a/src/shared/radio/SX1278/SX1278Lora.h
+++ b/src/shared/radio/SX1278/SX1278Lora.h
@@ -155,11 +155,6 @@ public:
      */
     bool checkVersion();
 
-    /**
-     * @brief Configure this device on the fly.
-     */
-    [[nodiscard]] virtual Error configure(const Config &config);
-
     /**
      * @brief Wait until a new packet is received.
      *
diff --git a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp
deleted file mode 100644
index 4bf32e6ba58c3719140a1e7a6d38e3071b434ce7..0000000000000000000000000000000000000000
--- a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp
+++ /dev/null
@@ -1,217 +0,0 @@
-/* Copyright (c) 2018 Skyward Experimental Rocketry
- * Authors: Alvise de'Faveri Tron, Nuno Barcellos, 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/SX1278Frontends.h>
-#include <radio/SX1278/SX1278Lora.h>
-
-#include <thread>
-
-// Ignore warnings, as we don't want to change third party generated files to
-// fix them
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wcast-align"
-#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
-#include <mavlink_lib/pyxis/mavlink.h>
-#pragma GCC diagnostic pop
-
-#include <radio/MavlinkDriver/MavlinkDriver.h>
-
-using namespace Boardcore;
-using namespace miosix;
-
-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;
-constexpr uint16_t SLEEP_AFTER_SEND     = 0;
-constexpr uint32_t FLIGHT_TM_PERIOD     = 8000;
-constexpr uint32_t STATS_TM_PERIOD      = 1000;
-
-// Mavlink out buffer with 10 packets, 256 bytes each.
-using Mav =
-    MavlinkDriver<RADIO_PKT_LENGTH, RADIO_OUT_QUEUE_SIZE, RADIO_MAV_MSG_LENGTH>;
-
-#if defined _BOARD_STM32F429ZI_SKYWARD_GS_V2
-#include "interfaces-impl/hwmapping.h"
-
-// Uncomment the following line to enable Ebyte module
-// #define IS_EBYTE
-
-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;
-
-#ifdef IS_EBYTE
-using txen = Gpio<GPIOE_BASE, 4>;
-using rxen = 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
-
-#else
-#error "Target not supported"
-#endif
-
-SX1278Lora* sx1278 = nullptr;
-
-void __attribute__((used)) SX1278_IRQ_DIO0()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ();
-}
-
-void __attribute__((used)) SX1278_IRQ_DIO1()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ();
-}
-
-void __attribute__((used)) SX1278_IRQ_DIO3()
-{
-    if (sx1278)
-        sx1278->handleDioIRQ();
-}
-
-void initBoard()
-{
-#ifdef IS_EBYTE
-    rxen::mode(Mode::OUTPUT);
-    txen::mode(Mode::OUTPUT);
-    rxen::low();
-    txen::low();
-#endif
-}
-
-Mav* channel;
-
-void onReceive(Mav* channel, const mavlink_message_t& msg)
-{
-    printf("Received something...\n");
-
-    if (msg.msgid != MAVLINK_MSG_ID_ACK_TM)
-    {
-        // 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);
-    }
-    else
-    {
-        printf("Received ACK!\n");
-    }
-}
-
-void flightTmLoop()
-{
-    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);
-
-        channel->enqueueMsg(msg);
-        printf("Enqueued flight_tm_tm!\n");
-
-        Thread::sleepUntil(start + FLIGHT_TM_PERIOD);
-    }
-}
-
-void statsTmLoop()
-{
-    while (1)
-    {
-        long long start = miosix::getTick();
-
-        mavlink_message_t msg;
-        mavlink_rocket_stats_tm_t tm = {0};
-        mavlink_msg_rocket_stats_tm_encode(171, 96, &msg, &tm);
-
-        channel->enqueueMsg(msg);
-        printf("Enqueued stats_tm!\n");
-
-        Thread::sleepUntil(start + STATS_TM_PERIOD);
-    }
-}
-
-int main()
-{
-    initBoard();
-
-    SX1278Lora::Config config = {};
-    config.power              = 15;
-    config.ocp                = 0;
-    config.coding_rate        = SX1278Lora::Config::Cr::CR_1;
-    config.spreading_factor   = SX1278Lora::Config::Sf::SF_7;
-    config.bandwidth          = SX1278Lora::Config::Bw::HZ_250000;
-
-    printf("Effective bitrate: %lukb/s\n", config.effectiveBitrate());
-
-    SX1278Lora::Error err;
-
-    SPIBus bus(SX1278_SPI);
-
-#ifdef IS_EBYTE
-    std::unique_ptr<SX1278::ISX1278Frontend> frontend(
-        new EbyteFrontend(txen::getPin(), rxen::getPin()));
-#else
-    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\n");
-        return -1;
-    }
-
-    printf("\n[sx1278] Initialization complete!\n");
-
-    channel =
-        new Mav(sx1278, &onReceive, SLEEP_AFTER_SEND, MAV_OUT_BUFFER_MAX_AGE);
-    channel->start();
-
-    std::thread flight_tm_loop([]() { flightTmLoop(); });
-    std::thread stats_tm_loop([]() { statsTmLoop(); });
-
-    while (1)
-        Thread::wait();
-
-    return 0;
-}
diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/test-sx1278-mavlink.cpp
similarity index 60%
rename from src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp
rename to src/tests/radio/sx1278/test-sx1278-mavlink.cpp
index 2ea4330776a25051354534ef0c85aa25fe5b15ef..d8bf407b40306a9b573f16b312cfa1f04d27a3fb 100644
--- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp
+++ b/src/tests/radio/sx1278/test-sx1278-mavlink.cpp
@@ -24,12 +24,11 @@
 #include <drivers/timer/TimestampTimer.h>
 #include <radio/SX1278/SX1278Frontends.h>
 #include <radio/SX1278/SX1278Fsk.h>
+#include <radio/SX1278/SX1278Lora.h>
 #include <utils/collections/CircularBuffer.h>
 
 #include <thread>
 
-#include "common.h"
-
 // Ignore warnings, as we don't want to change third party generated files to
 // fix them
 #pragma GCC diagnostic push
@@ -43,16 +42,6 @@
 using namespace Boardcore;
 using namespace miosix;
 
-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 = 10;
-constexpr uint32_t FLIGHT_TM_PERIOD     = 250;
-
-// Mavlink out buffer with 10 packets, 256 bytes each.
-using Mav =
-    MavlinkDriver<RADIO_PKT_LENGTH, RADIO_OUT_QUEUE_SIZE, RADIO_MAV_MSG_LENGTH>;
-
 #if defined _BOARD_STM32F429ZI_SKYWARD_GS_V2
 #include "interfaces-impl/hwmapping.h"
 
@@ -90,11 +79,11 @@ 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;
+using txen                         = miosix::radio1::txen;
+using rxen                         = miosix::radio1::rxen;
 
 #define SX1278_NRST
-using rst  = miosix::radio1::nrst;
+using rst                          = miosix::radio1::nrst;
 
 #define SX1278_SPI MIOSIX_RADIO1_SPI
 
@@ -128,25 +117,46 @@ using rst  = miosix::radio2::nrst;
 #error "Target not supported"
 #endif
 
-SX1278Fsk* sx1278 = nullptr;
+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 = 10;
+constexpr uint32_t FLIGHT_TM_PERIOD     = 250;
+
+#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
+
+// Mavlink out buffer with 10 packets, 256 bytes each.
+using Mav =
+    MavlinkDriver<SX1278_MTU, RADIO_OUT_QUEUE_SIZE, RADIO_MAV_MSG_LENGTH>;
 
+#ifdef SX1278_IRQ_DIO0
 void __attribute__((used)) SX1278_IRQ_DIO0()
 {
     if (sx1278)
         sx1278->handleDioIRQ();
 }
+#endif
 
+#ifdef SX1278_IRQ_DIO1
 void __attribute__((used)) SX1278_IRQ_DIO1()
 {
     if (sx1278)
         sx1278->handleDioIRQ();
 }
+#endif
 
+#ifdef SX1278_IRQ_DIO3
 void __attribute__((used)) SX1278_IRQ_DIO3()
 {
     if (sx1278)
         sx1278->handleDioIRQ();
 }
+#endif
 
 void initBoard() {}
 
@@ -165,6 +175,7 @@ void onReceive(Mav* channel, const mavlink_message_t& msg)
 {
     if (msg.msgid != MAVLINK_MSG_ID_ACK_TM)
     {
+        printf("[sx1278] Received packet!\n");
         Lock<FastMutex> l(mutex);
         pending_acks.put({msg.msgid, msg.seq});
     }
@@ -189,7 +200,11 @@ void flightTmLoop()
                 mavlink_msg_ack_tm_pack(171, 96, &msg, ack.msgid, ack.seq);
 
                 // Send the ack back to the sender
-                channel->enqueueMsg(msg);
+                bool result = channel->enqueueMsg(msg);
+                if (!result)
+                {
+                    printf("[sx1278] Failed to enqueue packet!\n");
+                }
             }
         }
 
@@ -202,49 +217,88 @@ void flightTmLoop()
 
         mavlink_msg_rocket_flight_tm_encode(171, 96, &msg, &tm);
 
-        channel->enqueueMsg(msg);
+        bool result = channel->enqueueMsg(msg);
+        if (!result)
+        {
+            printf("[sx1278] Failed to enqueue packet!\n");
+        }
 
         Thread::sleepUntil(start + FLIGHT_TM_PERIOD);
         i += 1;
     }
 }
 
+Boardcore::SPIBus sx1278_bus(SX1278_SPI);
+
 int main()
 {
-    initBoard();
 
-    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;
+    initBoard();
 
-    SPIBus bus(SX1278_SPI);
+    // 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
 
-    std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend());
+    // Initialize actual radio driver
+#ifdef SX1278_IS_LORA
+    // Run default configuration
+    Boardcore::SX1278Lora::Config config;
+    Boardcore::SX1278Lora::Error err;
 
-    sx1278 = new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(),
-                           dio3::getPin(), SPI::ClockDivider::DIV_64,
-                           std::move(frontend));
+    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...\n");
-    if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE)
+    printf("\n[sx1278] Configuring sx1278 lora...\n");
+    if ((err = sx1278->init(config)) != Boardcore::SX1278Lora::Error::NONE)
     {
-        printf("[sx1278] sx1278->init error: %s\n", stringFromErr(err));
+        printf("[sx1278] sx1278->init error\n");
+        return false;
+    }
 
-        while (1)
-            Thread::wait();
+    printf("\n[sx1278] Initialization complete!\n");
+#else
+    // Run default configuration
+    Boardcore::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};
+    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;
     }
 
-    printConfig(config);
+    printf("\n[sx1278] Initialization complete!\n");
+#endif
 
     channel = new Mav(sx1278, &onReceive, 0, MAV_OUT_BUFFER_MAX_AGE);
     channel->start();