mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
a couple optimizations for dynamic HSE frequency - moved SetSysClock() to run after reset vector + bss init, and changed rcc which used hardcoded HSE_VALUE.
turn off leds/beeper before initializing pins to prevent flash at startup uninitialized errorAngle fix in new PID git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@362 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
3afeb3d1c8
commit
57cbd784a9
11 changed files with 3091 additions and 3036 deletions
|
@ -42,6 +42,10 @@ bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc)
|
|||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
// Not supported with this frequency
|
||||
if (hse_value == 12000000)
|
||||
return false;
|
||||
|
||||
ack = i2cRead(ADXL345_ADDRESS, 0x00, 1, &sig);
|
||||
if (!ack || sig != 0xE5)
|
||||
return false;
|
||||
|
|
|
@ -95,6 +95,10 @@ bool bmp085Detect(baro_t *baro)
|
|||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
uint8_t data;
|
||||
|
||||
// Not supported with this frequency
|
||||
if (hse_value == 12000000)
|
||||
return false;
|
||||
|
||||
if (bmp085InitDone)
|
||||
return true;
|
||||
|
||||
|
|
|
@ -77,7 +77,6 @@ static void i2c_er_handler(void)
|
|||
|
||||
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
|
||||
{
|
||||
uint8_t i;
|
||||
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
|
||||
|
||||
addr = addr_ << 1;
|
||||
|
|
|
@ -59,6 +59,10 @@ bool mma8452Detect(sensor_t *acc)
|
|||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
// Not supported with this frequency
|
||||
if (hse_value == 12000000)
|
||||
return false;
|
||||
|
||||
ack = i2cRead(MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
||||
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
|
||||
return false;
|
||||
|
|
|
@ -36,17 +36,19 @@ static uint8_t ms5611_osr = CMD_ADC_4096;
|
|||
|
||||
bool ms5611Detect(baro_t *baro)
|
||||
{
|
||||
gpio_config_t gpio;
|
||||
bool ack = false;
|
||||
uint8_t sig;
|
||||
int i;
|
||||
|
||||
// PC13 (BMP085's XCLR reset input, which we use to disable it)
|
||||
gpio.pin = Pin_13;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(GPIOC, &gpio);
|
||||
BMP085_OFF;
|
||||
if (hse_value != 12000000) {
|
||||
// PC13 (BMP085's XCLR reset input, which we use to disable it). Only needed when running at 8MHz
|
||||
gpio_config_t gpio;
|
||||
gpio.pin = Pin_13;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(GPIOC, &gpio);
|
||||
BMP085_OFF;
|
||||
}
|
||||
|
||||
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms
|
||||
|
||||
|
|
|
@ -4,6 +4,8 @@
|
|||
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;
|
||||
// from system_stm32f10x.c
|
||||
void SetSysClock(void);
|
||||
|
||||
static void cycleCounterInit(void)
|
||||
{
|
||||
|
@ -60,8 +62,9 @@ void systemInit(void)
|
|||
uint32_t i;
|
||||
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
|
||||
|
||||
// This is needed because some shit inside Keil startup fucks with SystemCoreClock, setting it back to 72MHz even on HSI.
|
||||
SystemCoreClockUpdate();
|
||||
// Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers
|
||||
// Configure the Flash Latency cycles and enable prefetch buffer
|
||||
SetSysClock();
|
||||
|
||||
// Turn on clocks for stuff we use
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);
|
||||
|
@ -81,13 +84,13 @@ void systemInit(void)
|
|||
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
|
||||
|
||||
// Configure gpio
|
||||
for (i = 0; i < gpio_count; i++)
|
||||
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
BEEP_OFF;
|
||||
|
||||
for (i = 0; i < gpio_count; i++)
|
||||
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
|
||||
|
||||
// Init cycle counter
|
||||
cycleCounterInit();
|
||||
|
||||
|
|
|
@ -12,3 +12,6 @@ void failureMode(uint8_t mode);
|
|||
|
||||
// bootloader/IAP
|
||||
void systemReset(bool toBootloader);
|
||||
|
||||
// current crystal frequency - 8 or 12MHz
|
||||
extern uint32_t hse_value;
|
||||
|
|
2
src/mw.c
2
src/mw.c
|
@ -342,7 +342,7 @@ static void pidMultiWii(void)
|
|||
|
||||
static void pidRewrite(void)
|
||||
{
|
||||
int32_t errorAngle;
|
||||
int32_t errorAngle = 0;
|
||||
int axis;
|
||||
int32_t delta, deltaSum;
|
||||
static int32_t delta1[3], delta2[3];
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue