diff --git a/docs/1wire.md b/docs/1wire.md index 7ea11c55b9..7d2473c365 100644 --- a/docs/1wire.md +++ b/docs/1wire.md @@ -12,9 +12,15 @@ Currently supported on the SPRACINGF3, STM32F3DISCOVERY, NAZE32 (including clone ## Wiring - - For the NAZE, no external wiring is necessary. Simply plugin the board via USB cable. + - For the NAZE, no external wiring is necessary. Simply plug in the board via USB cable. - - For the CC3D, connect [a USB to UART adapter](http://bit.ly/cf-cp2102) to the main port. If you need one, I prefer the [CP2102](http://bit.ly/cf-cp2102) as it is cheap and [the driver](https://www.silabs.com/products/mcu/Pages/USBtoUARTBridgeVCPDrivers.aspx) is readily available. + - For the CC3D, connect [a USB to UART adapter](http://bit.ly/cf-cp2102) to the flex port. + + - Ensure MSP is enabled on the flex port. Unfortunatly the main port cannot be used in the current configuration due to the inverter on this port. + + - You'll only need this connection to the CC3D, do not plug in the normal USB connection. + + - If you need one, I prefer the [CP2102](http://bit.ly/cf-cp2102) as it is cheap and [the driver](https://www.silabs.com/products/mcu/Pages/USBtoUARTBridgeVCPDrivers.aspx) is readily available. - In the case that your board does not power on fully without a battery attached, it is OK to attach the battery before following the steps below. However, it may not be necessary in all cases. diff --git a/docs/Board - RMDO.md b/docs/Board - RMDO.md index abd4cf6454..b90ccf5f3d 100644 --- a/docs/Board - RMDO.md +++ b/docs/Board - RMDO.md @@ -4,7 +4,7 @@ The DoDo board is a clone of the SPRacingF3 board in terms of CPU pin mappings. Hardware differences compared to SPRacingF3 are as follows: -* The CPU is the cheaper version of the F3 with only 128KB FLASH. +* Rev 1 and Rev 2: the CPU is the cheaper version of the F3 with only 128KB FLASH. Rev 3: the CPU is a F3 version with 256KB FLASH. * The external flash rom is the same size as found on the Naze32 (2MBit) * The barometer is the cheaper BMP280. * It does not have any compass sensor. diff --git a/src/main/io/serial_1wire.c b/src/main/io/serial_1wire.c index 7fe12aebc4..175edcf03e 100644 --- a/src/main/io/serial_1wire.c +++ b/src/main/io/serial_1wire.c @@ -26,7 +26,6 @@ #include "drivers/gpio.h" #include "drivers/light_led.h" -#include "drivers/system.h" #include "io/serial_1wire.h" const escHardware_t escHardware[ESC_COUNT] = { @@ -95,9 +94,9 @@ void usb1WireInitialize() gpio_set_mode(escHardware[i].gpio, (1U << escHardware[i].pinpos), Mode_IPU); //GPIO_Mode_IPU } #ifdef BEEPER - // fix for buzzer often starts beeping continuously when the ESCs are read + // fix for buzzer often starts beeping continuously when the ESCs are read // switch beeper off until reboot - gpio_set_mode(BEEP_GPIO, BEEP_PIN, Mode_IN_FLOATING); //GPIO_Mode_IPU + gpio_set_mode(BEEP_GPIO, BEEP_PIN, Mode_IN_FLOATING); // set input no pull up or down #endif } @@ -138,8 +137,6 @@ static void gpioSetOne(uint32_t escIndex, GPIO_Mode mode) { } #endif -#define disable_hardware_uart __disable_irq() -#define enable_hardware_uart __enable_irq() #define ESC_HI(escIndex) ((escHardware[escIndex].gpio->IDR & (1U << escHardware[escIndex].pinpos)) != (uint32_t)Bit_RESET) #define RX_HI ((S1W_RX_GPIO->IDR & S1W_RX_PIN) != (uint32_t)Bit_RESET) #define ESC_SET_HI(escIndex) escHardware[escIndex].gpio->BSRR = (1U << escHardware[escIndex].pinpos) @@ -190,7 +187,7 @@ void usb1WirePassthrough(uint8_t escIndex) #endif //Disable all interrupts - disable_hardware_uart; + __disable_irq(); // reset all the pins GPIO_ResetBits(S1W_RX_GPIO, S1W_RX_PIN); @@ -210,7 +207,7 @@ void usb1WirePassthrough(uint8_t escIndex) TX_SET_HIGH; // Wait for programmer to go from 1 -> 0 indicating incoming data while(RX_HI); - + while(1) { // A new iteration on this loop starts when we have data from the programmer (read_programmer goes low) // Setup escIndex pin to send data, pullup is the default @@ -225,7 +222,7 @@ void usb1WirePassthrough(uint8_t escIndex) // Wait for programmer to go 0 -> 1 uint32_t ct=3333; while(!RX_HI) { - if (ct > 0) ct--; //count down until 0; + if (ct > 0) ct--; // count down until 0; // check for low time ->ct=3333 ~600uS //byte LO time for 0 @ 19200 baud -> 9*52 uS => 468.75uS // App must send a 0 at 9600 baud (or lower) which has a LO time of at 104uS (or more) > 0 = 937.5uS LO // BLHeliSuite will use 4800 baud @@ -249,17 +246,11 @@ void usb1WirePassthrough(uint8_t escIndex) } } } - // we get here in case ct reached zero TX_SET_HIGH; - RX_LED_OFF; - // Programmer TX - gpio_set_mode(S1W_TX_GPIO, S1W_TX_PIN, Mode_AF_PP); - // Enable Hardware UART - enable_hardware_uart; - // Wait a bit more to let App read the 0 byte and switch baudrate - // 2ms will most likely do the job, but give some grace time - delay(10); + RX_LED_OFF; + // Enable all irq (for Hardware UART) + __enable_irq(); return; } diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index bebc1c5cd3..269706c880 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1799,13 +1799,32 @@ static bool processInCommand(void) headSerialReply(0); tailSerialReply(); // wait for all data to send - while (!isSerialTransmitBufferEmpty(mspSerialPort)) { - delay(50); - } + waitForSerialPortToFinishTransmitting(currentPort->port); // Start to activate here // motor 1 => index 0 + + // search currentPort portIndex + /* next lines seems to be unnecessary, because the currentPort always point to the same mspPorts[portIndex] + uint8_t portIndex; + for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) { + if (currentPort == &mspPorts[portIndex]) { + break; + } + } + */ + mspReleasePortIfAllocated(mspSerialPort); // CloseSerialPort also marks currentPort as UNUSED_PORT usb1WirePassthrough(i); - // MPS uart is active again + // Wait a bit more to let App read the 0 byte and switch baudrate + // 2ms will most likely do the job, but give some grace time + delay(10); + // rebuild/refill currentPort structure, does openSerialPort if marked UNUSED_PORT - used ports are skiped + mspAllocateSerialPorts(&masterConfig.serialConfig); + /* restore currentPort and mspSerialPort + setCurrentPort(&mspPorts[portIndex]); // not needed same index will be restored + */ + // former used MSP uart is active again + // restore MSP_SET_1WIRE as current command for correct headSerialReply(0) + currentPort->cmdMSP = MSP_SET_1WIRE; } else { // ESC channel higher than max. allowed // rem: BLHeliSuite will not support more than 8 @@ -1909,10 +1928,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(); diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 12e0aa39a6..844949ed3c 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -102,9 +102,9 @@ #define USE_SERIAL_1WIRE // How many escs does this board support? #define ESC_COUNT 6 -// STM32F3DISCOVERY TX - PC3 connects to UART RX -#define S1W_TX_GPIO GPIOC -#define S1W_TX_PIN GPIO_Pin_3 -// STM32F3DISCOVERY RX - PC1 connects to UART TX -#define S1W_RX_GPIO GPIOC -#define S1W_RX_PIN GPIO_Pin_1 +// STM32F3DISCOVERY TX - PD5 connects to UART RX +#define S1W_TX_GPIO GPIOD +#define S1W_TX_PIN GPIO_Pin_5 +// STM32F3DISCOVERY RX - PD6 connects to UART TX +#define S1W_RX_GPIO GPIOD +#define S1W_RX_PIN GPIO_Pin_6