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

Configuration validation.

This enables a new feature setting for PARALLEL_PWM which is enabled by
default.

This starts to move much of the feature checking/excluding code that is
littered through into a single place - validateAndFixConfig().  Since
the config is known to be valid after the method is called other code
can just get on with it's job instead of checking for confliciting
features/settings.
This commit is contained in:
Dominic Clifton 2014-05-10 12:45:36 +01:00
parent 0fd127bf60
commit 5c4bfd4e58
13 changed files with 269 additions and 193 deletions

View file

@ -51,149 +51,7 @@ master_t masterConfig; // master config struct with data independent from profi
profile_t currentProfile; // profile config struct profile_t currentProfile; // profile config struct
static const uint8_t EEPROM_CONF_VERSION = 66; static const uint8_t EEPROM_CONF_VERSION = 66;
static void resetConf(void);
static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
{
uint8_t checksum = 0;
const uint8_t *byteOffset;
for (byteOffset = data; byteOffset < (data + length); byteOffset++)
checksum ^= *byteOffset;
return checksum;
}
static bool isEEPROMContentValid(void)
{
const master_t *temp = (const master_t *)FLASH_WRITE_ADDR;
uint8_t checksum = 0;
// check version number
if (EEPROM_CONF_VERSION != temp->version)
return false;
// check size and magic numbers
if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
return false;
// verify integrity of temporary copy
checksum = calculateChecksum((const uint8_t *)temp, sizeof(master_t));
if (checksum != 0)
return false;
// looks good, let's roll!
return true;
}
void activateConfig(void)
{
generatePitchCurve(&currentProfile.controlRateConfig);
generateThrottleCurve(&currentProfile.controlRateConfig, &masterConfig.escAndServoConfig);
useGyroConfig(&masterConfig.gyroConfig);
useTelemetryConfig(&masterConfig.telemetryConfig);
setPIDController(currentProfile.pidController);
gpsUseProfile(&currentProfile.gpsProfile);
gpsUsePIDs(&currentProfile.pidProfile);
useFailsafeConfig(&currentProfile.failsafeConfig);
setAccelerationTrims(&masterConfig.accZero);
mixerUseConfigs(
currentProfile.servoConf,
&masterConfig.flight3DConfig,
&masterConfig.escAndServoConfig,
&currentProfile.mixerConfig,
&masterConfig.airplaneConfig,
&masterConfig.rxConfig,
&currentProfile.gimbalConfig
);
#ifdef BARO
useBarometerConfig(&currentProfile.barometerConfig);
#endif
}
void readEEPROM(void)
{
// Sanity check
if (!isEEPROMContentValid())
failureMode(10);
// Read flash
memcpy(&masterConfig, (char *)FLASH_WRITE_ADDR, sizeof(master_t));
// Copy current profile
if (masterConfig.current_profile_index > 2) // sanity check
masterConfig.current_profile_index = 0;
memcpy(&currentProfile, &masterConfig.profile[masterConfig.current_profile_index], sizeof(profile_t));
activateConfig();
}
void readEEPROMAndNotify(void)
{
// re-read written data
readEEPROM();
blinkLedAndSoundBeeper(15, 20, 1);
}
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex)
{
// copy current in-memory profile to stored configuration
memcpy(&masterConfig.profile[profileSlotIndex], &currentProfile, sizeof(profile_t));
}
void writeEEPROM(void)
{
FLASH_Status status = 0;
uint32_t wordOffset;
int8_t attemptsRemaining = 3;
// prepare checksum/version constants
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.size = sizeof(master_t);
masterConfig.magic_be = 0xBE;
masterConfig.magic_ef = 0xEF;
masterConfig.chk = 0; // erase checksum before recalculating
masterConfig.chk = calculateChecksum((const uint8_t *)&masterConfig, sizeof(master_t));
// write it
FLASH_Unlock();
while (attemptsRemaining--) {
#ifdef STM32F3DISCOVERY
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
#endif
#ifdef STM32F10X_MD
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
#endif
status = FLASH_ErasePage(FLASH_WRITE_ADDR);
for (wordOffset = 0; wordOffset < sizeof(master_t) && status == FLASH_COMPLETE; wordOffset += 4) {
status = FLASH_ProgramWord(FLASH_WRITE_ADDR + wordOffset, *(uint32_t *) ((char *)&masterConfig + wordOffset));
}
if (status == FLASH_COMPLETE) {
break;
}
}
FLASH_Lock();
// Flash write failed - just die now
if (status != FLASH_COMPLETE || !isEEPROMContentValid()) {
failureMode(10);
}
}
void ensureEEPROMContainsValidData(void)
{
if (isEEPROMContentValid()) {
return;
}
resetEEPROM();
}
void resetEEPROM(void)
{
resetConf();
writeEEPROM();
}
static void resetAccelerometerTrims(int16_flightDynamicsTrims_t *accelerometerTrims) static void resetAccelerometerTrims(int16_flightDynamicsTrims_t *accelerometerTrims)
{ {
@ -423,6 +281,192 @@ static void resetConf(void)
memcpy(&masterConfig.profile[i], &currentProfile, sizeof(profile_t)); memcpy(&masterConfig.profile[i], &currentProfile, sizeof(profile_t));
} }
static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
{
uint8_t checksum = 0;
const uint8_t *byteOffset;
for (byteOffset = data; byteOffset < (data + length); byteOffset++)
checksum ^= *byteOffset;
return checksum;
}
static bool isEEPROMContentValid(void)
{
const master_t *temp = (const master_t *)FLASH_WRITE_ADDR;
uint8_t checksum = 0;
// check version number
if (EEPROM_CONF_VERSION != temp->version)
return false;
// check size and magic numbers
if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
return false;
// verify integrity of temporary copy
checksum = calculateChecksum((const uint8_t *)temp, sizeof(master_t));
if (checksum != 0)
return false;
// looks good, let's roll!
return true;
}
void activateConfig(void)
{
generatePitchCurve(&currentProfile.controlRateConfig);
generateThrottleCurve(&currentProfile.controlRateConfig, &masterConfig.escAndServoConfig);
useGyroConfig(&masterConfig.gyroConfig);
useTelemetryConfig(&masterConfig.telemetryConfig);
setPIDController(currentProfile.pidController);
gpsUseProfile(&currentProfile.gpsProfile);
gpsUsePIDs(&currentProfile.pidProfile);
useFailsafeConfig(&currentProfile.failsafeConfig);
setAccelerationTrims(&masterConfig.accZero);
mixerUseConfigs(
currentProfile.servoConf,
&masterConfig.flight3DConfig,
&masterConfig.escAndServoConfig,
&currentProfile.mixerConfig,
&masterConfig.airplaneConfig,
&masterConfig.rxConfig,
&currentProfile.gimbalConfig
);
#ifdef BARO
useBarometerConfig(&currentProfile.barometerConfig);
#endif
}
void validateAndFixConfig(void) {
if (!(feature(FEATURE_PARALLEL_PWM) || feature(FEATURE_PPM) || feature(FEATURE_SERIALRX))) {
featureSet(FEATURE_PARALLEL_PWM); // Consider changing the default to PPM
}
if (feature(FEATURE_SERIALRX)) {
if (feature(FEATURE_PARALLEL_PWM)) {
featureClear(FEATURE_PARALLEL_PWM);
}
if (feature(FEATURE_PPM)) {
featureClear(FEATURE_PPM);
}
}
if (feature(FEATURE_PPM)) {
if (feature(FEATURE_PARALLEL_PWM)) {
featureClear(FEATURE_PARALLEL_PWM);
}
}
#ifdef SONAR
if (feature(FEATURE_SONAR)) {
// sonar needs a free PWM port
if (!feature(FEATURE_PARALLEL_PWM)) {
featureClear(FEATURE_SONAR);
}
}
#endif
if (feature(FEATURE_SOFTSERIAL)) {
// software serial needs free PWM ports
if (feature(FEATURE_PARALLEL_PWM)) {
featureClear(FEATURE_SOFTSERIAL);
}
}
serialConfig_t *serialConfig = &masterConfig.serialConfig;
applySerialConfigToPortFunctions(serialConfig);
if (!isSerialConfigValid(serialConfig)) {
resetSerialConfig(serialConfig);
}
}
void readEEPROM(void)
{
// Sanity check
if (!isEEPROMContentValid())
failureMode(10);
// Read flash
memcpy(&masterConfig, (char *)FLASH_WRITE_ADDR, sizeof(master_t));
// Copy current profile
if (masterConfig.current_profile_index > 2) // sanity check
masterConfig.current_profile_index = 0;
memcpy(&currentProfile, &masterConfig.profile[masterConfig.current_profile_index], sizeof(profile_t));
validateAndFixConfig();
activateConfig();
}
void readEEPROMAndNotify(void)
{
// re-read written data
readEEPROM();
blinkLedAndSoundBeeper(15, 20, 1);
}
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex)
{
// copy current in-memory profile to stored configuration
memcpy(&masterConfig.profile[profileSlotIndex], &currentProfile, sizeof(profile_t));
}
void writeEEPROM(void)
{
FLASH_Status status = 0;
uint32_t wordOffset;
int8_t attemptsRemaining = 3;
// prepare checksum/version constants
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.size = sizeof(master_t);
masterConfig.magic_be = 0xBE;
masterConfig.magic_ef = 0xEF;
masterConfig.chk = 0; // erase checksum before recalculating
masterConfig.chk = calculateChecksum((const uint8_t *)&masterConfig, sizeof(master_t));
// write it
FLASH_Unlock();
while (attemptsRemaining--) {
#ifdef STM32F3DISCOVERY
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
#endif
#ifdef STM32F10X_MD
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
#endif
status = FLASH_ErasePage(FLASH_WRITE_ADDR);
for (wordOffset = 0; wordOffset < sizeof(master_t) && status == FLASH_COMPLETE; wordOffset += 4) {
status = FLASH_ProgramWord(FLASH_WRITE_ADDR + wordOffset, *(uint32_t *) ((char *)&masterConfig + wordOffset));
}
if (status == FLASH_COMPLETE) {
break;
}
}
FLASH_Lock();
// Flash write failed - just die now
if (status != FLASH_COMPLETE || !isEEPROMContentValid()) {
failureMode(10);
}
}
void ensureEEPROMContainsValidData(void)
{
if (isEEPROMContentValid()) {
return;
}
resetEEPROM();
}
void resetEEPROM(void)
{
resetConf();
writeEEPROM();
}
void saveAndReloadCurrentProfileToCurrentProfileSlot(void) void saveAndReloadCurrentProfileToCurrentProfileSlot(void)
{ {
copyCurrentProfileToProfileSlot(masterConfig.current_profile_index); copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
@ -455,13 +499,3 @@ uint32_t featureMask(void)
return masterConfig.enabledFeatures; return masterConfig.enabledFeatures;
} }
bool canSoftwareSerialBeUsed(void)
{
#ifdef FY90Q
return false;
#endif
// FIXME this is not ideal because it means you can't disable parallel PWM input even when using spektrum/sbus etc.
// really we want to say 'return !feature(FEATURE_PARALLEL_PWM);'
return feature(FEATURE_SOFTSERIAL) && feature(FEATURE_PPM); // Software serial can only be used in PPM mode because parallel PWM uses the same hardware pins/timers
}

View file

@ -16,6 +16,7 @@ typedef enum {
FEATURE_POWERMETER = 1 << 12, FEATURE_POWERMETER = 1 << 12,
FEATURE_VARIO = 1 << 13, FEATURE_VARIO = 1 << 13,
FEATURE_3D = 1 << 14, FEATURE_3D = 1 << 14,
FEATURE_PARALLEL_PWM = 1 << 15,
} AvailableFeatures; } AvailableFeatures;
bool feature(uint32_t mask); bool feature(uint32_t mask);

View file

@ -157,8 +157,8 @@ void pwmInit(drv_pwm_config_t *init)
#endif #endif
#ifdef STM32F10X_MD #ifdef STM32F10X_MD
// skip UART ports for GPS // skip UART2 ports
if (init->useUART && (timerIndex == PWM3 || timerIndex == PWM4)) if (init->useUART2 && (timerIndex == PWM3 || timerIndex == PWM4))
continue; continue;
#endif #endif
@ -189,7 +189,10 @@ void pwmInit(drv_pwm_config_t *init)
#endif #endif
// hacks to allow current functionality // hacks to allow current functionality
if (mask & (TYPE_IP | TYPE_IW) && !init->enableInput) if (mask & TYPE_IW && !init->useParallelPWM)
mask = 0;
if (mask & TYPE_IP && !init->usePPM)
mask = 0; mask = 0;
if (init->useServos && !init->airplane) { if (init->useServos && !init->airplane) {

View file

@ -21,9 +21,11 @@
#define PWM_TIMER_MHZ 1 #define PWM_TIMER_MHZ 1
typedef struct drv_pwm_config_t { typedef struct drv_pwm_config_t {
bool enableInput; bool useParallelPWM;
bool usePPM; bool usePPM;
bool useUART; #ifdef STM32F10X_MD
bool useUART2;
#endif
bool useSoftSerial; bool useSoftSerial;
bool useServos; bool useServos;
bool extraServos; // configure additional 4 channels in PPM mode as servos, not motors bool extraServos; // configure additional 4 channels in PPM mode as servos, not motors

View file

@ -89,8 +89,8 @@ void productionDebug(void)
int main(void) int main(void)
{ {
uint8_t i; uint8_t i;
drv_pwm_config_t pwm_params; drv_pwm_config_t pwm_params; // FIXME never freed, remains on heap
drv_adc_config_t adc_params; drv_adc_config_t adc_params; // FIXME never freed, remains on heap
bool sensorsOK = false; bool sensorsOK = false;
initPrintfSupport(); initPrintfSupport();
@ -146,10 +146,6 @@ int main(void)
imuInit(); // Mag is initialized inside imuInit imuInit(); // Mag is initialized inside imuInit
mixerInit(masterConfig.mixerConfiguration, masterConfig.customMixer); mixerInit(masterConfig.mixerConfiguration, masterConfig.customMixer);
if (!canSoftwareSerialBeUsed()) {
featureClear(FEATURE_SOFTSERIAL);
}
#ifndef FY90Q #ifndef FY90Q
timerInit(); timerInit();
#endif #endif
@ -161,10 +157,14 @@ int main(void)
pwm_params.airplane = true; pwm_params.airplane = true;
else else
pwm_params.airplane = false; pwm_params.airplane = false;
pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SERIALRX); // serial rx support uses UART too
pwm_params.useSoftSerial = canSoftwareSerialBeUsed(); #ifdef STM32F10X_MD
pwm_params.useUART2 = doesConfigurationUsePort(&masterConfig.serialConfig, SERIAL_PORT_USART2);
#endif
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
pwm_params.useParallelPWM = feature(FEATURE_PARALLEL_PWM);
pwm_params.usePPM = feature(FEATURE_PPM); pwm_params.usePPM = feature(FEATURE_PPM);
pwm_params.enableInput = !feature(FEATURE_SERIALRX); // disable inputs if using spektrum
pwm_params.useServos = isMixerUsingServos(); pwm_params.useServos = isMixerUsingServos();
pwm_params.extraServos = currentProfile.gimbalConfig.gimbal_flags & GIMBAL_FORWARDAUX; pwm_params.extraServos = currentProfile.gimbalConfig.gimbal_flags & GIMBAL_FORWARDAUX;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
@ -205,9 +205,7 @@ int main(void)
} }
#ifdef SONAR #ifdef SONAR
// sonar stuff only works with PPM if (feature(FEATURE_SONAR)) {
if (feature(FEATURE_PPM)) {
if (feature(FEATURE_SONAR))
Sonar_init(); Sonar_init();
} }
#endif #endif

View file

@ -19,10 +19,11 @@
#include "rx_common.h" #include "rx_common.h"
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback); void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
void sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback); bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback); bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback); bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
const char rcChannelLetters[] = "AERT1234"; const char rcChannelLetters[] = "AERT1234";
@ -54,28 +55,36 @@ void rxInit(rxConfig_t *rxConfig, failsafe_t *initialFailsafe)
if (feature(FEATURE_SERIALRX)) { if (feature(FEATURE_SERIALRX)) {
serialRxInit(rxConfig); serialRxInit(rxConfig);
} else { }
if (feature(FEATURE_PPM) || feature(FEATURE_PARALLEL_PWM)) {
rxPwmInit(&rxRuntimeConfig, &rcReadRawFunc); rxPwmInit(&rxRuntimeConfig, &rcReadRawFunc);
} }
} }
void serialRxInit(rxConfig_t *rxConfig) void serialRxInit(rxConfig_t *rxConfig)
{ {
bool enabled = false;
switch (rxConfig->serialrx_provider) { switch (rxConfig->serialrx_provider) {
case SERIALRX_SPEKTRUM1024: case SERIALRX_SPEKTRUM1024:
case SERIALRX_SPEKTRUM2048: case SERIALRX_SPEKTRUM2048:
spektrumInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc); enabled = spektrumInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
break; break;
case SERIALRX_SBUS: case SERIALRX_SBUS:
sbusInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc); enabled = sbusInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
break; break;
case SERIALRX_SUMD: case SERIALRX_SUMD:
sumdInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc); enabled = sumdInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
break; break;
case SERIALRX_MSP: case SERIALRX_MSP:
rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc); enabled = rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
break; break;
} }
if (!enabled) {
featureClear(FEATURE_SERIALRX);
rcReadRawFunc = NULL;
}
} }
bool isSerialRxFrameComplete(rxConfig_t *rxConfig) bool isSerialRxFrameComplete(rxConfig_t *rxConfig)
@ -115,6 +124,12 @@ void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
} }
for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) { for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) {
if (!rcReadRawFunc) {
rcData[chan] = rxConfig->midrc;
continue;
}
uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, chan); uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, chan);
// sample the channel // sample the channel

View file

@ -33,8 +33,10 @@ bool rxMspFrameComplete(void)
return false; return false;
} }
void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback) bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{ {
if (callback) if (callback)
*callback = rxMspReadRawRC; *callback = rxMspReadRawRC;
return true;
} }

View file

@ -1,5 +1,6 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h>
#include "platform.h" #include "platform.h"
@ -27,7 +28,7 @@ static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
static serialPort_t *sBusPort; static serialPort_t *sBusPort;
void sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback) bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{ {
int b; int b;
@ -38,6 +39,8 @@ void sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa
if (callback) if (callback)
*callback = sbusReadRawRC; *callback = sbusReadRawRC;
rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL; rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;
return sBusPort != NULL;
} }
struct sbus_dat struct sbus_dat

View file

@ -1,5 +1,6 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h>
#include "platform.h" #include "platform.h"
@ -33,7 +34,7 @@ static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t ch
static serialPort_t *spektrumPort; static serialPort_t *spektrumPort;
void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback) bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{ {
switch (rxConfig->serialrx_provider) { switch (rxConfig->serialrx_provider) {
case SERIALRX_SPEKTRUM2048: case SERIALRX_SPEKTRUM2048:
@ -55,6 +56,8 @@ void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcRe
spektrumPort = openSerialPort(FUNCTION_SERIAL_RX, spektrumDataReceive, 115200, MODE_RX, SERIAL_NOT_INVERTED); spektrumPort = openSerialPort(FUNCTION_SERIAL_RX, spektrumDataReceive, 115200, MODE_RX, SERIAL_NOT_INVERTED);
if (callback) if (callback)
*callback = spektrumReadRawRC; *callback = spektrumReadRawRC;
return spektrumPort != NULL;
} }
// Receive ISR callback // Receive ISR callback

View file

@ -1,5 +1,6 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h>
#include "platform.h" #include "platform.h"
@ -26,13 +27,15 @@ static uint32_t sumdChannelData[SUMD_MAX_CHANNEL];
static serialPort_t *sumdPort; static serialPort_t *sumdPort;
void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback) bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{ {
sumdPort = openSerialPort(FUNCTION_SERIAL_RX, sumdDataReceive, 115200, MODE_RX, SERIAL_NOT_INVERTED); sumdPort = openSerialPort(FUNCTION_SERIAL_RX, sumdDataReceive, 115200, MODE_RX, SERIAL_NOT_INVERTED);
if (callback) if (callback)
*callback = sumdReadRawRC; *callback = sumdReadRawRC;
rxRuntimeConfig->channelCount = SUMD_MAX_CHANNEL; rxRuntimeConfig->channelCount = SUMD_MAX_CHANNEL;
return sumdPort != NULL;
} }
static uint8_t sumd[SUMD_BUFFSIZE] = { 0, }; static uint8_t sumd[SUMD_BUFFSIZE] = { 0, };

View file

@ -84,8 +84,8 @@ static const char * const mixerNames[] = {
// sync this with AvailableFeatures enum from board.h // sync this with AvailableFeatures enum from board.h
static const char * const featureNames[] = { static const char * const featureNames[] = {
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP", "PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP",
"SERVO_TILT", "SOFTSERIAL", "LED_RING", "GPS", "SERVO_TILT", "SOFTSERIAL", "LED_RING", "GPS", "FAILSAFE",
"FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "PARALLEL_PWM",
NULL NULL
}; };

View file

@ -19,7 +19,6 @@
void mspInit(serialConfig_t *serialConfig); void mspInit(serialConfig_t *serialConfig);
void cliInit(serialConfig_t *serialConfig); void cliInit(serialConfig_t *serialConfig);
void resetSerialConfig(serialConfig_t *serialConfig);
// this exists so the user can reference scenarios by a number in the CLI instead of an unuser-friendly bitmask. // this exists so the user can reference scenarios by a number in the CLI instead of an unuser-friendly bitmask.
const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT] = { const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT] = {
@ -170,7 +169,7 @@ static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function)
uint8_t serialPortIndex = lookupSerialPortIndexByIdentifier(serialPortFunction->identifier); uint8_t serialPortIndex = lookupSerialPortIndexByIdentifier(serialPortFunction->identifier);
const serialPortConstraint_t *serialPortConstraint = &serialPortConstraints[serialPortIndex]; const serialPortConstraint_t *serialPortConstraint = &serialPortConstraints[serialPortIndex];
if (!canSoftwareSerialBeUsed() && ( if (!feature(FEATURE_SOFTSERIAL) && (
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL1 || serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL1 ||
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL2 serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL2
)) { )) {
@ -349,6 +348,20 @@ bool isSerialConfigValid(serialConfig_t *serialConfig)
return true; return true;
} }
bool doesConfigurationUsePort(serialConfig_t *serialConfig, serialPortIdentifier_e portIdentifier)
{
serialPortSearchResult_t *searchResult;
uint8_t index;
for (index = 0; index < FUNCTION_CONSTRAINT_COUNT; index++) {
searchResult = findSerialPort(functionConstraints[index].function);
if (searchResult->portConstraint->identifier == portIdentifier) {
return true;
}
}
return false;
}
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig) void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
{ {
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART1)].scenario = serialPortScenarios[serialConfig->serial_port_1_scenario]; serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART1)].scenario = serialPortScenarios[serialConfig->serial_port_1_scenario];
@ -363,11 +376,6 @@ void serialInit(serialConfig_t *initialSerialConfig)
serialConfig = initialSerialConfig; serialConfig = initialSerialConfig;
applySerialConfigToPortFunctions(serialConfig); applySerialConfigToPortFunctions(serialConfig);
if (!isSerialConfigValid(serialConfig)) {
resetSerialConfig(serialConfig);
applySerialConfigToPortFunctions(serialConfig);
}
mspInit(serialConfig); mspInit(serialConfig);
cliInit(serialConfig); cliInit(serialConfig);
} }

View file

@ -92,5 +92,9 @@ serialPortFunction_t *findSerialPortFunction(uint16_t functionMask);
void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort); void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig);
bool isSerialConfigValid(serialConfig_t *serialConfig);
bool doesConfigurationUsePort(serialConfig_t *serialConfig, serialPortIdentifier_e portIdentifier);
void evaluateOtherData(uint8_t sr); void evaluateOtherData(uint8_t sr);
void handleSerial(void); void handleSerial(void);