mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
took out cycle counter stuff for timing, now using systick + counter strictly. ... seems improved loop precision a bit.
put gyro interleave under define. this needs to be cleaned sometime. took out "gyro glitch" stuff that was leftover from nintendo days. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@162 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
19ca85963b
commit
572d5827cc
7 changed files with 2478 additions and 2794 deletions
|
@ -1,10 +1,5 @@
|
|||
#include "board.h"
|
||||
|
||||
// Cycle counter stuff - these should be defined by CMSIS, but they aren't
|
||||
#define DWT_CTRL (*(volatile uint32_t *)0xE0001000)
|
||||
#define DWT_CYCCNT ((volatile uint32_t *)0xE0001004)
|
||||
#define CYCCNTENA (1 << 0)
|
||||
|
||||
typedef struct gpio_config_t
|
||||
{
|
||||
GPIO_TypeDef *gpio;
|
||||
|
@ -16,38 +11,29 @@ typedef struct gpio_config_t
|
|||
static volatile uint32_t usTicks = 0;
|
||||
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
|
||||
static volatile uint32_t sysTickUptime = 0;
|
||||
static volatile uint32_t sysTickCycleCounter = 0;
|
||||
|
||||
static void cycleCounterInit(void)
|
||||
{
|
||||
RCC_ClocksTypeDef clocks;
|
||||
RCC_GetClocksFreq(&clocks);
|
||||
usTicks = clocks.SYSCLK_Frequency / 1000000;
|
||||
|
||||
// enable DWT access
|
||||
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
|
||||
// enable the CPU cycle counter
|
||||
DWT_CTRL |= CYCCNTENA;
|
||||
}
|
||||
|
||||
|
||||
// SysTick
|
||||
void SysTick_Handler(void)
|
||||
{
|
||||
sysTickCycleCounter = *DWT_CYCCNT;
|
||||
sysTickUptime++;
|
||||
}
|
||||
|
||||
// Return system uptime in microseconds (rollover in 70minutes)
|
||||
uint32_t micros(void)
|
||||
{
|
||||
register uint32_t oldCycle, cycle, timeMs;
|
||||
__disable_irq();
|
||||
cycle = *DWT_CYCCNT;
|
||||
oldCycle = sysTickCycleCounter;
|
||||
timeMs = sysTickUptime;
|
||||
__enable_irq();
|
||||
return (timeMs * 1000) + (cycle - oldCycle) / usTicks;
|
||||
register uint32_t ms, cycle_cnt;
|
||||
do {
|
||||
ms = sysTickUptime;
|
||||
cycle_cnt = SysTick->VAL;
|
||||
} while (ms != sysTickUptime);
|
||||
return (ms * 1000) + (72000 - cycle_cnt) / 72;
|
||||
}
|
||||
|
||||
// Return system uptime in milliseconds (rollover in 49 days)
|
||||
|
@ -71,16 +57,9 @@ void systemInit(void)
|
|||
uint8_t gpio_count = sizeof(gpio_cfg) / sizeof(gpio_cfg[0]);
|
||||
|
||||
// Turn on clocks for stuff we use
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO, ENABLE);
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_TIM1 | RCC_APB2Periph_ADC1 | RCC_APB2Periph_USART1, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA2, ENABLE);
|
||||
RCC_ClearFlag();
|
||||
|
||||
// Make all GPIO in by default to save power and reduce noise
|
||||
|
@ -121,13 +100,20 @@ void systemInit(void)
|
|||
delay(100);
|
||||
}
|
||||
|
||||
#if 1
|
||||
void delayMicroseconds(uint32_t us)
|
||||
{
|
||||
uint32_t now = micros();
|
||||
while (micros() - now < us);
|
||||
}
|
||||
#else
|
||||
void delayMicroseconds(uint32_t us)
|
||||
{
|
||||
uint32_t elapsed = 0;
|
||||
uint32_t lastCount = *DWT_CYCCNT;
|
||||
uint32_t lastCount = SysTick->VAL;
|
||||
|
||||
for (;;) {
|
||||
register uint32_t current_count = *DWT_CYCCNT;
|
||||
register uint32_t current_count = SysTick->VAL;
|
||||
uint32_t elapsed_us;
|
||||
|
||||
// measure the time elapsed since the last time we checked
|
||||
|
@ -146,6 +132,7 @@ void delayMicroseconds(uint32_t us)
|
|||
elapsed %= usTicks;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void delay(uint32_t ms)
|
||||
{
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue