mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
Converted tabs to spaces
This commit is contained in:
parent
adfa6c4f28
commit
ea283ab98c
63 changed files with 297 additions and 297 deletions
|
@ -87,7 +87,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
||||||
putf(putp, ch); written++;
|
putf(putp, ch); written++;
|
||||||
} else {
|
} else {
|
||||||
char lz = 0;
|
char lz = 0;
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
char lng = 0;
|
char lng = 0;
|
||||||
#endif
|
#endif
|
||||||
int w = 0;
|
int w = 0;
|
||||||
|
@ -99,7 +99,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
||||||
if (ch >= '0' && ch <= '9') {
|
if (ch >= '0' && ch <= '9') {
|
||||||
ch = a2i(ch, &fmt, 10, &w);
|
ch = a2i(ch, &fmt, 10, &w);
|
||||||
}
|
}
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
if (ch == 'l') {
|
if (ch == 'l') {
|
||||||
ch = *(fmt++);
|
ch = *(fmt++);
|
||||||
lng = 1;
|
lng = 1;
|
||||||
|
@ -109,7 +109,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
||||||
case 0:
|
case 0:
|
||||||
goto abort;
|
goto abort;
|
||||||
case 'u':{
|
case 'u':{
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
if (lng)
|
if (lng)
|
||||||
uli2a(va_arg(va, unsigned long int), 10, 0, bf);
|
uli2a(va_arg(va, unsigned long int), 10, 0, bf);
|
||||||
else
|
else
|
||||||
|
@ -119,7 +119,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case 'd':{
|
case 'd':{
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
if (lng)
|
if (lng)
|
||||||
li2a(va_arg(va, unsigned long int), bf);
|
li2a(va_arg(va, unsigned long int), bf);
|
||||||
else
|
else
|
||||||
|
@ -130,7 +130,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
||||||
}
|
}
|
||||||
case 'x':
|
case 'x':
|
||||||
case 'X':
|
case 'X':
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
if (lng)
|
if (lng)
|
||||||
uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf);
|
uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf);
|
||||||
else
|
else
|
||||||
|
|
|
@ -66,10 +66,10 @@ To use the printf you need to supply your own character output function,
|
||||||
something like :
|
something like :
|
||||||
|
|
||||||
void putc ( void* p, char c)
|
void putc ( void* p, char c)
|
||||||
{
|
{
|
||||||
while (!SERIAL_PORT_EMPTY) ;
|
while (!SERIAL_PORT_EMPTY) ;
|
||||||
SERIAL_PORT_TX_REGISTER = c;
|
SERIAL_PORT_TX_REGISTER = c;
|
||||||
}
|
}
|
||||||
|
|
||||||
Before you can call printf you need to initialize it to use your
|
Before you can call printf you need to initialize it to use your
|
||||||
character output function with something like:
|
character output function with something like:
|
||||||
|
|
|
@ -134,7 +134,7 @@ void adcInit(drv_adc_config_t *init)
|
||||||
if (!adcConfig[i].tag)
|
if (!adcConfig[i].tag)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0);
|
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0);
|
||||||
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||||
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
||||||
adcConfig[i].dmaIndex = configuredAdcChannels++;
|
adcConfig[i].dmaIndex = configuredAdcChannels++;
|
||||||
|
|
|
@ -385,8 +385,8 @@ void i2cInit(I2CDevice device)
|
||||||
IO_t scl = IOGetByTag(i2c->scl);
|
IO_t scl = IOGetByTag(i2c->scl);
|
||||||
IO_t sda = IOGetByTag(i2c->sda);
|
IO_t sda = IOGetByTag(i2c->sda);
|
||||||
|
|
||||||
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
||||||
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
||||||
|
|
||||||
// Enable RCC
|
// Enable RCC
|
||||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||||
|
|
|
@ -92,10 +92,10 @@ void i2cInit(I2CDevice device)
|
||||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||||
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||||
|
|
||||||
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
|
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
|
||||||
|
|
||||||
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
|
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
|
||||||
|
|
||||||
I2C_InitTypeDef i2cInit = {
|
I2C_InitTypeDef i2cInit = {
|
||||||
|
|
|
@ -114,8 +114,8 @@ void spiInitDevice(SPIDevice device)
|
||||||
RCC_ResetCmd(spi->rcc, ENABLE);
|
RCC_ResetCmd(spi->rcc, ENABLE);
|
||||||
|
|
||||||
IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1);
|
IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1);
|
||||||
IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1);
|
IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1);
|
||||||
IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1);
|
IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1);
|
||||||
|
|
||||||
#if defined(STM32F3) || defined(STM32F4)
|
#if defined(STM32F3) || defined(STM32F4)
|
||||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
||||||
|
|
|
@ -13,7 +13,7 @@ typedef struct ioRec_s {
|
||||||
uint16_t pin;
|
uint16_t pin;
|
||||||
resourceOwner_t owner;
|
resourceOwner_t owner;
|
||||||
resourceType_t resource;
|
resourceType_t resource;
|
||||||
uint8_t index;
|
uint8_t index;
|
||||||
} ioRec_t;
|
} ioRec_t;
|
||||||
|
|
||||||
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
||||||
|
|
|
@ -82,25 +82,25 @@ uint8_t ledOffset = 0;
|
||||||
|
|
||||||
void ledInit(bool alternative_led)
|
void ledInit(bool alternative_led)
|
||||||
{
|
{
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
|
|
||||||
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
||||||
if (alternative_led)
|
if (alternative_led)
|
||||||
ledOffset = LED_NUMBER;
|
ledOffset = LED_NUMBER;
|
||||||
#else
|
#else
|
||||||
UNUSED(alternative_led);
|
UNUSED(alternative_led);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
LED2_OFF;
|
LED2_OFF;
|
||||||
|
|
||||||
for (i = 0; i < LED_NUMBER; i++) {
|
for (i = 0; i < LED_NUMBER; i++) {
|
||||||
if (leds[i + ledOffset]) {
|
if (leds[i + ledOffset]) {
|
||||||
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
|
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
|
||||||
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
|
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
|
@ -109,11 +109,11 @@ void ledInit(bool alternative_led)
|
||||||
|
|
||||||
void ledToggle(int led)
|
void ledToggle(int led)
|
||||||
{
|
{
|
||||||
IOToggle(leds[led + ledOffset]);
|
IOToggle(leds[led + ledOffset]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ledSet(int led, bool on)
|
void ledSet(int led, bool on)
|
||||||
{
|
{
|
||||||
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
|
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
|
||||||
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
|
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
|
||||||
}
|
}
|
||||||
|
|
|
@ -69,7 +69,7 @@ void ws2811LedStripHardwareInit(void)
|
||||||
|
|
||||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
||||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
||||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
|
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
|
||||||
|
|
||||||
// Stop timer
|
// Stop timer
|
||||||
|
|
|
@ -90,9 +90,9 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
|
||||||
|
|
||||||
configTimeBase(timerHardware->tim, period, mhz);
|
configTimeBase(timerHardware->tim, period, mhz);
|
||||||
|
|
||||||
IO_t io = IOGetByTag(timerHardware->tag);
|
IO_t io = IOGetByTag(timerHardware->tag);
|
||||||
IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount);
|
IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount);
|
||||||
IOConfigGPIO(io, IOCFG_AF_PP);
|
IOConfigGPIO(io, IOCFG_AF_PP);
|
||||||
|
|
||||||
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED);
|
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED);
|
||||||
|
|
||||||
|
|
|
@ -366,9 +366,9 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)
|
||||||
self->mode = INPUT_MODE_PWM;
|
self->mode = INPUT_MODE_PWM;
|
||||||
self->timerHardware = timerHardwarePtr;
|
self->timerHardware = timerHardwarePtr;
|
||||||
|
|
||||||
IO_t io = IOGetByTag(timerHardwarePtr->tag);
|
IO_t io = IOGetByTag(timerHardwarePtr->tag);
|
||||||
IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel));
|
IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel));
|
||||||
IOConfigGPIO(io, timerHardwarePtr->ioMode);
|
IOConfigGPIO(io, timerHardwarePtr->ioMode);
|
||||||
|
|
||||||
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
|
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
|
||||||
|
|
||||||
|
@ -398,9 +398,9 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr)
|
||||||
self->mode = INPUT_MODE_PPM;
|
self->mode = INPUT_MODE_PPM;
|
||||||
self->timerHardware = timerHardwarePtr;
|
self->timerHardware = timerHardwarePtr;
|
||||||
|
|
||||||
IO_t io = IOGetByTag(timerHardwarePtr->tag);
|
IO_t io = IOGetByTag(timerHardwarePtr->tag);
|
||||||
IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0);
|
IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0);
|
||||||
IOConfigGPIO(io, timerHardwarePtr->ioMode);
|
IOConfigGPIO(io, timerHardwarePtr->ioMode);
|
||||||
|
|
||||||
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
|
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
|
||||||
|
|
||||||
|
|
|
@ -102,18 +102,18 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state)
|
||||||
|
|
||||||
void serialInputPortConfig(ioTag_t pin, uint8_t portIndex)
|
void serialInputPortConfig(ioTag_t pin, uint8_t portIndex)
|
||||||
{
|
{
|
||||||
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex));
|
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex));
|
||||||
#ifdef STM32F1
|
#ifdef STM32F1
|
||||||
IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU);
|
IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU);
|
||||||
#else
|
#else
|
||||||
IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP);
|
IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex)
|
static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex)
|
||||||
{
|
{
|
||||||
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex));
|
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex));
|
||||||
IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP);
|
IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
|
static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
|
||||||
|
@ -218,7 +218,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
||||||
serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex);
|
serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex);
|
||||||
|
|
||||||
softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag);
|
softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag);
|
||||||
serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex);
|
serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex);
|
||||||
|
|
||||||
setTxSignal(softSerial, ENABLE);
|
setTxSignal(softSerial, ENABLE);
|
||||||
delay(50);
|
delay(50);
|
||||||
|
|
|
@ -207,7 +207,7 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2);
|
IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU);
|
IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -260,16 +260,16 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
RCC_ClockCmd(RCC_APB1(USART3), ENABLE);
|
RCC_ClockCmd(RCC_APB1(USART3), ENABLE);
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
if (options & SERIAL_BIDIR) {
|
||||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3);
|
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD);
|
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD);
|
||||||
} else {
|
} else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3);
|
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP);
|
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3);
|
IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU);
|
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -120,7 +120,7 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index);
|
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index);
|
||||||
IOConfigGPIOAF(rx, ioCfg, af);
|
IOConfigGPIOAF(rx, ioCfg, af);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -312,17 +312,17 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
||||||
RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE);
|
RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE);
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
if (options & SERIAL_BIDIR) {
|
||||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
|
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
|
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
|
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
|
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -88,7 +88,7 @@ void hcsr04_init(sonarRange_t *sonarRange)
|
||||||
|
|
||||||
// echo pin
|
// echo pin
|
||||||
echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag);
|
echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag);
|
||||||
IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0);
|
IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0);
|
||||||
IOConfigGPIO(echoIO, IOCFG_IN_FLOATING);
|
IOConfigGPIO(echoIO, IOCFG_IN_FLOATING);
|
||||||
|
|
||||||
#ifdef USE_EXTI
|
#ifdef USE_EXTI
|
||||||
|
|
|
@ -69,7 +69,7 @@ bool isMPUSoftReset(void)
|
||||||
|
|
||||||
void systemInit(void)
|
void systemInit(void)
|
||||||
{
|
{
|
||||||
checkForBootLoaderRequest();
|
checkForBootLoaderRequest();
|
||||||
|
|
||||||
SetSysClock(false);
|
SetSysClock(false);
|
||||||
|
|
||||||
|
|
|
@ -83,7 +83,7 @@ bool isMPUSoftReset(void)
|
||||||
|
|
||||||
void systemInit(void)
|
void systemInit(void)
|
||||||
{
|
{
|
||||||
checkForBootLoaderRequest();
|
checkForBootLoaderRequest();
|
||||||
|
|
||||||
// Enable FPU
|
// Enable FPU
|
||||||
SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2));
|
SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2));
|
||||||
|
|
|
@ -169,7 +169,7 @@ bool isMPUSoftReset(void)
|
||||||
|
|
||||||
void systemInit(void)
|
void systemInit(void)
|
||||||
{
|
{
|
||||||
checkForBootLoaderRequest();
|
checkForBootLoaderRequest();
|
||||||
|
|
||||||
SetSysClock();
|
SetSysClock();
|
||||||
|
|
||||||
|
@ -199,15 +199,15 @@ void systemInit(void)
|
||||||
void(*bootJump)(void);
|
void(*bootJump)(void);
|
||||||
void checkForBootLoaderRequest(void)
|
void checkForBootLoaderRequest(void)
|
||||||
{
|
{
|
||||||
if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) {
|
if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) {
|
||||||
|
|
||||||
*((uint32_t *)0x2001FFFC) = 0x0;
|
*((uint32_t *)0x2001FFFC) = 0x0;
|
||||||
|
|
||||||
__enable_irq();
|
__enable_irq();
|
||||||
__set_MSP(0x20001000);
|
__set_MSP(0x20001000);
|
||||||
|
|
||||||
bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004));
|
bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004));
|
||||||
bootJump();
|
bootJump();
|
||||||
while (1);
|
while (1);
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -52,12 +52,12 @@ extern uint8_t motorCount;
|
||||||
****************************************************************************
|
****************************************************************************
|
||||||
*** G_Tune ***
|
*** G_Tune ***
|
||||||
****************************************************************************
|
****************************************************************************
|
||||||
G_Tune Mode
|
G_Tune Mode
|
||||||
This is the multiwii implementation of ZERO-PID Algorithm
|
This is the multiwii implementation of ZERO-PID Algorithm
|
||||||
http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html
|
http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html
|
||||||
The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com)
|
The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com)
|
||||||
|
|
||||||
You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution.
|
You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -107,13 +107,13 @@ void init_Gtune(pidProfile_t *pidProfileToTune)
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
|
||||||
pidProfile = pidProfileToTune;
|
pidProfile = pidProfileToTune;
|
||||||
if (pidProfile->pidController == 2) {
|
if (pidProfile->pidController == 2) {
|
||||||
floatPID = true; // LuxFloat is using float values for PID settings
|
floatPID = true; // LuxFloat is using float values for PID settings
|
||||||
} else {
|
} else {
|
||||||
floatPID = false;
|
floatPID = false;
|
||||||
}
|
}
|
||||||
updateDelayCycles();
|
updateDelayCycles();
|
||||||
for (i = 0; i < 3; i++) {
|
for (i = 0; i < 3; i++) {
|
||||||
if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning
|
if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning
|
||||||
pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter
|
pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter
|
||||||
}
|
}
|
||||||
|
|
|
@ -901,7 +901,7 @@ void mixTable(void)
|
||||||
|
|
||||||
/*
|
/*
|
||||||
case MIXER_GIMBAL:
|
case MIXER_GIMBAL:
|
||||||
servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH);
|
servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH);
|
||||||
servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL);
|
servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL);
|
||||||
break;
|
break;
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -166,7 +166,7 @@ void init(void)
|
||||||
//i2cSetOverclock(masterConfig.i2c_overclock);
|
//i2cSetOverclock(masterConfig.i2c_overclock);
|
||||||
|
|
||||||
// initialize IO (needed for all IO operations)
|
// initialize IO (needed for all IO operations)
|
||||||
IOInitGlobal();
|
IOInitGlobal();
|
||||||
|
|
||||||
debugMode = masterConfig.debug_mode;
|
debugMode = masterConfig.debug_mode;
|
||||||
|
|
||||||
|
@ -363,7 +363,7 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
if (masterConfig.use_buzzer_p6 == 1)
|
if (masterConfig.use_buzzer_p6 == 1)
|
||||||
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
|
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
beeperInit(&beeperConfig);
|
beeperInit(&beeperConfig);
|
||||||
|
|
|
@ -591,10 +591,10 @@ void updateRSSIPWM(void)
|
||||||
// Read value of AUX channel as rssi
|
// Read value of AUX channel as rssi
|
||||||
pwmRssi = rcData[rxConfig->rssi_channel - 1];
|
pwmRssi = rcData[rxConfig->rssi_channel - 1];
|
||||||
|
|
||||||
// RSSI_Invert option
|
// RSSI_Invert option
|
||||||
if (rxConfig->rssi_ppm_invert) {
|
if (rxConfig->rssi_ppm_invert) {
|
||||||
pwmRssi = ((2000 - pwmRssi) + 1000);
|
pwmRssi = ((2000 - pwmRssi) + 1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
|
// Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
|
||||||
rssi = (uint16_t)((constrain(pwmRssi - 1000, 0, 1000) / 1000.0f) * 1023.0f);
|
rssi = (uint16_t)((constrain(pwmRssi - 1000, 0, 1000) / 1000.0f) * 1023.0f);
|
||||||
|
|
|
@ -245,7 +245,7 @@ void spektrumBind(rxConfig_t *rxConfig)
|
||||||
#ifndef HARDWARE_BIND_PLUG
|
#ifndef HARDWARE_BIND_PLUG
|
||||||
// If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config
|
// If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config
|
||||||
// Don't reset if hardware bind plug is present
|
// Don't reset if hardware bind plug is present
|
||||||
// Reset only when autoreset is enabled
|
// Reset only when autoreset is enabled
|
||||||
if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) {
|
if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) {
|
||||||
rxConfig->spektrum_sat_bind = 0;
|
rxConfig->spektrum_sat_bind = 0;
|
||||||
saveConfigAndNotify();
|
saveConfigAndNotify();
|
||||||
|
|
|
@ -71,7 +71,7 @@
|
||||||
// 2200µs -> 0xFFF
|
// 2200µs -> 0xFFF
|
||||||
// Total range is: 2200 - 800 = 1400 <==> 4095
|
// Total range is: 2200 - 800 = 1400 <==> 4095
|
||||||
// Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12)
|
// Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12)
|
||||||
#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
|
#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
|
||||||
|
|
||||||
static bool xBusFrameReceived = false;
|
static bool xBusFrameReceived = false;
|
||||||
static bool xBusDataIncoming = false;
|
static bool xBusDataIncoming = false;
|
||||||
|
|
|
@ -139,7 +139,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros)
|
||||||
{
|
{
|
||||||
if (taskId == TASK_SELF || taskId < TASK_COUNT) {
|
if (taskId == TASK_SELF || taskId < TASK_COUNT) {
|
||||||
cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId];
|
cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId];
|
||||||
task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
|
task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue