1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 03:50:02 +03:00

Moved configuration validation into 'config.c'.

This commit is contained in:
mikeller 2019-11-24 18:54:11 +13:00
parent b137bbe80c
commit 99f77fa88d
41 changed files with 92 additions and 76 deletions

View file

@ -27,12 +27,8 @@
typedef enum BlackboxDevice { typedef enum BlackboxDevice {
BLACKBOX_DEVICE_NONE = 0, BLACKBOX_DEVICE_NONE = 0,
#ifdef USE_FLASHFS
BLACKBOX_DEVICE_FLASH = 1, BLACKBOX_DEVICE_FLASH = 1,
#endif
#ifdef USE_SDCARD
BLACKBOX_DEVICE_SDCARD = 2, BLACKBOX_DEVICE_SDCARD = 2,
#endif
BLACKBOX_DEVICE_SERIAL = 3 BLACKBOX_DEVICE_SERIAL = 3
} BlackboxDevice_e; } BlackboxDevice_e;

View file

@ -261,7 +261,7 @@ bool blackboxDeviceOpen(void)
switch (blackboxConfig()->device) { switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL: case BLACKBOX_DEVICE_SERIAL:
{ {
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX); const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX);
baudRate_e baudRateIndex; baudRate_e baudRateIndex;
portOptions_e portOptions = SERIAL_PARITY_NO | SERIAL_NOT_INVERTED; portOptions_e portOptions = SERIAL_PARITY_NO | SERIAL_NOT_INVERTED;

View file

@ -1238,14 +1238,14 @@ static void cliSerial(char *cmdline)
serialPortConfig_t portConfig; serialPortConfig_t portConfig;
memset(&portConfig, 0 , sizeof(portConfig)); memset(&portConfig, 0 , sizeof(portConfig));
serialPortConfig_t *currentConfig;
uint8_t validArgumentCount = 0; uint8_t validArgumentCount = 0;
const char *ptr = cmdline; const char *ptr = cmdline;
int val = atoi(ptr++); int val = atoi(ptr++);
currentConfig = serialFindPortConfiguration(val); serialPortConfig_t *currentConfig = serialFindPortConfigurationMutable(val);
if (currentConfig) { if (currentConfig) {
portConfig.identifier = val; portConfig.identifier = val;
validArgumentCount++; validArgumentCount++;

View file

@ -62,6 +62,7 @@
#include "osd/osd.h" #include "osd/osd.h"
#include "pg/adc.h"
#include "pg/beeper.h" #include "pg/beeper.h"
#include "pg/beeper_dev.h" #include "pg/beeper_dev.h"
#include "pg/gyrodev.h" #include "pg/gyrodev.h"
@ -69,9 +70,12 @@
#include "pg/pg.h" #include "pg/pg.h"
#include "pg/pg_ids.h" #include "pg/pg_ids.h"
#include "pg/rx.h" #include "pg/rx.h"
#include "pg/rx_spi.h"
#include "pg/sdcard.h"
#include "pg/vtx_table.h" #include "pg/vtx_table.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/rx_spi.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
@ -205,7 +209,7 @@ static void validateAndFixConfig(void)
} }
#if defined(USE_GPS) #if defined(USE_GPS)
serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS); const serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS);
if (gpsConfig()->provider == GPS_MSP && gpsSerial) { if (gpsConfig()->provider == GPS_MSP && gpsSerial) {
serialRemovePort(gpsSerial->identifier); serialRemovePort(gpsSerial->identifier);
} }
@ -392,6 +396,18 @@ static void validateAndFixConfig(void)
} }
#endif #endif
#ifdef USE_ADC
adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC);
adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC);
// The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2
adcConfigMutable()->rssi.enabled = featureIsEnabled(FEATURE_RSSI_ADC);
#ifdef USE_RX_SPI
adcConfigMutable()->rssi.enabled |= (featureIsEnabled(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D);
#endif
#endif // USE_ADC
// clear features that are not supported. // clear features that are not supported.
// I have kept them all here in one place, some could be moved to sections of code above. // I have kept them all here in one place, some could be moved to sections of code above.
@ -647,16 +663,19 @@ void validateAndFixGyroConfig(void)
#ifdef USE_BLACKBOX #ifdef USE_BLACKBOX
#ifndef USE_FLASHFS #ifndef USE_FLASHFS
if (blackboxConfig()->device == 1) { // BLACKBOX_DEVICE_FLASH (but not defined) if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) {
blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE; blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
} }
#endif // USE_FLASHFS #endif // USE_FLASHFS
#ifndef USE_SDCARD if (blackboxConfig()->device == BLACKBOX_DEVICE_SDCARD) {
if (blackboxConfig()->device == 2) { // BLACKBOX_DEVICE_SDCARD (but not defined) #if defined(USE_SDCARD)
blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE; if (!sdcardConfig()->mode)
#endif
{
blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
}
} }
#endif // USE_SDCARD
#endif // USE_BLACKBOX #endif // USE_BLACKBOX
if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) { if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {

View file

@ -241,7 +241,7 @@ int32_t lidarTFGetDistance(rangefinderDev_t *dev)
static bool lidarTFDetect(rangefinderDev_t *dev, uint8_t devtype) static bool lidarTFDetect(rangefinderDev_t *dev, uint8_t devtype)
{ {
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LIDAR_TF); const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LIDAR_TF);
if (!portConfig) { if (!portConfig) {
return false; return false;

View file

@ -87,6 +87,6 @@ void copyControlRateProfile(const uint8_t dstControlRateProfileIndex, const uint
if ((dstControlRateProfileIndex < CONTROL_RATE_PROFILE_COUNT && srcControlRateProfileIndex < CONTROL_RATE_PROFILE_COUNT) if ((dstControlRateProfileIndex < CONTROL_RATE_PROFILE_COUNT && srcControlRateProfileIndex < CONTROL_RATE_PROFILE_COUNT)
&& dstControlRateProfileIndex != srcControlRateProfileIndex && dstControlRateProfileIndex != srcControlRateProfileIndex
) { ) {
memcpy(controlRateProfilesMutable(dstControlRateProfileIndex), controlRateProfilesMutable(srcControlRateProfileIndex), sizeof(controlRateConfig_t)); memcpy(controlRateProfilesMutable(dstControlRateProfileIndex), controlRateProfiles(srcControlRateProfileIndex), sizeof(controlRateConfig_t));
} }
} }

View file

@ -144,14 +144,12 @@
#include "pg/pin_pull_up_down.h" #include "pg/pin_pull_up_down.h"
#include "pg/pg.h" #include "pg/pg.h"
#include "pg/rx.h" #include "pg/rx.h"
#include "pg/rx_spi.h"
#include "pg/rx_pwm.h" #include "pg/rx_pwm.h"
#include "pg/sdcard.h" #include "pg/sdcard.h"
#include "pg/vcd.h" #include "pg/vcd.h"
#include "pg/vtx_io.h" #include "pg/vtx_io.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/rx_spi.h"
#include "rx/spektrum.h" #include "rx/spektrum.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
@ -646,14 +644,6 @@ void init(void)
#endif #endif
#ifdef USE_ADC #ifdef USE_ADC
adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC);
adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC);
// The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2
adcConfigMutable()->rssi.enabled = featureIsEnabled(FEATURE_RSSI_ADC);
#ifdef USE_RX_SPI
adcConfigMutable()->rssi.enabled |= (featureIsEnabled(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D);
#endif
adcInit(adcConfig()); adcInit(adcConfig());
#endif #endif
@ -864,8 +854,6 @@ void init(void)
initFlags |= SD_INIT_ATTEMPTED; initFlags |= SD_INIT_ATTEMPTED;
sdCardAndFSInit(); sdCardAndFSInit();
} }
} else {
blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
} }
} }
#endif #endif

