1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 09:45:33 +03:00

Initial commit of new IO driver support

This commit is contained in:
Martin Budden 2016-06-16 19:12:02 +01:00
parent 57a33203a6
commit 295e7b3284
22 changed files with 1788 additions and 3 deletions

View file

@ -18,6 +18,7 @@
#pragma once
#include <stddef.h>
#include <stdint.h>
#define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0]))
@ -27,6 +28,14 @@
#define STR_HELPER(x) #x
#define STR(x) STR_HELPER(x)
#define EXPAND_I(x) x
#define EXPAND(x) EXPAND_I(x)
#define UNUSED(x) (void)(x)
#define BUILD_BUG_ON(condition) ((void)sizeof(char[1 - 2*!!(condition)]))
#define BIT(x) (1 << (x))
/*
http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html
*/
@ -35,6 +44,19 @@ http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html
#define UNUSED(x) (void)(x)
/*
* https://groups.google.com/forum/?hl=en#!msg/comp.lang.c/attFnqwhvGk/sGBKXvIkY3AJ
* Return (v ? floor(log2(v)) : 0) when 0 <= v < 1<<[8, 16, 32, 64].
* Inefficient algorithm, intended for compile-time constants.
*/
#define LOG2_8BIT(v) (8 - 90/(((v)/4+14)|1) - 2/((v)/2+1))
#define LOG2_16BIT(v) (8*((v)>255) + LOG2_8BIT((v) >>8*((v)>255)))
#define LOG2_32BIT(v) (16*((v)>65535L) + LOG2_16BIT((v)*1L >>16*((v)>65535L)))
#define LOG2_64BIT(v) \
(32*((v)/2L>>31 > 0) \
+ LOG2_32BIT((v)*1L >>16*((v)/2L>>31 > 0) \
>>16*((v)/2L>>31 > 0)))
#if 0
// ISO C version, but no type checking
#define container_of(ptr, type, member) \

310
src/main/drivers/io.c Normal file
View file

@ -0,0 +1,310 @@
#include "common/utils.h"
#include "io.h"
#include "io_impl.h"
#include "rcc.h"
#include "target.h"
// io ports defs are stored in array by index now
struct ioPortDef_s {
rccPeriphTag_t rcc;
};
#if defined(STM32F1)
const struct ioPortDef_s ioPortDefs[] = {
{ RCC_APB2(IOPA) },
{ RCC_APB2(IOPB) },
{ RCC_APB2(IOPC) },
{ RCC_APB2(IOPD) },
{ RCC_APB2(IOPE) },
{
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
RCC_APB2(IOPF),
#else
0,
#endif
},
{
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
RCC_APB2(IOPG),
#else
0,
#endif
},
};
#elif defined(STM32F3)
const struct ioPortDef_s ioPortDefs[] = {
{ RCC_AHB(GPIOA) },
{ RCC_AHB(GPIOB) },
{ RCC_AHB(GPIOC) },
{ RCC_AHB(GPIOD) },
{ RCC_AHB(GPIOE) },
{ RCC_AHB(GPIOF) },
};
#elif defined(STM32F4)
const struct ioPortDef_s ioPortDefs[] = {
{ RCC_AHB1(GPIOA) },
{ RCC_AHB1(GPIOB) },
{ RCC_AHB1(GPIOC) },
{ RCC_AHB1(GPIOD) },
{ RCC_AHB1(GPIOE) },
{ RCC_AHB1(GPIOF) },
};
# endif
ioRec_t* IO_Rec(IO_t io)
{
return io;
}
GPIO_TypeDef* IO_GPIO(IO_t io)
{
ioRec_t *ioRec = IO_Rec(io);
return ioRec->gpio;
}
uint16_t IO_Pin(IO_t io)
{
ioRec_t *ioRec = IO_Rec(io);
return ioRec->pin;
}
// port index, GPIOA == 0
int IO_GPIOPortIdx(IO_t io)
{
if (!io)
return -1;
return (((size_t)IO_GPIO(io) - GPIOA_BASE) >> 10); // ports are 0x400 apart
}
int IO_EXTI_PortSourceGPIO(IO_t io)
{
return IO_GPIOPortIdx(io);
}
int IO_GPIO_PortSource(IO_t io)
{
return IO_GPIOPortIdx(io);
}
// zero based pin index
int IO_GPIOPinIdx(IO_t io)
{
if (!io)
return -1;
return 31 - __builtin_clz(IO_Pin(io)); // CLZ is a bit faster than FFS
}
int IO_EXTI_PinSource(IO_t io)
{
return IO_GPIOPinIdx(io);
}
int IO_GPIO_PinSource(IO_t io)
{
return IO_GPIOPinIdx(io);
}
// mask on stm32f103, bit index on stm32f303
uint32_t IO_EXTI_Line(IO_t io)
{
if (!io)
return 0;
#if defined(STM32F1)
return 1 << IO_GPIOPinIdx(io);
#elif defined(STM32F3)
return IO_GPIOPinIdx(io);
#elif defined(STM32F4)
return 1 << IO_GPIOPinIdx(io);
#else
# error "Unknown target type"
#endif
}
bool IORead(IO_t io)
{
if (!io)
return false;
return !! (IO_GPIO(io)->IDR & IO_Pin(io));
}
void IOWrite(IO_t io, bool hi)
{
if (!io)
return;
#ifdef STM32F4
if (hi) {
IO_GPIO(io)->BSRRL = IO_Pin(io);
}
else {
IO_GPIO(io)->BSRRH = IO_Pin(io);
}
#else
IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16);
#endif
}
void IOHi(IO_t io)
{
if (!io)
return;
#ifdef STM32F4
IO_GPIO(io)->BSRRL = IO_Pin(io);
#else
IO_GPIO(io)->BSRR = IO_Pin(io);
#endif
}
void IOLo(IO_t io)
{
if (!io)
return;
#ifdef STM32F4
IO_GPIO(io)->BSRRH = IO_Pin(io);
#else
IO_GPIO(io)->BRR = IO_Pin(io);
#endif
}
void IOToggle(IO_t io)
{
if (!io)
return;
uint32_t mask = IO_Pin(io);
// 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
// setting other pins incorrectly because it change all pins' state.
#ifdef STM32F4
if (IO_GPIO(io)->ODR & mask) {
IO_GPIO(io)->BSRRH = mask;
} else {
IO_GPIO(io)->BSRRL = mask;
}
#else
if (IO_GPIO(io)->ODR & mask)
mask <<= 16; // bit is set, shift mask to reset half
IO_GPIO(io)->BSRR = mask;
#endif
}
// claim IO pin, set owner and resources
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources)
{
ioRec_t *ioRec = IO_Rec(io);
if (owner != OWNER_FREE) // pass OWNER_FREE to keep old owner
ioRec->owner = owner;
ioRec->resourcesUsed |= resources;
}
void IORelease(IO_t io)
{
ioRec_t *ioRec = IO_Rec(io);
ioRec->owner = OWNER_FREE;
}
resourceOwner_t IOGetOwner(IO_t io)
{
ioRec_t *ioRec = IO_Rec(io);
return ioRec->owner;
}
resourceType_t IOGetResources(IO_t io)
{
ioRec_t *ioRec = IO_Rec(io);
return ioRec->resourcesUsed;
}
#if defined(STM32F1)
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
{
if (!io)
return;
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
RCC_ClockCmd(rcc, ENABLE);
GPIO_InitTypeDef init = {
.GPIO_Pin = IO_Pin(io),
.GPIO_Speed = cfg & 0x03,
.GPIO_Mode = cfg & 0x7c,
};
GPIO_Init(IO_GPIO(io), &init);
}
#elif defined(STM32F3) || defined(STM32F4)
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
{
if (!io)
return;
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
RCC_ClockCmd(rcc, ENABLE);
GPIO_InitTypeDef init = {
.GPIO_Pin = IO_Pin(io),
.GPIO_Mode = (cfg >> 0) & 0x03,
.GPIO_Speed = (cfg >> 2) & 0x03,
.GPIO_OType = (cfg >> 4) & 0x01,
.GPIO_PuPd = (cfg >> 5) & 0x03,
};
GPIO_Init(IO_GPIO(io), &init);
}
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
{
if (!io)
return;
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
RCC_ClockCmd(rcc, ENABLE);
GPIO_PinAFConfig(IO_GPIO(io), IO_GPIO_PinSource(io), af);
GPIO_InitTypeDef init = {
.GPIO_Pin = IO_Pin(io),
.GPIO_Mode = (cfg >> 0) & 0x03,
.GPIO_Speed = (cfg >> 2) & 0x03,
.GPIO_OType = (cfg >> 4) & 0x01,
.GPIO_PuPd = (cfg >> 5) & 0x03,
};
GPIO_Init(IO_GPIO(io), &init);
}
#endif
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 };
ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
// 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)
{
int portIdx = DEFIO_TAG_GPIOID(tag);
int pinIdx = DEFIO_TAG_PIN(tag);
if (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 = __builtin_popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]);
// and add port offset
offset += ioDefUsedOffset[portIdx];
return ioRecs + offset;
}

98
src/main/drivers/io.h Normal file
View file

@ -0,0 +1,98 @@
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "resource.h"
// IO pin identification
// make sure that ioTag_t can't be assigned into IO_t without warning
typedef uint8_t ioTag_t; // packet tag to specify IO pin
typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
// NONE initializer for IO_t variable
#define IO_NONE ((IO_t)0)
// preprocessor is used to convert pinid to requested C data value
// compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx)
// ioTag_t and IO_t is supported, but ioTag_t is preferred
// expand pinid to to ioTag_t
#define IO_TAG(pinid) DEFIO_TAG(pinid)
// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin)
// this simplifies initialization (globals are zeroed on start) and allows
// omitting unused fields in structure initializers.
// it is also possible to use IO_t and ioTag_t as boolean value
// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment
// IO_t being pointer is only possibility I know of ..
// pin config handling
// pin config is packed into ioConfig_t to decrease memory requirements
// IOCFG_x macros are defined for common combinations for all CPUs; this
// helps masking CPU differences
typedef uint8_t ioConfig_t; // packed IO configuration
#if defined(STM32F1)
// mode is using only bits 6-2
#define IO_CONFIG(mode, speed) ((mode) | (speed))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_2MHz)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_2MHz)
#define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_2MHz)
#define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_2MHz)
#define IOCFG_IPD IO_CONFIG(GPIO_Mode_IPD, GPIO_Speed_2MHz)
#define IOCFG_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_2MHz)
#elif defined(STM32F3) || defined(STM32F4)
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO
#define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_UP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL)
#elif defined(UNIT_TEST)
# define IOCFG_OUT_PP 0
# define IOCFG_OUT_OD 0
# define IOCFG_AF_PP 0
# define IOCFG_AF_OD 0
# define IOCFG_IPD 0
# define IOCFG_IPU 0
# define IOCFG_IN_FLOATING 0
#else
# warning "Unknown TARGET"
#endif
// declare available IO pins. Available pins are specified per target
#include "io_def.h"
bool IORead(IO_t io);
void IOWrite(IO_t io, bool value);
void IOHi(IO_t io);
void IOLo(IO_t io);
void IOToggle(IO_t io);
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources);
void IORelease(IO_t io); // unimplemented
resourceOwner_t IOGetOwner(IO_t io);
resourceType_t IOGetResources(IO_t io);
IO_t IOGetByTag(ioTag_t tag);
void IOConfigGPIO(IO_t io, ioConfig_t cfg);
#if defined(STM32F3) || defined(STM32F4)
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af);
#endif
void IOInitGlobal(void);

35
src/main/drivers/io_def.h Normal file
View file

@ -0,0 +1,35 @@
#pragma once
#include "common/utils.h"
// return ioTag_t for given pinid
// tag for NONE must be false
#define DEFIO_TAG(pinid) CONCAT(DEFIO_TAG__, pinid)
#define DEFIO_TAG__NONE 0
#define DEFIO_TAG_E(pinid) CONCAT(DEFIO_TAG_E__, pinid)
#define DEFIO_TAG_E__NONE 0
// return ioRec_t or NULL for given pinid
// tags should be preferred, possibly removing it in future
// io_impl.h must be included when this macro is used
#define DEFIO_REC(pinid) CONCAT(DEFIO_REC__, pinid)
#define DEFIO_REC__NONE NULL
#define DEFIO_IO(pinid) (IO_t)DEFIO_REC(pinid)
// TODO - macro to check for pinid NONE (fully in preprocessor)
// get ioRec by index
#define DEFIO_REC_INDEXED(idx) (ioRecs + (idx))
// ioTag_t accessor macros
#define DEFIO_TAG_MAKE(gpioid, pin) ((((gpioid) + 1) << 4) | (pin))
#define DEFIO_TAG_ISEMPTY(tag) (!(tag))
#define DEFIO_TAG_GPIOID(tag) (((tag) >> 4) - 1)
#define DEFIO_TAG_PIN(tag) ((tag) & 0x0f)
// TARGET must define used pins
#include "target.h"
// include template-generated macros for IO pins
#include "io_def_generated.h"

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,38 @@
#pragma once
// TODO - GPIO_TypeDef include
#include "io.h"
#include "platform.h"
typedef struct ioDef_s {
ioTag_t tag;
} ioDef_t;
typedef struct ioRec_s {
GPIO_TypeDef *gpio;
uint16_t pin;
resourceOwner_t owner;
resourceType_t resourcesUsed; // TODO!
} ioRec_t;
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
int IO_GPIOPortIdx(IO_t io);
int IO_GPIOPinIdx(IO_t io);
int IO_GPIO_PinSource(IO_t io);
int IO_GPIO_PortSource(IO_t io);
#if defined(STM32F3) || defined(STM32F4)
int IO_EXTI_PortSourceGPIO(IO_t io);
int IO_EXTI_PinSource(IO_t io);
#endif
GPIO_TypeDef* IO_GPIO(IO_t io);
uint16_t IO_Pin(IO_t io);
#define IO_GPIOBYTAG(tag) IO_GPIO(IOGetByTag(tag))
#define IO_PINBYTAG(tag) IO_Pin(IOGetByTag(tag))
uint32_t IO_EXTI_Line(IO_t io);
ioRec_t *IO_Rec(IO_t io);

View file

@ -0,0 +1,43 @@
#pragma once
typedef enum {
OWNER_FREE = 0,
OWNER_PWMINPUT,
OWNER_PPMINPUT,
OWNER_PWMOUTPUT_MOTOR,
OWNER_PWMOUTPUT_SERVO,
OWNER_SOFTSERIAL_RX,
OWNER_SOFTSERIAL_TX,
OWNER_SOFTSERIAL_RXTX, // bidirectional pin for softserial
OWNER_SOFTSERIAL_AUXTIMER, // timer channel is used for softserial. No IO function on pin
OWNER_ADC,
OWNER_SERIAL_RX,
OWNER_SERIAL_TX,
OWNER_SERIAL_RXTX,
OWNER_PINDEBUG,
OWNER_TIMER,
OWNER_SONAR,
OWNER_SYSTEM,
OWNER_SDCARD,
OWNER_FLASH,
OWNER_USB,
OWNER_BEEPER
} resourceOwner_t;
// Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function)
// with mode switching (shared serial ports, ...) this will need some improvement
typedef enum {
RESOURCE_NONE = 0,
RESOURCE_INPUT = 1 << 0,
RESOURCE_OUTPUT = 1 << 1,
RESOURCE_IO = RESOURCE_INPUT | RESOURCE_OUTPUT,
RESOURCE_TIMER = 1 << 2,
RESOURCE_TIMER_DUAL = 1 << 3, // channel used in dual-capture, other channel will be allocated too
RESOURCE_USART = 1 << 4,
RESOURCE_ADC = 1 << 5,
RESOURCE_EXTI = 1 << 6,
RESOURCE_I2C = 1 << 7,
RESOURCE_SPI = 1 << 8,
} resourceType_t;

View file

@ -155,6 +155,13 @@
#undef TELEMETRY_SMARTPORT
#undef TELEMETRY_LTM
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -226,6 +226,11 @@
//#define USE_FAKE_BARO
//#define USE_FAKE_GPS
// IO - from schematics
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(14))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)

View file

@ -120,9 +120,18 @@
#define WS2811_IRQ DMA1_Channel2_IRQn
#endif
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB | RCC_AHBPeriph_GPIOC | RCC_AHBPeriph_GPIOD | RCC_AHBPeriph_GPIOF)

View file

@ -103,6 +103,11 @@
#undef SKIP_RX_MSP
// IO - assuming all IOs on 48pin package TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)

View file

@ -168,6 +168,12 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))

View file

@ -139,6 +139,12 @@
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
// IO - stm32f103RCT6 in 64pin package (TODO)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -157,6 +157,12 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))

View file

@ -57,7 +57,6 @@
//#define MAG
//#define USE_MAG_HMC5883
#define USE_VCP
#define USE_USART1
#define USE_USART2
@ -182,6 +181,13 @@
#undef GPS_PROTO_I2C_NAV
#undef GPS_PROTO_NAZA
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
// #define TARGET_IO_PORTF (BIT(0)|BIT(1))
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -250,9 +250,9 @@
#define BINDPLUG_PIN Pin_5
#endif // ALIENFLIGHTF1
#ifdef MICROSKYSKY
#ifdef MICROSCISKY
#undef TARGET_BOARD_IDENTIFIER
#define TARGET_BOARD_IDENTIFIER "MSKY" // Micro SKYsci
#define TARGET_BOARD_IDENTIFIER "MSKY" // Micro sciSKY
#define BRUSHED_MOTORS
#define USE_QUAD_MIXER_ONLY
#undef USE_SERVOS
@ -266,6 +266,12 @@
#undef TELEMETRY_SMARTPORT
// IO - assuming all IOs on 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)

View file

@ -113,6 +113,12 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
// IO - assuming all IOs on smt32f103rb LQFP64 package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -161,6 +161,12 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f103RCT6 in 64pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -179,6 +179,12 @@
#undef TELEMETRY_HOTT
#undef TELEMETRY_SMARTPORT
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))

View file

@ -165,6 +165,14 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
// available IO pins (from schematics)
//#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
//#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9))
// !!TODO - check following lines are correct
#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -177,8 +177,15 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View file

@ -92,6 +92,14 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - 303 in 100pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0x00ff
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17))