STM32F4: USARTS 4,5,6 added

Flag initialisation for motor_pwm_protocol
Fixes for AlienFlightF4 and timers
This commit is contained in:
blckmn 2016-06-08 05:43:28 +10:00
parent 6bf35e09ce
commit 51a99e74c6
31 changed files with 5476 additions and 57 deletions

View File

@ -37,6 +37,7 @@
#include "drivers/pwm_rx.h" #include "drivers/pwm_rx.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/gyro_sync.h" #include "drivers/gyro_sync.h"
#include "drivers/pwm_output.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "sensors/gyro.h" #include "sensors/gyro.h"
@ -121,8 +122,14 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#endif #endif
#if defined(FLASH_SIZE) #if defined(FLASH_SIZE)
#if defined(STM32F40_41xxx)
#define FLASH_PAGE_COUNT 4 // just to make calculations work
#elif defined (STM32F411xE)
#define FLASH_PAGE_COUNT 4 // just to make calculations work
#else
#define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE) #define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
#endif #endif
#endif
#if !defined(FLASH_PAGE_SIZE) #if !defined(FLASH_PAGE_SIZE)
#error "Flash page size not defined for target." #error "Flash page size not defined for target."
@ -148,6 +155,7 @@ size_t custom_flash_memory_address = 0;
#define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
#endif #endif
#endif #endif
master_t masterConfig; // master config struct with data independent from profiles master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile; profile_t *currentProfile;
static uint32_t activeFeaturesLatch = 0; static uint32_t activeFeaturesLatch = 0;
@ -322,7 +330,8 @@ void resetSerialConfig(serialConfig_t *serialConfig)
serialConfig->reboot_character = 'R'; serialConfig->reboot_character = 'R';
} }
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) { static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
{
controlRateConfig->rcRate8 = 100; controlRateConfig->rcRate8 = 100;
controlRateConfig->rcYawRate8 = 100; controlRateConfig->rcYawRate8 = 100;
controlRateConfig->rcExpo8 = 10; controlRateConfig->rcExpo8 = 10;
@ -338,14 +347,16 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
} }
void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) { void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
{
rcControlsConfig->deadband = 0; rcControlsConfig->deadband = 0;
rcControlsConfig->yaw_deadband = 0; rcControlsConfig->yaw_deadband = 0;
rcControlsConfig->alt_hold_deadband = 40; rcControlsConfig->alt_hold_deadband = 40;
rcControlsConfig->alt_hold_fast_change = 1; rcControlsConfig->alt_hold_fast_change = 1;
} }
void resetMixerConfig(mixerConfig_t *mixerConfig) { void resetMixerConfig(mixerConfig_t *mixerConfig)
{
mixerConfig->yaw_motor_direction = 1; mixerConfig->yaw_motor_direction = 1;
#ifdef USE_SERVOS #ifdef USE_SERVOS
mixerConfig->tri_unarmed_servo = 1; mixerConfig->tri_unarmed_servo = 1;
@ -371,14 +382,15 @@ uint8_t getCurrentControlRateProfile(void)
return currentControlRateProfileIndex; return currentControlRateProfileIndex;
} }
static void setControlRateProfile(uint8_t profileIndex) { static void setControlRateProfile(uint8_t profileIndex)
{
currentControlRateProfileIndex = profileIndex; currentControlRateProfileIndex = profileIndex;
masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex; masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex]; currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
} }
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex)
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) { {
return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile]; return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
} }
@ -399,7 +411,7 @@ static void resetConf(void)
masterConfig.version = EEPROM_CONF_VERSION; masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerMode = MIXER_QUADX; masterConfig.mixerMode = MIXER_QUADX;
featureClearAll(); featureClearAll();
#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) || defined(SINGULARITY) #ifdef CONFIG_RX_PPM
featureSet(FEATURE_RX_PPM); featureSet(FEATURE_RX_PPM);
#endif #endif
@ -474,7 +486,11 @@ static void resetConf(void)
masterConfig.rxConfig.rssi_ppm_invert = 0; masterConfig.rxConfig.rssi_ppm_invert = 0;
masterConfig.rxConfig.rcSmoothing = 0; masterConfig.rxConfig.rcSmoothing = 0;
masterConfig.rxConfig.fpvCamAngleDegrees = 0; masterConfig.rxConfig.fpvCamAngleDegrees = 0;
#ifdef STM32F4
masterConfig.rxConfig.max_aux_channel = 99;
#else
masterConfig.rxConfig.max_aux_channel = 6; masterConfig.rxConfig.max_aux_channel = 6;
#endif
masterConfig.rxConfig.airModeActivateThreshold = 1350; masterConfig.rxConfig.airModeActivateThreshold = 1350;
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges); resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
@ -496,12 +512,14 @@ static void resetConf(void)
#ifdef BRUSHED_MOTORS #ifdef BRUSHED_MOTORS
masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE; masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
masterConfig.motor_pwm_protocol = PWM_TYPE_BRUSHED;
#else #else
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE; masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125;
#endif #endif
masterConfig.servo_pwm_rate = 50; masterConfig.servo_pwm_rate = 50;
masterConfig.fast_pwm_protocol = 1; masterConfig.use_unsyncedPwm = false;
masterConfig.use_unsyncedPwm = 0;
#ifdef CC3D #ifdef CC3D
masterConfig.use_buzzer_p6 = 0; masterConfig.use_buzzer_p6 = 0;
#endif #endif
@ -628,8 +646,11 @@ static void resetConf(void)
featureSet(FEATURE_TELEMETRY); featureSet(FEATURE_TELEMETRY);
#endif #endif
// alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets #if defined(TARGET_CONFIG)
#ifdef ALIENFLIGHT targetConfiguration(&masterConfig);
#endif
#if defined(ALIENFLIGHT)
featureSet(FEATURE_RX_SERIAL); featureSet(FEATURE_RX_SERIAL);
featureSet(FEATURE_MOTOR_STOP); featureSet(FEATURE_MOTOR_STOP);
featureClear(FEATURE_ONESHOT125); featureClear(FEATURE_ONESHOT125);
@ -1000,10 +1021,11 @@ void writeEEPROM(void)
// write it // write it
FLASH_Unlock(); FLASH_Unlock();
while (attemptsRemaining--) { while (attemptsRemaining--) {
#ifdef STM32F303 #if defined(STM32F4)
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
#elif defined(STM32F303)
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR); FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
#endif #elif defined(STM32F10X)
#ifdef STM32F10X
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR); FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
#endif #endif
for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) { for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {

View File

@ -34,7 +34,7 @@ typedef struct master_t {
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz) uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
uint8_t fast_pwm_protocol; // Pwm Protocol uint8_t motor_pwm_protocol; // Pwm Protocol
uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop
#ifdef USE_SERVOS #ifdef USE_SERVOS

View File

@ -31,7 +31,7 @@
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint8_t useUnsyncedPwm, uint16_t idlePulse); void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
/* /*
@ -967,7 +967,7 @@ if (init->useBuzzerP6) {
if (type == MAP_TO_PPM_INPUT) { if (type == MAP_TO_PPM_INPUT) {
#if defined(SPARKY) || defined(ALIENFLIGHTF3) #if defined(SPARKY) || defined(ALIENFLIGHTF3)
if (init->useFastPwm || isMotorBrushed(init->motorPwmRate)) { if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED)) {
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2); ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
} }
#endif #endif
@ -978,16 +978,16 @@ if (init->useBuzzerP6) {
} else if (type == MAP_TO_MOTOR_OUTPUT) { } else if (type == MAP_TO_MOTOR_OUTPUT) {
#ifdef CC3D #ifdef CC3D
if (init->useFastPwm || isMotorBrushed(init->motorPwmRate)){ if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
// Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed // Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed
if (timerHardwarePtr->tim == TIM2) if (timerHardwarePtr->tim == TIM2)
continue; continue;
} }
#endif #endif
if (init->useFastPwm) { if (init->useFastPwm) {
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->useUnsyncedPwm, init->idlePulse); pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ;
} else if (isMotorBrushed(init->motorPwmRate)) { } else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM;
} else { } else {

View File

@ -136,7 +136,11 @@ enum {
PWM13, PWM13,
PWM14, PWM14,
PWM15, PWM15,
PWM16 PWM16,
PWM17,
PWM18,
PWM19,
PWM20
}; };
extern const uint16_t multiPPM[]; extern const uint16_t multiPPM[];

View File

@ -100,8 +100,8 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
configTimeBase(timerHardware->tim, period, mhz); configTimeBase(timerHardware->tim, period, mhz);
pwmGPIOConfig(timerHardware->gpio, timerHardware->pin, Mode_AF_PP); pwmGPIOConfig(timerHardware->gpio, timerHardware->pin, Mode_AF_PP);
pwmOCConfig(timerHardware->tim, timerHardware->channel, value); pwmOCConfig(timerHardware->tim, timerHardware->channel, value);
if (timerHardware->outputEnable) if (timerHardware->outputEnable)
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE); TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
TIM_Cmd(timerHardware->tim, ENABLE); TIM_Cmd(timerHardware->tim, ENABLE);
@ -187,11 +187,6 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
} }
} }
bool isMotorBrushed(uint16_t motorPwmRate)
{
return (motorPwmRate > 500);
}
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse) void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
{ {
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000; uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
@ -206,7 +201,7 @@ void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motor
motors[motorIndex]->pwmWritePtr = pwmWriteStandard; motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
} }
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint8_t useUnsyncedPwm, uint16_t idlePulse) void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse)
{ {
uint32_t timerMhzCounter; uint32_t timerMhzCounter;
@ -222,7 +217,7 @@ void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIn
timerMhzCounter = MULTISHOT_TIMER_MHZ; timerMhzCounter = MULTISHOT_TIMER_MHZ;
} }
if (useUnsyncedPwm) { if (motorPwmRate > 0) {
uint32_t hz = timerMhzCounter * 1000000; uint32_t hz = timerMhzCounter * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse); motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse);
} else { } else {

View File

@ -21,8 +21,9 @@ typedef enum {
PWM_TYPE_CONVENTIONAL = 0, PWM_TYPE_CONVENTIONAL = 0,
PWM_TYPE_ONESHOT125, PWM_TYPE_ONESHOT125,
PWM_TYPE_ONESHOT42, PWM_TYPE_ONESHOT42,
PWM_TYPE_MULTISHOT PWM_TYPE_MULTISHOT,
} FastPwmProtocolTypes_e; PWM_TYPE_BRUSHED
} motorPwmProtocolTypes_e;
void pwmWriteMotor(uint8_t index, uint16_t value); void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmShutdownPulsesForAllMotors(uint8_t motorCount); void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
@ -30,6 +31,5 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount);
void pwmWriteServo(uint8_t index, uint16_t value); void pwmWriteServo(uint8_t index, uint16_t value);
bool isMotorBrushed(uint16_t motorPwmRate);
void pwmDisableMotors(void); void pwmDisableMotors(void);
void pwmEnableMotors(void); void pwmEnableMotors(void);

View File

@ -108,6 +108,19 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
} else if (USARTx == USART3) { } else if (USARTx == USART3) {
s = serialUSART3(baudRate, mode, options); s = serialUSART3(baudRate, mode, options);
#endif #endif
#ifdef USE_USART4
} else if (USARTx == UART4) {
s = serialUSART4(baudRate, mode, options);
#endif
#ifdef USE_USART5
} else if (USARTx == UART5) {
s = serialUSART5(baudRate, mode, options);
#endif
#ifdef USE_USART6
} else if (USARTx == USART6) {
s = serialUSART6(baudRate, mode, options);
#endif
} else { } else {
return (serialPort_t *)s; return (serialPort_t *)s;
} }

View File

@ -29,6 +29,12 @@
#define UART2_TX_BUFFER_SIZE 256 #define UART2_TX_BUFFER_SIZE 256
#define UART3_RX_BUFFER_SIZE 256 #define UART3_RX_BUFFER_SIZE 256
#define UART3_TX_BUFFER_SIZE 256 #define UART3_TX_BUFFER_SIZE 256
#define UART4_RX_BUFFER_SIZE 256
#define UART4_TX_BUFFER_SIZE 256
#define UART5_RX_BUFFER_SIZE 256
#define UART5_TX_BUFFER_SIZE 256
#define UART6_RX_BUFFER_SIZE 256
#define UART6_TX_BUFFER_SIZE 256
typedef struct { typedef struct {
serialPort_t port; serialPort_t port;

View File

@ -26,4 +26,7 @@ void uartStartTxDMA(uartPort_t *s);
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options); uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options);
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options); uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options);
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options); uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options);
uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options);
uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options);
uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options);

View File

@ -535,7 +535,23 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
// "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11 // "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
// Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler // Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
#if defined (STM32F40_41xxx)
if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1; TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
}
else {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
}
#elif defined (STM32F411xE)
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
}
else {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
}
#else
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
#endif
TIM_TimeBaseStructure.TIM_ClockDivision = 0; TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
@ -555,6 +571,19 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
timerNVICConfigure(TIM1_UP_IRQn); timerNVICConfigure(TIM1_UP_IRQn);
break; break;
#endif #endif
#if defined (STM32F40_41xxx)
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
break;
case TIM8_CC_IRQn:
timerNVICConfigure(TIM8_UP_TIM13_IRQn);
break;
#endif
#if defined (STM32F411xE)
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
break;
#endif
#ifdef STM32F303xC #ifdef STM32F303xC
case TIM1_CC_IRQn: case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM16_IRQn); timerNVICConfigure(TIM1_UP_TIM16_IRQn);
@ -823,8 +852,6 @@ void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHig
} }
} }
static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig) static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
{ {
uint16_t capture; uint16_t capture;
@ -917,6 +944,13 @@ _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
# if defined(STM32F10X) # if defined(STM32F10X)
_TIM_IRQ_HANDLER(TIM1_UP_IRQHandler, 1); // timer can't be shared _TIM_IRQ_HANDLER(TIM1_UP_IRQHandler, 1); // timer can't be shared
# endif # endif
# if defined(STM32F40_41xxx) || defined (STM32F411xE)
# if USED_TIMERS & TIM_N(10)
_TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
# else
_TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler, 1); // timer10 is not used
# endif
# endif
# ifdef STM32F303xC # ifdef STM32F303xC
# if USED_TIMERS & TIM_N(16) # if USED_TIMERS & TIM_N(16)
_TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler, 1, 16); // both timers are in use _TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler, 1, 16); // both timers are in use
@ -934,6 +968,9 @@ _TIM_IRQ_HANDLER(TIM3_IRQHandler, 3);
#if USED_TIMERS & TIM_N(4) #if USED_TIMERS & TIM_N(4)
_TIM_IRQ_HANDLER(TIM4_IRQHandler, 4); _TIM_IRQ_HANDLER(TIM4_IRQHandler, 4);
#endif #endif
#if USED_TIMERS & TIM_N(5)
_TIM_IRQ_HANDLER(TIM5_IRQHandler, 5);
#endif
#if USED_TIMERS & TIM_N(8) #if USED_TIMERS & TIM_N(8)
_TIM_IRQ_HANDLER(TIM8_CC_IRQHandler, 8); _TIM_IRQ_HANDLER(TIM8_CC_IRQHandler, 8);
# if defined(STM32F10X_XL) # if defined(STM32F10X_XL)
@ -941,6 +978,24 @@ _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8);
# else // f10x_hd, f30x # else // f10x_hd, f30x
_TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8); _TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8);
# endif # endif
# if defined(STM32F40_41xxx)
# if USED_TIMERS & TIM_N(13)
_TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
# else
_TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8); // timer13 is not used
# endif
# endif
# if defined (STM32F411xE)
# endif
#endif
#if USED_TIMERS & TIM_N(9)
_TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler, 9);
#endif
# if USED_TIMERS & TIM_N(11)
_TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler, 11);
# endif
#if USED_TIMERS & TIM_N(12)
_TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler, 12);
#endif #endif
#if USED_TIMERS & TIM_N(15) #if USED_TIMERS & TIM_N(15)
_TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15); _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
@ -979,6 +1034,12 @@ void timerInit(void)
} }
#endif #endif
#if defined(STM32F40_41xxx) || defined (STM32F411xE)
for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
GPIO_PinAFConfig(timerHardwarePtr->gpio, (uint16_t)timerHardwarePtr->gpioPinSource, timerHardwarePtr->alternateFunction);
}
#endif
// initialize timer channel structures // initialize timer channel structures
for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) { for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
timerChannelInfo[i].type = TYPE_FREE; timerChannelInfo[i].type = TYPE_FREE;

View File

@ -633,15 +633,21 @@ void writeServos(void)
} }
#endif #endif
void writeMotors(uint8_t fastPwmProtocol, uint8_t unsyncedPwm) static bool syncPwm = false;
void syncMotors(bool enabled)
{
syncPwm = enabled;
}
void writeMotors(void)
{ {
uint8_t i; uint8_t i;
for (i = 0; i < motorCount; i++) for (i = 0; i < motorCount; i++)
pwmWriteMotor(i, motor[i]); pwmWriteMotor(i, motor[i]);
if (syncPwm) {
if (fastPwmProtocol && !unsyncedPwm) {
pwmCompleteOneshotMotorUpdate(motorCount); pwmCompleteOneshotMotorUpdate(motorCount);
} }
} }
@ -653,7 +659,7 @@ void writeAllMotors(int16_t mc)
// Sends commands to all motors // Sends commands to all motors
for (i = 0; i < motorCount; i++) for (i = 0; i < motorCount; i++)
motor[i] = mc; motor[i] = mc;
writeMotors(1,1); writeMotors();
} }
void stopMotors(void) void stopMotors(void)
@ -750,7 +756,7 @@ STATIC_UNIT_TESTED void servoMixer(void)
void mixTable(void) void mixTable(void)
{ {
uint32_t i; uint32_t i = 0;
fix12_t vbatCompensationFactor = 0; fix12_t vbatCompensationFactor = 0;
static fix12_t mixReduction; static fix12_t mixReduction;
bool use_vbat_compensation = false; bool use_vbat_compensation = false;

View File

@ -213,6 +213,7 @@ int servoDirection(int servoIndex, int fromChannel);
#endif #endif
void mixerResetDisarmedMotors(void); void mixerResetDisarmedMotors(void);
void mixTable(void); void mixTable(void);
void writeMotors(uint8_t fastPwmProtocol, uint8_t unsyncedPwm); void syncMotors(bool enabled);
void writeMotors(void);
void stopMotors(void); void stopMotors(void);
void StopPwmAllMotors(void); void StopPwmAllMotors(void);

View File

@ -32,7 +32,7 @@
#include "drivers/serial_softserial.h" #include "drivers/serial_softserial.h"
#endif #endif
#if defined(USE_USART1) || defined(USE_USART2) || defined(USE_USART3) #if defined(USE_USART1) || defined(USE_USART2) || defined(USE_USART3) || defined(USE_USART4) || defined(USE_USART5) || defined(USE_USART6)
#include "drivers/serial_uart.h" #include "drivers/serial_uart.h"
#endif #endif
@ -69,6 +69,15 @@ const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
#ifdef USE_USART3 #ifdef USE_USART3
SERIAL_PORT_USART3, SERIAL_PORT_USART3,
#endif #endif
#ifdef USE_USART4
SERIAL_PORT_USART4,
#endif
#ifdef USE_USART5
SERIAL_PORT_USART5,
#endif
#ifdef USE_USART6
SERIAL_PORT_USART6,
#endif
#ifdef USE_SOFTSERIAL1 #ifdef USE_SOFTSERIAL1
SERIAL_PORT_SOFTSERIAL1, SERIAL_PORT_SOFTSERIAL1,
#endif #endif
@ -293,6 +302,21 @@ serialPort_t *openSerialPort(
serialPort = uartOpen(USART3, callback, baudRate, mode, options); serialPort = uartOpen(USART3, callback, baudRate, mode, options);
break; break;
#endif #endif
#ifdef USE_USART4
case SERIAL_PORT_USART4:
serialPort = uartOpen(UART4, callback, baudRate, mode, options);
break;
#endif
#ifdef USE_USART5
case SERIAL_PORT_USART5:
serialPort = uartOpen(USART5, callback, baudRate, mode, options);
break;
#endif
#ifdef USE_USART6
case SERIAL_PORT_USART6:
serialPort = uartOpen(USART6, callback, baudRate, mode, options);
break;
#endif
#ifdef USE_SOFTSERIAL1 #ifdef USE_SOFTSERIAL1
case SERIAL_PORT_SOFTSERIAL1: case SERIAL_PORT_SOFTSERIAL1:
serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, options); serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, options);

View File

@ -452,7 +452,7 @@ static const char * const lookupTableSuperExpoYaw[] = {
}; };
static const char * const lookupTableFastPwm[] = { static const char * const lookupTableFastPwm[] = {
"OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT" "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED"
}; };
typedef struct lookupTableEntry_s { typedef struct lookupTableEntry_s {
@ -481,7 +481,7 @@ typedef enum {
TABLE_MAG_HARDWARE, TABLE_MAG_HARDWARE,
TABLE_DEBUG, TABLE_DEBUG,
TABLE_SUPEREXPO_YAW, TABLE_SUPEREXPO_YAW,
TABLE_FAST_PWM, TABLE_MOTOR_PWM_PROTOCOL,
} lookupTableIndex_e; } lookupTableIndex_e;
static const lookupTableEntry_t lookupTables[] = { static const lookupTableEntry_t lookupTables[] = {
@ -583,7 +583,8 @@ const clivalue_t valueTable[] = {
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "unsynced_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } }, { "unsynced_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
{ "fast_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.fast_pwm_protocol, .config.lookup = { TABLE_FAST_PWM } }, { "fast_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
#ifdef CC3D #ifdef CC3D
{ "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } }, { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
#endif #endif

View File

@ -399,7 +399,7 @@ static void serializeSDCardSummaryReply(void)
#ifdef USE_SDCARD #ifdef USE_SDCARD
uint8_t flags = 1 /* SD card supported */ ; uint8_t flags = 1 /* SD card supported */ ;
uint8_t state; uint8_t state = 0;
serialize8(flags); serialize8(flags);

View File

@ -329,20 +329,20 @@ void init(void)
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate; pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
#endif #endif
if (masterConfig.fast_pwm_protocol == PWM_TYPE_ONESHOT125) { if (masterConfig.motor_pwm_protocol == PWM_TYPE_ONESHOT125) {
featureSet(FEATURE_ONESHOT125); featureSet(FEATURE_ONESHOT125);
} else { } else {
featureClear(FEATURE_ONESHOT125); featureClear(FEATURE_ONESHOT125);
} }
pwm_params.useFastPwm = (masterConfig.fast_pwm_protocol != PWM_TYPE_CONVENTIONAL) ? true : false; // Configurator feature abused for enabling Fast PWM pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); // Configurator feature abused for enabling Fast PWM
pwm_params.pwmProtocolType = masterConfig.fast_pwm_protocol; pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm; pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm;
if (feature(FEATURE_3D)) if (feature(FEATURE_3D))
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
if (pwm_params.motorPwmRate > 500 && !pwm_params.useFastPwm) if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED)
pwm_params.idlePulse = 0; // brushed motors pwm_params.idlePulse = 0; // brushed motors
#ifdef CC3D #ifdef CC3D
pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false; pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false;
@ -351,6 +351,7 @@ void init(void)
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params); pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
syncMotors(pwm_params.useUnsyncedPwm && pwm_params.motorPwmRate != PWM_TYPE_BRUSHED);
mixerUsePWMOutputConfiguration(pwmOutputConfiguration); mixerUsePWMOutputConfiguration(pwmOutputConfiguration);
if (!feature(FEATURE_ONESHOT125)) if (!feature(FEATURE_ONESHOT125))

View File

@ -742,7 +742,7 @@ void subTaskMotorUpdate(void)
#endif #endif
if (motorControlEnable) { if (motorControlEnable) {
writeMotors(masterConfig.fast_pwm_protocol, masterConfig.use_unsyncedPwm); writeMotors();
} }
if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;} if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;}
} }

View File

@ -31,6 +31,11 @@
#include "drivers/system.h" #include "drivers/system.h"
#if defined (STM32F4)
#define DELAY_LIMIT 10
#else #define DELAY_LIMIT 100
#endif
static cfTask_t *currentTask = NULL; static cfTask_t *currentTask = NULL;
static uint32_t totalWaitingTasks; static uint32_t totalWaitingTasks;
@ -137,7 +142,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(100, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging task->desiredPeriod = MAX(DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
} }
} }

View File

@ -57,7 +57,11 @@ cfTask_t cfTasks[TASK_COUNT] = {
.taskName = "PID", .taskName = "PID",
.subTaskName = "GYRO", .subTaskName = "GYRO",
.taskFunc = taskMainPidLoopCheck, .taskFunc = taskMainPidLoopCheck,
#if defined(STM32F4)
.desiredPeriod = 125,
#else
.desiredPeriod = 1000, .desiredPeriod = 1000,
#endif
.staticPriority = TASK_PRIORITY_REALTIME, .staticPriority = TASK_PRIORITY_REALTIME,
}, },

View File

@ -18,6 +18,8 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3. #define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
#define ALIENFLIGHT
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PB2 #define HW_PIN PB2

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,105 @@
/**
******************************************************************************
* @file system_stm32f4xx.h
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f4xx_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_STM32F4XX_H
#define __SYSTEM_STM32F4XX_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup STM32F4xx_System_Includes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_types
* @{
*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Constants
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F4XX_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -17,6 +17,7 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "AFF4" #define TARGET_BOARD_IDENTIFIER "AFF4"
#define ALIENFLIGHT
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 #define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
@ -50,7 +51,7 @@
#define ACC #define ACC
#define USE_ACC_SPI_MPU6500 #define USE_ACC_SPI_MPU6500
//#define USE_ACC_SPI_MPU9250 #define USE_ACC_SPI_MPU9250
#define ACC_MPU6500_ALIGN CW270_DEG #define ACC_MPU6500_ALIGN CW270_DEG
#define ACC_MPU9250_ALIGN CW270_DEG #define ACC_MPU9250_ALIGN CW270_DEG

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,45 @@
/**
******************************************************************************
* @file system_stm32f4xx.h
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
#ifndef __SYSTEM_STM32F4XX_H
#define __SYSTEM_STM32F4XX_H
#ifdef __cplusplus
extern "C" {
#endif
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F4XX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,105 @@
/**
******************************************************************************
* @file system_stm32f4xx.h
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f4xx_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_STM32F4XX_H
#define __SYSTEM_STM32F4XX_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup STM32F4xx_System_Includes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_types
* @{
*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Constants
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F4XX_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -181,6 +181,8 @@
#undef TARGET_BOARD_IDENTIFIER #undef TARGET_BOARD_IDENTIFIER
#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienFlight F1. #define TARGET_BOARD_IDENTIFIER "AWF1" // AlienFlight F1.
#undef BOARD_HAS_VOLTAGE_DIVIDER #undef BOARD_HAS_VOLTAGE_DIVIDER
#define ALIENFLIGHT
#define HARDWARE_BIND_PLUG #define HARDWARE_BIND_PLUG
// Hardware bind plug at PB5 (Pin 41) // Hardware bind plug at PB5 (Pin 41)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,105 @@
/**
******************************************************************************
* @file system_stm32f4xx.h
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f4xx_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_STM32F4XX_H
#define __SYSTEM_STM32F4XX_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup STM32F4xx_System_Includes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_types
* @{
*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Constants
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F4XX_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/