diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index ced8d97ff..466370117 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -298,7 +298,7 @@ uint32_t uartTotalRxBytesWaiting(serialPort_t *instance) if (s->rxDMAStream) { uint32_t rxDMAHead = s->rxDMAStream->NDTR; #else - if (s->rxDMAChannel) { + if (s->rxDMAChannel) { uint32_t rxDMAHead = s->rxDMAChannel->CNDTR; #endif if (rxDMAHead >= s->rxDMAPos) { @@ -421,13 +421,13 @@ void uartWrite(serialPort_t *instance, uint8_t ch) const struct serialPortVTable uartVTable[] = { { - uartWrite, - uartTotalRxBytesWaiting, - uartTotalTxBytesFree, - uartRead, - uartSetBaudRate, - isUartTransmitBufferEmpty, - uartSetMode, + .serialWrite = uartWrite, + .serialTotalRxWaiting = uartTotalRxBytesWaiting, + .serialTotalTxFree = uartTotalTxBytesFree, + .serialRead = uartRead, + .serialSetBaudRate = uartSetBaudRate, + .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty, + .setMode = uartSetMode, .writeBuf = NULL, .beginWrite = NULL, .endWrite = NULL, diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 8360b0068..2c2cebbac 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -171,9 +171,9 @@ static const struct serialPortVTable usbVTable[] = { .serialSetBaudRate = usbVcpSetBaudRate, .isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty, .setMode = usbVcpSetMode, + .writeBuf = usbVcpWriteBuf, .beginWrite = usbVcpBeginWrite, - .endWrite = usbVcpEndWrite, - .writeBuf = usbVcpWriteBuf + .endWrite = usbVcpEndWrite } }; diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 0f94c7bc1..2e8e2eab4 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -194,7 +194,7 @@ serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction #ifdef TELEMETRY #define ALL_TELEMETRY_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT) #else -#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM) +#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK) #endif #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK) @@ -270,7 +270,7 @@ serialPort_t *openSerialPort( portMode_t mode, portOptions_t options) { -#if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1)) +#if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_UART4) && !defined(USE_UART5) && !defined(USE_UART6) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)) UNUSED(callback); UNUSED(baudRate); UNUSED(mode); diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 077ad0729..924f58232 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -34,6 +34,7 @@ typedef enum { FUNCTION_RX_SERIAL = (1 << 6), // 64 FUNCTION_BLACKBOX = (1 << 7), // 128 FUNCTION_PASSTHROUGH = (1 << 8), // 256 + FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512 } serialPortFunction_e; typedef enum { diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index d3ac73001..2836d5ebc 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -35,16 +35,17 @@ */ #include -#include #include -#include "common/utils.h" #include "platform.h" + +#include "common/utils.h" #include "build_config.h" #include "drivers/system.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" #include "io/serial.h" +#include "rx/rx.h" #include "rx/jetiexbus.h" @@ -55,6 +56,7 @@ #include "sensors/battery.h" #include "sensors/barometer.h" #include "telemetry/telemetry.h" +#include "telemetry/jetiexbus.h" #endif //TELEMETRY diff --git a/src/main/rx/jetiexbus.h b/src/main/rx/jetiexbus.h index a975e5c64..52b0bb45c 100644 --- a/src/main/rx/jetiexbus.h +++ b/src/main/rx/jetiexbus.h @@ -17,19 +17,6 @@ #pragma once - -#include "rx/rx.h" - bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback); uint8_t jetiExBusFrameStatus(void); - -#ifdef TELEMETRY - -#include "telemetry/telemetry.h" - -void initJetiExBusTelemetry(telemetryConfig_t *initialTelemetryConfig); -void checkJetiExBusTelemetryState(void); -void handleJetiExBusTelemetry(void); - -#endif //TELEMETRY diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index 35185b967..33bd13193 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -21,7 +21,6 @@ */ #include #include -#include #include "platform.h" diff --git a/src/main/telemetry/frsky.h b/src/main/telemetry/frsky.h index 8d1b82d61..555eb43e8 100644 --- a/src/main/telemetry/frsky.h +++ b/src/main/telemetry/frsky.h @@ -15,10 +15,9 @@ * along with Cleanflight. If not, see . */ -#include "rx/rx.h" +#pragma once -#ifndef TELEMETRY_FRSKY_H_ -#define TELEMETRY_FRSKY_H_ +#include "rx/rx.h" typedef enum { FRSKY_VFAS_PRECISION_LOW = 0, @@ -32,4 +31,3 @@ void initFrSkyTelemetry(telemetryConfig_t *telemetryConfig); void configureFrSkyTelemetryPort(void); void freeFrSkyTelemetryPort(void); -#endif /* TELEMETRY_FRSKY_H_ */ diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 7ccf8ea19..dcab855ae 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -57,11 +57,12 @@ #include #include "platform.h" -#include "build_config.h" -#include "debug.h" #ifdef TELEMETRY +#include "build_config.h" +#include "debug.h" + #include "common/axis.h" #include "drivers/system.h" diff --git a/src/main/telemetry/jetiexbus.h b/src/main/telemetry/jetiexbus.h new file mode 100644 index 000000000..79440c0df --- /dev/null +++ b/src/main/telemetry/jetiexbus.h @@ -0,0 +1,23 @@ +/* + * 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 + +struct telemetryConfig_s; +void initJetiExBusTelemetry(struct telemetryConfig_s *initialTelemetryConfig); +void checkJetiExBusTelemetryState(void); +void handleJetiExBusTelemetry(void); diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index c70146f64..fce4fbc91 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -33,10 +33,10 @@ #include "platform.h" -#include "build_config.h" - #ifdef TELEMETRY +#include "build_config.h" + #include "common/maths.h" #include "common/axis.h" #include "common/color.h" diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index e3871aead..96e2193e9 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -17,7 +17,6 @@ #include #include -#include #include "platform.h" @@ -40,7 +39,7 @@ #include "telemetry/hott.h" #include "telemetry/smartport.h" #include "telemetry/ltm.h" -#include "rx/jetiexbus.h" +#include "telemetry/jetiexbus.h" static telemetryConfig_t *telemetryConfig;