mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 17:55:30 +03:00
Fix conditionals for telemetry protocols.
This commit is contained in:
parent
1edb5411d9
commit
402a0c2c59
14 changed files with 45 additions and 41 deletions
|
@ -159,7 +159,7 @@ STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data)
|
||||||
if (crc == crsfFrame.bytes[fullFrameLength - 1]) {
|
if (crc == crsfFrame.bytes[fullFrameLength - 1]) {
|
||||||
switch (crsfFrame.frame.type)
|
switch (crsfFrame.frame.type)
|
||||||
{
|
{
|
||||||
#if defined(USE_MSP_OVER_TELEMETRY)
|
#if defined(USE_TELEMETRY_CRSF) && defined(USE_MSP_OVER_TELEMETRY)
|
||||||
case CRSF_FRAMETYPE_MSP_REQ:
|
case CRSF_FRAMETYPE_MSP_REQ:
|
||||||
case CRSF_FRAMETYPE_MSP_WRITE: {
|
case CRSF_FRAMETYPE_MSP_WRITE: {
|
||||||
uint8_t *frameStart = (uint8_t *)&crsfFrame.frame.payload + CRSF_FRAME_ORIGIN_DEST_SIZE;
|
uint8_t *frameStart = (uint8_t *)&crsfFrame.frame.payload + CRSF_FRAME_ORIGIN_DEST_SIZE;
|
||||||
|
|
|
@ -69,7 +69,7 @@ static volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
|
||||||
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
|
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
|
||||||
static serialPort_t *serialPort;
|
static serialPort_t *serialPort;
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
static uint8_t telemetryBuf[SRXL_FRAME_SIZE_MAX];
|
static uint8_t telemetryBuf[SRXL_FRAME_SIZE_MAX];
|
||||||
static uint8_t telemetryBufLen = 0;
|
static uint8_t telemetryBufLen = 0;
|
||||||
#endif
|
#endif
|
||||||
|
@ -108,13 +108,14 @@ static uint8_t spektrumFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||||
{
|
{
|
||||||
UNUSED(rxRuntimeConfig);
|
UNUSED(rxRuntimeConfig);
|
||||||
|
|
||||||
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
static timeUs_t telemetryFrameRequestedUs = 0;
|
static timeUs_t telemetryFrameRequestedUs = 0;
|
||||||
|
|
||||||
uint8_t result = RX_FRAME_PENDING;
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
|
||||||
timeUs_t currentTimeUs = micros();
|
timeUs_t currentTimeUs = micros();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
uint8_t result = RX_FRAME_PENDING;
|
||||||
|
|
||||||
if (rcFrameComplete) {
|
if (rcFrameComplete) {
|
||||||
rcFrameComplete = false;
|
rcFrameComplete = false;
|
||||||
|
|
||||||
|
@ -150,7 +151,7 @@ static uint8_t spektrumFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
if (srxlEnabled && (spekFrame[2] & 0x80) == 0) {
|
if (srxlEnabled && (spekFrame[2] & 0x80) == 0) {
|
||||||
telemetryFrameRequestedUs = currentTimeUs;
|
telemetryFrameRequestedUs = currentTimeUs;
|
||||||
}
|
}
|
||||||
|
@ -158,7 +159,7 @@ static uint8_t spektrumFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||||
result = RX_FRAME_COMPLETE;
|
result = RX_FRAME_COMPLETE;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
if (telemetryBufLen && telemetryFrameRequestedUs && cmpTimeUs(currentTimeUs, telemetryFrameRequestedUs) >= SPEKTRUM_TELEMETRY_FRAME_DELAY_US) {
|
if (telemetryBufLen && telemetryFrameRequestedUs && cmpTimeUs(currentTimeUs, telemetryFrameRequestedUs) >= SPEKTRUM_TELEMETRY_FRAME_DELAY_US) {
|
||||||
telemetryFrameRequestedUs = 0;
|
telemetryFrameRequestedUs = 0;
|
||||||
|
|
||||||
|
@ -241,12 +242,12 @@ void spektrumBind(rxConfig_t *rxConfig)
|
||||||
// Take care half-duplex case
|
// Take care half-duplex case
|
||||||
switch (rxConfig->serialrx_provider) {
|
switch (rxConfig->serialrx_provider) {
|
||||||
case SERIALRX_SRXL:
|
case SERIALRX_SRXL:
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
if (featureIsEnabled(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig)) {
|
if (featureIsEnabled(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig)) {
|
||||||
bindPin = txPin;
|
bindPin = txPin;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif // USE_TELEMETRY && USE_TELEMETRY_SRXL
|
#endif // USE_TELEMETRY_SRXL
|
||||||
|
|
||||||
default:
|
default:
|
||||||
bindPin = rxConfig->halfDuplex ? txPin : rxPin;
|
bindPin = rxConfig->halfDuplex ? txPin : rxPin;
|
||||||
|
@ -307,7 +308,7 @@ void spektrumBind(rxConfig_t *rxConfig)
|
||||||
}
|
}
|
||||||
#endif // USE_SPEKTRUM_BIND
|
#endif // USE_SPEKTRUM_BIND
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
static bool spektrumProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
|
static bool spektrumProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
|
||||||
{
|
{
|
||||||
UNUSED(rxRuntimeConfig);
|
UNUSED(rxRuntimeConfig);
|
||||||
|
@ -348,7 +349,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
|
||||||
}
|
}
|
||||||
|
|
||||||
srxlEnabled = false;
|
srxlEnabled = false;
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
bool portShared = telemetryCheckRxPortShared(portConfig);
|
bool portShared = telemetryCheckRxPortShared(portConfig);
|
||||||
#else
|
#else
|
||||||
bool portShared = false;
|
bool portShared = false;
|
||||||
|
@ -356,7 +357,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
|
||||||
|
|
||||||
switch (rxConfig->serialrx_provider) {
|
switch (rxConfig->serialrx_provider) {
|
||||||
case SERIALRX_SRXL:
|
case SERIALRX_SRXL:
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
srxlEnabled = (featureIsEnabled(FEATURE_TELEMETRY) && !portShared);
|
srxlEnabled = (featureIsEnabled(FEATURE_TELEMETRY) && !portShared);
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
#endif
|
#endif
|
||||||
|
@ -382,7 +383,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
|
||||||
|
|
||||||
rxRuntimeConfig->rcReadRawFn = spektrumReadRawRC;
|
rxRuntimeConfig->rcReadRawFn = spektrumReadRawRC;
|
||||||
rxRuntimeConfig->rcFrameStatusFn = spektrumFrameStatus;
|
rxRuntimeConfig->rcFrameStatusFn = spektrumFrameStatus;
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
rxRuntimeConfig->rcProcessFrameFn = spektrumProcessFrame;
|
rxRuntimeConfig->rcProcessFrameFn = spektrumProcessFrame;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -394,7 +395,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
|
||||||
portShared || srxlEnabled ? MODE_RXTX : MODE_RX,
|
portShared || srxlEnabled ? MODE_RXTX : MODE_RX,
|
||||||
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | ((srxlEnabled || rxConfig->halfDuplex) ? SERIAL_BIDIR : 0)
|
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | ((srxlEnabled || rxConfig->halfDuplex) ? SERIAL_BIDIR : 0)
|
||||||
);
|
);
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
if (portShared) {
|
if (portShared) {
|
||||||
telemetrySharedPort = serialPort;
|
telemetrySharedPort = serialPort;
|
||||||
}
|
}
|
||||||
|
|
|
@ -72,15 +72,6 @@
|
||||||
#undef USE_SERIALRX_FPORT
|
#undef USE_SERIALRX_FPORT
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(USE_SERIALRX_CRSF)
|
|
||||||
#undef USE_TELEMETRY_CRSF
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if !defined(USE_SERIALRX_JETIEXBUS)
|
|
||||||
#undef USE_TELEMETRY_JETIEXBUS
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
#if !defined(USE_TELEMETRY)
|
#if !defined(USE_TELEMETRY)
|
||||||
#undef USE_CRSF_CMS_TELEMETRY
|
#undef USE_CRSF_CMS_TELEMETRY
|
||||||
#undef USE_TELEMETRY_CRSF
|
#undef USE_TELEMETRY_CRSF
|
||||||
|
@ -96,10 +87,20 @@
|
||||||
#undef USE_SERIALRX_FPORT
|
#undef USE_SERIALRX_FPORT
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_MSP_OVER_TELEMETRY)
|
#if !defined(USE_SERIALRX_CRSF)
|
||||||
#if !defined(USE_TELEMETRY_SMARTPORT) && !defined(USE_TELEMETRY_CRSF)
|
#undef USE_TELEMETRY_CRSF
|
||||||
#undef USE_MSP_OVER_TELEMETRY
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !defined(USE_TELEMETRY_CRSF)
|
||||||
|
#undef USE_CRSF_CMS_TELEMETRY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(USE_SERIALRX_JETIEXBUS)
|
||||||
|
#undef USE_TELEMETRY_JETIEXBUS
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(USE_TELEMETRY_IBUS)
|
||||||
|
#undef USE_TELEMETRY_IBUS_EXTENDED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// If USE_SERIALRX_SPEKTRUM was dropped by a target, drop all related options
|
// If USE_SERIALRX_SPEKTRUM was dropped by a target, drop all related options
|
||||||
|
@ -115,6 +116,10 @@
|
||||||
#undef USE_TELEMETRY_SRXL
|
#undef USE_TELEMETRY_SRXL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !defined(USE_TELEMETRY_SMARTPORT) && !defined(USE_TELEMETRY_CRSF)
|
||||||
|
#undef USE_MSP_OVER_TELEMETRY
|
||||||
|
#endif
|
||||||
|
|
||||||
/* If either VTX_CONTROL or VTX_COMMON is undefined then remove common code and device drivers */
|
/* If either VTX_CONTROL or VTX_COMMON is undefined then remove common code and device drivers */
|
||||||
#if !defined(USE_VTX_COMMON) || !defined(USE_VTX_CONTROL)
|
#if !defined(USE_VTX_COMMON) || !defined(USE_VTX_CONTROL)
|
||||||
#undef USE_VTX_COMMON
|
#undef USE_VTX_COMMON
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef USE_TELEMETRY
|
#ifdef USE_TELEMETRY_CRSF
|
||||||
|
|
||||||
#include "build/atomic.h"
|
#include "build/atomic.h"
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_FRSKY_HUB)
|
#if defined(USE_TELEMETRY_FRSKY_HUB)
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
|
@ -63,7 +63,7 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
|
||||||
#ifdef USE_TELEMETRY
|
#ifdef USE_TELEMETRY_HOTT
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
|
#if defined(USE_TELEMETRY_IBUS)
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
|
|
|
@ -32,16 +32,14 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <limits.h>
|
#include <limits.h>
|
||||||
// #include <string.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
//#include "common/utils.h"
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/ibus_shared.h"
|
#include "telemetry/ibus_shared.h"
|
||||||
|
|
||||||
static uint16_t calculateChecksum(const uint8_t *ibusPacket);
|
static uint16_t calculateChecksum(const uint8_t *ibusPacket);
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
|
#if defined(USE_TELEMETRY_IBUS)
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
|
@ -24,8 +24,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef USE_SERIAL_RX
|
#if defined(USE_TELEMETRY_JETIEXBUS)
|
||||||
#ifdef USE_TELEMETRY
|
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
@ -553,5 +552,4 @@ uint8_t sendJetiExBusTelemetry(uint8_t packetID, uint8_t item)
|
||||||
|
|
||||||
return item;
|
return item;
|
||||||
}
|
}
|
||||||
#endif // TELEMETRY
|
#endif
|
||||||
#endif // SERIAL_RX
|
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef USE_TELEMETRY
|
#ifdef USE_TELEMETRY_LTM
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
|
#if defined(USE_TELEMETRY_MAVLINK)
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
|
#if defined(USE_TELEMETRY_SMARTPORT)
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/color.h"
|
#include "common/color.h"
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
|
#if defined(USE_TELEMETRY_SRXL)
|
||||||
|
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
||||||
|
|
|
@ -102,6 +102,9 @@ void telemetryInit(void)
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_TELEMETRY_CRSF
|
#ifdef USE_TELEMETRY_CRSF
|
||||||
initCrsfTelemetry();
|
initCrsfTelemetry();
|
||||||
|
#if defined(USE_MSP_OVER_TELEMETRY)
|
||||||
|
initCrsfMspBuffer();
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_TELEMETRY_SRXL
|
#ifdef USE_TELEMETRY_SRXL
|
||||||
initSrxlTelemetry();
|
initSrxlTelemetry();
|
||||||
|
@ -111,7 +114,6 @@ void telemetryInit(void)
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_MSP_OVER_TELEMETRY)
|
#if defined(USE_MSP_OVER_TELEMETRY)
|
||||||
initSharedMsp();
|
initSharedMsp();
|
||||||
initCrsfMspBuffer();
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
telemetryCheckState();
|
telemetryCheckState();
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue