mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 08:15:30 +03:00
Changed tabs to spaces.
This commit is contained in:
parent
f0f7220ff2
commit
db07217afd
2 changed files with 148 additions and 148 deletions
|
@ -8,115 +8,115 @@
|
||||||
|
|
||||||
// io ports defs are stored in array by index now
|
// io ports defs are stored in array by index now
|
||||||
struct ioPortDef_s {
|
struct ioPortDef_s {
|
||||||
rccPeriphTag_t rcc;
|
rccPeriphTag_t rcc;
|
||||||
};
|
};
|
||||||
|
|
||||||
#if defined(STM32F1)
|
#if defined(STM32F1)
|
||||||
const struct ioPortDef_s ioPortDefs[] = {
|
const struct ioPortDef_s ioPortDefs[] = {
|
||||||
{ RCC_APB2(IOPA) },
|
{ RCC_APB2(IOPA) },
|
||||||
{ RCC_APB2(IOPB) },
|
{ RCC_APB2(IOPB) },
|
||||||
{ RCC_APB2(IOPC) },
|
{ RCC_APB2(IOPC) },
|
||||||
{ RCC_APB2(IOPD) },
|
{ RCC_APB2(IOPD) },
|
||||||
{ RCC_APB2(IOPE) },
|
{ RCC_APB2(IOPE) },
|
||||||
{
|
{
|
||||||
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
|
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
|
||||||
RCC_APB2(IOPF),
|
RCC_APB2(IOPF),
|
||||||
#else
|
#else
|
||||||
0,
|
0,
|
||||||
#endif
|
#endif
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
|
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
|
||||||
RCC_APB2(IOPG),
|
RCC_APB2(IOPG),
|
||||||
#else
|
#else
|
||||||
0,
|
0,
|
||||||
#endif
|
#endif
|
||||||
},
|
},
|
||||||
};
|
};
|
||||||
#elif defined(STM32F3)
|
#elif defined(STM32F3)
|
||||||
const struct ioPortDef_s ioPortDefs[] = {
|
const struct ioPortDef_s ioPortDefs[] = {
|
||||||
{ RCC_AHB(GPIOA) },
|
{ RCC_AHB(GPIOA) },
|
||||||
{ RCC_AHB(GPIOB) },
|
{ RCC_AHB(GPIOB) },
|
||||||
{ RCC_AHB(GPIOC) },
|
{ RCC_AHB(GPIOC) },
|
||||||
{ RCC_AHB(GPIOD) },
|
{ RCC_AHB(GPIOD) },
|
||||||
{ RCC_AHB(GPIOE) },
|
{ RCC_AHB(GPIOE) },
|
||||||
{ RCC_AHB(GPIOF) },
|
{ RCC_AHB(GPIOF) },
|
||||||
};
|
};
|
||||||
#elif defined(STM32F4)
|
#elif defined(STM32F4)
|
||||||
const struct ioPortDef_s ioPortDefs[] = {
|
const struct ioPortDef_s ioPortDefs[] = {
|
||||||
{ RCC_AHB1(GPIOA) },
|
{ RCC_AHB1(GPIOA) },
|
||||||
{ RCC_AHB1(GPIOB) },
|
{ RCC_AHB1(GPIOB) },
|
||||||
{ RCC_AHB1(GPIOC) },
|
{ RCC_AHB1(GPIOC) },
|
||||||
{ RCC_AHB1(GPIOD) },
|
{ RCC_AHB1(GPIOD) },
|
||||||
{ RCC_AHB1(GPIOE) },
|
{ RCC_AHB1(GPIOE) },
|
||||||
{ RCC_AHB1(GPIOF) },
|
{ RCC_AHB1(GPIOF) },
|
||||||
};
|
};
|
||||||
# endif
|
# endif
|
||||||
|
|
||||||
ioRec_t* IO_Rec(IO_t io)
|
ioRec_t* IO_Rec(IO_t io)
|
||||||
{
|
{
|
||||||
return io;
|
return io;
|
||||||
}
|
}
|
||||||
|
|
||||||
GPIO_TypeDef* IO_GPIO(IO_t io)
|
GPIO_TypeDef* IO_GPIO(IO_t io)
|
||||||
{
|
{
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
ioRec_t *ioRec = IO_Rec(io);
|
||||||
return ioRec->gpio;
|
return ioRec->gpio;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t IO_Pin(IO_t io)
|
uint16_t IO_Pin(IO_t io)
|
||||||
{
|
{
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
ioRec_t *ioRec = IO_Rec(io);
|
||||||
return ioRec->pin;
|
return ioRec->pin;
|
||||||
}
|
}
|
||||||
|
|
||||||
// port index, GPIOA == 0
|
// port index, GPIOA == 0
|
||||||
int IO_GPIOPortIdx(IO_t io)
|
int IO_GPIOPortIdx(IO_t io)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return -1;
|
return -1;
|
||||||
return (((size_t)IO_GPIO(io) - GPIOA_BASE) >> 10); // ports are 0x400 apart
|
return (((size_t)IO_GPIO(io) - GPIOA_BASE) >> 10); // ports are 0x400 apart
|
||||||
}
|
}
|
||||||
|
|
||||||
int IO_EXTI_PortSourceGPIO(IO_t io)
|
int IO_EXTI_PortSourceGPIO(IO_t io)
|
||||||
{
|
{
|
||||||
return IO_GPIOPortIdx(io);
|
return IO_GPIOPortIdx(io);
|
||||||
}
|
}
|
||||||
|
|
||||||
int IO_GPIO_PortSource(IO_t io)
|
int IO_GPIO_PortSource(IO_t io)
|
||||||
{
|
{
|
||||||
return IO_GPIOPortIdx(io);
|
return IO_GPIOPortIdx(io);
|
||||||
}
|
}
|
||||||
|
|
||||||
// zero based pin index
|
// zero based pin index
|
||||||
int IO_GPIOPinIdx(IO_t io)
|
int IO_GPIOPinIdx(IO_t io)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return -1;
|
return -1;
|
||||||
return 31 - __builtin_clz(IO_Pin(io)); // CLZ is a bit faster than FFS
|
return 31 - __builtin_clz(IO_Pin(io)); // CLZ is a bit faster than FFS
|
||||||
}
|
}
|
||||||
|
|
||||||
int IO_EXTI_PinSource(IO_t io)
|
int IO_EXTI_PinSource(IO_t io)
|
||||||
{
|
{
|
||||||
return IO_GPIOPinIdx(io);
|
return IO_GPIOPinIdx(io);
|
||||||
}
|
}
|
||||||
|
|
||||||
int IO_GPIO_PinSource(IO_t io)
|
int IO_GPIO_PinSource(IO_t io)
|
||||||
{
|
{
|
||||||
return IO_GPIOPinIdx(io);
|
return IO_GPIOPinIdx(io);
|
||||||
}
|
}
|
||||||
|
|
||||||
// mask on stm32f103, bit index on stm32f303
|
// mask on stm32f103, bit index on stm32f303
|
||||||
uint32_t IO_EXTI_Line(IO_t io)
|
uint32_t IO_EXTI_Line(IO_t io)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return 0;
|
return 0;
|
||||||
#if defined(STM32F1)
|
#if defined(STM32F1)
|
||||||
return 1 << IO_GPIOPinIdx(io);
|
return 1 << IO_GPIOPinIdx(io);
|
||||||
#elif defined(STM32F3)
|
#elif defined(STM32F3)
|
||||||
return IO_GPIOPinIdx(io);
|
return IO_GPIOPinIdx(io);
|
||||||
#elif defined(STM32F4)
|
#elif defined(STM32F4)
|
||||||
return 1 << IO_GPIOPinIdx(io);
|
return 1 << IO_GPIOPinIdx(io);
|
||||||
#else
|
#else
|
||||||
# error "Unknown target type"
|
# error "Unknown target type"
|
||||||
#endif
|
#endif
|
||||||
|
@ -124,151 +124,151 @@ uint32_t IO_EXTI_Line(IO_t io)
|
||||||
|
|
||||||
bool IORead(IO_t io)
|
bool IORead(IO_t io)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return false;
|
return false;
|
||||||
return !! (IO_GPIO(io)->IDR & IO_Pin(io));
|
return !! (IO_GPIO(io)->IDR & IO_Pin(io));
|
||||||
}
|
}
|
||||||
|
|
||||||
void IOWrite(IO_t io, bool hi)
|
void IOWrite(IO_t io, bool hi)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return;
|
return;
|
||||||
#ifdef STM32F4
|
#ifdef STM32F4
|
||||||
if (hi) {
|
if (hi) {
|
||||||
IO_GPIO(io)->BSRRL = IO_Pin(io);
|
IO_GPIO(io)->BSRRL = IO_Pin(io);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
IO_GPIO(io)->BSRRH = IO_Pin(io);
|
IO_GPIO(io)->BSRRH = IO_Pin(io);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16);
|
IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void IOHi(IO_t io)
|
void IOHi(IO_t io)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return;
|
return;
|
||||||
#ifdef STM32F4
|
#ifdef STM32F4
|
||||||
IO_GPIO(io)->BSRRL = IO_Pin(io);
|
IO_GPIO(io)->BSRRL = IO_Pin(io);
|
||||||
#else
|
#else
|
||||||
IO_GPIO(io)->BSRR = IO_Pin(io);
|
IO_GPIO(io)->BSRR = IO_Pin(io);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void IOLo(IO_t io)
|
void IOLo(IO_t io)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return;
|
return;
|
||||||
#ifdef STM32F4
|
#ifdef STM32F4
|
||||||
IO_GPIO(io)->BSRRH = IO_Pin(io);
|
IO_GPIO(io)->BSRRH = IO_Pin(io);
|
||||||
#else
|
#else
|
||||||
IO_GPIO(io)->BRR = IO_Pin(io);
|
IO_GPIO(io)->BRR = IO_Pin(io);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void IOToggle(IO_t io)
|
void IOToggle(IO_t io)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return;
|
return;
|
||||||
uint32_t mask = IO_Pin(io);
|
uint32_t mask = IO_Pin(io);
|
||||||
// Read pin state from ODR but write to BSRR because it only changes the pins
|
// Read pin state from ODR but write to BSRR because it only changes the pins
|
||||||
// high in the mask value rather than all pins. XORing ODR directly risks
|
// high in the mask value rather than all pins. XORing ODR directly risks
|
||||||
// setting other pins incorrectly because it change all pins' state.
|
// setting other pins incorrectly because it change all pins' state.
|
||||||
#ifdef STM32F4
|
#ifdef STM32F4
|
||||||
if (IO_GPIO(io)->ODR & mask) {
|
if (IO_GPIO(io)->ODR & mask) {
|
||||||
IO_GPIO(io)->BSRRH = mask;
|
IO_GPIO(io)->BSRRH = mask;
|
||||||
} else {
|
} else {
|
||||||
IO_GPIO(io)->BSRRL = mask;
|
IO_GPIO(io)->BSRRL = mask;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
if (IO_GPIO(io)->ODR & mask)
|
if (IO_GPIO(io)->ODR & mask)
|
||||||
mask <<= 16; // bit is set, shift mask to reset half
|
mask <<= 16; // bit is set, shift mask to reset half
|
||||||
|
|
||||||
IO_GPIO(io)->BSRR = mask;
|
IO_GPIO(io)->BSRR = mask;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// claim IO pin, set owner and resources
|
// claim IO pin, set owner and resources
|
||||||
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources)
|
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources)
|
||||||
{
|
{
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
ioRec_t *ioRec = IO_Rec(io);
|
||||||
if (owner != OWNER_FREE) // pass OWNER_FREE to keep old owner
|
if (owner != OWNER_FREE) // pass OWNER_FREE to keep old owner
|
||||||
ioRec->owner = owner;
|
ioRec->owner = owner;
|
||||||
ioRec->resourcesUsed |= resources;
|
ioRec->resourcesUsed |= resources;
|
||||||
}
|
}
|
||||||
|
|
||||||
void IORelease(IO_t io)
|
void IORelease(IO_t io)
|
||||||
{
|
{
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
ioRec_t *ioRec = IO_Rec(io);
|
||||||
ioRec->owner = OWNER_FREE;
|
ioRec->owner = OWNER_FREE;
|
||||||
}
|
}
|
||||||
|
|
||||||
resourceOwner_t IOGetOwner(IO_t io)
|
resourceOwner_t IOGetOwner(IO_t io)
|
||||||
{
|
{
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
ioRec_t *ioRec = IO_Rec(io);
|
||||||
return ioRec->owner;
|
return ioRec->owner;
|
||||||
}
|
}
|
||||||
|
|
||||||
resourceType_t IOGetResources(IO_t io)
|
resourceType_t IOGetResources(IO_t io)
|
||||||
{
|
{
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
ioRec_t *ioRec = IO_Rec(io);
|
||||||
return ioRec->resourcesUsed;
|
return ioRec->resourcesUsed;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(STM32F1)
|
#if defined(STM32F1)
|
||||||
|
|
||||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return;
|
return;
|
||||||
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||||
RCC_ClockCmd(rcc, ENABLE);
|
RCC_ClockCmd(rcc, ENABLE);
|
||||||
|
|
||||||
GPIO_InitTypeDef init = {
|
GPIO_InitTypeDef init = {
|
||||||
.GPIO_Pin = IO_Pin(io),
|
.GPIO_Pin = IO_Pin(io),
|
||||||
.GPIO_Speed = cfg & 0x03,
|
.GPIO_Speed = cfg & 0x03,
|
||||||
.GPIO_Mode = cfg & 0x7c,
|
.GPIO_Mode = cfg & 0x7c,
|
||||||
};
|
};
|
||||||
GPIO_Init(IO_GPIO(io), &init);
|
GPIO_Init(IO_GPIO(io), &init);
|
||||||
}
|
}
|
||||||
|
|
||||||
#elif defined(STM32F3) || defined(STM32F4)
|
#elif defined(STM32F3) || defined(STM32F4)
|
||||||
|
|
||||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return;
|
return;
|
||||||
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||||
RCC_ClockCmd(rcc, ENABLE);
|
RCC_ClockCmd(rcc, ENABLE);
|
||||||
|
|
||||||
GPIO_InitTypeDef init = {
|
GPIO_InitTypeDef init = {
|
||||||
.GPIO_Pin = IO_Pin(io),
|
.GPIO_Pin = IO_Pin(io),
|
||||||
.GPIO_Mode = (cfg >> 0) & 0x03,
|
.GPIO_Mode = (cfg >> 0) & 0x03,
|
||||||
.GPIO_Speed = (cfg >> 2) & 0x03,
|
.GPIO_Speed = (cfg >> 2) & 0x03,
|
||||||
.GPIO_OType = (cfg >> 4) & 0x01,
|
.GPIO_OType = (cfg >> 4) & 0x01,
|
||||||
.GPIO_PuPd = (cfg >> 5) & 0x03,
|
.GPIO_PuPd = (cfg >> 5) & 0x03,
|
||||||
};
|
};
|
||||||
GPIO_Init(IO_GPIO(io), &init);
|
GPIO_Init(IO_GPIO(io), &init);
|
||||||
}
|
}
|
||||||
|
|
||||||
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
||||||
{
|
{
|
||||||
if (!io)
|
if (!io)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||||
RCC_ClockCmd(rcc, ENABLE);
|
RCC_ClockCmd(rcc, ENABLE);
|
||||||
GPIO_PinAFConfig(IO_GPIO(io), IO_GPIO_PinSource(io), af);
|
GPIO_PinAFConfig(IO_GPIO(io), IO_GPIO_PinSource(io), af);
|
||||||
|
|
||||||
GPIO_InitTypeDef init = {
|
GPIO_InitTypeDef init = {
|
||||||
.GPIO_Pin = IO_Pin(io),
|
.GPIO_Pin = IO_Pin(io),
|
||||||
.GPIO_Mode = (cfg >> 0) & 0x03,
|
.GPIO_Mode = (cfg >> 0) & 0x03,
|
||||||
.GPIO_Speed = (cfg >> 2) & 0x03,
|
.GPIO_Speed = (cfg >> 2) & 0x03,
|
||||||
.GPIO_OType = (cfg >> 4) & 0x01,
|
.GPIO_OType = (cfg >> 4) & 0x01,
|
||||||
.GPIO_PuPd = (cfg >> 5) & 0x03,
|
.GPIO_PuPd = (cfg >> 5) & 0x03,
|
||||||
};
|
};
|
||||||
GPIO_Init(IO_GPIO(io), &init);
|
GPIO_Init(IO_GPIO(io), &init);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -279,32 +279,32 @@ ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
||||||
// initialize all ioRec_t structures from ROM
|
// initialize all ioRec_t structures from ROM
|
||||||
// currently only bitmask is used, this may change in future
|
// currently only bitmask is used, this may change in future
|
||||||
void IOInitGlobal(void) {
|
void IOInitGlobal(void) {
|
||||||
ioRec_t *ioRec = ioRecs;
|
ioRec_t *ioRec = ioRecs;
|
||||||
|
|
||||||
for (unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++) {
|
for (unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++) {
|
||||||
for (unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++) {
|
for (unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++) {
|
||||||
if (ioDefUsedMask[port] & (1 << pin)) {
|
if (ioDefUsedMask[port] & (1 << pin)) {
|
||||||
ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart
|
ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart
|
||||||
ioRec->pin = 1 << pin;
|
ioRec->pin = 1 << pin;
|
||||||
ioRec++;
|
ioRec++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
IO_t IOGetByTag(ioTag_t tag)
|
IO_t IOGetByTag(ioTag_t tag)
|
||||||
{
|
{
|
||||||
int portIdx = DEFIO_TAG_GPIOID(tag);
|
int portIdx = DEFIO_TAG_GPIOID(tag);
|
||||||
int pinIdx = DEFIO_TAG_PIN(tag);
|
int pinIdx = DEFIO_TAG_PIN(tag);
|
||||||
|
|
||||||
if (portIdx >= DEFIO_PORT_USED_COUNT)
|
if (portIdx >= DEFIO_PORT_USED_COUNT)
|
||||||
return NULL;
|
return NULL;
|
||||||
// check if pin exists
|
// check if pin exists
|
||||||
if (!(ioDefUsedMask[portIdx] & (1 << pinIdx)))
|
if (!(ioDefUsedMask[portIdx] & (1 << pinIdx)))
|
||||||
return NULL;
|
return NULL;
|
||||||
// count bits before this pin on single port
|
// count bits before this pin on single port
|
||||||
int offset = __builtin_popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]);
|
int offset = __builtin_popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]);
|
||||||
// and add port offset
|
// and add port offset
|
||||||
offset += ioDefUsedOffset[portIdx];
|
offset += ioDefUsedOffset[portIdx];
|
||||||
return ioRecs + offset;
|
return ioRecs + offset;
|
||||||
}
|
}
|
||||||
|
|
|
@ -5,14 +5,14 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
typedef struct ioDef_s {
|
typedef struct ioDef_s {
|
||||||
ioTag_t tag;
|
ioTag_t tag;
|
||||||
} ioDef_t;
|
} ioDef_t;
|
||||||
|
|
||||||
typedef struct ioRec_s {
|
typedef struct ioRec_s {
|
||||||
GPIO_TypeDef *gpio;
|
GPIO_TypeDef *gpio;
|
||||||
uint16_t pin;
|
uint16_t pin;
|
||||||
resourceOwner_t owner;
|
resourceOwner_t owner;
|
||||||
resourceType_t resourcesUsed; // TODO!
|
resourceType_t resourcesUsed; // TODO!
|
||||||
} ioRec_t;
|
} ioRec_t;
|
||||||
|
|
||||||
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue