1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Merge remote-tracking branch 'multiwii/master'

Conflicts:
	obj/baseflight.hex
	src/config.c
	src/drivers/system_common.c
	src/main.c
	src/mw.h
	src/serial_cli.c
This commit is contained in:
Dominic Clifton 2014-04-21 12:29:19 +01:00
commit a3d2a3df2d
8 changed files with 32 additions and 15 deletions

View file

@ -1,3 +1,4 @@
#include <stdbool.h>
#include "stm32f10x.h" #include "stm32f10x.h"
#define SYSCLK_FREQ_72MHz 72000000 #define SYSCLK_FREQ_72MHz 72000000
@ -86,7 +87,7 @@ enum {
}; };
// Set system clock to 72 (HSE) or 64 (HSI) MHz // Set system clock to 72 (HSE) or 64 (HSI) MHz
void SetSysClock(void) void SetSysClock(bool overclock)
{ {
__IO uint32_t StartUpCounter = 0, status = 0, clocksrc = SRC_NONE; __IO uint32_t StartUpCounter = 0, status = 0, clocksrc = SRC_NONE;
__IO uint32_t *RCC_CRH = &GPIOC->CRH; __IO uint32_t *RCC_CRH = &GPIOC->CRH;
@ -140,10 +141,18 @@ void SetSysClock(void)
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16); *RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET); GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET);
RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9; RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9;
switch (clocksrc) { switch (clocksrc) {
case SRC_HSE: case SRC_HSE:
// PLL configuration: PLLCLK = HSE * 9 = 72 MHz if (overclock) {
if (RCC_CFGR_PLLMUL == RCC_CFGR_PLLMULL6)
RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL7;
else if (RCC_CFGR_PLLMUL == RCC_CFGR_PLLMULL9)
RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL10;
}
// overclock=false : PLL configuration: PLLCLK = HSE * 9 = 72 MHz || HSE * 6 = 72 MHz
// overclock=true : PLL configuration: PLLCLK = HSE * 10 = 80 MHz || HSE * 7 = 84 MHz
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMUL); RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMUL);
break; break;
case SRC_HSI: case SRC_HSI:

View file

@ -79,6 +79,16 @@ static bool isEEPROMContentValid(void)
return true; return true;
} }
void activateConfig(void)
{
generatePitchCurve(&cfg.controlRateConfig);
generateThrottleCurve(&cfg.controlRateConfig, mcfg.minthrottle, mcfg.maxthrottle);
setPIDController(cfg.pidController);
gpsSetPIDs();
useFailsafeConfig(&cfg.failsafeConfig);
}
void readEEPROM(void) void readEEPROM(void)
{ {
// Sanity check // Sanity check
@ -92,12 +102,7 @@ void readEEPROM(void)
mcfg.current_profile = 0; mcfg.current_profile = 0;
memcpy(&cfg, &mcfg.profile[mcfg.current_profile], sizeof(config_t)); memcpy(&cfg, &mcfg.profile[mcfg.current_profile], sizeof(config_t));
generatePitchCurve(&cfg.controlRateConfig); activateConfig();
generateThrottleCurve(&cfg.controlRateConfig, mcfg.minthrottle, mcfg.maxthrottle);
setPIDController(cfg.pidController);
gpsSetPIDs();
useFailsafeConfig(&cfg.failsafeConfig);
} }
void readEEPROMAndNotify(void) void readEEPROMAndNotify(void)
@ -232,6 +237,7 @@ static void resetConf(void)
mcfg.serialConfig.reboot_character = 'R'; mcfg.serialConfig.reboot_character = 'R';
mcfg.looptime = 3500; mcfg.looptime = 3500;
mcfg.emfAvoidance = 0;
mcfg.rssi_aux_channel = 0; mcfg.rssi_aux_channel = 0;
cfg.pidController = 0; cfg.pidController = 0;

View file

@ -66,6 +66,7 @@ typedef struct master_t {
uint8_t mixerConfiguration; uint8_t mixerConfiguration;
uint32_t enabledFeatures; uint32_t enabledFeatures;
uint16_t looptime; // imu loop time in us uint16_t looptime; // imu loop time in us
uint8_t emfAvoidance; // change pll settings to avoid noise in the uhf band
motorMixer_t customMixer[MAX_SUPPORTED_MOTORS]; // custom mixtable motorMixer_t customMixer[MAX_SUPPORTED_MOTORS]; // custom mixtable
// motor/esc/servo related stuff // motor/esc/servo related stuff

View file

@ -18,7 +18,7 @@ static volatile uint32_t usTicks = 0;
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care. // 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 sysTickUptime = 0;
// from system_stm32f10x.c // from system_stm32f10x.c
void SetSysClock(void); void SetSysClock(bool overclock);
static void cycleCounterInit(void) static void cycleCounterInit(void)
{ {
@ -50,7 +50,7 @@ uint32_t millis(void)
return sysTickUptime; return sysTickUptime;
} }
void systemInit(void) void systemInit(bool overclock)
{ {
struct { struct {
GPIO_TypeDef *gpio; GPIO_TypeDef *gpio;
@ -82,7 +82,7 @@ void systemInit(void)
// Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers // Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers
// Configure the Flash Latency cycles and enable prefetch buffer // Configure the Flash Latency cycles and enable prefetch buffer
SetSysClock(); SetSysClock(overclock);
// Turn on clocks for stuff we use // Turn on clocks for stuff we use
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE); RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);

View file

@ -1,6 +1,6 @@
#pragma once #pragma once
void systemInit(void); void systemInit(bool overclock);
void delayMicroseconds(uint32_t us); void delayMicroseconds(uint32_t us);
void delay(uint32_t ms); void delay(uint32_t ms);

View file

@ -37,7 +37,7 @@ int main(void)
serialPort_t* loopbackPort1 = NULL; serialPort_t* loopbackPort1 = NULL;
serialPort_t* loopbackPort2 = NULL; serialPort_t* loopbackPort2 = NULL;
#endif #endif
systemInit(); systemInit(mcfg.emfAvoidance);
initPrintfSupport(); initPrintfSupport();
ensureEEPROMContainsValidData(); ensureEEPROMContainsValidData();

View file

@ -123,6 +123,7 @@ typedef struct {
const clivalue_t valueTable[] = { const clivalue_t valueTable[] = {
{ "looptime", VAR_UINT16, &mcfg.looptime, 0, 9000 }, { "looptime", VAR_UINT16, &mcfg.looptime, 0, 9000 },
{ "emf_avoidance", VAR_UINT8, &mcfg.emfAvoidance, 0, 1 },
{ "midrc", VAR_UINT16, &mcfg.rxConfig.midrc, 1200, 1700 }, { "midrc", VAR_UINT16, &mcfg.rxConfig.midrc, 1200, 1700 },
{ "minthrottle", VAR_UINT16, &mcfg.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX }, { "minthrottle", VAR_UINT16, &mcfg.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "maxthrottle", VAR_UINT16, &mcfg.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX }, { "maxthrottle", VAR_UINT16, &mcfg.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },