mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Cleanup project structure. Update unit test Makefile to place object
files in obj/test
This commit is contained in:
parent
fb9e3a2358
commit
d19a5e7046
330 changed files with 657 additions and 638 deletions
171
src/main/telemetry/telemetry.c
Normal file
171
src/main/telemetry/telemetry.c
Normal file
|
@ -0,0 +1,171 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_softserial.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/frsky.h"
|
||||
#include "telemetry/hott.h"
|
||||
#include "telemetry/msp.h"
|
||||
|
||||
|
||||
static bool isTelemetryConfigurationValid = false; // flag used to avoid repeated configuration checks
|
||||
static bool telemetryEnabled = false;
|
||||
static bool telemetryPortIsShared;
|
||||
|
||||
static telemetryConfig_t *telemetryConfig;
|
||||
|
||||
void useTelemetryConfig(telemetryConfig_t *telemetryConfigToUse)
|
||||
{
|
||||
telemetryConfig = telemetryConfigToUse;
|
||||
}
|
||||
|
||||
bool isTelemetryProviderFrSky(void)
|
||||
{
|
||||
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_FRSKY;
|
||||
}
|
||||
|
||||
bool isTelemetryProviderHoTT(void)
|
||||
{
|
||||
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_HOTT;
|
||||
}
|
||||
|
||||
bool isTelemetryProviderMSP(void)
|
||||
{
|
||||
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_MSP;
|
||||
}
|
||||
|
||||
bool canUseTelemetryWithCurrentConfiguration(void)
|
||||
{
|
||||
if (!feature(FEATURE_TELEMETRY)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!canOpenSerialPort(FUNCTION_TELEMETRY)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void initTelemetry()
|
||||
{
|
||||
telemetryPortIsShared = isSerialPortFunctionShared(FUNCTION_TELEMETRY, FUNCTION_MSP);
|
||||
isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration();
|
||||
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
initFrSkyTelemetry(telemetryConfig);
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
initHoTTTelemetry(telemetryConfig);
|
||||
}
|
||||
|
||||
if (isTelemetryProviderMSP()) {
|
||||
initMSPTelemetry(telemetryConfig);
|
||||
}
|
||||
|
||||
checkTelemetryState();
|
||||
}
|
||||
|
||||
bool determineNewTelemetryEnabledState(void)
|
||||
{
|
||||
bool enabled = true;
|
||||
|
||||
if (telemetryPortIsShared) {
|
||||
if (telemetryConfig->telemetry_switch)
|
||||
enabled = rcOptions[BOXTELEMETRY];
|
||||
else
|
||||
enabled = f.ARMED;
|
||||
}
|
||||
|
||||
return enabled;
|
||||
}
|
||||
|
||||
bool shouldChangeTelemetryStateNow(bool newState)
|
||||
{
|
||||
return newState != telemetryEnabled;
|
||||
}
|
||||
|
||||
uint32_t getTelemetryProviderBaudRate(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
return getFrSkyTelemetryProviderBaudRate();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
return getHoTTTelemetryProviderBaudRate();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void configureTelemetryPort(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
configureFrSkyTelemetryPort();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
configureHoTTTelemetryPort();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void freeTelemetryPort(void)
|
||||
{
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
freeFrSkyTelemetryPort();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
freeHoTTTelemetryPort();
|
||||
}
|
||||
}
|
||||
|
||||
void checkTelemetryState(void)
|
||||
{
|
||||
if (!isTelemetryConfigurationValid) {
|
||||
return;
|
||||
}
|
||||
|
||||
bool newEnabledState = determineNewTelemetryEnabledState();
|
||||
|
||||
if (!shouldChangeTelemetryStateNow(newEnabledState)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (newEnabledState)
|
||||
configureTelemetryPort();
|
||||
else
|
||||
freeTelemetryPort();
|
||||
|
||||
telemetryEnabled = newEnabledState;
|
||||
}
|
||||
|
||||
void handleTelemetry(void)
|
||||
{
|
||||
if (!isTelemetryConfigurationValid || !determineNewTelemetryEnabledState())
|
||||
return;
|
||||
|
||||
if (isTelemetryProviderFrSky()) {
|
||||
handleFrSkyTelemetry();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderHoTT()) {
|
||||
handleHoTTTelemetry();
|
||||
}
|
||||
|
||||
if (isTelemetryProviderMSP()) {
|
||||
handleMSPTelemetry();
|
||||
}
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue