mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Initial implementation of SPEK SRXL telemetry protocol
This commit is contained in:
parent
1475138e75
commit
c49d36a346
7 changed files with 365 additions and 13 deletions
|
@ -47,6 +47,7 @@
|
|||
#include "telemetry/jetiexbus.h"
|
||||
#include "telemetry/mavlink.h"
|
||||
#include "telemetry/crsf.h"
|
||||
#include "telemetry/srxl.h"
|
||||
|
||||
static telemetryConfig_t *telemetryConfig;
|
||||
|
||||
|
@ -78,6 +79,9 @@ void telemetryInit(void)
|
|||
#ifdef TELEMETRY_CRSF
|
||||
initCrsfTelemetry();
|
||||
#endif
|
||||
#ifdef TELEMETRY_SRXL
|
||||
initSrxlTelemetry();
|
||||
#endif
|
||||
|
||||
telemetryCheckState();
|
||||
}
|
||||
|
@ -126,6 +130,9 @@ void telemetryCheckState(void)
|
|||
#ifdef TELEMETRY_CRSF
|
||||
checkCrsfTelemetryState();
|
||||
#endif
|
||||
#ifdef TELEMETRY_SRXL
|
||||
checkSrxlTelemetryState();
|
||||
#endif
|
||||
}
|
||||
|
||||
void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||
|
@ -156,6 +163,9 @@ void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadb
|
|||
#ifdef TELEMETRY_CRSF
|
||||
handleCrsfTelemetry(currentTime);
|
||||
#endif
|
||||
#ifdef TELEMETRY_SRXL
|
||||
handleSrxlTelemetry(currentTime);
|
||||
#endif
|
||||
}
|
||||
|
||||
#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_SMARTPORT)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue