mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
Merge pull request #1501 from martinbudden/bf_rx_telem_split
Added fine-grained TELEMETRY build #defines as per iNav
This commit is contained in:
commit
945a0d275c
2 changed files with 46 additions and 7 deletions
|
@ -51,6 +51,11 @@
|
||||||
#define BLACKBOX
|
#define BLACKBOX
|
||||||
#define GPS
|
#define GPS
|
||||||
#define TELEMETRY
|
#define TELEMETRY
|
||||||
|
#define TELEMETRY_FRSKY
|
||||||
|
#define TELEMETRY_HOTT
|
||||||
|
#define TELEMETRY_IBUS
|
||||||
|
#define TELEMETRY_LTM
|
||||||
|
#define TELEMETRY_SMARTPORT
|
||||||
#define USE_SERVOS
|
#define USE_SERVOS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -58,6 +63,7 @@
|
||||||
#define CMS
|
#define CMS
|
||||||
#define USE_DASHBOARD
|
#define USE_DASHBOARD
|
||||||
#define USE_MSP_DISPLAYPORT
|
#define USE_MSP_DISPLAYPORT
|
||||||
|
#define TELEMETRY_JETIEXBUS
|
||||||
#define TELEMETRY_MAVLINK
|
#define TELEMETRY_MAVLINK
|
||||||
#else
|
#else
|
||||||
#define SKIP_CLI_COMMAND_HELP
|
#define SKIP_CLI_COMMAND_HELP
|
||||||
|
|
|
@ -23,6 +23,8 @@
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
|
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_softserial.h"
|
#include "drivers/serial_softserial.h"
|
||||||
|
@ -42,7 +44,6 @@
|
||||||
#include "telemetry/ltm.h"
|
#include "telemetry/ltm.h"
|
||||||
#include "telemetry/jetiexbus.h"
|
#include "telemetry/jetiexbus.h"
|
||||||
#include "telemetry/mavlink.h"
|
#include "telemetry/mavlink.h"
|
||||||
#include "rx/jetiexbus.h"
|
|
||||||
|
|
||||||
static telemetryConfig_t *telemetryConfig;
|
static telemetryConfig_t *telemetryConfig;
|
||||||
|
|
||||||
|
@ -53,13 +54,22 @@ void telemetryUseConfig(telemetryConfig_t *telemetryConfigToUse)
|
||||||
|
|
||||||
void telemetryInit(void)
|
void telemetryInit(void)
|
||||||
{
|
{
|
||||||
|
#ifdef TELEMETRY_FRSKY
|
||||||
initFrSkyTelemetry(telemetryConfig);
|
initFrSkyTelemetry(telemetryConfig);
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_HOTT
|
||||||
initHoTTTelemetry(telemetryConfig);
|
initHoTTTelemetry(telemetryConfig);
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_SMARTPORT
|
||||||
initSmartPortTelemetry(telemetryConfig);
|
initSmartPortTelemetry(telemetryConfig);
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_LTM
|
||||||
initLtmTelemetry(telemetryConfig);
|
initLtmTelemetry(telemetryConfig);
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_JETIEXBUS
|
||||||
initJetiExBusTelemetry(telemetryConfig);
|
initJetiExBusTelemetry(telemetryConfig);
|
||||||
|
#endif
|
||||||
#if defined(TELEMETRY_MAVLINK)
|
#ifdef TELEMETRY_MAVLINK
|
||||||
initMAVLinkTelemetry();
|
initMAVLinkTelemetry();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -89,26 +99,49 @@ serialPort_t *telemetrySharedPort = NULL;
|
||||||
|
|
||||||
void telemetryCheckState(void)
|
void telemetryCheckState(void)
|
||||||
{
|
{
|
||||||
|
#ifdef TELEMETRY_FRSKY
|
||||||
checkFrSkyTelemetryState();
|
checkFrSkyTelemetryState();
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_HOTT
|
||||||
checkHoTTTelemetryState();
|
checkHoTTTelemetryState();
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_SMARTPORT
|
||||||
checkSmartPortTelemetryState();
|
checkSmartPortTelemetryState();
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_LTM
|
||||||
checkLtmTelemetryState();
|
checkLtmTelemetryState();
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_JETIEXBUS
|
||||||
checkJetiExBusTelemetryState();
|
checkJetiExBusTelemetryState();
|
||||||
|
#endif
|
||||||
#if defined(TELEMETRY_MAVLINK)
|
#ifdef TELEMETRY_MAVLINK
|
||||||
checkMAVLinkTelemetryState();
|
checkMAVLinkTelemetryState();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||||
{
|
{
|
||||||
|
#ifdef TELEMETRY_FRSKY
|
||||||
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
||||||
|
#else
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(deadband3d_throttle);
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_HOTT
|
||||||
handleHoTTTelemetry(currentTime);
|
handleHoTTTelemetry(currentTime);
|
||||||
|
#else
|
||||||
|
UNUSED(currentTime);
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_SMARTPORT
|
||||||
handleSmartPortTelemetry();
|
handleSmartPortTelemetry();
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_LTM
|
||||||
handleLtmTelemetry();
|
handleLtmTelemetry();
|
||||||
|
#endif
|
||||||
|
#ifdef TELEMETRY_JETIEXBUS
|
||||||
handleJetiExBusTelemetry();
|
handleJetiExBusTelemetry();
|
||||||
|
#endif
|
||||||
#if defined(TELEMETRY_MAVLINK)
|
#ifdef TELEMETRY_MAVLINK
|
||||||
handleMAVLinkTelemetry();
|
handleMAVLinkTelemetry();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue