1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 03:50:02 +03:00

Removed trailing whitespace

This commit is contained in:
Martin Budden 2016-07-16 07:54:58 +01:00
parent 22e8a61a6f
commit 141b369667
97 changed files with 415 additions and 415 deletions

View file

@ -632,7 +632,7 @@ static void writeInterframe(void)
arraySubInt32(deltas, blackboxCurrent->axisPID_P, blackboxLast->axisPID_P, XYZ_AXIS_COUNT); arraySubInt32(deltas, blackboxCurrent->axisPID_P, blackboxLast->axisPID_P, XYZ_AXIS_COUNT);
blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT); blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT);
/* /*
* The PID I field changes very slowly, most of the time +-2, so use an encoding * The PID I field changes very slowly, most of the time +-2, so use an encoding
* that can pack all three fields into one byte in that situation. * that can pack all three fields into one byte in that situation.
*/ */
@ -1315,7 +1315,7 @@ static void blackboxCheckAndLogFlightMode()
} }
} }
/* /*
* Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control * Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control
* the portion of logged loop iterations. * the portion of logged loop iterations.
*/ */

View file

@ -507,7 +507,7 @@ void blackboxWriteFloat(float value)
/** /**
* If there is data waiting to be written to the blackbox device, attempt to write (a portion of) that now. * If there is data waiting to be written to the blackbox device, attempt to write (a portion of) that now.
* *
* Intended to be called regularly for the blackbox device to perform housekeeping. * Intended to be called regularly for the blackbox device to perform housekeeping.
*/ */
void blackboxDeviceFlush(void) void blackboxDeviceFlush(void)

View file

@ -231,7 +231,7 @@ int32_t quickMedianFilter5(int32_t * v)
QMF_SORT(p[0], p[1]); QMF_SORT(p[3], p[4]); QMF_SORT(p[0], p[3]); QMF_SORT(p[0], p[1]); QMF_SORT(p[3], p[4]); QMF_SORT(p[0], p[3]);
QMF_SORT(p[1], p[4]); QMF_SORT(p[1], p[2]); QMF_SORT(p[2], p[3]); QMF_SORT(p[1], p[4]); QMF_SORT(p[1], p[2]); QMF_SORT(p[2], p[3]);
QMF_SORT(p[1], p[2]); QMF_SORT(p[1], p[2]);
return p[2]; return p[2];
} }
@ -279,7 +279,7 @@ float quickMedianFilter5f(float * v)
QMF_SORTF(p[0], p[1]); QMF_SORTF(p[3], p[4]); QMF_SORTF(p[0], p[3]); QMF_SORTF(p[0], p[1]); QMF_SORTF(p[3], p[4]); QMF_SORTF(p[0], p[3]);
QMF_SORTF(p[1], p[4]); QMF_SORTF(p[1], p[2]); QMF_SORTF(p[2], p[3]); QMF_SORTF(p[1], p[4]); QMF_SORTF(p[1], p[2]); QMF_SORTF(p[2], p[3]);
QMF_SORTF(p[1], p[2]); QMF_SORTF(p[1], p[2]);
return p[2]; return p[2];
} }

View file

@ -56,7 +56,7 @@ typedef void (*putcf) (void *, char);
static putcf stdout_putf; static putcf stdout_putf;
static void *stdout_putp; static void *stdout_putp;
// print bf, padded from left to at least n characters. // print bf, padded from left to at least n characters.
// padding is zero ('0') if z!=0, space (' ') otherwise // padding is zero ('0') if z!=0, space (' ') otherwise
static int putchw(void *putp, putcf putf, int n, char z, char *bf) static int putchw(void *putp, putcf putf, int n, char z, char *bf)
{ {

View file

@ -159,7 +159,7 @@ size_t custom_flash_memory_address = 0;
#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address) #define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
#else #else
// use the last flash pages for storage // use the last flash pages for storage
#ifndef CONFIG_START_FLASH_ADDRESS #ifndef CONFIG_START_FLASH_ADDRESS
#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
@ -349,7 +349,7 @@ 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;
@ -366,7 +366,7 @@ 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;
@ -374,7 +374,7 @@ void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
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
@ -658,7 +658,7 @@ static void resetConf(void)
targetConfiguration(); targetConfiguration();
#endif #endif
// copy first profile into remaining profile // copy first profile into remaining profile
for (int i = 1; i < MAX_PROFILE_COUNT; i++) { for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));

View file

@ -137,7 +137,7 @@ typedef struct master_t {
profile_t profile[MAX_PROFILE_COUNT]; profile_t profile[MAX_PROFILE_COUNT];
uint8_t current_profile_index; uint8_t current_profile_index;
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT]; modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT]; adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
@ -161,9 +161,9 @@ typedef struct master_t {
uint8_t magic_ef; // magic number, should be 0xEF uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum uint8_t chk; // XOR checksum
char name[MAX_NAME_LENGTH+1]; char name[MAX_NAME_LENGTH+1];
} master_t; } master_t;
extern master_t masterConfig; extern master_t masterConfig;

View file

@ -252,7 +252,7 @@ void mpuIntExtiInit(void)
EXTIEnable(mpuIntIO, true); EXTIEnable(mpuIntIO, true);
#endif #endif
mpuExtiInitDone = true; mpuExtiInitDone = true;
} }
static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data) static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data)

View file

@ -18,7 +18,7 @@
#pragma once #pragma once
#include "exti.h" #include "exti.h"
// MPU6050 // MPU6050
#define MPU_RA_WHO_AM_I 0x75 #define MPU_RA_WHO_AM_I 0x75
#define MPU_RA_WHO_AM_I_LEGACY 0x00 #define MPU_RA_WHO_AM_I_LEGACY 0x00
@ -119,7 +119,7 @@
typedef bool (*mpuReadRegisterFunc)(uint8_t reg, uint8_t length, uint8_t* data); typedef bool (*mpuReadRegisterFunc)(uint8_t reg, uint8_t length, uint8_t* data);
typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data); typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data);
typedef void(*mpuResetFuncPtr)(void); typedef void(*mpuResetFuncPtr)(void);
typedef struct mpuConfiguration_s { typedef struct mpuConfiguration_s {
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each

View file

@ -104,7 +104,7 @@ static void mpu6050GyroInit(uint8_t lpf)
delay(100); delay(100);
ack = mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference) ack = mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
ack = mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) ack = mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure
ack = mpuConfiguration.write(MPU_RA_CONFIG, lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz) ack = mpuConfiguration.write(MPU_RA_CONFIG, lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
ack = mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec ack = mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec

View file

@ -158,7 +158,7 @@ bool mpu6000SpiDetect(void)
uint8_t in; uint8_t in;
uint8_t attemptsRemaining = 5; uint8_t attemptsRemaining = 5;
#ifdef MPU6000_CS_PIN #ifdef MPU6000_CS_PIN
mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN)); mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN));
#endif #endif
IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
@ -253,7 +253,7 @@ static void mpu6000AccAndGyroInit(void) {
delayMicroseconds(15); delayMicroseconds(15);
#endif #endif
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST);
delayMicroseconds(1); delayMicroseconds(1);
mpuSpi6000InitDone = true; mpuSpi6000InitDone = true;

View file

@ -54,7 +54,7 @@ static IO_t mpuSpi9250CsPin = IO_NONE;
#define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin) #define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin)
#define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin) #define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin)
void mpu9250ResetGyro(void) void mpu9250ResetGyro(void)
{ {
// Device Reset // Device Reset
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
@ -123,7 +123,7 @@ void mpu9250SpiAccInit(acc_t *acc)
acc->acc_1G = 512 * 8; acc->acc_1G = 512 * 8;
} }
bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) bool verifympu9250WriteRegister(uint8_t reg, uint8_t data)
{ {
uint8_t in; uint8_t in;
uint8_t attemptsRemaining = 20; uint8_t attemptsRemaining = 20;
@ -176,7 +176,7 @@ static void mpu9250AccAndGyroInit(uint8_t lpf) {
verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly. verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly.
#endif #endif
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
mpuSpi9250InitDone = true; //init done mpuSpi9250InitDone = true; //init done
} }
@ -208,7 +208,7 @@ bool mpu9250SpiDetect(void)
} }
} while (attemptsRemaining--); } while (attemptsRemaining--);
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
return true; return true;
} }

View file

@ -24,14 +24,14 @@
#define ADC_TAG_MAP_COUNT 16 #define ADC_TAG_MAP_COUNT 16
#elif defined(STM32F3) #elif defined(STM32F3)
#define ADC_TAG_MAP_COUNT 39 #define ADC_TAG_MAP_COUNT 39
#else #else
#define ADC_TAG_MAP_COUNT 10 #define ADC_TAG_MAP_COUNT 10
#endif #endif
typedef enum ADCDevice { typedef enum ADCDevice {
ADCINVALID = -1, ADCINVALID = -1,
ADCDEV_1 = 0, ADCDEV_1 = 0,
#if defined(STM32F3) #if defined(STM32F3)
ADCDEV_2, ADCDEV_2,
ADCDEV_MAX = ADCDEV_2, ADCDEV_MAX = ADCDEV_2,
#elif defined(STM32F4) #elif defined(STM32F4)

View file

@ -35,13 +35,13 @@
#define ADC_INSTANCE ADC1 #define ADC_INSTANCE ADC1
#endif #endif
const adcDevice_t adcHardware[] = { const adcDevice_t adcHardware[] = {
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 } { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }
}; };
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{ {
if (instance == ADC1) if (instance == ADC1)
return ADCDEV_1; return ADCDEV_1;
/* TODO -- ADC2 available on large 10x devices. /* TODO -- ADC2 available on large 10x devices.
@ -51,7 +51,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
return ADCINVALID; return ADCINVALID;
} }
const adcTagMap_t adcTagMap[] = { const adcTagMap_t adcTagMap[] = {
{ DEFIO_TAG_E__PA0, ADC_Channel_0 }, // ADC12 { DEFIO_TAG_E__PA0, ADC_Channel_0 }, // ADC12
{ DEFIO_TAG_E__PA1, ADC_Channel_1 }, // ADC12 { DEFIO_TAG_E__PA1, ADC_Channel_1 }, // ADC12
{ DEFIO_TAG_E__PA2, ADC_Channel_2 }, // ADC12 { DEFIO_TAG_E__PA2, ADC_Channel_2 }, // ADC12
@ -61,7 +61,7 @@ const adcTagMap_t adcTagMap[] = {
{ DEFIO_TAG_E__PA6, ADC_Channel_6 }, // ADC12 { DEFIO_TAG_E__PA6, ADC_Channel_6 }, // ADC12
{ DEFIO_TAG_E__PA7, ADC_Channel_7 }, // ADC12 { DEFIO_TAG_E__PA7, ADC_Channel_7 }, // ADC12
{ DEFIO_TAG_E__PB0, ADC_Channel_8 }, // ADC12 { DEFIO_TAG_E__PB0, ADC_Channel_8 }, // ADC12
{ DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12 { DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12
}; };
// Driver for STM32F103CB onboard ADC // Driver for STM32F103CB onboard ADC

View file

@ -37,12 +37,12 @@
#define ADC_INSTANCE ADC1 #define ADC_INSTANCE ADC1
#endif #endif
const adcDevice_t adcHardware[] = { const adcDevice_t adcHardware[] = {
{ .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }, { .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 },
{ .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 } { .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 }
}; };
const adcTagMap_t adcTagMap[] = { const adcTagMap_t adcTagMap[] = {
{ DEFIO_TAG_E__PA0, ADC_Channel_1 }, // ADC1 { DEFIO_TAG_E__PA0, ADC_Channel_1 }, // ADC1
{ DEFIO_TAG_E__PA1, ADC_Channel_2 }, // ADC1 { DEFIO_TAG_E__PA1, ADC_Channel_2 }, // ADC1
{ DEFIO_TAG_E__PA2, ADC_Channel_3 }, // ADC1 { DEFIO_TAG_E__PA2, ADC_Channel_3 }, // ADC1
@ -86,7 +86,7 @@ const adcTagMap_t adcTagMap[] = {
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{ {
if (instance == ADC1) if (instance == ADC1)
return ADCDEV_1; return ADCDEV_1;
if (instance == ADC2) if (instance == ADC2)
@ -133,7 +133,7 @@ void adcInit(drv_adc_config_t *init)
if (device == ADCINVALID) if (device == ADCINVALID)
return; return;
adcDevice_t adc = adcHardware[device]; adcDevice_t adc = adcHardware[device];
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag) if (!adcConfig[i].tag)

View file

@ -36,13 +36,13 @@
#define ADC_INSTANCE ADC1 #define ADC_INSTANCE ADC1
#endif #endif
const adcDevice_t adcHardware[] = { const adcDevice_t adcHardware[] = {
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 }, { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 },
//{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 } //{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 }
}; };
/* note these could be packed up for saving space */ /* note these could be packed up for saving space */
const adcTagMap_t adcTagMap[] = { const adcTagMap_t adcTagMap[] = {
/* /*
{ DEFIO_TAG_E__PF3, ADC_Channel_9 }, { DEFIO_TAG_E__PF3, ADC_Channel_9 },
{ DEFIO_TAG_E__PF4, ADC_Channel_14 }, { DEFIO_TAG_E__PF4, ADC_Channel_14 },
@ -73,7 +73,7 @@ const adcTagMap_t adcTagMap[] = {
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{ {
if (instance == ADC1) if (instance == ADC1)
return ADCDEV_1; return ADCDEV_1;
/* /*
if (instance == ADC2) // TODO add ADC2 and 3 if (instance == ADC2) // TODO add ADC2 and 3
@ -126,7 +126,7 @@ void adcInit(drv_adc_config_t *init)
if (device == ADCINVALID) if (device == ADCINVALID)
return; return;
adcDevice_t adc = adcHardware[device]; adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag) if (!adcConfig[i].tag)

View file

@ -35,7 +35,7 @@
#ifdef BARO #ifdef BARO
#if defined(BARO_EOC_GPIO) #if defined(BARO_EOC_GPIO)
static IO_t eocIO; static IO_t eocIO;
@ -49,7 +49,7 @@ void bmp085_extiHandler(extiCallbackRec_t* cb)
isConversionComplete = true; isConversionComplete = true;
} }
bool bmp085TestEOCConnected(const bmp085Config_t *config); bool bmp085TestEOCConnected(const bmp085Config_t *config);
# endif # endif
typedef struct { typedef struct {
@ -139,7 +139,7 @@ static IO_t xclrIO;
#endif #endif
void bmp085InitXclrIO(const bmp085Config_t *config) void bmp085InitXclrIO(const bmp085Config_t *config)
{ {
if (!xclrIO && config && config->xclrIO) { if (!xclrIO && config && config->xclrIO) {
xclrIO = IOGetByTag(config->xclrIO); xclrIO = IOGetByTag(config->xclrIO);
@ -184,7 +184,7 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
delay(20); // datasheet says 10ms, we'll be careful and do 20. delay(20); // datasheet says 10ms, we'll be careful and do 20.
ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
if (ack) { if (ack) {
bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID); bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
bmp085.oversampling_setting = 3; bmp085.oversampling_setting = 3;

View file

@ -19,7 +19,7 @@
typedef struct bmp085Config_s { typedef struct bmp085Config_s {
ioTag_t xclrIO; ioTag_t xclrIO;
ioTag_t eocIO; ioTag_t eocIO;
} bmp085Config_t; } bmp085Config_t;
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro); bool bmp085Detect(const bmp085Config_t *config, baro_t *baro);

View file

@ -26,7 +26,7 @@
#ifndef I2C_DEVICE #ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID #define I2C_DEVICE I2CINVALID
#endif #endif
typedef enum I2CDevice { typedef enum I2CDevice {
I2CINVALID = -1, I2CINVALID = -1,

View file

@ -47,35 +47,35 @@ static void i2cUnstick(IO_t scl, IO_t sda);
#define IOCFG_I2C IOCFG_AF_OD #define IOCFG_I2C IOCFG_AF_OD
#endif #endif
#ifndef I2C1_SCL #ifndef I2C1_SCL
#define I2C1_SCL PB8 #define I2C1_SCL PB8
#endif #endif
#ifndef I2C1_SDA #ifndef I2C1_SDA
#define I2C1_SDA PB9 #define I2C1_SDA PB9
#endif #endif
#else #else
#ifndef I2C1_SCL #ifndef I2C1_SCL
#define I2C1_SCL PB6 #define I2C1_SCL PB6
#endif #endif
#ifndef I2C1_SDA #ifndef I2C1_SDA
#define I2C1_SDA PB7 #define I2C1_SDA PB7
#endif #endif
#endif #endif
#ifndef I2C2_SCL #ifndef I2C2_SCL
#define I2C2_SCL PB10 #define I2C2_SCL PB10
#endif #endif
#ifndef I2C2_SDA #ifndef I2C2_SDA
#define I2C2_SDA PB11 #define I2C2_SDA PB11
#endif #endif
#ifdef STM32F4 #ifdef STM32F4
#ifndef I2C3_SCL #ifndef I2C3_SCL
#define I2C3_SCL PA8 #define I2C3_SCL PA8
#endif #endif
#ifndef I2C3_SDA #ifndef I2C3_SDA
#define I2C3_SDA PB4 #define I2C3_SDA PB4
#endif #endif
#endif #endif
@ -93,7 +93,7 @@ static i2cState_t i2cState[] = {
{ false, false, 0, 0, 0, 0, 0, 0, 0 }, { false, false, 0, 0, 0, 0, 0, 0, 0 },
{ false, false, 0, 0, 0, 0, 0, 0, 0 }, { false, false, 0, 0, 0, 0, 0, 0, 0 },
{ false, false, 0, 0, 0, 0, 0, 0, 0 } { false, false, 0, 0, 0, 0, 0, 0, 0 }
}; };
void I2C1_ER_IRQHandler(void) { void I2C1_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_1); i2c_er_handler(I2CDEV_1);
@ -121,7 +121,7 @@ void I2C3_EV_IRQHandler(void) {
} }
#endif #endif
static bool i2cHandleHardwareFailure(I2CDevice device) static bool i2cHandleHardwareFailure(I2CDevice device)
{ {
i2cErrorCount++; i2cErrorCount++;
// reinit peripheral + clock out garbage // reinit peripheral + clock out garbage
@ -129,7 +129,7 @@ static bool i2cHandleHardwareFailure(I2CDevice device)
return false; return false;
} }
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
{ {
if (device == I2CINVALID) if (device == I2CINVALID)
@ -138,7 +138,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
uint32_t timeout = I2C_DEFAULT_TIMEOUT; uint32_t timeout = I2C_DEFAULT_TIMEOUT;
I2C_TypeDef *I2Cx; I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev; I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state; i2cState_t *state;
state = &(i2cState[device]); state = &(i2cState[device]);
@ -171,12 +171,12 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
return !(state->error); return !(state->error);
} }
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data) bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data)
{ {
return i2cWriteBuffer(device, addr_, reg_, 1, &data); return i2cWriteBuffer(device, addr_, reg_, 1, &data);
} }
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
{ {
if (device == I2CINVALID) if (device == I2CINVALID)
return false; return false;
@ -369,7 +369,7 @@ void i2c_ev_handler(I2CDevice device) {
} }
} }
void i2cInit(I2CDevice device) void i2cInit(I2CDevice device)
{ {
if (device == I2CINVALID) if (device == I2CINVALID)
return; return;
@ -392,7 +392,7 @@ void i2cInit(I2CDevice device)
I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
i2cUnstick(scl, sda); i2cUnstick(scl, sda);
// Init pins // Init pins
#ifdef STM32F4 #ifdef STM32F4
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C); IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);

View file

@ -39,18 +39,18 @@
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000) #define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT)) #define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_GPIO_AF GPIO_AF_4 #define I2C_GPIO_AF GPIO_AF_4
#ifndef I2C1_SCL #ifndef I2C1_SCL
#define I2C1_SCL PB6 #define I2C1_SCL PB6
#endif #endif
#ifndef I2C1_SDA #ifndef I2C1_SDA
#define I2C1_SDA PB7 #define I2C1_SDA PB7
#endif #endif
#ifndef I2C2_SCL #ifndef I2C2_SCL
#define I2C2_SCL PF4 #define I2C2_SCL PF4
#endif #endif
#ifndef I2C2_SDA #ifndef I2C2_SDA
#define I2C2_SDA PA10 #define I2C2_SDA PA10
#endif #endif
@ -82,7 +82,7 @@ void i2cInit(I2CDevice device)
I2C_TypeDef *I2Cx; I2C_TypeDef *I2Cx;
I2Cx = i2c->dev; I2Cx = i2c->dev;
IO_t scl = IOGetByTag(i2c->scl); IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda); IO_t sda = IOGetByTag(i2c->sda);
@ -108,7 +108,7 @@ void i2cInit(I2CDevice device)
I2C_Init(I2Cx, &i2cInit); I2C_Init(I2Cx, &i2cInit);
I2C_StretchClockCmd(I2Cx, ENABLE); I2C_StretchClockCmd(I2Cx, ENABLE);
I2C_Cmd(I2Cx, ENABLE); I2C_Cmd(I2Cx, ENABLE);
} }
@ -122,7 +122,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
addr_ <<= 1; addr_ <<= 1;
I2C_TypeDef *I2Cx; I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev; I2Cx = i2cHardwareMap[device].dev;
/* Test on BUSY Flag */ /* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
@ -188,7 +188,7 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t*
addr_ <<= 1; addr_ <<= 1;
I2C_TypeDef *I2Cx; I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev; I2Cx = i2cHardwareMap[device].dev;
/* Test on BUSY Flag */ /* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;

View file

@ -36,7 +36,7 @@
#ifndef GPIO_AF_SPI3 #ifndef GPIO_AF_SPI3
#define GPIO_AF_SPI3 GPIO_AF_6 #define GPIO_AF_SPI3 GPIO_AF_6
#endif #endif
#endif #endif
#ifndef SPI1_SCK_PIN #ifndef SPI1_SCK_PIN
#define SPI1_NSS_PIN PA4 #define SPI1_NSS_PIN PA4
@ -84,7 +84,7 @@ static spiDevice_t spiHardwareMap[] = {
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance) SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
{ {
if (instance == SPI1) if (instance == SPI1)
return SPIDEV_1; return SPIDEV_1;
if (instance == SPI2) if (instance == SPI2)

View file

@ -65,7 +65,7 @@ typedef struct dmaChannelDescriptor_s {
#define DMA_IT_TEIF ((uint32_t)0x00000008) #define DMA_IT_TEIF ((uint32_t)0x00000008)
#define DMA_IT_DMEIF ((uint32_t)0x00000004) #define DMA_IT_DMEIF ((uint32_t)0x00000004)
#define DMA_IT_FEIF ((uint32_t)0x00000001) #define DMA_IT_FEIF ((uint32_t)0x00000001)
#else #else
typedef enum { typedef enum {

View file

@ -24,22 +24,22 @@ static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS];
#if defined(STM32F1) || defined(STM32F4) #if defined(STM32F1) || defined(STM32F4)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
EXTI0_IRQn, EXTI0_IRQn,
EXTI1_IRQn, EXTI1_IRQn,
EXTI2_IRQn, EXTI2_IRQn,
EXTI3_IRQn, EXTI3_IRQn,
EXTI4_IRQn, EXTI4_IRQn,
EXTI9_5_IRQn, EXTI9_5_IRQn,
EXTI15_10_IRQn EXTI15_10_IRQn
}; };
#elif defined(STM32F3) #elif defined(STM32F3)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
EXTI0_IRQn, EXTI0_IRQn,
EXTI1_IRQn, EXTI1_IRQn,
EXTI2_TS_IRQn, EXTI2_TS_IRQn,
EXTI3_IRQn, EXTI3_IRQn,
EXTI4_IRQn, EXTI4_IRQn,
EXTI9_5_IRQn, EXTI9_5_IRQn,
EXTI15_10_IRQn EXTI15_10_IRQn
}; };
#else #else

View file

@ -199,7 +199,7 @@ static bool m25p16_readIdentification()
bool m25p16_init() bool m25p16_init()
{ {
#ifdef M25P16_CS_PIN #ifdef M25P16_CS_PIN
m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN)); m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN));
#endif #endif
IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0); IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0);

View file

@ -20,7 +20,7 @@
#include "platform.h" #include "platform.h"
#ifdef INVERTER #ifdef INVERTER
#include "io.h" #include "io.h"
#include "io_impl.h" #include "io_impl.h"

View file

@ -52,7 +52,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) #define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO #define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL) #define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN) #define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN)

View file

@ -12,7 +12,7 @@ typedef struct ioRec_s {
GPIO_TypeDef *gpio; GPIO_TypeDef *gpio;
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;
@ -26,7 +26,7 @@ int IO_GPIO_PortSource(IO_t io);
#if defined(STM32F3) || defined(STM32F4) #if defined(STM32F3) || defined(STM32F4)
int IO_EXTI_PortSourceGPIO(IO_t io); int IO_EXTI_PortSourceGPIO(IO_t io);
int IO_EXTI_PinSource(IO_t io); int IO_EXTI_PinSource(IO_t io);
#endif #endif
GPIO_TypeDef* IO_GPIO(IO_t io); GPIO_TypeDef* IO_GPIO(IO_t io);

View file

@ -27,12 +27,12 @@ static const IO_t leds[] = {
DEFIO_IO(LED0), DEFIO_IO(LED0),
#else #else
DEFIO_IO(NONE), DEFIO_IO(NONE),
#endif #endif
#ifdef LED1 #ifdef LED1
DEFIO_IO(LED1), DEFIO_IO(LED1),
#else #else
DEFIO_IO(NONE), DEFIO_IO(NONE),
#endif #endif
#ifdef LED2 #ifdef LED2
DEFIO_IO(LED2), DEFIO_IO(LED2),
#else #else

View file

@ -31,8 +31,8 @@
#ifdef LED_STRIP #ifdef LED_STRIP
#if !defined(WS2811_PIN) #if !defined(WS2811_PIN)
#define WS2811_PIN PA0 #define WS2811_PIN PA0
#define WS2811_TIMER TIM5 #define WS2811_TIMER TIM5
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER #define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream2 #define WS2811_DMA_STREAM DMA1_Stream2

View file

@ -147,7 +147,7 @@ void max7456_dma_irq_handler(dmaChannelDescriptor_t* descriptor) {
} }
#endif #endif
void max7456_init(uint8_t video_system) void max7456_init(uint8_t video_system)
{ {
uint8_t max_screen_rows; uint8_t max_screen_rows;
uint8_t srdata = 0; uint8_t srdata = 0;

View file

@ -95,7 +95,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
int channelIndex = 0; int channelIndex = 0;
memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration)); memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration));
// this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ] // this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ]
if (init->airplane) if (init->airplane)
i = 2; // switch to air hardware config i = 2; // switch to air hardware config
@ -260,7 +260,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
if (init->useChannelForwarding && !init->airplane) { if (init->useChannelForwarding && !init->airplane) {
#if defined(NAZE) && defined(WS2811_TIMER) #if defined(NAZE) && defined(WS2811_TIMER)
// if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14 // if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14
if (init->useLEDStrip) { if (init->useLEDStrip) {
if (timerIndex >= PWM13 && timerIndex <= PWM14) { if (timerIndex >= PWM13 && timerIndex <= PWM14) {
type = MAP_TO_SERVO_OUTPUT; type = MAP_TO_SERVO_OUTPUT;
} }

View file

@ -117,7 +117,7 @@ enum {
PWM13, PWM13,
PWM14, PWM14,
PWM15, PWM15,
PWM16, PWM16,
PWM17, PWM17,
PWM18, PWM18,
PWM19, PWM19,

View file

@ -131,7 +131,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
p->tim = timerHardware->tim; p->tim = timerHardware->tim;
*p->ccr = 0; *p->ccr = 0;
return p; return p;
} }

View file

@ -126,7 +126,7 @@ void sdcardInsertionDetectDeinit(void)
#ifdef SDCARD_DETECT_PIN #ifdef SDCARD_DETECT_PIN
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0); IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0);
IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING); IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING);
#endif #endif
} }
@ -135,7 +135,7 @@ void sdcardInsertionDetectInit(void)
#ifdef SDCARD_DETECT_PIN #ifdef SDCARD_DETECT_PIN
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0); IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0);
IOConfigGPIO(sdCardDetectPin, IOCFG_IPU); IOConfigGPIO(sdCardDetectPin, IOCFG_IPU);
#endif #endif
} }

View file

@ -114,8 +114,8 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index) void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index)
{ {
if (options & SERIAL_BIDIR) { if (options & SERIAL_BIDIR) {
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
(options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD, (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD,
(options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
); );

View file

@ -64,17 +64,17 @@ typedef struct uartDevice_s {
//static uartPort_t uartPort[MAX_UARTS]; //static uartPort_t uartPort[MAX_UARTS];
#ifdef USE_UART1 #ifdef USE_UART1
static uartDevice_t uart1 = static uartDevice_t uart1 =
{ {
.DMAChannel = DMA_Channel_4, .DMAChannel = DMA_Channel_4,
.txDMAStream = DMA2_Stream7, .txDMAStream = DMA2_Stream7,
#ifdef USE_UART1_RX_DMA #ifdef USE_UART1_RX_DMA
.rxDMAStream = DMA2_Stream5, .rxDMAStream = DMA2_Stream5,
#endif #endif
.dev = USART1, .dev = USART1,
.rx = IO_TAG(UART1_RX_PIN), .rx = IO_TAG(UART1_RX_PIN),
.tx = IO_TAG(UART1_TX_PIN), .tx = IO_TAG(UART1_TX_PIN),
.af = GPIO_AF_USART1, .af = GPIO_AF_USART1,
#ifdef UART1_AHB1_PERIPHERALS #ifdef UART1_AHB1_PERIPHERALS
.rcc_ahb1 = UART1_AHB1_PERIPHERALS, .rcc_ahb1 = UART1_AHB1_PERIPHERALS,
#endif #endif
@ -87,17 +87,17 @@ static uartDevice_t uart1 =
#endif #endif
#ifdef USE_UART2 #ifdef USE_UART2
static uartDevice_t uart2 = static uartDevice_t uart2 =
{ {
.DMAChannel = DMA_Channel_4, .DMAChannel = DMA_Channel_4,
#ifdef USE_UART2_RX_DMA #ifdef USE_UART2_RX_DMA
.rxDMAStream = DMA1_Stream5, .rxDMAStream = DMA1_Stream5,
#endif #endif
.txDMAStream = DMA1_Stream6, .txDMAStream = DMA1_Stream6,
.dev = USART2, .dev = USART2,
.rx = IO_TAG(UART2_RX_PIN), .rx = IO_TAG(UART2_RX_PIN),
.tx = IO_TAG(UART2_TX_PIN), .tx = IO_TAG(UART2_TX_PIN),
.af = GPIO_AF_USART2, .af = GPIO_AF_USART2,
#ifdef UART2_AHB1_PERIPHERALS #ifdef UART2_AHB1_PERIPHERALS
.rcc_ahb1 = UART2_AHB1_PERIPHERALS, .rcc_ahb1 = UART2_AHB1_PERIPHERALS,
#endif #endif
@ -110,17 +110,17 @@ static uartDevice_t uart2 =
#endif #endif
#ifdef USE_UART3 #ifdef USE_UART3
static uartDevice_t uart3 = static uartDevice_t uart3 =
{ {
.DMAChannel = DMA_Channel_4, .DMAChannel = DMA_Channel_4,
#ifdef USE_UART3_RX_DMA #ifdef USE_UART3_RX_DMA
.rxDMAStream = DMA1_Stream1, .rxDMAStream = DMA1_Stream1,
#endif #endif
.txDMAStream = DMA1_Stream3, .txDMAStream = DMA1_Stream3,
.dev = USART3, .dev = USART3,
.rx = IO_TAG(UART3_RX_PIN), .rx = IO_TAG(UART3_RX_PIN),
.tx = IO_TAG(UART3_TX_PIN), .tx = IO_TAG(UART3_TX_PIN),
.af = GPIO_AF_USART3, .af = GPIO_AF_USART3,
#ifdef UART3_AHB1_PERIPHERALS #ifdef UART3_AHB1_PERIPHERALS
.rcc_ahb1 = UART3_AHB1_PERIPHERALS, .rcc_ahb1 = UART3_AHB1_PERIPHERALS,
#endif #endif
@ -133,17 +133,17 @@ static uartDevice_t uart3 =
#endif #endif
#ifdef USE_UART4 #ifdef USE_UART4
static uartDevice_t uart4 = static uartDevice_t uart4 =
{ {
.DMAChannel = DMA_Channel_4, .DMAChannel = DMA_Channel_4,
#ifdef USE_UART1_RX_DMA #ifdef USE_UART1_RX_DMA
.rxDMAStream = DMA1_Stream2, .rxDMAStream = DMA1_Stream2,
#endif #endif
.txDMAStream = DMA1_Stream4, .txDMAStream = DMA1_Stream4,
.dev = UART4, .dev = UART4,
.rx = IO_TAG(UART4_RX_PIN), .rx = IO_TAG(UART4_RX_PIN),
.tx = IO_TAG(UART4_TX_PIN), .tx = IO_TAG(UART4_TX_PIN),
.af = GPIO_AF_UART4, .af = GPIO_AF_UART4,
#ifdef UART4_AHB1_PERIPHERALS #ifdef UART4_AHB1_PERIPHERALS
.rcc_ahb1 = UART4_AHB1_PERIPHERALS, .rcc_ahb1 = UART4_AHB1_PERIPHERALS,
#endif #endif
@ -156,17 +156,17 @@ static uartDevice_t uart4 =
#endif #endif
#ifdef USE_UART5 #ifdef USE_UART5
static uartDevice_t uart5 = static uartDevice_t uart5 =
{ {
.DMAChannel = DMA_Channel_4, .DMAChannel = DMA_Channel_4,
#ifdef USE_UART1_RX_DMA #ifdef USE_UART1_RX_DMA
.rxDMAStream = DMA1_Stream0, .rxDMAStream = DMA1_Stream0,
#endif #endif
.txDMAStream = DMA2_Stream7, .txDMAStream = DMA2_Stream7,
.dev = UART5, .dev = UART5,
.rx = IO_TAG(UART5_RX_PIN), .rx = IO_TAG(UART5_RX_PIN),
.tx = IO_TAG(UART5_TX_PIN), .tx = IO_TAG(UART5_TX_PIN),
.af = GPIO_AF_UART5, .af = GPIO_AF_UART5,
#ifdef UART5_AHB1_PERIPHERALS #ifdef UART5_AHB1_PERIPHERALS
.rcc_ahb1 = UART5_AHB1_PERIPHERALS, .rcc_ahb1 = UART5_AHB1_PERIPHERALS,
#endif #endif
@ -179,17 +179,17 @@ static uartDevice_t uart5 =
#endif #endif
#ifdef USE_UART6 #ifdef USE_UART6
static uartDevice_t uart6 = static uartDevice_t uart6 =
{ {
.DMAChannel = DMA_Channel_5, .DMAChannel = DMA_Channel_5,
#ifdef USE_UART6_RX_DMA #ifdef USE_UART6_RX_DMA
.rxDMAStream = DMA2_Stream1, .rxDMAStream = DMA2_Stream1,
#endif #endif
.txDMAStream = DMA2_Stream6, .txDMAStream = DMA2_Stream6,
.dev = USART6, .dev = USART6,
.rx = IO_TAG(UART6_RX_PIN), .rx = IO_TAG(UART6_RX_PIN),
.tx = IO_TAG(UART6_TX_PIN), .tx = IO_TAG(UART6_TX_PIN),
.af = GPIO_AF_USART6, .af = GPIO_AF_USART6,
#ifdef UART6_AHB1_PERIPHERALS #ifdef UART6_AHB1_PERIPHERALS
.rcc_ahb1 = UART6_AHB1_PERIPHERALS, .rcc_ahb1 = UART6_AHB1_PERIPHERALS,
#endif #endif
@ -344,7 +344,7 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
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);
} }

View file

@ -36,7 +36,7 @@ void systemReset(void)
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
} }
void systemResetToBootloader(void) void systemResetToBootloader(void)
{ {
// 1FFFF000 -> 20000200 -> SP // 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC // 1FFFF004 -> 1FFFF021 -> PC

View file

@ -34,7 +34,7 @@ void systemReset(void)
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
} }
void systemResetToBootloader(void) void systemResetToBootloader(void)
{ {
// 1FFFF000 -> 20000200 -> SP // 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC // 1FFFF004 -> 1FFFF021 -> PC

View file

@ -41,7 +41,7 @@ void systemReset(void)
NVIC_SystemReset(); NVIC_SystemReset();
} }
void systemResetToBootloader(void) void systemResetToBootloader(void)
{ {
if (mpuConfiguration.reset) if (mpuConfiguration.reset)
mpuConfiguration.reset(); mpuConfiguration.reset();

View file

@ -253,7 +253,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
} }
#else #else
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1; TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
#endif #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;

View file

@ -87,7 +87,7 @@ typedef struct timerHardware_s {
} timerHardware_t; } timerHardware_t;
enum { enum {
TIMER_OUTPUT_ENABLED = 0x01, TIMER_OUTPUT_ENABLED = 0x01,
TIMER_OUTPUT_INVERTED = 0x02 TIMER_OUTPUT_INVERTED = 0x02
}; };

View file

@ -23,10 +23,10 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM8, .rcc = RCC_APB1(TIM8) }, { .TIMx = TIM8, .rcc = RCC_APB1(TIM8) },
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9) }, { .TIMx = TIM9, .rcc = RCC_APB2(TIM9) },
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10) }, { .TIMx = TIM10, .rcc = RCC_APB2(TIM10) },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) }, { .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12) }, { .TIMx = TIM12, .rcc = RCC_APB1(TIM12) },
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13) }, { .TIMx = TIM13, .rcc = RCC_APB1(TIM13) },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) }, { .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
#endif #endif
}; };

View file

@ -54,7 +54,7 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
*/ */
#define CCMR_OFFSET ((uint16_t)0x0018) #define CCMR_OFFSET ((uint16_t)0x0018)
#define CCMR_OC13M_MASK ((uint32_t)0xFFFEFF8F) #define CCMR_OC13M_MASK ((uint32_t)0xFFFEFF8F)
#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF) #define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF)
void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t TIM_OCMode) void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t TIM_OCMode)
{ {

View file

@ -66,7 +66,7 @@ bool usbCableIsInserted(void)
void usbGenerateDisconnectPulse(void) void usbGenerateDisconnectPulse(void)
{ {
/* Pull down PA12 to create USB disconnect pulse */ /* Pull down PA12 to create USB disconnect pulse */
IO_t usbPin = IOGetByTag(IO_TAG(PA12)); IO_t usbPin = IOGetByTag(IO_TAG(PA12));
IOConfigGPIO(usbPin, IOCFG_OUT_OD); IOConfigGPIO(usbPin, IOCFG_OUT_OD);
IOHi(usbPin); IOHi(usbPin);

View file

@ -179,7 +179,7 @@ void rtc6705SetFreq(uint16_t freq)
uint32_t val_a = ((((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) % RTC6705_SET_FDIV) / RTC6705_SET_NDIV; //Casts required to make sure correct math (large numbers) uint32_t val_a = ((((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) % RTC6705_SET_FDIV) / RTC6705_SET_NDIV; //Casts required to make sure correct math (large numbers)
uint32_t val_n = (((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) / RTC6705_SET_FDIV; //Casts required to make sure correct math (large numbers) uint32_t val_n = (((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) / RTC6705_SET_FDIV; //Casts required to make sure correct math (large numbers)
val_hex |= RTC6705_SET_WRITE; val_hex |= RTC6705_SET_WRITE;
val_hex |= (val_a << 5); val_hex |= (val_a << 5);
val_hex |= (val_n << 12); val_hex |= (val_n << 12);

View file

@ -71,12 +71,12 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin
pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using
void setTargetPidLooptime(uint8_t pidProcessDenom) void setTargetPidLooptime(uint8_t pidProcessDenom)
{ {
targetPidLooptime = gyro.targetLooptime * pidProcessDenom; targetPidLooptime = gyro.targetLooptime * pidProcessDenom;
} }
uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate)
{ {
uint16_t dynamicKi; uint16_t dynamicKi;
uint16_t resetRate; uint16_t resetRate;

View file

@ -1069,7 +1069,7 @@ static void gpsHandlePassthrough(uint8_t data)
#endif #endif
} }
void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort)
{ {

View file

@ -672,8 +672,8 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rx
applyStepAdjustment(controlRateConfig, adjustmentFunction, delta); applyStepAdjustment(controlRateConfig, adjustmentFunction, delta);
} else if (adjustmentState->config->mode == ADJUSTMENT_MODE_SELECT) { } else if (adjustmentState->config->mode == ADJUSTMENT_MODE_SELECT) {
uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions); uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions);
uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth; uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;
applySelectAdjustment(adjustmentFunction, position); applySelectAdjustment(adjustmentFunction, position);
} }

View file

@ -465,7 +465,7 @@ static void nopConsumer(uint8_t data)
arbitrary serial passthrough "proxy". Optional callbacks can be given to allow arbitrary serial passthrough "proxy". Optional callbacks can be given to allow
for specialized data processing. for specialized data processing.
*/ */
void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer
*leftC, serialConsumer *rightC) *leftC, serialConsumer *rightC)
{ {
waitForSerialPortToFinishTransmitting(left); waitForSerialPortToFinishTransmitting(left);

View file

@ -16,7 +16,7 @@
* Author: 4712 * Author: 4712
* have a look at https://github.com/sim-/tgy/blob/master/boot.inc * have a look at https://github.com/sim-/tgy/blob/master/boot.inc
* for info about the stk500v2 implementation * for info about the stk500v2 implementation
*/ */
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <string.h> #include <string.h>

View file

@ -112,7 +112,7 @@ static void cliRxFail(char *cmdline);
static void cliAdjustmentRange(char *cmdline); static void cliAdjustmentRange(char *cmdline);
static void cliMotorMix(char *cmdline); static void cliMotorMix(char *cmdline);
static void cliDefaults(char *cmdline); static void cliDefaults(char *cmdline);
void cliDfu(char *cmdLine); void cliDfu(char *cmdLine);
static void cliDump(char *cmdLine); static void cliDump(char *cmdLine);
void cliDumpProfile(uint8_t profileIndex); void cliDumpProfile(uint8_t profileIndex);
void cliDumpRateProfile(uint8_t rateProfileIndex) ; void cliDumpRateProfile(uint8_t rateProfileIndex) ;
@ -488,7 +488,7 @@ typedef enum {
TABLE_GPS_SBAS_MODE, TABLE_GPS_SBAS_MODE,
#endif #endif
#ifdef BLACKBOX #ifdef BLACKBOX
TABLE_BLACKBOX_DEVICE, TABLE_BLACKBOX_DEVICE,
#endif #endif
TABLE_CURRENT_SENSOR, TABLE_CURRENT_SENSOR,
TABLE_GIMBAL_MODE, TABLE_GIMBAL_MODE,
@ -1943,7 +1943,7 @@ static void cliDump(char *cmdline)
dumpMask = DUMP_PROFILE; // only dumpMask = DUMP_PROFILE; // only
} }
if (strcasecmp(cmdline, "rates") == 0) { if (strcasecmp(cmdline, "rates") == 0) {
dumpMask = DUMP_RATES; dumpMask = DUMP_RATES;
} }
if (strcasecmp(cmdline, "all") == 0) { if (strcasecmp(cmdline, "all") == 0) {
@ -2502,11 +2502,11 @@ static void cliName(char *cmdline)
{ {
uint32_t len = strlen(cmdline); uint32_t len = strlen(cmdline);
if (len > 0) { if (len > 0) {
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name)); memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH)); strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
} }
cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-"); cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-");
return; return;
} }
@ -2697,7 +2697,7 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
break; break;
} }
} }
static void cliPrintVarRange(const clivalue_t *var) static void cliPrintVarRange(const clivalue_t *var)
{ {
switch (var->type & VALUE_MODE_MASK) { switch (var->type & VALUE_MODE_MASK) {
case (MODE_DIRECT): { case (MODE_DIRECT): {
@ -2709,7 +2709,7 @@ static void cliPrintVarRange(const clivalue_t *var)
cliPrint("Allowed values:"); cliPrint("Allowed values:");
uint8_t i; uint8_t i;
for (i = 0; i < tableEntry->valueCount ; i++) { for (i = 0; i < tableEntry->valueCount ; i++) {
if (i > 0) if (i > 0)
cliPrint(","); cliPrint(",");
cliPrintf(" %s", tableEntry->values[i]); cliPrintf(" %s", tableEntry->values[i]);
} }
@ -2923,7 +2923,7 @@ static void cliStatus(char *cmdline)
#ifdef USE_SDCARD #ifdef USE_SDCARD
cliSdInfo(NULL); cliSdInfo(NULL);
#endif #endif
} }
#ifndef SKIP_TASK_STATISTICS #ifndef SKIP_TASK_STATISTICS

View file

@ -1876,9 +1876,9 @@ static bool processInCommand(void)
masterConfig.baro_hardware = read8(); masterConfig.baro_hardware = read8();
masterConfig.mag_hardware = read8(); masterConfig.mag_hardware = read8();
break; break;
case MSP_SET_NAME: case MSP_SET_NAME:
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name)); memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
for (i = 0; i < MIN(MAX_NAME_LENGTH, currentPort->dataSize); i++) { for (i = 0; i < MIN(MAX_NAME_LENGTH, currentPort->dataSize); i++) {
masterConfig.name[i] = read8(); masterConfig.name[i] = read8();
} }

View file

@ -14,7 +14,7 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#pragma once #pragma once
#define VTX_BAND_MIN 1 #define VTX_BAND_MIN 1

View file

@ -313,7 +313,7 @@ void init(void)
bool use_unsyncedPwm = masterConfig.use_unsyncedPwm; bool use_unsyncedPwm = masterConfig.use_unsyncedPwm;
// Configurator feature abused for enabling Fast PWM // Configurator feature abused for enabling Fast PWM
pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED);
pwm_params.pwmProtocolType = masterConfig.motor_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;

View file

@ -226,7 +226,7 @@ static void xBusUnpackRJ01Frame(void)
uint8_t outerCrc = 0; uint8_t outerCrc = 0;
uint8_t i = 0; uint8_t i = 0;
// When using the Align RJ01 receiver with // When using the Align RJ01 receiver with
// a MODE B setting in the radio (XG14 tested) // a MODE B setting in the radio (XG14 tested)
// the MODE_B -frame is packed within some // the MODE_B -frame is packed within some
// at the moment unknown bytes before and after: // at the moment unknown bytes before and after:
@ -234,7 +234,7 @@ static void xBusUnpackRJ01Frame(void)
// Compared to a standard MODE B frame that only // Compared to a standard MODE B frame that only
// contains the "middle" package. // contains the "middle" package.
// Hence, at the moment, the unknown header and footer // Hence, at the moment, the unknown header and footer
// of the RJ01 MODEB packages are discarded. // of the RJ01 MODEB packages are discarded.
// However, the LAST byte (CRC_OUTER) is infact an 8-bit // However, the LAST byte (CRC_OUTER) is infact an 8-bit
// CRC for the whole package, using the Dallas-One-Wire CRC // CRC for the whole package, using the Dallas-One-Wire CRC
// method. // method.

View file

@ -91,7 +91,7 @@ void updateBattery(void)
/* Actual battery state is calculated below, this is really BATTERY_PRESENT */ /* Actual battery state is calculated below, this is really BATTERY_PRESENT */
batteryState = BATTERY_OK; batteryState = BATTERY_OK;
/* wait for VBatt to stabilise then we can calc number of cells /* wait for VBatt to stabilise then we can calc number of cells
(using the filtered value takes a long time to ramp up) (using the filtered value takes a long time to ramp up)
We only do this on the ground so don't care if we do block, not We only do this on the ground so don't care if we do block, not
worse than original code anyway*/ worse than original code anyway*/
delay(VBATTERY_STABLE_DELAY); delay(VBATTERY_STABLE_DELAY);

View file

@ -89,7 +89,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
#if defined(MPU_INT_EXTI) #if defined(MPU_INT_EXTI)
static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) }; static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) };
return &mpuIntExtiConfig; return &mpuIntExtiConfig;
#elif defined(USE_HARDWARE_REVISION_DETECTION) #elif defined(USE_HARDWARE_REVISION_DETECTION)
return selectMPUIntExtiConfigByHardwareRevision(); return selectMPUIntExtiConfigByHardwareRevision();
#else #else
return NULL; return NULL;

View file

@ -21,7 +21,7 @@
#define USE_CLI #define USE_CLI
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB5 // Blue LED - PB5 #define LED0 PB5 // Blue LED - PB5
#define BEEPER PA0 #define BEEPER PA0

View file

@ -15,7 +15,7 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#pragma once #pragma once
#include "drivers/exti.h" #include "drivers/exti.h"
typedef enum awf3HardwareRevision_t { typedef enum awf3HardwareRevision_t {

View file

@ -33,7 +33,7 @@ const uint16_t multiPPM[] = {
}; };
const uint16_t multiPWM[] = { const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),

View file

@ -141,7 +141,7 @@
#define LED_STRIP #define LED_STRIP
// LED Strip can run off Pin 6 (PB1) of the ESC outputs. // LED Strip can run off Pin 6 (PB1) of the ESC outputs.
#define WS2811_PIN PB1 #define WS2811_PIN PB1
#define WS2811_TIMER TIM3 #define WS2811_TIMER TIM3
#define WS2811_TIMER_CHANNEL TIM_Channel_4 #define WS2811_TIMER_CHANNEL TIM_Channel_4
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER #define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER

View file

@ -22,8 +22,8 @@
#ifndef STM32F3DISCOVERY #ifndef STM32F3DISCOVERY
#define STM32F3DISCOVERY #define STM32F3DISCOVERY
#endif #endif
#define LED0 PE8 // Blue LEDs - PE8/PE12 #define LED0 PE8 // Blue LEDs - PE8/PE12
#define LED0_INVERTED #define LED0_INVERTED
#define LED1 PE10 // Orange LEDs - PE10/PE14 #define LED1 PE10 // Orange LEDs - PE10/PE14

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "drivers/exti.h" #include "drivers/exti.h"
typedef enum cjmcuHardwareRevision_t { typedef enum cjmcuHardwareRevision_t {
UNKNOWN = 0, UNKNOWN = 0,
REV_1, // Blue LED3 REV_1, // Blue LED3

View file

@ -23,7 +23,7 @@
#define TARGET_CONFIG #define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PC15 #define LED0 PC15
#define LED1 PC14 #define LED1 PC14
#define LED2 PC13 #define LED2 PC13

View file

@ -43,7 +43,7 @@ const uint16_t multiPWM[] = {
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF 0xFFFF
}; };

View file

@ -20,7 +20,7 @@
#define TARGET_BOARD_IDENTIFIER "DOGE" #define TARGET_BOARD_IDENTIFIER "DOGE"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
// tqfp48 pin 34 // tqfp48 pin 34
#define LED0 PA13 #define LED0 PA13
// tqfp48 pin 37 // tqfp48 pin 37

View file

@ -30,11 +30,11 @@ const uint16_t multiPWM[] = {
PWM3 | (MAP_TO_PWM_INPUT << 8), PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8), PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8), PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8), PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // input #8 PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // input #8
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
@ -69,11 +69,11 @@ const uint16_t airPWM[] = {
PWM3 | (MAP_TO_PWM_INPUT << 8), PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8), PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8), PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8), PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
@ -101,7 +101,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed { TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed
}; };

View file

@ -76,7 +76,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - S2 { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - S2
{ TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10}, // PWM6 - S3 { TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10}, // PWM6 - S3
{ TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - S4 { TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - S4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO TIMER - LED_STRIP { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO TIMER - LED_STRIP
}; };

View file

@ -24,7 +24,7 @@
#define MPU_INT_EXTI PC4 #define MPU_INT_EXTI PC4
#define USE_EXTI #define USE_EXTI
#define CONFIG_PREFER_ACC_ON #define CONFIG_PREFER_ACC_ON
#define LED0 PC14 #define LED0 PC14
#define BEEPER PC15 #define BEEPER PC15

View file

@ -21,7 +21,7 @@
#define BOARD_HAS_VOLTAGE_DIVIDER #define BOARD_HAS_VOLTAGE_DIVIDER
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PC15 #define LED0 PC15
#define LED1 PC14 #define LED1 PC14
#define LED2 PC13 #define LED2 PC13

View file

@ -21,7 +21,7 @@
#define USE_CLI #define USE_CLI
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB5 // Blue LEDs - PB5 #define LED0 PB5 // Blue LEDs - PB5
//#define LED1 PB9 // Green LEDs - PB9 //#define LED1 PB9 // Green LEDs - PB9

View file

@ -73,7 +73,7 @@
//#define DEBUG_MAG_DATA_READY_INTERRUPT //#define DEBUG_MAG_DATA_READY_INTERRUPT
#define USE_MAG_DATA_READY_SIGNAL #define USE_MAG_DATA_READY_SIGNAL
#define MAG_INT_EXTI PC14 #define MAG_INT_EXTI PC14
#define GYRO #define GYRO
#define USE_GYRO_MPU3050 #define USE_GYRO_MPU3050
#define USE_GYRO_MPU6050 #define USE_GYRO_MPU6050

View file

@ -93,7 +93,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S4_IN { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S5_IN { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S6_IN { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S1_OUT { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S2_OUT { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9 }, // S3_OUT { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9 }, // S3_OUT

View file

@ -107,7 +107,7 @@
#define VBAT_ADC_PIN PC2 #define VBAT_ADC_PIN PC2
#define RSSI_ADC_GPIO_PIN PA0 #define RSSI_ADC_GPIO_PIN PA0
#define SENSORS_SET (SENSOR_ACC) #define SENSORS_SET (SENSOR_ACC)

View file

@ -20,7 +20,7 @@
#define TARGET_BOARD_IDENTIFIER "SPEV" #define TARGET_BOARD_IDENTIFIER "SPEV"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define LED0 PB8 #define LED0 PB8
#define BEEPER PC15 #define BEEPER PC15

View file

@ -74,7 +74,7 @@
#define SPI1_SCK_PIN PB3 #define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4 #define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5 #define SPI1_MOSI_PIN PB5
#define MPU6500_CS_PIN PB9 #define MPU6500_CS_PIN PB9
#define MPU6500_SPI_INSTANCE SPI1 #define MPU6500_SPI_INSTANCE SPI1

View file

@ -14,7 +14,7 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#pragma once #pragma once
#define I2C1_OVERCLOCK true #define I2C1_OVERCLOCK true

View file

@ -9,17 +9,17 @@
* and is generated by the clock configuration tool * and is generated by the clock configuration tool
* stm32f30x_Clock_Configuration_V1.0.0.xls * stm32f30x_Clock_Configuration_V1.0.0.xls
* *
* 1. This file provides two functions and one global variable to be called from * 1. This file provides two functions and one global variable to be called from
* user application: * user application:
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
* and Divider factors, AHB/APBx prescalers and Flash settings), * and Divider factors, AHB/APBx prescalers and Flash settings),
* depending on the configuration made in the clock xls tool. * depending on the configuration made in the clock xls tool.
* This function is called at startup just after reset and * This function is called at startup just after reset and
* before branch to main program. This call is made inside * before branch to main program. This call is made inside
* the "startup_stm32f30x.s" file. * the "startup_stm32f30x.s" file.
* *
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick * by the user application to setup the SysTick
* timer or configure other parameters. * timer or configure other parameters.
* *
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
@ -31,7 +31,7 @@
* configure the system clock before to branch to main program. * configure the system clock before to branch to main program.
* *
* 3. If the system clock source selected by user fails to startup, the SystemInit() * 3. If the system clock source selected by user fails to startup, the SystemInit()
* function will do nothing and HSI still used as system clock source. User can * function will do nothing and HSI still used as system clock source. User can
* add some code to deal with this issue inside the SetSysClock() function. * add some code to deal with this issue inside the SetSysClock() function.
* *
* 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
@ -79,8 +79,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
@ -93,8 +93,8 @@
/** @addtogroup stm32f30x_system /** @addtogroup stm32f30x_system
* @{ * @{
*/ */
/** @addtogroup STM32F30x_System_Private_Includes /** @addtogroup STM32F30x_System_Private_Includes
* @{ * @{
*/ */
@ -113,13 +113,13 @@ uint32_t hse_value = HSE_VALUE;
* @{ * @{
*/ */
/*!< Uncomment the following line if you need to relocate your vector Table in /*!< Uncomment the following line if you need to relocate your vector Table in
Internal SRAM. */ Internal SRAM. */
/* #define VECT_TAB_SRAM */ /* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. #define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */ This value must be a multiple of 0x200. */
/** /**
* @} * @}
*/ */
/* Private macro -------------------------------------------------------------*/ /* Private macro -------------------------------------------------------------*/
@ -151,7 +151,7 @@ void SetSysClock(void);
/** /**
* @brief Setup the microcontroller system * @brief Setup the microcontroller system
* Initialize the Embedded Flash Interface, the PLL and update the * Initialize the Embedded Flash Interface, the PLL and update the
* SystemFrequency variable. * SystemFrequency variable.
* @param None * @param None
* @retval None * @retval None
@ -184,19 +184,19 @@ void SystemInit(void)
/* Reset USARTSW[1:0], I2CSW and TIMs bits */ /* Reset USARTSW[1:0], I2CSW and TIMs bits */
RCC->CFGR3 &= (uint32_t)0xFF00FCCC; RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
/* Disable all interrupts */ /* Disable all interrupts */
RCC->CIR = 0x00000000; RCC->CIR = 0x00000000;
/* Configure the System clock source, PLL Multiplier and Divider factors, /* Configure the System clock source, PLL Multiplier and Divider factors,
AHB/APBx prescalers and Flash settings ----------------------------------*/ AHB/APBx prescalers and Flash settings ----------------------------------*/
//SetSysClock(); // called from main() //SetSysClock(); // called from main()
#ifdef VECT_TAB_SRAM #ifdef VECT_TAB_SRAM
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
#else #else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
#endif #endif
} }
/** /**
@ -204,25 +204,25 @@ void SystemInit(void)
* The SystemCoreClock variable contains the core clock (HCLK), it can * The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure * be used by the user application to setup the SysTick timer or configure
* other parameters. * other parameters.
* *
* @note Each time the core clock (HCLK) changes, this function must be called * @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration * to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect. * based on this variable will be incorrect.
* *
* @note - The system frequency computed by this function is not the real * @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined * frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source: * constant and the selected clock source:
* *
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
* *
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
* *
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied/divided by the PLL factors. * or HSI_VALUE(*) multiplied/divided by the PLL factors.
* *
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value * (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
* 8 MHz) but the real value may vary depending on the variations * 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature. * in voltage and temperature.
* *
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value * (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
* 8 MHz), user has to ensure that HSE_VALUE is same as the real * 8 MHz), user has to ensure that HSE_VALUE is same as the real
@ -231,7 +231,7 @@ void SystemInit(void)
* *
* - The result of this function could be not correct when using fractional * - The result of this function could be not correct when using fractional
* value for HSE crystal. * value for HSE crystal.
* *
* @param None * @param None
* @retval None * @retval None
*/ */
@ -241,7 +241,7 @@ void SystemCoreClockUpdate (void)
/* Get SYSCLK source -------------------------------------------------------*/ /* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS; tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp) switch (tmp)
{ {
case 0x00: /* HSI used as system clock */ case 0x00: /* HSI used as system clock */
@ -255,7 +255,7 @@ void SystemCoreClockUpdate (void)
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = ( pllmull >> 18) + 2; pllmull = ( pllmull >> 18) + 2;
if (pllsource == 0x00) if (pllsource == 0x00)
{ {
/* HSI oscillator clock divided by 2 selected as PLL clock entry */ /* HSI oscillator clock divided by 2 selected as PLL clock entry */
@ -265,8 +265,8 @@ void SystemCoreClockUpdate (void)
{ {
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
/* HSE oscillator clock selected as PREDIV1 clock entry */ /* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
} }
break; break;
default: /* HSI used as system clock */ default: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE; SystemCoreClock = HSI_VALUE;
@ -276,7 +276,7 @@ void SystemCoreClockUpdate (void)
/* Get HCLK prescaler */ /* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */ /* HCLK clock frequency */
SystemCoreClock >>= tmp; SystemCoreClock >>= tmp;
} }
/** /**
@ -298,7 +298,7 @@ void SetSysClock(void)
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
/* Enable HSE */ /* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON); RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */ /* Wait till HSE is ready and if Time out is reached exit */
do do
{ {
@ -319,13 +319,13 @@ void SetSysClock(void)
{ {
/* Enable Prefetch Buffer and set Flash Latency */ /* Enable Prefetch Buffer and set Flash Latency */
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1; FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
/* HCLK = SYSCLK / 1 */ /* HCLK = SYSCLK / 1 */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK / 1 */ /* PCLK2 = HCLK / 1 */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK / 2 */ /* PCLK1 = HCLK / 2 */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;

View file

@ -4,7 +4,7 @@
* @author MCD Application Team * @author MCD Application Team
* @version V1.1.1 * @version V1.1.1
* @date 28-March-2014 * @date 28-March-2014
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices. * @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
****************************************************************************** ******************************************************************************
* @attention * @attention
* *
@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
@ -31,8 +31,8 @@
/** @addtogroup stm32f30x_system /** @addtogroup stm32f30x_system
* @{ * @{
*/ */
/** /**
* @brief Define to prevent recursive inclusion * @brief Define to prevent recursive inclusion
*/ */
@ -41,7 +41,7 @@
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
/* Exported types ------------------------------------------------------------*/ /* Exported types ------------------------------------------------------------*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
@ -52,7 +52,7 @@ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Cloc
/** @addtogroup STM32F30x_System_Exported_Functions /** @addtogroup STM32F30x_System_Exported_Functions
* @{ * @{
*/ */
extern void SystemInit(void); extern void SystemInit(void);
extern void SystemCoreClockUpdate(void); extern void SystemCoreClockUpdate(void);
@ -69,8 +69,8 @@ extern void SystemCoreClockUpdate(void);
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -4,8 +4,8 @@
* @author MCD Application Team * @author MCD Application Team
* @version V1.6.1 * @version V1.6.1
* @date 21-October-2015 * @date 21-October-2015
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
****************************************************************************** ******************************************************************************
* @attention * @attention
* *
* <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2> * <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2>
@ -16,21 +16,21 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
* *
****************************************************************************** ******************************************************************************
*/ */
#ifndef __SYSTEM_STM32F4XX_H #ifndef __SYSTEM_STM32F4XX_H
#define __SYSTEM_STM32F4XX_H #define __SYSTEM_STM32F4XX_H
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
extern void SystemInit(void); extern void SystemInit(void);

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
@ -68,13 +68,13 @@ void Set_System(void)
{ {
#if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS) #if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS)
GPIO_InitTypeDef GPIO_InitStructure; GPIO_InitTypeDef GPIO_InitStructure;
#endif /* STM32L1XX_MD && STM32L1XX_XD */ #endif /* STM32L1XX_MD && STM32L1XX_XD */
#if defined(USB_USE_EXTERNAL_PULLUP) #if defined(USB_USE_EXTERNAL_PULLUP)
GPIO_InitTypeDef GPIO_InitStructure; GPIO_InitTypeDef GPIO_InitStructure;
#endif /* USB_USE_EXTERNAL_PULLUP */ #endif /* USB_USE_EXTERNAL_PULLUP */
/*!< At this stage the microcontroller clock setting is already configured, /*!< At this stage the microcontroller clock setting is already configured,
this is done through SystemInit() function which is called from startup this is done through SystemInit() function which is called from startup
file (startup_stm32f10x_xx.s) before to branch to application main. file (startup_stm32f10x_xx.s) before to branch to application main.
To reconfigure the default setting of SystemInit() function, refer to To reconfigure the default setting of SystemInit() function, refer to
@ -83,7 +83,7 @@ void Set_System(void)
#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F303xC) #if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F303xC)
/* Enable the SYSCFG module clock */ /* Enable the SYSCFG module clock */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif /* STM32L1XX_XD */ #endif /* STM32L1XX_XD */
/*Pull down PA12 to create USB Disconnect Pulse*/ // HJI /*Pull down PA12 to create USB Disconnect Pulse*/ // HJI
#if defined(STM32F303xC) // HJI #if defined(STM32F303xC) // HJI
@ -277,7 +277,7 @@ static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len)
/******************************************************************************* /*******************************************************************************
* Function Name : Send DATA . * Function Name : Send DATA .
* Description : send the data received from the STM32 to the PC through USB * Description : send the data received from the STM32 to the PC through USB
* Input : None. * Input : None.
* Output : None. * Output : None.
* Return : None. * Return : None.

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.

View file

@ -1,6 +1,6 @@
/** /**
****************************************************************************** ******************************************************************************
* @file GPIO/IOToggle/stm32f4xx_it.h * @file GPIO/IOToggle/stm32f4xx_it.h
* @author MCD Application Team * @author MCD Application Team
* @version V1.0.0 * @version V1.0.0
* @date 19-September-2011 * @date 19-September-2011
@ -17,7 +17,7 @@
* *
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2> * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
****************************************************************************** ******************************************************************************
*/ */
/* Define to prevent recursive inclusion -------------------------------------*/ /* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F4xx_IT_H #ifndef __STM32F4xx_IT_H
@ -25,7 +25,7 @@
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "stm32f4xx.h" #include "stm32f4xx.h"

View file

@ -30,15 +30,15 @@
/** @addtogroup USB_OTG_DRIVER /** @addtogroup USB_OTG_DRIVER
* @{ * @{
*/ */
/** @defgroup USB_CONF /** @defgroup USB_CONF
* @brief USB low level driver configuration file * @brief USB low level driver configuration file
* @{ * @{
*/ */
/** @defgroup USB_CONF_Exported_Defines /** @defgroup USB_CONF_Exported_Defines
* @{ * @{
*/ */
/* USB Core and PHY interface configuration. /* USB Core and PHY interface configuration.
Tip: To avoid modifying these defines each time you need to change the USB Tip: To avoid modifying these defines each time you need to change the USB
@ -66,7 +66,7 @@
#endif /* USE_I2C_PHY */ #endif /* USE_I2C_PHY */
#ifdef USE_USB_OTG_FS #ifdef USE_USB_OTG_FS
#define USB_OTG_FS_CORE #define USB_OTG_FS_CORE
#endif #endif
@ -76,35 +76,35 @@
/******************************************************************************* /*******************************************************************************
* FIFO Size Configuration in Device mode * FIFO Size Configuration in Device mode
* *
* (i) Receive data FIFO size = RAM for setup packets + * (i) Receive data FIFO size = RAM for setup packets +
* OUT endpoint control information + * OUT endpoint control information +
* data OUT packets + miscellaneous * data OUT packets + miscellaneous
* Space = ONE 32-bits words * Space = ONE 32-bits words
* --> RAM for setup packets = 10 spaces * --> RAM for setup packets = 10 spaces
* (n is the nbr of CTRL EPs the device core supports) * (n is the nbr of CTRL EPs the device core supports)
* --> OUT EP CTRL info = 1 space * --> OUT EP CTRL info = 1 space
* (one space for status information written to the FIFO along with each * (one space for status information written to the FIFO along with each
* received packet) * received packet)
* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces * --> data OUT packets = (Largest Packet Size / 4) + 1 spaces
* (MINIMUM to receive packets) * (MINIMUM to receive packets)
* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces * --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces
* (if high-bandwidth EP is enabled or multiple isochronous EPs) * (if high-bandwidth EP is enabled or multiple isochronous EPs)
* --> miscellaneous = 1 space per OUT EP * --> miscellaneous = 1 space per OUT EP
* (one space for transfer complete status information also pushed to the * (one space for transfer complete status information also pushed to the
* FIFO with each endpoint's last packet) * FIFO with each endpoint's last packet)
* *
* (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for * (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for
* that particular IN EP. More space allocated in the IN EP Tx FIFO results * that particular IN EP. More space allocated in the IN EP Tx FIFO results
* in a better performance on the USB and can hide latencies on the AHB. * in a better performance on the USB and can hide latencies on the AHB.
* *
* (iii) TXn min size = 16 words. (n : Transmit FIFO index) * (iii) TXn min size = 16 words. (n : Transmit FIFO index)
* (iv) When a TxFIFO is not used, the Configuration should be as follows: * (iv) When a TxFIFO is not used, the Configuration should be as follows:
* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) * case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txm can use the space allocated for Txn. * --> Txm can use the space allocated for Txn.
* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) * case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txn should be configured with the minimum space of 16 words * --> Txn should be configured with the minimum space of 16 words
* (v) The FIFO is used optimally when used TxFIFOs are allocated in the top * (v) The FIFO is used optimally when used TxFIFOs are allocated in the top
* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. * of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones.
*******************************************************************************/ *******************************************************************************/
@ -126,7 +126,7 @@
* then the space must be at least two times the maximum packet size for * then the space must be at least two times the maximum packet size for
* that channel. * that channel.
*******************************************************************************/ *******************************************************************************/
/****************** USB OTG HS CONFIGURATION **********************************/ /****************** USB OTG HS CONFIGURATION **********************************/
#ifdef USB_OTG_HS_CORE #ifdef USB_OTG_HS_CORE
#define RX_FIFO_HS_SIZE 512 #define RX_FIFO_HS_SIZE 512
@ -211,20 +211,20 @@
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined (__GNUC__) /* GNU Compiler */ #if defined (__GNUC__) /* GNU Compiler */
#define __ALIGN_END __attribute__ ((aligned (4))) #define __ALIGN_END __attribute__ ((aligned (4)))
#define __ALIGN_BEGIN #define __ALIGN_BEGIN
#else #else
#define __ALIGN_END #define __ALIGN_END
#if defined (__CC_ARM) /* ARM Compiler */ #if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#elif defined (__TASKING__) /* TASKING Compiler */
#define __ALIGN_BEGIN __align(4) #define __ALIGN_BEGIN __align(4)
#endif /* __CC_ARM */ #elif defined (__ICCARM__) /* IAR Compiler */
#endif /* __GNUC__ */ #define __ALIGN_BEGIN
#elif defined (__TASKING__) /* TASKING Compiler */
#define __ALIGN_BEGIN __align(4)
#endif /* __CC_ARM */
#endif /* __GNUC__ */
#else #else
#define __ALIGN_BEGIN #define __ALIGN_BEGIN
#define __ALIGN_END #define __ALIGN_END
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* __packed keyword used to decrease the data type alignment to 1-byte */ /* __packed keyword used to decrease the data type alignment to 1-byte */
@ -242,37 +242,37 @@
/** /**
* @} * @}
*/ */
/** @defgroup USB_CONF_Exported_Types /** @defgroup USB_CONF_Exported_Types
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USB_CONF_Exported_Macros /** @defgroup USB_CONF_Exported_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USB_CONF_Exported_Variables /** @defgroup USB_CONF_Exported_Variables
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USB_CONF_Exported_FunctionsPrototype /** @defgroup USB_CONF_Exported_FunctionsPrototype
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
#endif //__USB_CONF__H__ #endif //__USB_CONF__H__
@ -280,10 +280,10 @@
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View file

@ -19,8 +19,8 @@
****************************************************************************** ******************************************************************************
*/ */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#pragma data_alignment = 4 #pragma data_alignment = 4
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
@ -34,7 +34,7 @@ LINE_CODING g_lc;
extern __IO uint8_t USB_Tx_State; extern __IO uint8_t USB_Tx_State;
__IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */ __IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
/* These are external variables imported from CDC core to be used for IN /* These are external variables imported from CDC core to be used for IN
transfer management. */ transfer management. */
extern uint8_t APP_Rx_Buffer[]; /* Write CDC received data in this buffer. extern uint8_t APP_Rx_Buffer[]; /* Write CDC received data in this buffer.
These data will be sent over USB IN endpoint These data will be sent over USB IN endpoint
@ -105,7 +105,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
assert_param(Len>=sizeof(LINE_CODING)); assert_param(Len>=sizeof(LINE_CODING));
switch (Cmd) { switch (Cmd) {
/* Not needed for this driver, AT modem commands */ /* Not needed for this driver, AT modem commands */
case SEND_ENCAPSULATED_COMMAND: case SEND_ENCAPSULATED_COMMAND:
case GET_ENCAPSULATED_RESPONSE: case GET_ENCAPSULATED_RESPONSE:
break; break;
@ -116,18 +116,18 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
case CLEAR_COMM_FEATURE: case CLEAR_COMM_FEATURE:
break; break;
//Note - hw flow control on UART 1-3 and 6 only //Note - hw flow control on UART 1-3 and 6 only
case SET_LINE_CODING: case SET_LINE_CODING:
ust_cpy(&g_lc, plc); //Copy into structure to save for later ust_cpy(&g_lc, plc); //Copy into structure to save for later
break; break;
case GET_LINE_CODING: case GET_LINE_CODING:
ust_cpy(plc, &g_lc); ust_cpy(plc, &g_lc);
break; break;
case SET_CONTROL_LINE_STATE: case SET_CONTROL_LINE_STATE:
/* Not needed for this driver */ /* Not needed for this driver */
//RSW - This tells how to set RTS and DTR //RSW - This tells how to set RTS and DTR
@ -153,7 +153,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
*******************************************************************************/ *******************************************************************************/
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength) uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
{ {
if (USB_Tx_State) if (USB_Tx_State)
return 0; return 0;
VCP_DataTx(ptrBuffer, sendLength); VCP_DataTx(ptrBuffer, sendLength);
@ -177,7 +177,7 @@ static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len)
return USBD_OK; return USBD_OK;
} }
uint8_t usbAvailable(void) uint8_t usbAvailable(void)
{ {
return (usbData.bufferInPosition != usbData.bufferOutPosition); return (usbData.bufferInPosition != usbData.bufferOutPosition);
} }

View file

@ -59,7 +59,7 @@ typedef enum _DEVICE_STATE {
} DEVICE_STATE; } DEVICE_STATE;
/* Exported typef ------------------------------------------------------------*/ /* Exported typef ------------------------------------------------------------*/
/* The following structures groups all needed parameters to be configured for the /* The following structures groups all needed parameters to be configured for the
ComPort. These parameters can modified on the fly by the host through CDC class ComPort. These parameters can modified on the fly by the host through CDC class
command class requests. */ command class requests. */
typedef struct typedef struct

View file

@ -60,36 +60,36 @@
#define APP_FOPS VCP_fops #define APP_FOPS VCP_fops
/** /**
* @} * @}
*/ */
/** @defgroup USB_CONF_Exported_Types /** @defgroup USB_CONF_Exported_Types
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USB_CONF_Exported_Macros /** @defgroup USB_CONF_Exported_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USB_CONF_Exported_Variables /** @defgroup USB_CONF_Exported_Variables
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USB_CONF_Exported_FunctionsPrototype /** @defgroup USB_CONF_Exported_FunctionsPrototype
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
#endif //__USBD_CONF__H__ #endif //__USBD_CONF__H__

View file

@ -17,7 +17,7 @@
* *
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2> * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
****************************************************************************** ******************************************************************************
*/ */
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "usbd_core.h" #include "usbd_core.h"
@ -32,22 +32,22 @@
*/ */
/** @defgroup USBD_DESC /** @defgroup USBD_DESC
* @brief USBD descriptors module * @brief USBD descriptors module
* @{ * @{
*/ */
/** @defgroup USBD_DESC_Private_TypesDefinitions /** @defgroup USBD_DESC_Private_TypesDefinitions
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Private_Defines /** @defgroup USBD_DESC_Private_Defines
* @{ * @{
*/ */
#define USBD_VID 0x0483 #define USBD_VID 0x0483
@ -55,7 +55,7 @@
/** @defgroup USB_String_Descriptors /** @defgroup USB_String_Descriptors
* @{ * @{
*/ */
#define USBD_LANGID_STRING 0x409 #define USBD_LANGID_STRING 0x409
#define USBD_MANUFACTURER_STRING "BetaFlight" #define USBD_MANUFACTURER_STRING "BetaFlight"
@ -83,36 +83,36 @@
#define USBD_INTERFACE_FS_STRING "VCP Interface" #define USBD_INTERFACE_FS_STRING "VCP Interface"
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Private_Macros /** @defgroup USBD_DESC_Private_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Private_Variables /** @defgroup USBD_DESC_Private_Variables
* @{ * @{
*/ */
USBD_DEVICE USR_desc = USBD_DEVICE USR_desc =
{ {
USBD_USR_DeviceDescriptor, USBD_USR_DeviceDescriptor,
USBD_USR_LangIDStrDescriptor, USBD_USR_LangIDStrDescriptor,
USBD_USR_ManufacturerStrDescriptor, USBD_USR_ManufacturerStrDescriptor,
USBD_USR_ProductStrDescriptor, USBD_USR_ProductStrDescriptor,
USBD_USR_SerialStrDescriptor, USBD_USR_SerialStrDescriptor,
USBD_USR_ConfigStrDescriptor, USBD_USR_ConfigStrDescriptor,
USBD_USR_InterfaceStrDescriptor, USBD_USR_InterfaceStrDescriptor,
}; };
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */ #if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4 #pragma data_alignment=4
#endif #endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */ /* USB Standard Device Descriptor */
@ -140,7 +140,7 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_SIZ_DEVICE_DESC] __ALIGN_END =
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */ #if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4 #pragma data_alignment=4
#endif #endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */ /* USB Standard Device Descriptor */
@ -160,36 +160,36 @@ __ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALI
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */ #if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4 #pragma data_alignment=4
#endif #endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */ /* USB Standard Device Descriptor */
__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END = __ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END =
{ {
USB_SIZ_STRING_LANGID, USB_SIZ_STRING_LANGID,
USB_DESC_TYPE_STRING, USB_DESC_TYPE_STRING,
LOBYTE(USBD_LANGID_STRING), LOBYTE(USBD_LANGID_STRING),
HIBYTE(USBD_LANGID_STRING), HIBYTE(USBD_LANGID_STRING),
}; };
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Private_FunctionPrototypes /** @defgroup USBD_DESC_Private_FunctionPrototypes
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Private_Functions /** @defgroup USBD_DESC_Private_Functions
* @{ * @{
*/ */
/** /**
* @brief USBD_USR_DeviceDescriptor * @brief USBD_USR_DeviceDescriptor
* return the device descriptor * return the device descriptor
* @param speed : current device speed * @param speed : current device speed
* @param length : pointer to data length variable * @param length : pointer to data length variable
@ -203,7 +203,7 @@ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length)
} }
/** /**
* @brief USBD_USR_LangIDStrDescriptor * @brief USBD_USR_LangIDStrDescriptor
* return the LangID string descriptor * return the LangID string descriptor
* @param speed : current device speed * @param speed : current device speed
* @param length : pointer to data length variable * @param length : pointer to data length variable
@ -212,13 +212,13 @@ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length)
uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length) uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length)
{ {
(void)speed; (void)speed;
*length = sizeof(USBD_LangIDDesc); *length = sizeof(USBD_LangIDDesc);
return USBD_LangIDDesc; return USBD_LangIDDesc;
} }
/** /**
* @brief USBD_USR_ProductStrDescriptor * @brief USBD_USR_ProductStrDescriptor
* return the product string descriptor * return the product string descriptor
* @param speed : current device speed * @param speed : current device speed
* @param length : pointer to data length variable * @param length : pointer to data length variable
@ -226,8 +226,8 @@ uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length)
*/ */
uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length) uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length)
{ {
if(speed == 0) if(speed == 0)
USBD_GetString ((uint8_t*)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length); USBD_GetString ((uint8_t*)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
else else
@ -237,7 +237,7 @@ uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length)
} }
/** /**
* @brief USBD_USR_ManufacturerStrDescriptor * @brief USBD_USR_ManufacturerStrDescriptor
* return the manufacturer string descriptor * return the manufacturer string descriptor
* @param speed : current device speed * @param speed : current device speed
* @param length : pointer to data length variable * @param length : pointer to data length variable
@ -251,7 +251,7 @@ uint8_t * USBD_USR_ManufacturerStrDescriptor( uint8_t speed , uint16_t *length)
} }
/** /**
* @brief USBD_USR_SerialStrDescriptor * @brief USBD_USR_SerialStrDescriptor
* return the serial number string descriptor * return the serial number string descriptor
* @param speed : current device speed * @param speed : current device speed
* @param length : pointer to data length variable * @param length : pointer to data length variable
@ -268,7 +268,7 @@ uint8_t * USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length)
} }
/** /**
* @brief USBD_USR_ConfigStrDescriptor * @brief USBD_USR_ConfigStrDescriptor
* return the configuration string descriptor * return the configuration string descriptor
* @param speed : current device speed * @param speed : current device speed
* @param length : pointer to data length variable * @param length : pointer to data length variable
@ -281,12 +281,12 @@ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length)
else else
USBD_GetString ((uint8_t*)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length); USBD_GetString ((uint8_t*)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
return USBD_StrDesc; return USBD_StrDesc;
} }
/** /**
* @brief USBD_USR_InterfaceStrDescriptor * @brief USBD_USR_InterfaceStrDescriptor
* return the interface string descriptor * return the interface string descriptor
* @param speed : current device speed * @param speed : current device speed
* @param length : pointer to data length variable * @param length : pointer to data length variable
@ -299,22 +299,22 @@ uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length)
else else
USBD_GetString ((uint8_t*)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length); USBD_GetString ((uint8_t*)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length);
return USBD_StrDesc; return USBD_StrDesc;
} }
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View file

@ -6,18 +6,18 @@
* @date 19-September-2011 * @date 19-September-2011
* @brief header file for the usbd_desc.c file * @brief header file for the usbd_desc.c file
****************************************************************************** ******************************************************************************
* @attention * @attention
* *
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
* *
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2> * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
****************************************************************************** ******************************************************************************
*/ */
/* Define to prevent recursive inclusion -------------------------------------*/ /* Define to prevent recursive inclusion -------------------------------------*/
@ -30,11 +30,11 @@
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{ * @{
*/ */
/** @defgroup USB_DESC /** @defgroup USB_DESC
* @brief general defines for the usb device library file * @brief general defines for the usb device library file
* @{ * @{
*/ */
/** @defgroup USB_DESC_Exported_Defines /** @defgroup USB_DESC_Exported_Defines
* @{ * @{
@ -49,7 +49,7 @@
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Exported_TypesDefinitions /** @defgroup USBD_DESC_Exported_TypesDefinitions
@ -57,33 +57,33 @@
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Exported_Macros /** @defgroup USBD_DESC_Exported_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Exported_Variables /** @defgroup USBD_DESC_Exported_Variables
* @{ * @{
*/ */
extern uint8_t USBD_DeviceDesc [USB_SIZ_DEVICE_DESC]; extern uint8_t USBD_DeviceDesc [USB_SIZ_DEVICE_DESC];
extern uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ]; extern uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ];
extern uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC]; extern uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC];
extern uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]; extern uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC];
extern uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID]; extern uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID];
extern USBD_DEVICE USR_desc; extern USBD_DEVICE USR_desc;
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DESC_Exported_FunctionsPrototype /** @defgroup USBD_DESC_Exported_FunctionsPrototype
* @{ * @{
*/ */
uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length);
@ -95,20 +95,20 @@ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length);
#ifdef USB_SUPPORT_USER_STRING_DESC #ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length); uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */ #endif /* USB_SUPPORT_USER_STRING_DESC */
/** /**
* @} * @}
*/ */
#endif /* __USBD_DESC_H */ #endif /* __USBD_DESC_H */
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View file

@ -17,7 +17,7 @@
* *
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2> * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
****************************************************************************** ******************************************************************************
*/ */
#include "usbd_usr.h" #include "usbd_usr.h"
#include "usbd_ioreq.h" #include "usbd_ioreq.h"
@ -29,25 +29,25 @@ USBD_Usr_cb_TypeDef USR_cb =
USBD_USR_DeviceConfigured, USBD_USR_DeviceConfigured,
USBD_USR_DeviceSuspended, USBD_USR_DeviceSuspended,
USBD_USR_DeviceResumed, USBD_USR_DeviceResumed,
USBD_USR_DeviceConnected, USBD_USR_DeviceConnected,
USBD_USR_DeviceDisconnected, USBD_USR_DeviceDisconnected,
}; };
/** /**
* @brief USBD_USR_Init * @brief USBD_USR_Init
* Displays the message on LCD for host lib initialization * Displays the message on LCD for host lib initialization
* @param None * @param None
* @retval None * @retval None
*/ */
void USBD_USR_Init(void) void USBD_USR_Init(void)
{ {
} }
/** /**
* @brief USBD_USR_DeviceReset * @brief USBD_USR_DeviceReset
* Displays the message on LCD on device Reset Event * Displays the message on LCD on device Reset Event
* @param speed : device speed * @param speed : device speed
* @retval None * @retval None
@ -56,14 +56,14 @@ void USBD_USR_DeviceReset(uint8_t speed )
{ {
switch (speed) switch (speed)
{ {
case USB_OTG_SPEED_HIGH: case USB_OTG_SPEED_HIGH:
break; break;
case USB_OTG_SPEED_FULL: case USB_OTG_SPEED_FULL:
break; break;
default: default:
break; break;
} }
} }
@ -101,7 +101,7 @@ void USBD_USR_DeviceDisconnected (void)
} }
/** /**
* @brief USBD_USR_DeviceSuspended * @brief USBD_USR_DeviceSuspended
* Displays the message on LCD on device suspend Event * Displays the message on LCD on device suspend Event
* @param None * @param None
* @retval None * @retval None
@ -113,7 +113,7 @@ void USBD_USR_DeviceSuspended(void)
/** /**
* @brief USBD_USR_DeviceResumed * @brief USBD_USR_DeviceResumed
* Displays the message on LCD on device resume Event * Displays the message on LCD on device resume Event
* @param None * @param None
* @retval None * @retval None