diff --git a/src/shared/radio/SX1278/SX1278.cpp b/src/shared/radio/SX1278/SX1278.cpp
index 52a91f3ba06520aa4b18974468319a22256b6774..bed1ae549d6daf57f3b77e8f6f0787c3efa9b5d9 100644
--- a/src/shared/radio/SX1278/SX1278.cpp
+++ b/src/shared/radio/SX1278/SX1278.cpp
@@ -31,6 +31,8 @@ namespace Boardcore
 
 using namespace SX1278Defs;
 
+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 |
@@ -247,10 +249,14 @@ ssize_t SX1278::receive(uint8_t *pkt, size_t max_len)
 
 bool SX1278::send(uint8_t *pkt, size_t len)
 {
-    // Packets longer than 255 are not supported
-    if (len > 255)
+    // Packets longer than FIFO_LEN (-1 for the len byte) are not supported
+    if (len > SX1278Defs::FIFO_LEN - 1)
         return false;
 
+    // This shouldn't be needed, but for some reason the device "lies" about
+    // being ready, so lock up if we are going too fast
+    rateLimitTx();
+
     bus_mgr.lock(SX1278BusManager::Mode::MODE_TX);
 
     // Wait for TX ready
@@ -267,11 +273,24 @@ bool SX1278::send(uint8_t *pkt, size_t len)
     // Wait for packet sent
     bus_mgr.waitForIrq(RegIrqFlags::PACKET_SENT);
     bus_mgr.unlock();
+
+    last_tx = now();
     return true;
 }
 
 void SX1278::handleDioIRQ() { bus_mgr.handleDioIRQ(); }
 
+void SX1278::rateLimitTx()
+{
+    const long long RATE_LIMIT = 2;
+
+    long long delta = now() - last_tx;
+    if (delta <= RATE_LIMIT)
+    {
+        miosix::Thread::sleep(RATE_LIMIT - delta);
+    }
+}
+
 uint8_t SX1278::getVersion()
 {
     SPITransaction spi(bus_mgr.getBus(), SPITransaction::WriteBit::INVERTED);
diff --git a/src/shared/radio/SX1278/SX1278.h b/src/shared/radio/SX1278/SX1278.h
index 6fb4c355d36f81331e7299e6a291e58c737e4156..3d89a9f9494a95ddcae4871f84a8c21132571066 100644
--- a/src/shared/radio/SX1278/SX1278.h
+++ b/src/shared/radio/SX1278/SX1278.h
@@ -228,6 +228,8 @@ public:
 public:
     using Mode = SX1278BusManager::Mode;
 
+    void rateLimitTx();
+
     void setBitrate(int bitrate);
     void setFreqDev(int freq_dev);
     void setFreqRF(int freq_rf);
@@ -240,6 +242,7 @@ public:
 
     void waitForIrq(uint16_t mask);
 
+    long long last_tx = 0;
     SX1278BusManager bus_mgr;
     PrintLogger logger = Logging::getLogger("sx1278");
 };
diff --git a/src/shared/radio/SX1278/SX1278Defs.h b/src/shared/radio/SX1278/SX1278Defs.h
index cd50d09a8c3294659f1c1186f2ad1fd0512937c6..06954099644e8a7b6d6b6566e0ad7d2ef1118f3b 100644
--- a/src/shared/radio/SX1278/SX1278Defs.h
+++ b/src/shared/radio/SX1278/SX1278Defs.h
@@ -33,6 +33,11 @@ namespace Boardcore
 namespace SX1278Defs
 {
 
+/**
+ * @brief Length of the internal FIFO
+ */
+constexpr int FIFO_LEN = 64;
+
 /**
  * @brief Main oscillator frequency (Hz)
  */
diff --git a/src/tests/drivers/sx1278/test-sx1278-bench.cpp b/src/tests/drivers/sx1278/test-sx1278-bench.cpp
index d484d39cab98c3703d89d27da0c176900cca7690..e407368feb3f172370b5d0dc2cba9fac784c5c89 100644
--- a/src/tests/drivers/sx1278/test-sx1278-bench.cpp
+++ b/src/tests/drivers/sx1278/test-sx1278-bench.cpp
@@ -143,8 +143,6 @@ void sendLoop(int idx)
 {
     while (1)
     {
-        miosix::Thread::sleep(TX_INTERVAL);
-
         int next_idx = stats.send_count + 1;
 
         Msg msg;
@@ -269,6 +267,7 @@ int main()
     std::thread recv([]() { recvLoop(0); });
 #endif
 #ifndef DISABLE_TX
+    miosix::Thread::sleep(500);
     std::thread send([]() { sendLoop(1); });
 #endif