mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
Move common telemetry code to telemetry_common.c/.h
This commit is contained in:
parent
d73094396d
commit
1cbe166c49
9 changed files with 100 additions and 55 deletions
51
src/telemetry_common.c
Normal file
51
src/telemetry_common.c
Normal file
|
@ -0,0 +1,51 @@
|
|||
#include "board.h"
|
||||
#include "mw.h"
|
||||
|
||||
#include "telemetry_frsky.h"
|
||||
|
||||
void initTelemetry(void)
|
||||
{
|
||||
// Sanity check for softserial vs. telemetry port
|
||||
if (!feature(FEATURE_SOFTSERIAL))
|
||||
mcfg.telemetry_softserial = TELEMETRY_UART;
|
||||
|
||||
if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_1)
|
||||
core.telemport = &(softSerialPorts[0].port);
|
||||
else if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_2)
|
||||
core.telemport = &(softSerialPorts[1].port);
|
||||
else
|
||||
core.telemport = core.mainport;
|
||||
}
|
||||
|
||||
void updateTelemetryState(void) {
|
||||
updateFrSkyTelemetryState();
|
||||
}
|
||||
|
||||
bool isTelemetryEnabled(void)
|
||||
{
|
||||
bool telemetryCurrentlyEnabled = true;
|
||||
|
||||
if (mcfg.telemetry_softserial == TELEMETRY_UART) {
|
||||
if (!mcfg.telemetry_switch)
|
||||
telemetryCurrentlyEnabled = f.ARMED;
|
||||
else
|
||||
telemetryCurrentlyEnabled = rcOptions[BOXTELEMETRY];
|
||||
}
|
||||
|
||||
return telemetryCurrentlyEnabled;
|
||||
}
|
||||
|
||||
bool isFrSkyTelemetryEnabled(void)
|
||||
{
|
||||
return mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY;
|
||||
}
|
||||
|
||||
void sendTelemetry(void)
|
||||
{
|
||||
if (!isTelemetryEnabled())
|
||||
return;
|
||||
|
||||
if (isFrSkyTelemetryEnabled()) {
|
||||
sendFrSkyTelemetry();
|
||||
}
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue