mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Move STM (and clone) specific IO initialisation to platform (#14123)
* Move stm (and clone) specific io initialisation to platform * Removed unused includes and implemented get by tag for SITL * Update sitl.c Corrected return value * Update io_impl.c Corrected licence file
This commit is contained in:
parent
926c21ce7d
commit
d82cd5a28a
6 changed files with 87 additions and 45 deletions
|
@ -129,14 +129,6 @@ bool IOIsFreeOrPreinit(IO_t io)
|
|||
return false;
|
||||
}
|
||||
|
||||
#if DEFIO_PORT_USED_COUNT > 0
|
||||
static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST };
|
||||
static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_OFFSET_LIST };
|
||||
#else
|
||||
// Avoid -Wpedantic warning
|
||||
static const uint16_t ioDefUsedMask[1] = {0};
|
||||
static const uint8_t ioDefUsedOffset[1] = {0};
|
||||
#endif
|
||||
#if DEFIO_IO_USED_COUNT
|
||||
ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
||||
#else
|
||||
|
@ -144,42 +136,6 @@ ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
|||
ioRec_t ioRecs[1];
|
||||
#endif
|
||||
|
||||
// initialize all ioRec_t structures from ROM
|
||||
// currently only bitmask is used, this may change in future
|
||||
void IOInitGlobal(void)
|
||||
{
|
||||
ioRec_t *ioRec = ioRecs;
|
||||
|
||||
for (unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++) {
|
||||
for (unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++) {
|
||||
if (ioDefUsedMask[port] & (1 << pin)) {
|
||||
ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart
|
||||
ioRec->pin = 1 << pin;
|
||||
ioRec++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
IO_t IOGetByTag(ioTag_t tag)
|
||||
{
|
||||
const int portIdx = DEFIO_TAG_GPIOID(tag);
|
||||
const int pinIdx = DEFIO_TAG_PIN(tag);
|
||||
|
||||
if (portIdx < 0 || portIdx >= DEFIO_PORT_USED_COUNT) {
|
||||
return NULL;
|
||||
}
|
||||
// check if pin exists
|
||||
if (!(ioDefUsedMask[portIdx] & (1 << pinIdx))) {
|
||||
return NULL;
|
||||
}
|
||||
// count bits before this pin on single port
|
||||
int offset = popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]);
|
||||
// and add port offset
|
||||
offset += ioDefUsedOffset[portIdx];
|
||||
return ioRecs + offset;
|
||||
}
|
||||
|
||||
void IOTraversePins(IOTraverseFuncPtr_t fnPtr)
|
||||
{
|
||||
for (int i = 0; i < DEFIO_IO_USED_COUNT; i++) {
|
||||
|
|
|
@ -147,6 +147,7 @@ endif
|
|||
|
||||
MCU_COMMON_SRC = \
|
||||
common/stm32/system.c \
|
||||
common/stm32/io_impl.c \
|
||||
APM32/startup/system_apm32f4xx.c \
|
||||
drivers/inverter.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
|
|
|
@ -82,6 +82,7 @@ DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32
|
|||
|
||||
MCU_COMMON_SRC = \
|
||||
common/stm32/system.c \
|
||||
common/stm32/io_impl.c \
|
||||
AT32/startup/at32f435_437_clock.c \
|
||||
AT32/startup/system_at32f435_437.c \
|
||||
AT32/adc_at32f43x.c \
|
||||
|
|
|
@ -757,3 +757,14 @@ void IOLo(IO_t io)
|
|||
{
|
||||
UNUSED(io);
|
||||
}
|
||||
|
||||
void IOInitGlobal(void)
|
||||
{
|
||||
// NOOP
|
||||
}
|
||||
|
||||
IO_t IOGetByTag(ioTag_t tag)
|
||||
{
|
||||
UNUSED(tag);
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -4,9 +4,12 @@ INCLUDE_DIRS += $(PLATFORM_DIR)/common/stm32
|
|||
MCU_COMMON_SRC += \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/io_impl.c
|
||||
|
||||
SIZE_OPTIMISED_SRC += \
|
||||
common/stm32/bus_spi_pinconfig.c
|
||||
|
||||
SPEED_OPTIMISED_SRC += \
|
||||
common/stm32/bus_spi_hw.c
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/io_impl.c
|
||||
|
||||
|
|
70
src/platform/common/stm32/io_impl.c
Normal file
70
src/platform/common/stm32/io_impl.c
Normal file
|
@ -0,0 +1,70 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the GNU General
|
||||
* Public License as published by the Free Software Foundation,
|
||||
* either version 3 of the License, or (at your option) any later
|
||||
* version.
|
||||
*
|
||||
* Betaflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
*
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public
|
||||
* License along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
|
||||
#if DEFIO_PORT_USED_COUNT > 0
|
||||
static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST };
|
||||
static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_OFFSET_LIST };
|
||||
#else
|
||||
// Avoid -Wpedantic warning
|
||||
static const uint16_t ioDefUsedMask[1] = {0};
|
||||
static const uint8_t ioDefUsedOffset[1] = {0};
|
||||
#endif
|
||||
|
||||
// initialize all ioRec_t structures from ROM
|
||||
// currently only bitmask is used, this may change in future
|
||||
void IOInitGlobal(void)
|
||||
{
|
||||
ioRec_t *ioRec = ioRecs;
|
||||
|
||||
for (unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++) {
|
||||
for (unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++) {
|
||||
if (ioDefUsedMask[port] & (1 << pin)) {
|
||||
ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart
|
||||
ioRec->pin = 1 << pin;
|
||||
ioRec++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
IO_t IOGetByTag(ioTag_t tag)
|
||||
{
|
||||
const int portIdx = DEFIO_TAG_GPIOID(tag);
|
||||
const int pinIdx = DEFIO_TAG_PIN(tag);
|
||||
|
||||
if (portIdx < 0 || portIdx >= DEFIO_PORT_USED_COUNT) {
|
||||
return NULL;
|
||||
}
|
||||
// check if pin exists
|
||||
if (!(ioDefUsedMask[portIdx] & (1 << pinIdx))) {
|
||||
return NULL;
|
||||
}
|
||||
// count bits before this pin on single port
|
||||
int offset = popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]);
|
||||
// and add port offset
|
||||
offset += ioDefUsedOffset[portIdx];
|
||||
return ioRecs + offset;
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue