Merge pull request #1436 from ProDrone/fix_waiting_for_data_problem

Fix for Waiting for data (in configurator) problem on F1 targets
This commit is contained in:
Dominic Clifton 2015-10-29 21:44:11 +00:00
commit 46f6ff403e
2 changed files with 11 additions and 6 deletions

View File

@ -151,11 +151,19 @@ void systemInit(void)
cachedRccCsrValue = RCC->CSR;
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
#ifdef STM32F10X
// Set USART1 TX (PA9) to output and high state to prevent a rs232 break condition on reset.
// See issue https://github.com/cleanflight/cleanflight/issues/1433
gpio_config_t gpio;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpio.pin = Pin_9;
digitalHi(GPIOA, gpio.pin);
gpioInit(GPIOA, &gpio);
// Turn off JTAG port 'cause we're using the GPIO for leds
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;

View File

@ -1823,10 +1823,7 @@ void mspProcess(void)
}
if (isRebootScheduled) {
// pause a little while to allow response to be sent
while (!isSerialTransmitBufferEmpty(candidatePort->port)) {
delay(50);
}
waitForSerialPortToFinishTransmitting(candidatePort->port);
stopMotors();
handleOneshotFeatureChangeOnRestart();
systemReset();