diff --git a/make/source.mk b/make/source.mk
index b2499b3dc1..2efbcd2c72 100644
--- a/make/source.mk
+++ b/make/source.mk
@@ -58,6 +58,7 @@ COMMON_SRC = \
fc/runtime_config.c \
interface/msp.c \
interface/msp_box.c \
+ interface/tramp_protocol.c \
io/beeper.c \
io/piniobox.c \
io/serial.c \
diff --git a/src/main/interface/tramp_protocol.c b/src/main/interface/tramp_protocol.c
new file mode 100644
index 0000000000..ffc70632b8
--- /dev/null
+++ b/src/main/interface/tramp_protocol.c
@@ -0,0 +1,94 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#include
+#include "platform.h"
+#include "common/utils.h"
+#include "interface/tramp_protocol.h"
+
+#define TRAMP_SYNC_START 0x0F
+#define TRAMP_SYNC_STOP 0x00
+#define TRAMP_COMMAND_SET_FREQ 'F' // 0x46
+#define TRAMP_COMMAND_SET_POWER 'P' // 0x50
+#define TRAMP_COMMAND_ACTIVE_STATE 'I' // 0x49
+#define TRAMP_COMMAND_GET_CONFIG 'v' // 0x76
+
+static uint8_t trampCrc(const trampFrame_t *frame)
+{
+ uint8_t crc = 0;
+ const uint8_t *p = (const uint8_t *)frame;
+ const uint8_t *pEnd = p + (TRAMP_HEADER_LENGTH + TRAMP_PAYLOAD_LENGTH);
+ for (; p != pEnd; p++) {
+ crc += *p;
+ }
+ return crc;
+}
+
+static void trampFrameInit(uint8_t frameType, trampFrame_t *frame)
+{
+ frame->header.syncStart = TRAMP_SYNC_START;
+ frame->header.command = frameType;
+ const uint8_t emptyPayload[TRAMP_PAYLOAD_LENGTH] = { 0 };
+ memcpy(frame->payload.buf, emptyPayload, sizeof(frame->payload.buf));
+}
+
+static void trampFrameClose(trampFrame_t *frame)
+{
+ frame->footer.crc = trampCrc(frame);
+ frame->footer.syncStop = TRAMP_SYNC_STOP;
+}
+
+void trampFrameGetSettings(trampFrame_t *frame)
+{
+ trampFrameInit(TRAMP_COMMAND_GET_CONFIG, frame);
+ trampFrameClose(frame);
+}
+
+void trampFrameSetFrequency(trampFrame_t *frame, const uint16_t frequency)
+{
+ trampFrameInit(TRAMP_COMMAND_SET_FREQ, frame);
+ frame->payload.frequency = frequency;
+ trampFrameClose(frame);
+}
+
+void trampFrameSetPower(trampFrame_t *frame, const uint16_t power)
+{
+ trampFrameInit(TRAMP_COMMAND_SET_POWER, frame);
+ frame->payload.power = power;
+ trampFrameClose(frame);
+}
+
+void trampFrameSetActiveState(trampFrame_t *frame, const bool active)
+{
+ trampFrameInit(TRAMP_COMMAND_ACTIVE_STATE, frame);
+ frame->payload.active = (uint8_t) active;
+ trampFrameClose(frame);
+}
+
+bool trampParseResponseBuffer(trampSettings_t *settings, const uint8_t *buffer, size_t bufferLen)
+{
+ if (bufferLen != TRAMP_FRAME_LENGTH) {
+ return false;
+ }
+ const trampFrame_t *frame = (const trampFrame_t *)buffer;
+ const uint8_t crc = trampCrc(frame);
+ if (crc != frame->footer.crc) {
+ return false;
+ }
+ memcpy(settings, &frame->payload.settings, sizeof(*settings));
+ return true;
+}
diff --git a/src/main/interface/tramp_protocol.h b/src/main/interface/tramp_protocol.h
new file mode 100644
index 0000000000..e75f79fe36
--- /dev/null
+++ b/src/main/interface/tramp_protocol.h
@@ -0,0 +1,68 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#pragma once
+
+#include "drivers/serial.h"
+
+#define TRAMP_SERIAL_OPTIONS SERIAL_NOT_INVERTED | SERIAL_BIDIR
+#define TRAMP_BAUD 9600
+#define TRAMP_PAYLOAD_LENGTH 12
+
+typedef struct trampSettings_s {
+ uint16_t frequency;
+ uint16_t power;
+ uint8_t raceModeEnabled;
+ uint8_t pitModeEnabled;
+} __attribute__((packed)) trampSettings_t;
+
+typedef struct trampFrameHeader_s {
+ uint8_t syncStart;
+ uint8_t command;
+} __attribute__((packed)) trampFrameHeader_t;
+
+#define TRAMP_HEADER_LENGTH sizeof(trampFrameHeader_t)
+
+typedef struct trampFrameFooter_s {
+ uint8_t crc;
+ uint8_t syncStop;
+} __attribute__((packed)) trampFrameFooter_t;
+
+typedef union trampPayload_u {
+ uint8_t buf[TRAMP_PAYLOAD_LENGTH];
+ trampSettings_t settings;
+ uint16_t frequency;
+ uint16_t power;
+ uint8_t active;
+} trampPayload_t;
+
+typedef struct trampFrame_s {
+ trampFrameHeader_t header;
+ trampPayload_t payload;
+ trampFrameFooter_t footer;
+} __attribute__((packed)) trampFrame_t;
+
+#define TRAMP_FRAME_LENGTH sizeof(trampFrame_t)
+
+STATIC_ASSERT(sizeof(trampFrameHeader_t) == 2, trampInterface_headerSizeMismatch);
+STATIC_ASSERT(sizeof(trampFrame_t) == 16, trampInterface_frameSizeMismatch);
+
+void trampFrameGetSettings(trampFrame_t *frame);
+void trampFrameSetFrequency(trampFrame_t *frame, const uint16_t frequency);
+void trampFrameSetPower(trampFrame_t *frame, const uint16_t power);
+void trampFrameSetActiveState(trampFrame_t *frame, const bool active);
+bool trampParseResponseBuffer(trampSettings_t *settings, const uint8_t *buffer, size_t bufferLen);