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:
parent
c6a891e57e
commit
2d63010dc8
10 changed files with 34 additions and 58 deletions
|
@ -31,10 +31,6 @@ struct ioPortDef_s {
|
||||||
rccPeriphTag_t rcc;
|
rccPeriphTag_t rcc;
|
||||||
};
|
};
|
||||||
|
|
||||||
#if defined(SITL)
|
|
||||||
const struct ioPortDef_s ioPortDefs[] = { 0 };
|
|
||||||
#endif
|
|
||||||
|
|
||||||
ioRec_t* IO_Rec(IO_t io)
|
ioRec_t* IO_Rec(IO_t io)
|
||||||
{
|
{
|
||||||
return io;
|
return io;
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(USE_UART) || defined(USE_LPUART) || defined(USE_SOFTSERIAL)
|
#if SERIAL_TRAIT_PIN_CONFIG
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
|
|
@ -521,22 +521,7 @@ void init(void)
|
||||||
uartPinConfigure(serialPinConfig());
|
uartPinConfigure(serialPinConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(AVOID_UART1_FOR_PWM_PPM)
|
serialInit(featureIsEnabled(FEATURE_SOFTSERIAL));
|
||||||
# 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);
|
|
||||||
}
|
|
||||||
|
|
||||||
mixerInit(mixerConfig()->mixerMode);
|
mixerInit(mixerConfig()->mixerMode);
|
||||||
|
|
||||||
|
@ -545,20 +530,24 @@ void init(void)
|
||||||
* may send spurious pulses to esc's causing their early initialization. Also ppm
|
* 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. */
|
* receiver may share timer with motors so motors MUST be initialized here. */
|
||||||
motorDevInit(getMotorCount());
|
motorDevInit(getMotorCount());
|
||||||
|
// TODO: add check here that motors actually initialised correctly
|
||||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (0) {}
|
do {
|
||||||
#if defined(USE_RX_PPM)
|
#if defined(USE_RX_PPM)
|
||||||
else if (featureIsEnabled(FEATURE_RX_PPM)) {
|
if (featureIsEnabled(FEATURE_RX_PPM)) {
|
||||||
ppmRxInit(ppmConfig());
|
ppmRxInit(ppmConfig());
|
||||||
}
|
break;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_RX_PWM)
|
#if defined(USE_RX_PWM)
|
||||||
else if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
|
if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
|
||||||
pwmRxInit(pwmConfig());
|
pwmRxInit(pwmConfig());
|
||||||
}
|
break;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
} while (false);
|
||||||
|
|
||||||
#ifdef USE_BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperInit(beeperDevConfig());
|
beeperInit(beeperDevConfig());
|
||||||
|
|
|
@ -572,41 +572,26 @@ void closeSerialPort(serialPort_t *serialPort)
|
||||||
serialPortUsage->serialPort = NULL;
|
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));
|
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
|
||||||
|
|
||||||
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
|
for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||||
serialPortUsageList[index].identifier = serialPortIdentifiers[index];
|
serialPortUsageList[index].identifier = serialPortIdentifiers[index];
|
||||||
|
|
||||||
if (serialPortToDisable != SERIAL_PORT_NONE
|
#if SERIAL_TRAIT_PIN_CONFIG
|
||||||
&& serialPortUsageList[index].identifier == serialPortToDisable) {
|
const int resourceIndex = serialResourceIndex(serialPortUsageList[index].identifier);
|
||||||
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
if (resourceIndex >= 0 && !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
|
||||||
continue; // this index is deleted
|
// 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
|
#endif
|
||||||
}
|
|
||||||
if (serialType(serialPortUsageList[index].identifier) == SERIALTYPE_SOFTSERIAL) {
|
if (serialType(serialPortUsageList[index].identifier) == SERIALTYPE_SOFTSERIAL && !softserialEnabled) {
|
||||||
if (true
|
// soft serial is not enabled, or not built into the firmware
|
||||||
#ifdef USE_SOFTSERIAL
|
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
||||||
&& !softserialEnabled
|
continue;
|
||||||
#endif
|
|
||||||
) {
|
|
||||||
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -171,7 +171,7 @@ typedef void serialConsumer(uint8_t);
|
||||||
//
|
//
|
||||||
// configuration
|
// configuration
|
||||||
//
|
//
|
||||||
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
void serialInit(bool softserialEnabled);
|
||||||
void serialRemovePort(serialPortIdentifier_e identifier);
|
void serialRemovePort(serialPortIdentifier_e identifier);
|
||||||
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
||||||
bool isSerialConfigValid(serialConfig_t *serialConfig);
|
bool isSerialConfigValid(serialConfig_t *serialConfig);
|
||||||
|
|
|
@ -192,6 +192,7 @@
|
||||||
|
|
||||||
#define PLATFORM_TRAIT_RCC 1
|
#define PLATFORM_TRAIT_RCC 1
|
||||||
#define UART_TRAIT_AF_PORT 1
|
#define UART_TRAIT_AF_PORT 1
|
||||||
|
#define SERIAL_TRAIT_PIN_CONFIG 1
|
||||||
|
|
||||||
#define UARTHARDWARE_MAX_PINS 4
|
#define UARTHARDWARE_MAX_PINS 4
|
||||||
|
|
||||||
|
|
|
@ -147,6 +147,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||||
#define PLATFORM_TRAIT_RCC 1
|
#define PLATFORM_TRAIT_RCC 1
|
||||||
#define UART_TRAIT_AF_PIN 1
|
#define UART_TRAIT_AF_PIN 1
|
||||||
#define UART_TRAIT_PINSWAP 1
|
#define UART_TRAIT_PINSWAP 1
|
||||||
|
#define SERIAL_TRAIT_PIN_CONFIG 1
|
||||||
|
|
||||||
#define UARTHARDWARE_MAX_PINS 5
|
#define UARTHARDWARE_MAX_PINS 5
|
||||||
|
|
||||||
|
|
|
@ -30,3 +30,6 @@
|
||||||
#define IOCFG_IN_FLOATING 0
|
#define IOCFG_IN_FLOATING 0
|
||||||
|
|
||||||
#define SPIDEV_COUNT 0
|
#define SPIDEV_COUNT 0
|
||||||
|
|
||||||
|
// no serial pins are defined for the simulator
|
||||||
|
#define SERIAL_TRAIT_PIN_CONFIG 0
|
||||||
|
|
|
@ -417,4 +417,5 @@ extern uint8_t _dmaram_end__;
|
||||||
#define DMA_TRAIT_CHANNEL 1
|
#define DMA_TRAIT_CHANNEL 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define SERIAL_TRAIT_PIN_CONFIG 1
|
||||||
#define USB_DP_PIN PA12
|
#define USB_DP_PIN PA12
|
||||||
|
|
|
@ -33,7 +33,7 @@ extern "C" {
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
#include "pg/rx.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(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
|
||||||
PG_REGISTER(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0);
|
PG_REGISTER(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0);
|
||||||
|
@ -45,7 +45,7 @@ extern "C" {
|
||||||
TEST(IoSerialTest, TestFindPortConfig)
|
TEST(IoSerialTest, TestFindPortConfig)
|
||||||
{
|
{
|
||||||
// given
|
// given
|
||||||
serialInit(false, SERIAL_PORT_NONE);
|
serialInit(false);
|
||||||
|
|
||||||
// when
|
// when
|
||||||
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
|
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue