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

Converted tabs to spaces

This commit is contained in:
Martin Budden 2016-07-09 14:39:39 +01:00
parent adfa6c4f28
commit ea283ab98c
63 changed files with 297 additions and 297 deletions

View file

@ -401,7 +401,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7:
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8:
return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1; return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
return masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI; return masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI;
@ -638,7 +638,7 @@ static void writeInterframe(void)
*/ */
arraySubInt32(deltas, blackboxCurrent->axisPID_I, blackboxLast->axisPID_I, XYZ_AXIS_COUNT); arraySubInt32(deltas, blackboxCurrent->axisPID_I, blackboxLast->axisPID_I, XYZ_AXIS_COUNT);
blackboxWriteTag2_3S32(deltas); blackboxWriteTag2_3S32(deltas);
/* /*
* The PID D term is frequently set to zero for yaw, which makes the result from the calculation * The PID D term is frequently set to zero for yaw, which makes the result from the calculation
* always zero. So don't bother recording D results when PID D terms are zero. * always zero. So don't bother recording D results when PID D terms are zero.
@ -852,7 +852,7 @@ void startBlackbox(void)
* cache those now. * cache those now.
*/ */
blackboxBuildConditionCache(); blackboxBuildConditionCache();
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(masterConfig.modeActivationConditions, BOXBLACKBOX); blackboxModeActivationConditionPresent = isModeActivationConditionPresent(masterConfig.modeActivationConditions, BOXBLACKBOX);
blackboxIteration = 0; blackboxIteration = 0;
@ -1359,7 +1359,7 @@ static void blackboxLogIteration()
} else { } else {
blackboxCheckAndLogArmingBeep(); blackboxCheckAndLogArmingBeep();
blackboxCheckAndLogFlightMode(); // Check for FlightMode status change event blackboxCheckAndLogFlightMode(); // Check for FlightMode status change event
if (blackboxShouldLogPFrame(blackboxPFrameIndex)) { if (blackboxShouldLogPFrame(blackboxPFrameIndex)) {
/* /*
* We assume that slow frames are only interesting in that they aid the interpretation of the main data stream. * We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
@ -1496,7 +1496,7 @@ void handleBlackbox(void)
blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume); blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume);
blackboxSetState(BLACKBOX_STATE_RUNNING); blackboxSetState(BLACKBOX_STATE_RUNNING);
blackboxLogIteration(); blackboxLogIteration();
} }

View file

@ -87,7 +87,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
putf(putp, ch); written++; putf(putp, ch); written++;
} else { } else {
char lz = 0; char lz = 0;
#ifdef REQUIRE_PRINTF_LONG_SUPPORT #ifdef REQUIRE_PRINTF_LONG_SUPPORT
char lng = 0; char lng = 0;
#endif #endif
int w = 0; int w = 0;
@ -99,7 +99,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
if (ch >= '0' && ch <= '9') { if (ch >= '0' && ch <= '9') {
ch = a2i(ch, &fmt, 10, &w); ch = a2i(ch, &fmt, 10, &w);
} }
#ifdef REQUIRE_PRINTF_LONG_SUPPORT #ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (ch == 'l') { if (ch == 'l') {
ch = *(fmt++); ch = *(fmt++);
lng = 1; lng = 1;
@ -109,7 +109,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
case 0: case 0:
goto abort; goto abort;
case 'u':{ case 'u':{
#ifdef REQUIRE_PRINTF_LONG_SUPPORT #ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (lng) if (lng)
uli2a(va_arg(va, unsigned long int), 10, 0, bf); uli2a(va_arg(va, unsigned long int), 10, 0, bf);
else else
@ -119,7 +119,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
break; break;
} }
case 'd':{ case 'd':{
#ifdef REQUIRE_PRINTF_LONG_SUPPORT #ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (lng) if (lng)
li2a(va_arg(va, unsigned long int), bf); li2a(va_arg(va, unsigned long int), bf);
else else
@ -130,7 +130,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
} }
case 'x': case 'x':
case 'X': case 'X':
#ifdef REQUIRE_PRINTF_LONG_SUPPORT #ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (lng) if (lng)
uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf); uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf);
else else

View file

@ -66,10 +66,10 @@ To use the printf you need to supply your own character output function,
something like : something like :
void putc ( void* p, char c) void putc ( void* p, char c)
{ {
while (!SERIAL_PORT_EMPTY) ; while (!SERIAL_PORT_EMPTY) ;
SERIAL_PORT_TX_REGISTER = c; SERIAL_PORT_TX_REGISTER = c;
} }
Before you can call printf you need to initialize it to use your Before you can call printf you need to initialize it to use your
character output function with something like: character output function with something like:

View file

@ -56,7 +56,7 @@ http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html
(32*((v)/2L>>31 > 0) \ (32*((v)/2L>>31 > 0) \
+ LOG2_32BIT((v)*1L >>16*((v)/2L>>31 > 0) \ + LOG2_32BIT((v)*1L >>16*((v)/2L>>31 > 0) \
>>16*((v)/2L>>31 > 0))) >>16*((v)/2L>>31 > 0)))
#if 0 #if 0
// ISO C version, but no type checking // ISO C version, but no type checking
#define container_of(ptr, type, member) \ #define container_of(ptr, type, member) \

View file

@ -538,7 +538,7 @@ static void resetConf(void)
masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125; masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125;
#endif #endif
masterConfig.servo_pwm_rate = 50; masterConfig.servo_pwm_rate = 50;
#ifdef CC3D #ifdef CC3D
masterConfig.use_buzzer_p6 = 0; masterConfig.use_buzzer_p6 = 0;
#endif #endif
@ -556,7 +556,7 @@ static void resetConf(void)
masterConfig.emf_avoidance = 0; // TODO - needs removal masterConfig.emf_avoidance = 0; // TODO - needs removal
resetPidProfile(&currentProfile->pidProfile); resetPidProfile(&currentProfile->pidProfile);
for (int rI = 0; rI<MAX_RATEPROFILES; rI++) { for (int rI = 0; rI<MAX_RATEPROFILES; rI++) {
resetControlRateConfig(&masterConfig.profile[0].controlRateProfile[rI]); resetControlRateConfig(&masterConfig.profile[0].controlRateProfile[rI]);
} }
@ -1007,12 +1007,12 @@ void changeProfile(uint8_t profileIndex)
} }
void changeControlRateProfile(uint8_t profileIndex) void changeControlRateProfile(uint8_t profileIndex)
{ {
if (profileIndex > MAX_RATEPROFILES) { if (profileIndex > MAX_RATEPROFILES) {
profileIndex = MAX_RATEPROFILES - 1; profileIndex = MAX_RATEPROFILES - 1;
} }
setControlRateProfile(profileIndex); setControlRateProfile(profileIndex);
activateControlRateConfig(); activateControlRateConfig();
} }
void latchActiveFeatures() void latchActiveFeatures()

View file

@ -165,7 +165,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(void)
return true; return true;
} }
#endif #endif
return false; return false;
} }
#endif #endif
@ -236,7 +236,7 @@ void mpuIntExtiInit(void)
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI) #if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag); IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag);
#ifdef ENSURE_MPU_DATA_READY_IS_LOW #ifdef ENSURE_MPU_DATA_READY_IS_LOW
uint8_t status = IORead(mpuIntIO); uint8_t status = IORead(mpuIntIO);
if (status) { if (status) {
@ -251,7 +251,7 @@ void mpuIntExtiInit(void)
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(mpuIntIO, true); EXTIEnable(mpuIntIO, true);
#endif #endif
mpuExtiInitDone = true; mpuExtiInitDone = true;
} }

View file

@ -156,12 +156,12 @@ 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);
IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG); IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET); mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET);

View file

@ -193,7 +193,7 @@ bool mpu9250SpiDetect(void)
#endif #endif
IOInit(mpuSpi9250CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOInit(mpuSpi9250CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG); IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);

View file

@ -39,7 +39,7 @@ uint8_t adcChannelByTag(ioTag_t ioTag)
if (ioTag == adcTagMap[i].tag) if (ioTag == adcTagMap[i].tag)
return adcTagMap[i].channel; return adcTagMap[i].channel;
} }
return 0; return 0;
} }
uint16_t adcGetChannel(uint8_t channel) uint16_t adcGetChannel(uint8_t channel)

View file

@ -37,7 +37,7 @@ typedef enum ADCDevice {
#elif defined(STM32F4) #elif defined(STM32F4)
ADCDEV_2, ADCDEV_2,
ADCDEV_3, ADCDEV_3,
ADCDEV_MAX = ADCDEV_3, ADCDEV_MAX = ADCDEV_3,
#else #else
ADCDEV_MAX = ADCDEV_1, ADCDEV_MAX = ADCDEV_1,
#endif #endif
@ -47,7 +47,7 @@ typedef struct adcTagMap_s {
ioTag_t tag; ioTag_t tag;
uint8_t channel; uint8_t channel;
} adcTagMap_t; } adcTagMap_t;
typedef struct adcDevice_s { typedef struct adcDevice_s {
ADC_TypeDef* ADCx; ADC_TypeDef* ADCx;
rccPeriphTag_t rccADC; rccPeriphTag_t rccADC;

View file

@ -79,7 +79,7 @@ const adcTagMap_t adcTagMap[] = {
void adcInit(drv_adc_config_t *init) void adcInit(drv_adc_config_t *init)
{ {
#if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN) #if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN)
UNUSED(init); UNUSED(init);
#endif #endif
@ -130,11 +130,11 @@ void adcInit(drv_adc_config_t *init)
adcConfig[i].sampleTime = ADC_SampleTime_239Cycles5; adcConfig[i].sampleTime = ADC_SampleTime_239Cycles5;
adcConfig[i].enabled = true; adcConfig[i].enabled = true;
} }
RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI) RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI)
RCC_ClockCmd(adc.rccADC, ENABLE); RCC_ClockCmd(adc.rccADC, ENABLE);
RCC_ClockCmd(adc.rccDMA, ENABLE); RCC_ClockCmd(adc.rccDMA, ENABLE);
DMA_DeInit(adc.DMAy_Channelx); DMA_DeInit(adc.DMAy_Channelx);
DMA_InitTypeDef DMA_InitStructure; DMA_InitTypeDef DMA_InitStructure;
DMA_StructInit(&DMA_InitStructure); DMA_StructInit(&DMA_InitStructure);

View file

@ -132,8 +132,8 @@ void adcInit(drv_adc_config_t *init)
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
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

@ -70,7 +70,7 @@ const adcTagMap_t adcTagMap[] = {
{ DEFIO_TAG_E__PA4, ADC_Channel_4 }, { DEFIO_TAG_E__PA4, ADC_Channel_4 },
{ DEFIO_TAG_E__PA5, ADC_Channel_5 }, { DEFIO_TAG_E__PA5, ADC_Channel_5 },
{ DEFIO_TAG_E__PA6, ADC_Channel_6 }, { DEFIO_TAG_E__PA6, ADC_Channel_6 },
{ DEFIO_TAG_E__PA7, ADC_Channel_7 }, { DEFIO_TAG_E__PA7, ADC_Channel_7 },
}; };
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
@ -109,7 +109,7 @@ void adcInit(drv_adc_config_t *init)
adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL; adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL;
} }
#endif #endif
#ifdef EXTERNAL1_ADC_PIN #ifdef EXTERNAL1_ADC_PIN
if (init->enableExternal1) { if (init->enableExternal1) {
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL; adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL;
@ -123,25 +123,25 @@ void adcInit(drv_adc_config_t *init)
#endif #endif
//RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz //RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
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)
continue; continue;
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0); IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0);
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
adcConfig[i].dmaIndex = configuredAdcChannels++; adcConfig[i].dmaIndex = configuredAdcChannels++;
adcConfig[i].sampleTime = ADC_SampleTime_480Cycles; adcConfig[i].sampleTime = ADC_SampleTime_480Cycles;
adcConfig[i].enabled = true; adcConfig[i].enabled = true;
} }
RCC_ClockCmd(adc.rccDMA, ENABLE); RCC_ClockCmd(adc.rccDMA, ENABLE);
RCC_ClockCmd(adc.rccADC, ENABLE); RCC_ClockCmd(adc.rccADC, ENABLE);

View file

@ -367,7 +367,7 @@ static void bmp085_get_cal_param(void)
bool bmp085TestEOCConnected(const bmp085Config_t *config) bool bmp085TestEOCConnected(const bmp085Config_t *config)
{ {
UNUSED(config); UNUSED(config);
if (!bmp085InitDone && eocIO) { if (!bmp085InitDone && eocIO) {
bmp085_start_ut(); bmp085_start_ut();
delayMicroseconds(UT_DELAY * 2); // wait twice as long as normal, just to be sure delayMicroseconds(UT_DELAY * 2); // wait twice as long as normal, just to be sure

View file

@ -178,7 +178,7 @@ void i2cInit(I2CDevice device)
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)
{ {
UNUSED(device); UNUSED(device);
int i; int i;
if (!I2C_Start()) { if (!I2C_Start()) {
i2cErrorCount++; i2cErrorCount++;
@ -206,7 +206,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, ui
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)
{ {
UNUSED(device); UNUSED(device);
if (!I2C_Start()) { if (!I2C_Start()) {
return false; return false;
} }
@ -227,7 +227,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t 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)
{ {
UNUSED(device); UNUSED(device);
if (!I2C_Start()) { if (!I2C_Start()) {
return false; return false;
} }

View file

@ -133,7 +133,7 @@ static bool i2cHandleHardwareFailure(I2CDevice device)
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)
return false; return false;
@ -141,10 +141,10 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
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]);
state->addr = addr_ << 1; state->addr = addr_ << 1;
state->reg = reg_; state->reg = reg_;
state->writing = 1; state->writing = 1;
@ -182,12 +182,12 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t
{ {
if (device == I2CINVALID) if (device == I2CINVALID)
return false; return false;
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]);
@ -220,13 +220,13 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t
} }
static void i2c_er_handler(I2CDevice device) { static void i2c_er_handler(I2CDevice device) {
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]);
// Read the I2C1 status register // Read the I2C1 status register
volatile uint32_t SR1Register = I2Cx->SR1; volatile uint32_t SR1Register = I2Cx->SR1;
@ -255,13 +255,13 @@ static void i2c_er_handler(I2CDevice device) {
} }
void i2c_ev_handler(I2CDevice device) { void i2c_ev_handler(I2CDevice device) {
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]);
static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition
static int8_t index; // index is signed -1 == send the subaddress static int8_t index; // index is signed -1 == send the subaddress
uint8_t SReg_1 = I2Cx->SR1; // read the status register here uint8_t SReg_1 = I2Cx->SR1; // read the status register here
@ -384,17 +384,17 @@ void i2cInit(I2CDevice device)
IO_t scl = IOGetByTag(i2c->scl); IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda); IO_t sda = IOGetByTag(i2c->sda);
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
// Enable RCC // Enable RCC
RCC_ClockCmd(i2c->rcc, ENABLE); RCC_ClockCmd(i2c->rcc, ENABLE);
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);
@ -403,10 +403,10 @@ void i2cInit(I2CDevice device)
IOConfigGPIO(scl, IOCFG_AF_OD); IOConfigGPIO(scl, IOCFG_AF_OD);
IOConfigGPIO(sda, IOCFG_AF_OD); IOConfigGPIO(sda, IOCFG_AF_OD);
#endif #endif
I2C_DeInit(i2c->dev); I2C_DeInit(i2c->dev);
I2C_StructInit(&i2cInit); I2C_StructInit(&i2cInit);
I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request
i2cInit.I2C_Mode = I2C_Mode_I2C; i2cInit.I2C_Mode = I2C_Mode_I2C;
i2cInit.I2C_DutyCycle = I2C_DutyCycle_2; i2cInit.I2C_DutyCycle = I2C_DutyCycle_2;
@ -424,8 +424,8 @@ void i2cInit(I2CDevice device)
I2C_Init(i2c->dev, &i2cInit); I2C_Init(i2c->dev, &i2cInit);
I2C_StretchClockCmd(i2c->dev, ENABLE); I2C_StretchClockCmd(i2c->dev, ENABLE);
// I2C ER Interrupt // I2C ER Interrupt
nvic.NVIC_IRQChannel = i2c->er_irq; nvic.NVIC_IRQChannel = i2c->er_irq;
nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER); nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER);

View file

@ -79,23 +79,23 @@ uint32_t i2cTimeoutUserCallback(void)
void i2cInit(I2CDevice device) void i2cInit(I2CDevice device)
{ {
i2cDevice_t *i2c; i2cDevice_t *i2c;
i2c = &(i2cHardwareMap[device]); i2c = &(i2cHardwareMap[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);
RCC_ClockCmd(i2c->rcc, ENABLE); RCC_ClockCmd(i2c->rcc, ENABLE);
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4); IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4); IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
I2C_InitTypeDef i2cInit = { I2C_InitTypeDef i2cInit = {
@ -107,11 +107,11 @@ void i2cInit(I2CDevice device)
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING) .I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING)
}; };
I2C_Init(I2Cx, &i2cInit); I2C_Init(I2Cx, &i2cInit);
I2C_StretchClockCmd(I2Cx, ENABLE); I2C_StretchClockCmd(I2Cx, ENABLE);
I2C_Cmd(I2Cx, ENABLE); I2C_Cmd(I2Cx, ENABLE);
} }
@ -126,7 +126,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
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;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
@ -192,7 +192,7 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t*
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;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {

View file

@ -114,9 +114,9 @@ void spiInitDevice(SPIDevice device)
RCC_ResetCmd(spi->rcc, ENABLE); RCC_ResetCmd(spi->rcc, ENABLE);
IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1); IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1);
IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1);
IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1);
#if defined(STM32F3) || defined(STM32F4) #if defined(STM32F3) || defined(STM32F4)
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af);
@ -129,11 +129,11 @@ void spiInitDevice(SPIDevice device)
IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG); IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG);
IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG); IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG);
IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG); IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG);
if (spi->nss) if (spi->nss)
IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG); IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG);
#endif #endif
// Init SPI hardware // Init SPI hardware
SPI_I2S_DeInit(spi->dev); SPI_I2S_DeInit(spi->dev);
@ -349,4 +349,4 @@ void spiResetErrorCounter(SPI_TypeDef *instance)
SPIDevice device = spiDeviceByInstance(instance); SPIDevice device = spiDeviceByInstance(instance);
if (device != SPIINVALID) if (device != SPIINVALID)
spiHardwareMap[device].errorCount = 0; spiHardwareMap[device].errorCount = 0;
} }

View file

@ -199,13 +199,13 @@ 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);
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG); IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
DISABLE_M25P16; DISABLE_M25P16;
#ifndef M25P16_SPI_SHARED #ifndef M25P16_SPI_SHARED

View file

@ -102,8 +102,8 @@ typedef struct
#ifndef UNIT_TEST #ifndef UNIT_TEST
#ifdef STM32F4 #ifdef STM32F4
static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRRL = i; } static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRRL = i; }
static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BSRRH = i; } static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BSRRH = i; }
#else #else
static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRR = i; } static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRR = i; }
static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BRR = i; } static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BRR = i; }

View file

@ -33,7 +33,7 @@ void initInverter(void)
{ {
IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0); IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0);
IOConfigGPIO(pin, IOCFG_OUT_PP); IOConfigGPIO(pin, IOCFG_OUT_PP);
inverterSet(false); inverterSet(false);
} }

View file

@ -13,7 +13,7 @@ typedef struct ioRec_s {
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;
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];

View file

@ -26,17 +26,17 @@ static const IO_t leds[] = {
#ifdef LED0 #ifdef LED0
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
DEFIO_IO(NONE), DEFIO_IO(NONE),
#endif #endif
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A) #if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
#ifdef LED0_A #ifdef LED0_A
@ -82,25 +82,25 @@ uint8_t ledOffset = 0;
void ledInit(bool alternative_led) void ledInit(bool alternative_led)
{ {
uint32_t i; uint32_t i;
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A) #if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
if (alternative_led) if (alternative_led)
ledOffset = LED_NUMBER; ledOffset = LED_NUMBER;
#else #else
UNUSED(alternative_led); UNUSED(alternative_led);
#endif #endif
LED0_OFF; LED0_OFF;
LED1_OFF; LED1_OFF;
LED2_OFF; LED2_OFF;
for (i = 0; i < LED_NUMBER; i++) { for (i = 0; i < LED_NUMBER; i++) {
if (leds[i + ledOffset]) { if (leds[i + ledOffset]) {
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i)); IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP); IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
} }
} }
LED0_OFF; LED0_OFF;
LED1_OFF; LED1_OFF;
@ -109,11 +109,11 @@ void ledInit(bool alternative_led)
void ledToggle(int led) void ledToggle(int led)
{ {
IOToggle(leds[led + ledOffset]); IOToggle(leds[led + ledOffset]);
} }
void ledSet(int led, bool on) void ledSet(int led, bool on)
{ {
bool inverted = (1 << (led + ledOffset)) & ledPolarity; bool inverted = (1 << (led + ledOffset)) & ledPolarity;
IOWrite(leds[led + ledOffset], on ? inverted : !inverted); IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
} }

View file

@ -50,14 +50,14 @@ void ws2811LedStripHardwareInit(void)
uint16_t prescalerValue; uint16_t prescalerValue;
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler);
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP)); IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP));
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
/* Compute the prescaler value */ /* Compute the prescaler value */
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
/* Time base configuration */ /* Time base configuration */
@ -123,7 +123,7 @@ void ws2811LedStripDMAEnable(void)
{ {
if (!ws2811Initialised) if (!ws2811Initialised)
return; return;
DMA_SetCurrDataCounter(DMA1_Channel6, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred DMA_SetCurrDataCounter(DMA1_Channel6, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
TIM_SetCounter(TIM3, 0); TIM_SetCounter(TIM3, 0);
TIM_Cmd(TIM3, ENABLE); TIM_Cmd(TIM3, ENABLE);

View file

@ -59,14 +59,14 @@ void ws2811LedStripHardwareInit(void)
DMA_InitTypeDef DMA_InitStructure; DMA_InitTypeDef DMA_InitStructure;
uint16_t prescalerValue; uint16_t prescalerValue;
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler);
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
/* Compute the prescaler value */ /* Compute the prescaler value */
@ -134,7 +134,7 @@ void ws2811LedStripDMAEnable(void)
{ {
if (!ws2811Initialised) if (!ws2811Initialised)
return; return;
DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
TIM_SetCounter(WS2811_TIMER, 0); TIM_SetCounter(WS2811_TIMER, 0);
TIM_Cmd(WS2811_TIMER, ENABLE); TIM_Cmd(WS2811_TIMER, ENABLE);

View file

@ -69,15 +69,15 @@ void ws2811LedStripHardwareInit(void)
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
// Stop timer // Stop timer
TIM_Cmd(WS2811_TIMER, DISABLE); TIM_Cmd(WS2811_TIMER, DISABLE);
/* Compute the prescaler value */ /* Compute the prescaler value */
prescalerValue = (uint16_t)(SystemCoreClock / 2 / 84000000) - 1; prescalerValue = (uint16_t)(SystemCoreClock / 2 / 84000000) - 1;
/* Time base configuration */ /* Time base configuration */
TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
@ -94,7 +94,7 @@ void ws2811LedStripHardwareInit(void)
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
TIM_OCInitStructure.TIM_Pulse = 0; TIM_OCInitStructure.TIM_Pulse = 0;
uint32_t channelAddress = 0; uint32_t channelAddress = 0;
switch (WS2811_TIMER_CHANNEL) { switch (WS2811_TIMER_CHANNEL) {
case TIM_Channel_1: case TIM_Channel_1:
@ -102,28 +102,28 @@ void ws2811LedStripHardwareInit(void)
timDMASource = TIM_DMA_CC1; timDMASource = TIM_DMA_CC1;
channelAddress = (uint32_t)(&WS2811_TIMER->CCR1); channelAddress = (uint32_t)(&WS2811_TIMER->CCR1);
TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
break; break;
case TIM_Channel_2: case TIM_Channel_2:
TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure); TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure);
timDMASource = TIM_DMA_CC2; timDMASource = TIM_DMA_CC2;
channelAddress = (uint32_t)(&WS2811_TIMER->CCR2); channelAddress = (uint32_t)(&WS2811_TIMER->CCR2);
TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
break; break;
case TIM_Channel_3: case TIM_Channel_3:
TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure); TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure);
timDMASource = TIM_DMA_CC3; timDMASource = TIM_DMA_CC3;
channelAddress = (uint32_t)(&WS2811_TIMER->CCR3); channelAddress = (uint32_t)(&WS2811_TIMER->CCR3);
TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
break; break;
case TIM_Channel_4: case TIM_Channel_4:
TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure); TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure);
timDMASource = TIM_DMA_CC4; timDMASource = TIM_DMA_CC4;
channelAddress = (uint32_t)(&WS2811_TIMER->CCR4); channelAddress = (uint32_t)(&WS2811_TIMER->CCR4);
TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
break; break;
} }
TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE); TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
TIM_ARRPreloadConfig(WS2811_TIMER, ENABLE); TIM_ARRPreloadConfig(WS2811_TIMER, ENABLE);
TIM_CCxCmd(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_CCx_Enable); TIM_CCxCmd(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_CCx_Enable);
@ -132,7 +132,7 @@ void ws2811LedStripHardwareInit(void)
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler);
/* configure DMA */ /* configure DMA */
DMA_Cmd(WS2811_DMA_STREAM, DISABLE); DMA_Cmd(WS2811_DMA_STREAM, DISABLE);
DMA_DeInit(WS2811_DMA_STREAM); DMA_DeInit(WS2811_DMA_STREAM);
DMA_StructInit(&DMA_InitStructure); DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL; DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL;
@ -151,13 +151,13 @@ void ws2811LedStripHardwareInit(void)
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single; DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE); RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE);
DMA_Init(WS2811_DMA_STREAM, &DMA_InitStructure); DMA_Init(WS2811_DMA_STREAM, &DMA_InitStructure);
DMA_ITConfig(WS2811_DMA_STREAM, DMA_IT_TC, ENABLE); DMA_ITConfig(WS2811_DMA_STREAM, DMA_IT_TC, ENABLE);
DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT); DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT);
NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = WS2811_DMA_IRQ; NVIC_InitStructure.NVIC_IRQChannel = WS2811_DMA_IRQ;
@ -175,11 +175,11 @@ void ws2811LedStripDMAEnable(void)
{ {
if (!ws2811Initialised) if (!ws2811Initialised)
return; return;
DMA_SetCurrDataCounter(WS2811_DMA_STREAM, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred DMA_SetCurrDataCounter(WS2811_DMA_STREAM, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
TIM_SetCounter(WS2811_TIMER, 0); TIM_SetCounter(WS2811_TIMER, 0);
DMA_Cmd(WS2811_DMA_STREAM, ENABLE); DMA_Cmd(WS2811_DMA_STREAM, ENABLE);
TIM_DMACmd(WS2811_TIMER, timDMASource, ENABLE); TIM_DMACmd(WS2811_TIMER, timDMASource, ENABLE);
} }
#endif #endif

View file

@ -101,7 +101,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

View file

@ -90,9 +90,9 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
configTimeBase(timerHardware->tim, period, mhz); configTimeBase(timerHardware->tim, period, mhz);
IO_t io = IOGetByTag(timerHardware->tag); IO_t io = IOGetByTag(timerHardware->tag);
IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount); IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount);
IOConfigGPIO(io, IOCFG_AF_PP); IOConfigGPIO(io, IOCFG_AF_PP);
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED); pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED);

View file

@ -366,9 +366,9 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)
self->mode = INPUT_MODE_PWM; self->mode = INPUT_MODE_PWM;
self->timerHardware = timerHardwarePtr; self->timerHardware = timerHardwarePtr;
IO_t io = IOGetByTag(timerHardwarePtr->tag); IO_t io = IOGetByTag(timerHardwarePtr->tag);
IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel)); IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel));
IOConfigGPIO(io, timerHardwarePtr->ioMode); IOConfigGPIO(io, timerHardwarePtr->ioMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
@ -398,10 +398,10 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr)
self->mode = INPUT_MODE_PPM; self->mode = INPUT_MODE_PPM;
self->timerHardware = timerHardwarePtr; self->timerHardware = timerHardwarePtr;
IO_t io = IOGetByTag(timerHardwarePtr->tag); IO_t io = IOGetByTag(timerHardwarePtr->tag);
IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0); IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0);
IOConfigGPIO(io, timerHardwarePtr->ioMode); IOConfigGPIO(io, timerHardwarePtr->ioMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ); timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ);

View file

@ -550,7 +550,7 @@ void sdcard_init(bool useDMA)
IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI_CS, 0); IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI_CS, 0);
IOConfigGPIO(sdCardCsPin, SPI_IO_CS_CFG); IOConfigGPIO(sdCardCsPin, SPI_IO_CS_CFG);
#endif // SDCARD_SPI_CS_PIN #endif // SDCARD_SPI_CS_PIN
// Max frequency is initially 400kHz // Max frequency is initially 400kHz
spiSetDivisor(SDCARD_SPI_INSTANCE, SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER); spiSetDivisor(SDCARD_SPI_INSTANCE, SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER);
@ -559,7 +559,7 @@ void sdcard_init(bool useDMA)
// Transmit at least 74 dummy clock cycles with CS high so the SD card can start up // Transmit at least 74 dummy clock cycles with CS high so the SD card can start up
SET_CS_HIGH; SET_CS_HIGH;
spiTransfer(SDCARD_SPI_INSTANCE, NULL, NULL, SDCARD_INIT_NUM_DUMMY_BYTES); spiTransfer(SDCARD_SPI_INSTANCE, NULL, NULL, SDCARD_INIT_NUM_DUMMY_BYTES);
// Wait for that transmission to finish before we enable the SDCard, so it receives the required number of cycles: // Wait for that transmission to finish before we enable the SDCard, so it receives the required number of cycles:
@ -1059,7 +1059,7 @@ bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationComp
sdcard.pendingOperation.blockIndex = blockIndex; sdcard.pendingOperation.blockIndex = blockIndex;
sdcard.pendingOperation.callback = callback; sdcard.pendingOperation.callback = callback;
sdcard.pendingOperation.callbackData = callbackData; sdcard.pendingOperation.callbackData = callbackData;
sdcard.state = SDCARD_STATE_READING; sdcard.state = SDCARD_STATE_READING;
sdcard.operationStartTime = millis(); sdcard.operationStartTime = millis();

View file

@ -102,18 +102,18 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state)
void serialInputPortConfig(ioTag_t pin, uint8_t portIndex) void serialInputPortConfig(ioTag_t pin, uint8_t portIndex)
{ {
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex)); IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex));
#ifdef STM32F1 #ifdef STM32F1
IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU); IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU);
#else #else
IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP); IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP);
#endif #endif
} }
static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex) static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex)
{ {
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex)); IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex));
IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP); IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP);
} }
static bool isTimerPeriodTooLarge(uint32_t timerPeriod) static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
@ -216,9 +216,9 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->tag); softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->tag);
serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex); serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex);
softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag); softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag);
serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex); serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex);
setTxSignal(softSerial, ENABLE); setTxSignal(softSerial, ENABLE);
delay(50); delay(50);

View file

@ -88,14 +88,14 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
s = &uartPort1; s = &uartPort1;
s->port.vTable = uartVTable; s->port.vTable = uartVTable;
s->port.baudRate = baudRate; s->port.baudRate = baudRate;
s->port.rxBuffer = rx1Buffer; s->port.rxBuffer = rx1Buffer;
s->port.txBuffer = tx1Buffer; s->port.txBuffer = tx1Buffer;
s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.rxBufferSize = UART1_RX_BUFFER_SIZE;
s->port.txBufferSize = UART1_TX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE;
s->USARTx = USART1; s->USARTx = USART1;
@ -179,14 +179,14 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
s = &uartPort2; s = &uartPort2;
s->port.vTable = uartVTable; s->port.vTable = uartVTable;
s->port.baudRate = baudRate; s->port.baudRate = baudRate;
s->port.rxBufferSize = UART2_RX_BUFFER_SIZE; s->port.rxBufferSize = UART2_RX_BUFFER_SIZE;
s->port.txBufferSize = UART2_TX_BUFFER_SIZE; s->port.txBufferSize = UART2_TX_BUFFER_SIZE;
s->port.rxBuffer = rx2Buffer; s->port.rxBuffer = rx2Buffer;
s->port.txBuffer = tx2Buffer; s->port.txBuffer = tx2Buffer;
s->USARTx = USART2; s->USARTx = USART2;
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
@ -207,7 +207,7 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
} }
if (mode & MODE_RX) { if (mode & MODE_RX) {
IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2); IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2);
IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU); IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU);
} }
} }
@ -260,16 +260,16 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option
RCC_ClockCmd(RCC_APB1(USART3), ENABLE); RCC_ClockCmd(RCC_APB1(USART3), ENABLE);
if (options & SERIAL_BIDIR) { if (options & SERIAL_BIDIR) {
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3); IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3);
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD);
} else { } else {
if (mode & MODE_TX) { if (mode & MODE_TX) {
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3); IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3);
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP);
} }
if (mode & MODE_RX) { if (mode & MODE_RX) {
IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3); IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3);
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU);
} }
} }

View file

@ -120,7 +120,7 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui
} }
if (mode & MODE_RX) { if (mode & MODE_RX) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index);
IOConfigGPIOAF(rx, ioCfg, af); IOConfigGPIOAF(rx, ioCfg, af);
} }
} }
@ -136,14 +136,14 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
s = &uartPort1; s = &uartPort1;
s->port.vTable = uartVTable; s->port.vTable = uartVTable;
s->port.baudRate = baudRate; s->port.baudRate = baudRate;
s->port.rxBuffer = rx1Buffer; s->port.rxBuffer = rx1Buffer;
s->port.txBuffer = tx1Buffer; s->port.txBuffer = tx1Buffer;
s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.rxBufferSize = UART1_RX_BUFFER_SIZE;
s->port.txBufferSize = UART1_TX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE;
#ifdef USE_UART1_RX_DMA #ifdef USE_UART1_RX_DMA
s->rxDMAChannel = DMA1_Channel5; s->rxDMAChannel = DMA1_Channel5;
#endif #endif
@ -188,16 +188,16 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
s = &uartPort2; s = &uartPort2;
s->port.vTable = uartVTable; s->port.vTable = uartVTable;
s->port.baudRate = baudRate; s->port.baudRate = baudRate;
s->port.rxBufferSize = UART2_RX_BUFFER_SIZE; s->port.rxBufferSize = UART2_RX_BUFFER_SIZE;
s->port.txBufferSize = UART2_TX_BUFFER_SIZE; s->port.txBufferSize = UART2_TX_BUFFER_SIZE;
s->port.rxBuffer = rx2Buffer; s->port.rxBuffer = rx2Buffer;
s->port.txBuffer = tx2Buffer; s->port.txBuffer = tx2Buffer;
s->USARTx = USART2; s->USARTx = USART2;
#ifdef USE_UART2_RX_DMA #ifdef USE_UART2_RX_DMA
s->rxDMAChannel = DMA1_Channel6; s->rxDMAChannel = DMA1_Channel6;
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;

View file

@ -277,17 +277,17 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
uartDevice_t *uart = uartHardwareMap[device]; uartDevice_t *uart = uartHardwareMap[device];
if (!uart) return NULL; if (!uart) return NULL;
s = &(uart->port); s = &(uart->port);
s->port.vTable = uartVTable; s->port.vTable = uartVTable;
s->port.baudRate = baudRate; s->port.baudRate = baudRate;
s->port.rxBuffer = uart->rxBuffer; s->port.rxBuffer = uart->rxBuffer;
s->port.txBuffer = uart->txBuffer; s->port.txBuffer = uart->txBuffer;
s->port.rxBufferSize = sizeof(uart->rxBuffer); s->port.rxBufferSize = sizeof(uart->rxBuffer);
s->port.txBufferSize = sizeof(uart->txBuffer); s->port.txBufferSize = sizeof(uart->txBuffer);
s->USARTx = uart->dev; s->USARTx = uart->dev;
if (uart->rxDMAStream) { if (uart->rxDMAStream) {
s->rxDMAChannel = uart->DMAChannel; s->rxDMAChannel = uart->DMAChannel;
@ -295,34 +295,34 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
} }
s->txDMAChannel = uart->DMAChannel; s->txDMAChannel = uart->DMAChannel;
s->txDMAStream = uart->txDMAStream; s->txDMAStream = uart->txDMAStream;
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
IO_t tx = IOGetByTag(uart->tx); IO_t tx = IOGetByTag(uart->tx);
IO_t rx = IOGetByTag(uart->rx); IO_t rx = IOGetByTag(uart->rx);
if (uart->rcc_apb2) if (uart->rcc_apb2)
RCC_ClockCmd(uart->rcc_apb2, ENABLE); RCC_ClockCmd(uart->rcc_apb2, ENABLE);
if (uart->rcc_apb1) if (uart->rcc_apb1)
RCC_ClockCmd(uart->rcc_apb1, ENABLE); RCC_ClockCmd(uart->rcc_apb1, ENABLE);
if (uart->rcc_ahb1) if (uart->rcc_ahb1)
RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE); RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE);
if (options & SERIAL_BIDIR) { if (options & SERIAL_BIDIR) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af); IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
} }
else { else {
if (mode & MODE_TX) { if (mode & MODE_TX) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device)); IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
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

@ -117,7 +117,7 @@ static bool usbVcpFlush(vcpPort_t *port)
if (count == 0) { if (count == 0) {
return true; return true;
} }
if (!usbIsConnected() || !usbIsConfigured()) { if (!usbIsConnected() || !usbIsConfigured()) {
return false; return false;
} }

View file

@ -85,10 +85,10 @@ void hcsr04_init(sonarRange_t *sonarRange)
triggerIO = IOGetByTag(sonarHardwareHCSR04.triggerTag); triggerIO = IOGetByTag(sonarHardwareHCSR04.triggerTag);
IOInit(triggerIO, OWNER_SONAR, RESOURCE_OUTPUT, 0); IOInit(triggerIO, OWNER_SONAR, RESOURCE_OUTPUT, 0);
IOConfigGPIO(triggerIO, IOCFG_OUT_PP); IOConfigGPIO(triggerIO, IOCFG_OUT_PP);
// echo pin // echo pin
echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag); echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag);
IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0); IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0);
IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); IOConfigGPIO(echoIO, IOCFG_IN_FLOATING);
#ifdef USE_EXTI #ifdef USE_EXTI

View file

@ -69,10 +69,10 @@ bool isMPUSoftReset(void)
void systemInit(void) void systemInit(void)
{ {
checkForBootLoaderRequest(); checkForBootLoaderRequest();
SetSysClock(false); SetSysClock(false);
#ifdef CC3D #ifdef CC3D
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */ /* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
extern void *isr_vector_table_base; extern void *isr_vector_table_base;
@ -115,4 +115,4 @@ void systemInit(void)
void checkForBootLoaderRequest(void) void checkForBootLoaderRequest(void)
{ {
} }

View file

@ -83,7 +83,7 @@ bool isMPUSoftReset(void)
void systemInit(void) void systemInit(void)
{ {
checkForBootLoaderRequest(); checkForBootLoaderRequest();
// Enable FPU // Enable FPU
SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2)); SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2));

View file

@ -169,7 +169,7 @@ bool isMPUSoftReset(void)
void systemInit(void) void systemInit(void)
{ {
checkForBootLoaderRequest(); checkForBootLoaderRequest();
SetSysClock(); SetSysClock();
@ -183,7 +183,7 @@ void systemInit(void)
extern void *isr_vector_table_base; extern void *isr_vector_table_base;
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0); NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE); RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE);
RCC_ClearFlag(); RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions(); enableGPIOPowerUsageAndNoiseReductions();
@ -199,15 +199,15 @@ void systemInit(void)
void(*bootJump)(void); void(*bootJump)(void);
void checkForBootLoaderRequest(void) void checkForBootLoaderRequest(void)
{ {
if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) { if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) {
*((uint32_t *)0x2001FFFC) = 0x0; *((uint32_t *)0x2001FFFC) = 0x0;
__enable_irq(); __enable_irq();
__set_MSP(0x20001000); __set_MSP(0x20001000);
bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004)); bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004));
bootJump(); bootJump();
while (1); while (1);
} }
} }

View file

@ -52,12 +52,12 @@ extern uint8_t motorCount;
**************************************************************************** ****************************************************************************
*** G_Tune *** *** G_Tune ***
**************************************************************************** ****************************************************************************
G_Tune Mode G_Tune Mode
This is the multiwii implementation of ZERO-PID Algorithm This is the multiwii implementation of ZERO-PID Algorithm
http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html
The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com) The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com)
You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution. You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution.
*/ */
/* /*
@ -107,13 +107,13 @@ void init_Gtune(pidProfile_t *pidProfileToTune)
uint8_t i; uint8_t i;
pidProfile = pidProfileToTune; pidProfile = pidProfileToTune;
if (pidProfile->pidController == 2) { if (pidProfile->pidController == 2) {
floatPID = true; // LuxFloat is using float values for PID settings floatPID = true; // LuxFloat is using float values for PID settings
} else { } else {
floatPID = false; floatPID = false;
} }
updateDelayCycles(); updateDelayCycles();
for (i = 0; i < 3; i++) { for (i = 0; i < 3; i++) {
if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning
pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter
} }

View file

@ -84,7 +84,7 @@ STATIC_UNIT_TESTED void imuComputeRotationMatrix(void)
float q1q1 = sq(q1); float q1q1 = sq(q1);
float q2q2 = sq(q2); float q2q2 = sq(q2);
float q3q3 = sq(q3); float q3q3 = sq(q3);
float q0q1 = q0 * q1; float q0q1 = q0 * q1;
float q0q2 = q0 * q2; float q0q2 = q0 * q2;
float q0q3 = q0 * q3; float q0q3 = q0 * q3;

View file

@ -395,7 +395,7 @@ void loadCustomServoMixer(void)
// check if done // check if done
if (customServoMixers[i].rate == 0) if (customServoMixers[i].rate == 0)
break; break;
currentServoMixer[i] = customServoMixers[i]; currentServoMixer[i] = customServoMixers[i];
servoRuleCount++; servoRuleCount++;
} }
@ -426,9 +426,9 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura
motorCount = 0; motorCount = 0;
servoCount = pwmOutputConfiguration->servoCount; servoCount = pwmOutputConfiguration->servoCount;
syncPwm = use_unsyncedPwm; syncPwm = use_unsyncedPwm;
if (currentMixerMode == MIXER_CUSTOM || currentMixerMode == MIXER_CUSTOM_TRI || currentMixerMode == MIXER_CUSTOM_AIRPLANE) { if (currentMixerMode == MIXER_CUSTOM || currentMixerMode == MIXER_CUSTOM_TRI || currentMixerMode == MIXER_CUSTOM_AIRPLANE) {
// load custom mixer into currentMixer // load custom mixer into currentMixer
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) { for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
@ -454,7 +454,7 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura
currentServoMixer[i] = servoMixers[currentMixerMode].rule[i]; currentServoMixer[i] = servoMixers[currentMixerMode].rule[i];
} }
} }
// in 3D mode, mixer gain has to be halved // in 3D mode, mixer gain has to be halved
if (feature(FEATURE_3D)) { if (feature(FEATURE_3D)) {
if (motorCount > 1) { if (motorCount > 1) {
@ -472,7 +472,7 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura
currentMixerMode == MIXER_CUSTOM_AIRPLANE currentMixerMode == MIXER_CUSTOM_AIRPLANE
) { ) {
ENABLE_STATE(FIXED_WING); ENABLE_STATE(FIXED_WING);
if (currentMixerMode == MIXER_CUSTOM_AIRPLANE) { if (currentMixerMode == MIXER_CUSTOM_AIRPLANE) {
loadCustomServoMixer(); loadCustomServoMixer();
} }
@ -901,7 +901,7 @@ void mixTable(void)
/* /*
case MIXER_GIMBAL: case MIXER_GIMBAL:
servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH); servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH);
servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL); servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL);
break; break;
*/ */

View file

@ -166,8 +166,8 @@ void init(void)
//i2cSetOverclock(masterConfig.i2c_overclock); //i2cSetOverclock(masterConfig.i2c_overclock);
// initialize IO (needed for all IO operations) // initialize IO (needed for all IO operations)
IOInitGlobal(); IOInitGlobal();
debugMode = masterConfig.debug_mode; debugMode = masterConfig.debug_mode;
#ifdef USE_HARDWARE_REVISION_DETECTION #ifdef USE_HARDWARE_REVISION_DETECTION
@ -188,7 +188,7 @@ void init(void)
ledInit(false); ledInit(false);
#endif #endif
LED2_ON; LED2_ON;
#ifdef USE_EXTI #ifdef USE_EXTI
EXTIInit(); EXTIInit();
#endif #endif
@ -286,7 +286,7 @@ void init(void)
#endif #endif
#if defined(USE_UART6) && defined(STM32F40_41xxx) #if defined(USE_UART6) && defined(STM32F40_41xxx)
pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6); pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6);
#endif #endif
pwm_params.useVbat = feature(FEATURE_VBAT); pwm_params.useVbat = feature(FEATURE_VBAT);
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL); pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM); pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM);
@ -309,7 +309,7 @@ void init(void)
} else { } else {
featureClear(FEATURE_ONESHOT125); featureClear(FEATURE_ONESHOT125);
} }
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
@ -319,7 +319,7 @@ void init(void)
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
if (feature(FEATURE_3D)) if (feature(FEATURE_3D))
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) { if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) {
featureClear(FEATURE_3D); featureClear(FEATURE_3D);
pwm_params.idlePulse = 0; // brushed motors pwm_params.idlePulse = 0; // brushed motors
@ -363,7 +363,7 @@ void init(void)
#endif #endif
#ifdef CC3D #ifdef CC3D
if (masterConfig.use_buzzer_p6 == 1) if (masterConfig.use_buzzer_p6 == 1)
beeperConfig.ioTag = IO_TAG(BEEPER_OPT); beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
#endif #endif
beeperInit(&beeperConfig); beeperInit(&beeperConfig);
@ -501,7 +501,7 @@ void init(void)
LED1_ON; LED1_ON;
LED0_OFF; LED0_OFF;
LED2_OFF; LED2_OFF;
for (int i = 0; i < 10; i++) { for (int i = 0; i < 10; i++) {
LED1_TOGGLE; LED1_TOGGLE;
LED0_TOGGLE; LED0_TOGGLE;

View file

@ -590,12 +590,12 @@ void updateRSSIPWM(void)
int16_t pwmRssi = 0; int16_t pwmRssi = 0;
// Read value of AUX channel as rssi // Read value of AUX channel as rssi
pwmRssi = rcData[rxConfig->rssi_channel - 1]; pwmRssi = rcData[rxConfig->rssi_channel - 1];
// RSSI_Invert option // RSSI_Invert option
if (rxConfig->rssi_ppm_invert) { if (rxConfig->rssi_ppm_invert) {
pwmRssi = ((2000 - pwmRssi) + 1000); pwmRssi = ((2000 - pwmRssi) + 1000);
} }
// Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023]; // Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
rssi = (uint16_t)((constrain(pwmRssi - 1000, 0, 1000) / 1000.0f) * 1023.0f); rssi = (uint16_t)((constrain(pwmRssi - 1000, 0, 1000) / 1000.0f) * 1023.0f);
} }

View file

@ -245,7 +245,7 @@ void spektrumBind(rxConfig_t *rxConfig)
#ifndef HARDWARE_BIND_PLUG #ifndef HARDWARE_BIND_PLUG
// If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config // If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config
// Don't reset if hardware bind plug is present // Don't reset if hardware bind plug is present
// Reset only when autoreset is enabled // Reset only when autoreset is enabled
if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) { if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) {
rxConfig->spektrum_sat_bind = 0; rxConfig->spektrum_sat_bind = 0;
saveConfigAndNotify(); saveConfigAndNotify();

View file

@ -71,7 +71,7 @@
// 2200µs -> 0xFFF // 2200µs -> 0xFFF
// Total range is: 2200 - 800 = 1400 <==> 4095 // Total range is: 2200 - 800 = 1400 <==> 4095
// Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12) // Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12)
#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12)) #define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
static bool xBusFrameReceived = false; static bool xBusFrameReceived = false;
static bool xBusDataIncoming = false; static bool xBusDataIncoming = false;
@ -148,7 +148,7 @@ bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa
static uint16_t xBusCRC16(uint16_t crc, uint8_t value) static uint16_t xBusCRC16(uint16_t crc, uint8_t value)
{ {
uint8_t i; uint8_t i;
crc = crc ^ (int16_t)value << 8; crc = crc ^ (int16_t)value << 8;
for (i = 0; i < 8; i++) { for (i = 0; i < 8; i++) {
@ -181,7 +181,7 @@ uint8_t xBusRj01CRC8(uint8_t inData, uint8_t seed)
inData >>= 1; inData >>= 1;
} }
return seed; return seed;
} }
@ -240,7 +240,7 @@ static void xBusUnpackRJ01Frame(void)
// method. // method.
// So, we check both these values as well as the provided length // So, we check both these values as well as the provided length
// of the outer/full message (LEN) // of the outer/full message (LEN)
// //
// Check we have correct length of message // Check we have correct length of message
// //
@ -249,14 +249,14 @@ static void xBusUnpackRJ01Frame(void)
// Unknown package as length is not ok // Unknown package as length is not ok
return; return;
} }
// //
// CRC calculation & check for full message // CRC calculation & check for full message
// //
for (i = 0; i < xBusFrameLength - 1; i++) { for (i = 0; i < xBusFrameLength - 1; i++) {
outerCrc = xBusRj01CRC8(outerCrc, xBusFrame[i]); outerCrc = xBusRj01CRC8(outerCrc, xBusFrame[i]);
} }
if (outerCrc != xBusFrame[xBusFrameLength - 1]) if (outerCrc != xBusFrame[xBusFrameLength - 1])
{ {
// CRC does not match, skip this frame // CRC does not match, skip this frame
@ -281,7 +281,7 @@ static void xBusDataReceive(uint16_t c)
xBusFramePosition = 0; xBusFramePosition = 0;
xBusDataIncoming = false; xBusDataIncoming = false;
} }
// Check if we shall start a frame? // Check if we shall start a frame?
if ((xBusFramePosition == 0) && (c == XBUS_START_OF_FRAME_BYTE)) { if ((xBusFramePosition == 0) && (c == XBUS_START_OF_FRAME_BYTE)) {
xBusDataIncoming = true; xBusDataIncoming = true;
@ -293,7 +293,7 @@ static void xBusDataReceive(uint16_t c)
xBusFrame[xBusFramePosition] = (uint8_t)c; xBusFrame[xBusFramePosition] = (uint8_t)c;
xBusFramePosition++; xBusFramePosition++;
} }
// Done? // Done?
if (xBusFramePosition == xBusFrameLength) { if (xBusFramePosition == xBusFrameLength) {
switch (xBusProvider) { switch (xBusProvider) {

View file

@ -139,7 +139,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros)
{ {
if (taskId == TASK_SELF || taskId < TASK_COUNT) { if (taskId == TASK_SELF || taskId < TASK_COUNT) {
cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId]; cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId];
task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
} }
} }

View file

@ -68,7 +68,7 @@ static int32_t applyBarometerMedianFilter(int32_t newPressureReading)
static int currentFilterSampleIndex = 0; static int currentFilterSampleIndex = 0;
static bool medianFilterReady = false; static bool medianFilterReady = false;
int nextSampleIndex; int nextSampleIndex;
nextSampleIndex = (currentFilterSampleIndex + 1); nextSampleIndex = (currentFilterSampleIndex + 1);
if (nextSampleIndex == PRESSURE_SAMPLES_MEDIAN) { if (nextSampleIndex == PRESSURE_SAMPLES_MEDIAN) {
nextSampleIndex = 0; nextSampleIndex = 0;
@ -77,7 +77,7 @@ static int32_t applyBarometerMedianFilter(int32_t newPressureReading)
barometerFilterSamples[currentFilterSampleIndex] = newPressureReading; barometerFilterSamples[currentFilterSampleIndex] = newPressureReading;
currentFilterSampleIndex = nextSampleIndex; currentFilterSampleIndex = nextSampleIndex;
if (medianFilterReady) if (medianFilterReady)
return quickMedianFilter3(barometerFilterSamples); return quickMedianFilter3(barometerFilterSamples);
else else

View file

@ -86,7 +86,7 @@ static void updateBatteryVoltage(void)
void updateBattery(void) void updateBattery(void)
{ {
updateBatteryVoltage(); updateBatteryVoltage();
/* battery has just been connected*/ /* battery has just been connected*/
if (batteryState == BATTERY_NOT_PRESENT && vbat > VBATT_PRESENT_THRESHOLD_MV) if (batteryState == BATTERY_NOT_PRESENT && vbat > VBATT_PRESENT_THRESHOLD_MV)
{ {
@ -115,7 +115,7 @@ void updateBattery(void)
batteryCellCount = 0; batteryCellCount = 0;
batteryWarningVoltage = 0; batteryWarningVoltage = 0;
batteryCriticalVoltage = 0; batteryCriticalVoltage = 0;
} }
switch(batteryState) switch(batteryState)
{ {

View file

@ -93,7 +93,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
return selectMPUIntExtiConfigByHardwareRevision(); return selectMPUIntExtiConfigByHardwareRevision();
#else #else
return NULL; return NULL;
#endif #endif
} }
#ifdef USE_FAKE_GYRO #ifdef USE_FAKE_GYRO
@ -233,7 +233,7 @@ bool detectGyro(void)
} }
#endif #endif
; // fallthrough ; // fallthrough
case GYRO_MPU9250: case GYRO_MPU9250:
#ifdef USE_GYRO_SPI_MPU9250 #ifdef USE_GYRO_SPI_MPU9250

View file

@ -94,7 +94,7 @@
#define USE_VCP #define USE_VCP
//#define VBUS_SENSING_PIN PA8 //#define VBUS_SENSING_PIN PA8
//#define VBUS_SENSING_ENABLED //#define VBUS_SENSING_ENABLED
#define USE_UART1 #define USE_UART1
#define UART1_RX_PIN PA10 #define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9 #define UART1_TX_PIN PA9

View file

@ -237,7 +237,7 @@ void bstInitPort(I2C_TypeDef *BSTx/*, uint8_t Address*/)
NVIC_Init(&nvic); NVIC_Init(&nvic);
I2C_ITConfig(I2C1, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE); I2C_ITConfig(I2C1, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE);
I2C_Cmd(I2C1, ENABLE); I2C_Cmd(I2C1, ENABLE);
} }

View file

@ -78,7 +78,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB8 { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB9 { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB9
{ TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PMW4 - PA10 { TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PMW4 - PA10
{ TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM5 - PA9 { TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM5 - PA9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0 { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0

View file

@ -23,7 +23,7 @@
const uint16_t multiPPM[] = { const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
@ -46,7 +46,7 @@ const uint16_t multiPWM[] = {
const uint16_t airPPM[] = { const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), PWM6 | (MAP_TO_SERVO_OUTPUT << 8),

View file

@ -70,7 +70,7 @@ uint8_t detectSpiDevice(void)
#ifdef NAZE_SPI_CS_PIN #ifdef NAZE_SPI_CS_PIN
nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN)); nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN));
#endif #endif
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 }; uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 };
uint8_t in[4]; uint8_t in[4];
uint32_t flash_id; uint32_t flash_id;

View file

@ -8,7 +8,7 @@
* This file contains the system clock configuration for STM32F30x devices, * This file contains the system clock configuration for STM32F30x devices,
* 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
@ -21,7 +21,7 @@
* - 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
* be called whenever the core clock is changed * be called whenever the core clock is changed
* during program execution. * during program execution.
@ -41,7 +41,7 @@
* *
* 5. This file configures the system clock as follows: * 5. This file configures the system clock as follows:
*============================================================================= *=============================================================================
* Supported STM32F30x device * Supported STM32F30x device
*----------------------------------------------------------------------------- *-----------------------------------------------------------------------------
* System Clock source | PLL (HSE) * System Clock source | PLL (HSE)
*----------------------------------------------------------------------------- *-----------------------------------------------------------------------------
@ -204,34 +204,34 @@ 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
* frequency of the crystal used. Otherwise, this function may * frequency of the crystal used. Otherwise, this function may
* have wrong result. * have wrong result.
* *
* - 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
*/ */
@ -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 */
@ -266,7 +266,7 @@ 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;
@ -282,8 +282,8 @@ void SystemCoreClockUpdate (void)
/** /**
* @brief Configures the System clock source, PLL Multiplier and Divider factors, * @brief Configures the System clock source, PLL Multiplier and Divider factors,
* AHB/APBx prescalers and Flash settings * AHB/APBx prescalers and Flash settings
* @note This function should be called only once the RCC clock configuration * @note This function should be called only once the RCC clock configuration
* is reset to the default reset state (done in SystemInit() function). * is reset to the default reset state (done in SystemInit() function).
* @param None * @param None
* @retval None * @retval None
*/ */
@ -322,10 +322,10 @@ void SetSysClock(void)
/* 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;
@ -340,7 +340,7 @@ void SetSysClock(void)
while((RCC->CR & RCC_CR_PLLRDY) == 0) while((RCC->CR & RCC_CR_PLLRDY) == 0)
{ {
} }
/* Select PLL as system clock source */ /* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;

View file

@ -4,7 +4,7 @@
* @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
* *

View file

@ -279,7 +279,7 @@ void checkSmartPortTelemetryState(void)
void handleSmartPortTelemetry(void) void handleSmartPortTelemetry(void)
{ {
uint32_t smartPortLastServiceTime = millis(); uint32_t smartPortLastServiceTime = millis();
if (!smartPortTelemetryEnabled) { if (!smartPortTelemetryEnabled) {
return; return;
} }
@ -307,7 +307,7 @@ void handleSmartPortTelemetry(void)
smartPortHasRequest = 0; smartPortHasRequest = 0;
return; return;
} }
// we can send back any data we want, our table keeps track of the order and frequency of each data type we send // we can send back any data we want, our table keeps track of the order and frequency of each data type we send
uint16_t id = frSkyDataIdTable[smartPortIdCnt]; uint16_t id = frSkyDataIdTable[smartPortIdCnt];
if (id == 0) { // end of table reached, loop back if (id == 0) { // end of table reached, loop back

View file

@ -56,7 +56,7 @@ void telemetryInit(void)
initSmartPortTelemetry(telemetryConfig); initSmartPortTelemetry(telemetryConfig);
initLtmTelemetry(telemetryConfig); initLtmTelemetry(telemetryConfig);
initJetiExBusTelemetry(telemetryConfig); initJetiExBusTelemetry(telemetryConfig);
telemetryCheckState(); telemetryCheckState();
} }

View file

@ -207,12 +207,12 @@
/****************** C Compilers dependant keywords ****************************/ /****************** C Compilers dependant keywords ****************************/
/* In HS mode and when the DMA is used, all variables and data structures dealing /* In HS mode and when the DMA is used, all variables and data structures dealing
with the DMA during the transaction process should be 4-bytes aligned */ with the DMA during the transaction process should be 4-bytes aligned */
#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) #define __ALIGN_BEGIN __align(4)

View file

@ -111,23 +111,23 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
break; break;
// Not needed for this driver // Not needed for this driver
case SET_COMM_FEATURE: case SET_COMM_FEATURE:
case GET_COMM_FEATURE: case GET_COMM_FEATURE:
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
@ -234,7 +234,7 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len)
if(receiveLength > (USB_RX_BUFSIZE-1)) if(receiveLength > (USB_RX_BUFSIZE-1))
return USBD_FAIL; return USBD_FAIL;
return USBD_OK; return USBD_OK;
} }

View file

@ -166,8 +166,8 @@ __ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALI
/* 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),
}; };

View file

@ -63,7 +63,7 @@ void USBD_USR_DeviceReset(uint8_t speed )
break; break;
default: default:
break; break;
} }
} }