View file

@ -249,7 +249,7 @@ void beeper(beeperMode_e mode)
{ {
if ( if (
mode == BEEPER_SILENCE || ( mode == BEEPER_SILENCE || (
(beeperConfigMutable()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_USB)) (beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_USB))
&& getBatteryState() == BATTERY_NOT_PRESENT && getBatteryState() == BATTERY_NOT_PRESENT
) )
) { ) {
@ -361,7 +361,7 @@ void beeperWarningBeeps(uint8_t beepCount)
#ifdef USE_GPS #ifdef USE_GPS
static void beeperGpsStatus(void) static void beeperGpsStatus(void)
{ {
if (!(beeperConfigMutable()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_GPS_STATUS))) { if (!(beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_GPS_STATUS))) {
// if GPS fix then beep out number of satellites // if GPS fix then beep out number of satellites
if (STATE(GPS_FIX) && gpsSol.numSat >= 5) { if (STATE(GPS_FIX) && gpsSol.numSat >= 5) {
uint8_t i = 0; uint8_t i = 0;
@ -417,7 +417,7 @@ void beeperUpdate(timeUs_t currentTimeUs)
#endif #endif
if (currentBeeperEntry->sequence[beeperPos] != 0) { if (currentBeeperEntry->sequence[beeperPos] != 0) {
if (!(beeperConfigMutable()->beeper_off_flags & BEEPER_GET_FLAG(currentBeeperEntry->mode))) { if (!(beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(currentBeeperEntry->mode))) {
BEEP_ON; BEEP_ON;
beeperIsOn = true; beeperIsOn = true;
} }

View file

@ -279,7 +279,7 @@ void gpsInit(void)
return; return;
} }
serialPortConfig_t *gpsPortConfig = findSerialPortConfig(FUNCTION_GPS); const serialPortConfig_t *gpsPortConfig = findSerialPortConfig(FUNCTION_GPS);
if (!gpsPortConfig) { if (!gpsPortConfig) {
return; return;
} }

View file

@ -435,14 +435,14 @@ static quadrant_e getLedQuadrant(const int ledIndex)
return quad; return quad;
} }
static hsvColor_t* getDirectionalModeColor(const int ledIndex, const modeColorIndexes_t *modeColors) static const hsvColor_t* getDirectionalModeColor(const int ledIndex, const modeColorIndexes_t *modeColors)
{ {
const ledConfig_t *ledConfig = &ledStripStatusModeConfig()->ledConfigs[ledIndex]; const ledConfig_t *ledConfig = &ledStripStatusModeConfig()->ledConfigs[ledIndex];
const int ledDirection = ledGetDirection(ledConfig); const int ledDirection = ledGetDirection(ledConfig);
for (unsigned i = 0; i < LED_DIRECTION_COUNT; i++) { for (unsigned i = 0; i < LED_DIRECTION_COUNT; i++) {
if (ledDirection & (1 << i)) { if (ledDirection & (1 << i)) {
return &ledStripStatusModeConfigMutable()->colors[modeColors->color[i]]; return &ledStripStatusModeConfig()->colors[modeColors->color[i]];
} }
} }

View file

@ -272,7 +272,7 @@ void runcamDeviceInit(runcamDevice_t *device)
{ {
device->isReady = false; device->isReady = false;
serialPortFunction_e portID = FUNCTION_RCDEVICE; serialPortFunction_e portID = FUNCTION_RCDEVICE;
serialPortConfig_t *portConfig = findSerialPortConfig(portID); const serialPortConfig_t *portConfig = findSerialPortConfig(portID);
if (portConfig != NULL) { if (portConfig != NULL) {
device->serialPort = openSerialPort(portConfig->identifier, portID, NULL, NULL, 115200, MODE_RXTX, SERIAL_NOT_INVERTED); device->serialPort = openSerialPort(portConfig->identifier, portID, NULL, NULL, 115200, MODE_RXTX, SERIAL_NOT_INVERTED);
device->info.protocolVersion = rcdeviceConfig()->protocolVersion; device->info.protocolVersion = rcdeviceConfig()->protocolVersion;

View file

@ -108,6 +108,17 @@ const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 2500
#define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0])) #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier)
{
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index];
if (candidate->identifier == identifier) {
return candidate;
}
}
return NULL;
}
PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 0); PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 0);
void pgResetFn_serialConfig(serialConfig_t *serialConfig) void pgResetFn_serialConfig(serialConfig_t *serialConfig)
@ -125,14 +136,14 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig)
serialConfig->portConfigs[0].functionMask = FUNCTION_MSP; serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
#ifdef SERIALRX_UART #ifdef SERIALRX_UART
serialPortConfig_t *serialRxUartConfig = serialFindPortConfiguration(SERIALRX_UART); serialPortConfig_t *serialRxUartConfig = serialFindPortConfigurationMutable(SERIALRX_UART);
if (serialRxUartConfig) { if (serialRxUartConfig) {
serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL; serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL;
} }
#endif #endif
#ifdef SBUS_TELEMETRY_UART #ifdef SBUS_TELEMETRY_UART
serialPortConfig_t *serialTlemetryUartConfig = serialFindPortConfiguration(SBUS_TELEMETRY_UART); serialPortConfig_t *serialTlemetryUartConfig = serialFindPortConfigurationMutable(SBUS_TELEMETRY_UART);
if (serialTlemetryUartConfig) { if (serialTlemetryUartConfig) {
serialTlemetryUartConfig->functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialTlemetryUartConfig->functionMask = FUNCTION_TELEMETRY_SMARTPORT;
} }
@ -140,7 +151,7 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig)
#if defined(USE_VCP) && defined(USE_MSP_UART) #if defined(USE_VCP) && defined(USE_MSP_UART)
if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) { if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) {
serialPortConfig_t * uart1Config = serialFindPortConfiguration(SERIAL_PORT_USART1); serialPortConfig_t * uart1Config = serialFindPortConfigurationMutable(SERIAL_PORT_USART1);
if (uart1Config) { if (uart1Config) {
uart1Config->functionMask = FUNCTION_MSP; uart1Config->functionMask = FUNCTION_MSP;
} }
@ -202,17 +213,17 @@ typedef struct findSerialPortConfigState_s {
static findSerialPortConfigState_t findSerialPortConfigState; static findSerialPortConfigState_t findSerialPortConfigState;
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
{ {
memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState)); memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState));
return findNextSerialPortConfig(function); return findNextSerialPortConfig(function);
} }
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function) const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
{ {
while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) { while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) {
serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[findSerialPortConfigState.lastIndex++]; const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSerialPortConfigState.lastIndex++];
if (candidate->functionMask & function) { if (candidate->functionMask & function) {
return candidate; return candidate;
@ -306,10 +317,10 @@ bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
return true; return true;
} }
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier) const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
{ {
for (int index = 0; index < SERIAL_PORT_COUNT; index++) { for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index]; const serialPortConfig_t *candidate = &serialConfig()->portConfigs[index];
if (candidate->identifier == identifier) { if (candidate->identifier == identifier) {
return candidate; return candidate;
} }
@ -319,7 +330,7 @@ serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifie
bool doesConfigurationUsePort(serialPortIdentifier_e identifier) bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
{ {
serialPortConfig_t *candidate = serialFindPortConfiguration(identifier); const serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
return candidate != NULL && candidate->functionMask; return candidate != NULL && candidate->functionMask;
} }

View file

@ -139,10 +139,11 @@ void serialRemovePort(serialPortIdentifier_e identifier);
uint8_t serialGetAvailablePortCount(void); uint8_t serialGetAvailablePortCount(void);
bool serialIsPortAvailable(serialPortIdentifier_e identifier); bool serialIsPortAvailable(serialPortIdentifier_e identifier);
bool isSerialConfigValid(const serialConfig_t *serialConfig); bool isSerialConfigValid(const serialConfig_t *serialConfig);
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier); const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier);
serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier);
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier); bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function); const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function);
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function); const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function);
portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function); portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function);
bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction); bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction);

View file

@ -697,7 +697,7 @@ bool vtxSmartAudioInit(void)
dprintf(("smartAudioInit: OK\r\n")); dprintf(("smartAudioInit: OK\r\n"));
#endif #endif
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_SMARTAUDIO); const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_SMARTAUDIO);
if (portConfig) { if (portConfig) {
portOptions_e portOptions = SERIAL_STOPBITS_2 | SERIAL_BIDIR_NOPULL; portOptions_e portOptions = SERIAL_STOPBITS_2 | SERIAL_BIDIR_NOPULL;
#if defined(USE_VTX_COMMON) #if defined(USE_VTX_COMMON)

View file

@ -620,7 +620,7 @@ static const vtxVTable_t trampVTable = {
bool vtxTrampInit(void) bool vtxTrampInit(void)
{ {
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_TRAMP); const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_TRAMP);
if (portConfig) { if (portConfig) {
portOptions_e portOptions = 0; portOptions_e portOptions = 0;

View file

@ -2961,7 +2961,8 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, uint8_t cmdMSP,
while (remainingPortsInPacket--) { while (remainingPortsInPacket--) {
uint8_t identifier = sbufReadU8(src); uint8_t identifier = sbufReadU8(src);
serialPortConfig_t *portConfig = serialFindPortConfiguration(identifier); serialPortConfig_t *portConfig = serialFindPortConfigurationMutable(identifier);
if (!portConfig) { if (!portConfig) {
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
} }

View file

@ -54,7 +54,7 @@ static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, bo
void mspSerialAllocatePorts(void) void mspSerialAllocatePorts(void)
{ {
uint8_t portIndex = 0; uint8_t portIndex = 0;
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP); const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
while (portConfig && portIndex < MAX_MSP_PORT_COUNT) { while (portConfig && portIndex < MAX_MSP_PORT_COUNT) {
mspPort_t *mspPort = &mspPorts[portIndex]; mspPort_t *mspPort = &mspPorts[portIndex];

View file

@ -209,7 +209,7 @@ static void escSensorDataReceive(uint16_t c, void *data)
bool escSensorInit(void) bool escSensorInit(void)
{ {
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_ESC_SENSOR); const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_ESC_SENSOR);
if (!portConfig) { if (!portConfig) {
return false; return false;
} }

View file

@ -55,7 +55,7 @@ void targetPreInit(void)
IOConfigGPIO(inverter, IOCFG_OUT_PP); IOConfigGPIO(inverter, IOCFG_OUT_PP);
bool high = false; bool high = false;
serialPortConfig_t *portConfig = serialFindPortConfiguration(SERIAL_PORT_USART1); serialPortConfig_t *portConfig = serialFindPortConfigurationMutable(SERIAL_PORT_USART1);
if (portConfig) { if (portConfig) {
bool smartportEnabled = (portConfig->functionMask & FUNCTION_TELEMETRY_SMARTPORT); bool smartportEnabled = (portConfig->functionMask & FUNCTION_TELEMETRY_SMARTPORT);
if (smartportEnabled && (!telemetryConfig()->telemetry_inverted) && (featureIsEnabled(FEATURE_TELEMETRY))) { if (smartportEnabled && (!telemetryConfig()->telemetry_inverted) && (featureIsEnabled(FEATURE_TELEMETRY))) {

View file

@ -37,10 +37,10 @@ void targetConfiguration(void)
pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP; pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP;
pinioBoxConfigMutable()->permanentId[0] = BOXARM; pinioBoxConfigMutable()->permanentId[0] = BOXARM;
serialPortConfig_t *bluetoothMspUART = serialFindPortConfiguration(BLUETOOTH_MSP_UART); serialPortConfig_t *bluetoothMspUART = serialFindPortConfigurationMutable(BLUETOOTH_MSP_UART);
if (bluetoothMspUART) { if (bluetoothMspUART) {
bluetoothMspUART->functionMask = FUNCTION_MSP; bluetoothMspUART->functionMask = FUNCTION_MSP;
bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE;
} }
} }
#endif #endif

View file

@ -37,7 +37,7 @@ void targetConfiguration(void)
pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP; pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP;
pinioBoxConfigMutable()->permanentId[0] = BOXARM; pinioBoxConfigMutable()->permanentId[0] = BOXARM;
serialPortConfig_t *bluetoothMspUART = serialFindPortConfiguration(BLUETOOTH_MSP_UART); serialPortConfig_t *bluetoothMspUART = serialFindPortConfigurationMutable(BLUETOOTH_MSP_UART);
if (bluetoothMspUART) { if (bluetoothMspUART) {
bluetoothMspUART->functionMask = FUNCTION_MSP; bluetoothMspUART->functionMask = FUNCTION_MSP;
bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE;

View file

@ -47,7 +47,7 @@ void targetConfiguration(void)
pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP; pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP;
pinioBoxConfigMutable()->permanentId[0] = BOXARM; pinioBoxConfigMutable()->permanentId[0] = BOXARM;
serialPortConfig_t *bluetoothMspUART = serialFindPortConfiguration(BLUETOOTH_MSP_UART); serialPortConfig_t *bluetoothMspUART = serialFindPortConfigurationMutable(BLUETOOTH_MSP_UART);
if (bluetoothMspUART) { if (bluetoothMspUART) {
bluetoothMspUART->functionMask = FUNCTION_MSP; bluetoothMspUART->functionMask = FUNCTION_MSP;
bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE;

View file

@ -74,7 +74,7 @@
#include "frsky_hub.h" #include "frsky_hub.h"
static serialPort_t *frSkyHubPort = NULL; static serialPort_t *frSkyHubPort = NULL;
static serialPortConfig_t *portConfig = NULL; static const serialPortConfig_t *portConfig = NULL;
#define FRSKY_HUB_BAUDRATE 9600 #define FRSKY_HUB_BAUDRATE 9600
#define FRSKY_HUB_INITIAL_PORT_MODE MODE_TX #define FRSKY_HUB_INITIAL_PORT_MODE MODE_TX

View file

@ -124,7 +124,7 @@ static uint8_t hottMsgCrc;
#define HOTT_PORT_MODE MODE_RXTX // must be opened in RXTX so that TX and RX pins are allocated. #define HOTT_PORT_MODE MODE_RXTX // must be opened in RXTX so that TX and RX pins are allocated.
static serialPort_t *hottPort = NULL; static serialPort_t *hottPort = NULL;
static serialPortConfig_t *portConfig; static const serialPortConfig_t *portConfig;
static bool hottTelemetryEnabled = false; static bool hottTelemetryEnabled = false;
static portSharing_e hottPortSharing; static portSharing_e hottPortSharing;

View file

@ -76,7 +76,7 @@
static serialPort_t *ibusSerialPort = NULL; static serialPort_t *ibusSerialPort = NULL;
static serialPortConfig_t *ibusSerialPortConfig; static const serialPortConfig_t *ibusSerialPortConfig;
/* The sent bytes will be echoed back since Tx and Rx are wired together, this counter /* The sent bytes will be echoed back since Tx and Rx are wired together, this counter
* will keep track of how many rx chars that shall be discarded */ * will keep track of how many rx chars that shall be discarded */

View file

@ -84,7 +84,7 @@
#define LTM_CYCLETIME 100 #define LTM_CYCLETIME 100
static serialPort_t *ltmPort; static serialPort_t *ltmPort;
static serialPortConfig_t *portConfig; static const serialPortConfig_t *portConfig;
static bool ltmEnabled; static bool ltmEnabled;
static portSharing_e ltmPortSharing; static portSharing_e ltmPortSharing;
static uint8_t ltm_crc; static uint8_t ltm_crc;

View file

@ -86,7 +86,7 @@
extern uint16_t rssi; // FIXME dependency on mw.c extern uint16_t rssi; // FIXME dependency on mw.c
static serialPort_t *mavlinkPort = NULL; static serialPort_t *mavlinkPort = NULL;
static serialPortConfig_t *portConfig; static const serialPortConfig_t *portConfig;
static bool mavlinkTelemetryEnabled = false; static bool mavlinkTelemetryEnabled = false;
static portSharing_e mavlinkPortSharing; static portSharing_e mavlinkPortSharing;

View file

@ -180,7 +180,7 @@ static frSkyTableInfo_t frSkyEscDataIdTableInfo = {frSkyEscDataIdTable, 0, 0};
#define SMARTPORT_SERVICE_TIMEOUT_US 1000 // max allowed time to find a value to send #define SMARTPORT_SERVICE_TIMEOUT_US 1000 // max allowed time to find a value to send
static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port. static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port.
static serialPortConfig_t *portConfig; static const serialPortConfig_t *portConfig;
static portSharing_e smartPortPortSharing; static portSharing_e smartPortPortSharing;

View file

@ -228,6 +228,6 @@ void telemetryProcess(uint32_t currentTime)
bool telemetryIsSensorEnabled(sensor_e sensor) bool telemetryIsSensorEnabled(sensor_e sensor)
{ {
return ~(telemetryConfigMutable()->disabledSensors) & sensor; return ~(telemetryConfig()->disabledSensors) & sensor;
} }
#endif #endif

View file

@ -394,7 +394,7 @@ uint32_t serialTxBytesFree(const serialPort_t *) {return 0;}
bool isSerialTransmitBufferEmpty(const serialPort_t *) {return false;} bool isSerialTransmitBufferEmpty(const serialPort_t *) {return false;}
bool featureIsEnabled(uint32_t) {return false;} bool featureIsEnabled(uint32_t) {return false;}
void mspSerialReleasePortIfAllocated(serialPort_t *) {} void mspSerialReleasePortIfAllocated(serialPort_t *) {}
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
serialPort_t *findSharedSerialPort(uint16_t , serialPortFunction_e ) {return NULL;} serialPort_t *findSharedSerialPort(uint16_t , serialPortFunction_e ) {return NULL;}
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
void closeSerialPort(serialPort_t *) {} void closeSerialPort(serialPort_t *) {}

View file

@ -278,7 +278,7 @@ uint8_t getCurrentControlRateProfileIndex(void){ return 1; }
void changeControlRateProfile(uint8_t) {} void changeControlRateProfile(uint8_t) {}
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *) {} void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *) {}
void writeEEPROM() {} void writeEEPROM() {}
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e) {return NULL; } serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e) {return NULL; }
baudRate_e lookupBaudRateIndex(uint32_t){return BAUD_9600; } baudRate_e lookupBaudRateIndex(uint32_t){return BAUD_9600; }
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e){ return NULL; } serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e){ return NULL; }
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) { return NULL; } serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) { return NULL; }

View file

@ -47,7 +47,7 @@ TEST(IoSerialTest, TestFindPortConfig)
serialInit(false, SERIAL_PORT_NONE); serialInit(false, SERIAL_PORT_NONE);
// when // when
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP); const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
// then // then
EXPECT_EQ(NULL, portConfig); EXPECT_EQ(NULL, portConfig);

View file

@ -431,7 +431,7 @@ extern "C" {
bool isBlackboxDeviceWorking() { return true; } bool isBlackboxDeviceWorking() { return true; }
bool isBlackboxDeviceFull() { return false; } bool isBlackboxDeviceFull() { return false; }
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;} bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;}
bool cmsDisplayPortRegister(displayPort_t *) { return false; } bool cmsDisplayPortRegister(displayPort_t *) { return false; }
uint16_t getCoreTemperatureCelsius(void) { return 0; } uint16_t getCoreTemperatureCelsius(void) { return 0; }

View file

@ -791,7 +791,7 @@ extern "C" {
return NULL; return NULL;
} }
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
{ {
UNUSED(function); UNUSED(function);
if (testData.isRunCamSplitPortConfigurated) { if (testData.isRunCamSplitPortConfigurated) {
@ -960,7 +960,7 @@ extern "C" {
// testData.maxTimesOfRespDataAvailable = testData.responseDataLen + 1; // testData.maxTimesOfRespDataAvailable = testData.responseDataLen + 1;
} }
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function) const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
{ {
UNUSED(function); UNUSED(function);

View file

@ -291,7 +291,7 @@ int16_t debug[DEBUG16_VALUE_COUNT];
uint32_t micros(void) {return dummyTimeUs;} uint32_t micros(void) {return dummyTimeUs;}
uint32_t microsISR(void) {return micros();} uint32_t microsISR(void) {return micros();}
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;} bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;}
serialPort_t *telemetrySharedPort = NULL; serialPort_t *telemetrySharedPort = NULL;
void crsfScheduleDeviceInfoResponse(void) {}; void crsfScheduleDeviceInfoResponse(void) {};

View file

@ -103,7 +103,7 @@ bool isSerialPortShared(const serialPortConfig_t *portConfig,
return portIsShared; return portIsShared;
} }
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
{ {
EXPECT_EQ(function, FUNCTION_RX_SERIAL); EXPECT_EQ(function, FUNCTION_RX_SERIAL);
return findSerialPortConfig_stub_retval; return findSerialPortConfig_stub_retval;

View file

@ -99,7 +99,7 @@ static portMode_e serialExpectedMode = MODE_RX;
static portOptions_e serialExpectedOptions = SERIAL_UNIDIR; static portOptions_e serialExpectedOptions = SERIAL_UNIDIR;
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
{ {
EXPECT_EQ(function, FUNCTION_RX_SERIAL); EXPECT_EQ(function, FUNCTION_RX_SERIAL);
return findSerialPortConfig_stub_retval; return findSerialPortConfig_stub_retval;

View file

@ -257,7 +257,7 @@ extern "C" {
uint32_t micros(void) {return dummyTimeUs;} uint32_t micros(void) {return dummyTimeUs;}
uint32_t microsISR(void) {return micros();} uint32_t microsISR(void) {return micros();}
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
bool isBatteryVoltageConfigured(void) { return true; } bool isBatteryVoltageConfigured(void) { return true; }
uint16_t getBatteryVoltage(void) { uint16_t getBatteryVoltage(void) {
return testBatteryVoltage; return testBatteryVoltage;

View file

@ -327,7 +327,7 @@ serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, seria
void closeSerialPort(serialPort_t *) {} void closeSerialPort(serialPort_t *) {}
bool isSerialTransmitBufferEmpty(const serialPort_t *) { return true; } bool isSerialTransmitBufferEmpty(const serialPort_t *) { return true; }
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) {return NULL;} const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) {return NULL;}
bool telemetryDetermineEnabledState(portSharing_e) {return true;} bool telemetryDetermineEnabledState(portSharing_e) {return true;}
bool telemetryCheckRxPortShared(const serialPortConfig_t *, SerialRXType) {return true;} bool telemetryCheckRxPortShared(const serialPortConfig_t *, SerialRXType) {return true;}

View file

@ -237,7 +237,7 @@ void closeSerialPort(serialPort_t *serialPort)
UNUSED(serialPort); UNUSED(serialPort);
} }
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
{ {
UNUSED(function); UNUSED(function);

View file

@ -162,7 +162,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros)
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
{ {
EXPECT_EQ(FUNCTION_TELEMETRY_IBUS, function); EXPECT_EQ(FUNCTION_TELEMETRY_IBUS, function);
return findSerialPortConfig_stub_retval; return findSerialPortConfig_stub_retval;