1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 17:25:20 +03:00

Remove redundant SITL ioPortDef_s array definition (#14202)

* Remove redundant SITL ioPortDef_s array definition

* Minor cleanup of some logic where SIMULATOR is in ./src/main

* Updated based on feedback from @ledvinap

* Reducing scope as per @ledvinap

* Fix unit test

* Removing serial port avoidance in totality (unused).

TODO: Remove PWM/PPM radio inputs in another PR.
This commit is contained in:
Jay Blackman 2025-01-28 11:37:57 +11:00 committed by GitHub
parent c6a891e57e
commit 2d63010dc8
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
10 changed files with 34 additions and 58 deletions

View file

@ -31,10 +31,6 @@ struct ioPortDef_s {
rccPeriphTag_t rcc;
};
#if defined(SITL)
const struct ioPortDef_s ioPortDefs[] = { 0 };
#endif
ioRec_t* IO_Rec(IO_t io)
{
return io;

View file

@ -24,7 +24,7 @@
#include "platform.h"
#if defined(USE_UART) || defined(USE_LPUART) || defined(USE_SOFTSERIAL)
#if SERIAL_TRAIT_PIN_CONFIG
#include "build/build_config.h"

View file

@ -521,22 +521,7 @@ void init(void)
uartPinConfigure(serialPinConfig());
#endif
#if defined(AVOID_UART1_FOR_PWM_PPM)
# define SERIALPORT_TO_AVOID SERIAL_PORT_USART1
#elif defined(AVOID_UART2_FOR_PWM_PPM)
# define SERIALPORT_TO_AVOID SERIAL_PORT_USART2
#elif defined(AVOID_UART3_FOR_PWM_PPM)
# define SERIALPORT_TO_AVOID SERIAL_PORT_USART3
#endif
{
serialPortIdentifier_e serialPortToAvoid = SERIAL_PORT_NONE;
#if defined(SERIALPORT_TO_AVOID)
if (featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
serialPortToAvoid = SERIALPORT_TO_AVOID;
}
#endif
serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), serialPortToAvoid);
}
serialInit(featureIsEnabled(FEATURE_SOFTSERIAL));
mixerInit(mixerConfig()->mixerMode);
@ -545,20 +530,24 @@ void init(void)
* may send spurious pulses to esc's causing their early initialization. Also ppm
* receiver may share timer with motors so motors MUST be initialized here. */
motorDevInit(getMotorCount());
// TODO: add check here that motors actually initialised correctly
systemState |= SYSTEM_STATE_MOTORS_READY;
#endif
if (0) {}
do {
#if defined(USE_RX_PPM)
else if (featureIsEnabled(FEATURE_RX_PPM)) {
ppmRxInit(ppmConfig());
}
if (featureIsEnabled(FEATURE_RX_PPM)) {
ppmRxInit(ppmConfig());
break;
}
#endif
#if defined(USE_RX_PWM)
else if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
pwmRxInit(pwmConfig());
}
if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
pwmRxInit(pwmConfig());
break;
}
#endif
} while (false);
#ifdef USE_BEEPER
beeperInit(beeperDevConfig());

View file

@ -572,41 +572,26 @@ void closeSerialPort(serialPort_t *serialPort)
serialPortUsage->serialPort = NULL;
}
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
void serialInit(bool softserialEnabled)
{
#if !defined(USE_SOFTSERIAL)
UNUSED(softserialEnabled);
#endif
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortUsageList[index].identifier = serialPortIdentifiers[index];
if (serialPortToDisable != SERIAL_PORT_NONE
&& serialPortUsageList[index].identifier == serialPortToDisable) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
continue; // this index is deleted
#if SERIAL_TRAIT_PIN_CONFIG
const int resourceIndex = serialResourceIndex(serialPortUsageList[index].identifier);
if (resourceIndex >= 0 && !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
// resource exists but no pin is assigned
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
continue;
}
{
#if !defined(SIMULATOR_BUILD) // no serialPinConfig on SITL
const int resourceIndex = serialResourceIndex(serialPortUsageList[index].identifier);
if (resourceIndex >= 0 // resource exists
&& !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
continue;
}
#endif
}
if (serialType(serialPortUsageList[index].identifier) == SERIALTYPE_SOFTSERIAL) {
if (true
#ifdef USE_SOFTSERIAL
&& !softserialEnabled
#endif
) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
continue;
}
if (serialType(serialPortUsageList[index].identifier) == SERIALTYPE_SOFTSERIAL && !softserialEnabled) {
// soft serial is not enabled, or not built into the firmware
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
continue;
}
}
}

View file

@ -171,7 +171,7 @@ typedef void serialConsumer(uint8_t);
//
// configuration
//
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
void serialInit(bool softserialEnabled);
void serialRemovePort(serialPortIdentifier_e identifier);
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
bool isSerialConfigValid(serialConfig_t *serialConfig);

View file

@ -192,6 +192,7 @@
#define PLATFORM_TRAIT_RCC 1
#define UART_TRAIT_AF_PORT 1
#define SERIAL_TRAIT_PIN_CONFIG 1
#define UARTHARDWARE_MAX_PINS 4

View file

@ -147,6 +147,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define PLATFORM_TRAIT_RCC 1
#define UART_TRAIT_AF_PIN 1
#define UART_TRAIT_PINSWAP 1
#define SERIAL_TRAIT_PIN_CONFIG 1
#define UARTHARDWARE_MAX_PINS 5

View file

@ -30,3 +30,6 @@
#define IOCFG_IN_FLOATING 0
#define SPIDEV_COUNT 0
// no serial pins are defined for the simulator
#define SERIAL_TRAIT_PIN_CONFIG 0

View file

@ -417,4 +417,5 @@ extern uint8_t _dmaram_end__;
#define DMA_TRAIT_CHANNEL 1
#endif
#define SERIAL_TRAIT_PIN_CONFIG 1
#define USB_DP_PIN PA12

View file

@ -33,7 +33,7 @@ extern "C" {
#include "pg/pg_ids.h"
#include "pg/rx.h"
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
void serialInit(bool softserialEnabled);
PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
PG_REGISTER(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0);
@ -45,7 +45,7 @@ extern "C" {
TEST(IoSerialTest, TestFindPortConfig)
{
// given
serialInit(false, SERIAL_PORT_NONE);
serialInit(false);
// when
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);