1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00

Refactor serial port configuration, stage 1.

Tested and working:
* multiple MSP ports at different baud rates.
* cli on any MSP port.
* GPS
* gps passthough on currently active cli port.

Example config used for testing:

feature SOFTSERIAL
feature GPS
feature RX_PPM
serial_port_1_functions = 1
serial_port_1_baudrate = 115200
serial_port_2_functions = 128
serial_port_2_baudrate = 115200
serial_port_3_functions = 1
serial_port_3_baudrate = 19200
serial_port_4_functions = 0
serial_port_4_baudrate = 0

Known broken:
* Telemetry and shared serial ports
* Telemetry when unarmed.

Probably broken:
* Blackbox on shared port.

Untested.
* Serial RX.
* Blackbox.
This commit is contained in:
Dominic Clifton 2015-02-12 01:28:53 +00:00
parent 519cc5f238
commit 5163bef0b2
31 changed files with 459 additions and 1247 deletions

View file

@ -42,9 +42,7 @@
#include "telemetry/smartport.h"
static bool isTelemetryConfigurationValid = false; // flag used to avoid repeated configuration checks
static bool telemetryEnabled = false;
static bool telemetryPortIsShared;
static telemetryConfig_t *telemetryConfig;
@ -53,72 +51,15 @@ 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 isTelemetryProviderSmartPort(void)
{
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_SMARTPORT;
}
bool isTelemetryPortShared(void)
{
return telemetryPortIsShared;
}
bool canUseTelemetryWithCurrentConfiguration(void)
{
if (!feature(FEATURE_TELEMETRY)) {
return false;
}
if (telemetryConfig->telemetry_provider != TELEMETRY_PROVIDER_SMARTPORT && !canOpenSerialPort(FUNCTION_TELEMETRY)) {
return false;
}
if (telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_SMARTPORT && !canOpenSerialPort(FUNCTION_SMARTPORT_TELEMETRY)) {
return false;
}
return true;
}
void telemetryInit()
{
if (isTelemetryProviderSmartPort()) {
telemetryPortIsShared = isSerialPortFunctionShared(FUNCTION_SMARTPORT_TELEMETRY, FUNCTION_MSP);
} else {
telemetryPortIsShared = isSerialPortFunctionShared(FUNCTION_TELEMETRY, FUNCTION_MSP);
}
isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration();
initFrSkyTelemetry(telemetryConfig);
if (isTelemetryProviderFrSky()) {
initFrSkyTelemetry(telemetryConfig);
}
initHoTTTelemetry(telemetryConfig);
if (isTelemetryProviderHoTT()) {
initHoTTTelemetry(telemetryConfig);
}
initMSPTelemetry(telemetryConfig);
if (isTelemetryProviderMSP()) {
initMSPTelemetry(telemetryConfig);
}
if (isTelemetryProviderSmartPort()) {
initSmartPortTelemetry(telemetryConfig);
}
initSmartPortTelemetry(telemetryConfig);
checkTelemetryState();
}
@ -127,18 +68,10 @@ bool determineNewTelemetryEnabledState(void)
{
bool enabled = true;
if (telemetryPortIsShared) {
if (telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_SMARTPORT) {
if (isSmartPortTimedOut()) {
enabled = false;
}
} else {
if (telemetryConfig->telemetry_switch)
enabled = IS_RC_MODE_ACTIVE(BOXTELEMETRY);
else
enabled = ARMING_FLAG(ARMED);
}
}
if (telemetryConfig->telemetry_switch)
enabled = IS_RC_MODE_ACTIVE(BOXTELEMETRY);
else
enabled = ARMING_FLAG(ARMED);
return enabled;
}
@ -148,72 +81,24 @@ bool shouldChangeTelemetryStateNow(bool newState)
return newState != telemetryEnabled;
}
uint32_t getTelemetryProviderBaudRate(void)
{
if (isTelemetryProviderFrSky()) {
return getFrSkyTelemetryProviderBaudRate();
}
if (isTelemetryProviderHoTT()) {
return getHoTTTelemetryProviderBaudRate();
}
if (isTelemetryProviderMSP()) {
return getMSPTelemetryProviderBaudRate();
}
if (isTelemetryProviderSmartPort()) {
return getSmartPortTelemetryProviderBaudRate();
}
return 0;
}
static void configureTelemetryPort(void)
{
if (isTelemetryProviderFrSky()) {
configureFrSkyTelemetryPort();
}
if (isTelemetryProviderHoTT()) {
configureHoTTTelemetryPort();
}
if (isTelemetryProviderMSP()) {
configureMSPTelemetryPort();
}
if (isTelemetryProviderSmartPort()) {
configureSmartPortTelemetryPort();
}
configureFrSkyTelemetryPort();
configureHoTTTelemetryPort();
configureMSPTelemetryPort();
configureSmartPortTelemetryPort();
}
void freeTelemetryPort(void)
{
if (isTelemetryProviderFrSky()) {
freeFrSkyTelemetryPort();
}
if (isTelemetryProviderHoTT()) {
freeHoTTTelemetryPort();
}
if (isTelemetryProviderMSP()) {
freeMSPTelemetryPort();
}
if (isTelemetryProviderSmartPort()) {
freeSmartPortTelemetryPort();
}
freeFrSkyTelemetryPort();
freeHoTTTelemetryPort();
freeMSPTelemetryPort();
freeSmartPortTelemetryPort();
}
void checkTelemetryState(void)
{
if (!isTelemetryConfigurationValid) {
return;
}
bool newEnabledState = determineNewTelemetryEnabledState();
if (!shouldChangeTelemetryStateNow(newEnabledState)) {
@ -230,41 +115,17 @@ void checkTelemetryState(void)
void handleTelemetry(void)
{
if (!isTelemetryConfigurationValid || !determineNewTelemetryEnabledState())
if (!determineNewTelemetryEnabledState())
return;
if (!telemetryEnabled) {
return;
}
if (isTelemetryProviderFrSky()) {
handleFrSkyTelemetry();
}
if (isTelemetryProviderHoTT()) {
handleHoTTTelemetry();
}
if (isTelemetryProviderMSP()) {
handleMSPTelemetry();
}
if (isTelemetryProviderSmartPort()) {
handleSmartPortTelemetry();
}
}
bool telemetryAllowsOtherSerial(int serialPortFunction)
{
if (!feature(FEATURE_TELEMETRY)) {
return true;
}
if (isTelemetryProviderSmartPort() && isSerialPortFunctionShared(FUNCTION_SMARTPORT_TELEMETRY, (serialPortFunction_e)serialPortFunction)) {
return canSmartPortAllowOtherSerial();
}
return true;
handleFrSkyTelemetry();
handleHoTTTelemetry();
handleMSPTelemetry();
handleSmartPortTelemetry();
}
#endif