aboutsummaryrefslogtreecommitdiff
path: root/src/modules/px4iofirmware/serial.c
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/px4iofirmware/serial.c')
-rw-r--r--src/modules/px4iofirmware/serial.c7
1 files changed, 7 insertions, 0 deletions
diff --git a/src/modules/px4iofirmware/serial.c b/src/modules/px4iofirmware/serial.c
index 722d05809..6c6a9a2b1 100644
--- a/src/modules/px4iofirmware/serial.c
+++ b/src/modules/px4iofirmware/serial.c
@@ -64,6 +64,7 @@ static perf_counter_t pc_ore;
static perf_counter_t pc_fe;
static perf_counter_t pc_ne;
static perf_counter_t pc_regerr;
+static perf_counter_t pc_crcerr;
static void rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg);
static void tx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg);
@@ -124,6 +125,7 @@ interface_init(void)
pc_fe = perf_alloc(PC_COUNT, "framing");
pc_ne = perf_alloc(PC_COUNT, "noise");
pc_regerr = perf_alloc(PC_COUNT, "regerr");
+ pc_crcerr = perf_alloc(PC_COUNT, "crcerr");
/* allocate DMA */
tx_dma = stm32_dmachannel(PX4FMU_SERIAL_TX_DMA);
@@ -205,6 +207,11 @@ rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
perf_count(pc_rx);
+ uint8_t crc = dma_packet.crc;
+ dma_packet.crc = 0;
+ if (crc != crc_packet())
+ perf_count(pc_crcerr);
+
/* default to not sending a reply */
if (PKT_CODE(dma_packet) == PKT_CODE_WRITE) {