Fix 1wire pass through for F3 + target config changes

This commit is contained in:
4712 2015-11-05 00:40:11 +01:00
parent 42523e4bcb
commit ce743d3acc
5 changed files with 47 additions and 34 deletions

View File

@ -12,9 +12,15 @@ Currently supported on the SPRACINGF3, STM32F3DISCOVERY, NAZE32 (including clone
## Wiring ## 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. - 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.

View File

@ -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: 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 external flash rom is the same size as found on the Naze32 (2MBit)
* The barometer is the cheaper BMP280. * The barometer is the cheaper BMP280.
* It does not have any compass sensor. * It does not have any compass sensor.

View File

@ -26,7 +26,6 @@
#include "drivers/gpio.h" #include "drivers/gpio.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"
#include "drivers/system.h"
#include "io/serial_1wire.h" #include "io/serial_1wire.h"
const escHardware_t escHardware[ESC_COUNT] = { const escHardware_t escHardware[ESC_COUNT] = {
@ -97,7 +96,7 @@ void usb1WireInitialize()
#ifdef BEEPER #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 // 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 #endif
} }
@ -138,8 +137,6 @@ static void gpioSetOne(uint32_t escIndex, GPIO_Mode mode) {
} }
#endif #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 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 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) #define ESC_SET_HI(escIndex) escHardware[escIndex].gpio->BSRR = (1U << escHardware[escIndex].pinpos)
@ -190,7 +187,7 @@ void usb1WirePassthrough(uint8_t escIndex)
#endif #endif
//Disable all interrupts //Disable all interrupts
disable_hardware_uart; __disable_irq();
// reset all the pins // reset all the pins
GPIO_ResetBits(S1W_RX_GPIO, S1W_RX_PIN); GPIO_ResetBits(S1W_RX_GPIO, S1W_RX_PIN);
@ -225,7 +222,7 @@ void usb1WirePassthrough(uint8_t escIndex)
// Wait for programmer to go 0 -> 1 // Wait for programmer to go 0 -> 1
uint32_t ct=3333; uint32_t ct=3333;
while(!RX_HI) { 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 // 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 // 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 // BLHeliSuite will use 4800 baud
@ -249,17 +246,11 @@ void usb1WirePassthrough(uint8_t escIndex)
} }
} }
} }
// we get here in case ct reached zero // we get here in case ct reached zero
TX_SET_HIGH; TX_SET_HIGH;
RX_LED_OFF; RX_LED_OFF;
// Programmer TX // Enable all irq (for Hardware UART)
gpio_set_mode(S1W_TX_GPIO, S1W_TX_PIN, Mode_AF_PP); __enable_irq();
// 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);
return; return;
} }

View File

@ -1799,13 +1799,32 @@ static bool processInCommand(void)
headSerialReply(0); headSerialReply(0);
tailSerialReply(); tailSerialReply();
// wait for all data to send // wait for all data to send
while (!isSerialTransmitBufferEmpty(mspSerialPort)) { waitForSerialPortToFinishTransmitting(currentPort->port);
delay(50);
}
// Start to activate here // Start to activate here
// motor 1 => index 0 // 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); 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 { } else {
// ESC channel higher than max. allowed // ESC channel higher than max. allowed
// rem: BLHeliSuite will not support more than 8 // rem: BLHeliSuite will not support more than 8
@ -1909,10 +1928,7 @@ void mspProcess(void)
} }
if (isRebootScheduled) { if (isRebootScheduled) {
// pause a little while to allow response to be sent waitForSerialPortToFinishTransmitting(candidatePort->port);
while (!isSerialTransmitBufferEmpty(candidatePort->port)) {
delay(50);
}
stopMotors(); stopMotors();
handleOneshotFeatureChangeOnRestart(); handleOneshotFeatureChangeOnRestart();
systemReset(); systemReset();

View File

@ -102,9 +102,9 @@
#define USE_SERIAL_1WIRE #define USE_SERIAL_1WIRE
// How many escs does this board support? // How many escs does this board support?
#define ESC_COUNT 6 #define ESC_COUNT 6
// STM32F3DISCOVERY TX - PC3 connects to UART RX // STM32F3DISCOVERY TX - PD5 connects to UART RX
#define S1W_TX_GPIO GPIOC #define S1W_TX_GPIO GPIOD
#define S1W_TX_PIN GPIO_Pin_3 #define S1W_TX_PIN GPIO_Pin_5
// STM32F3DISCOVERY RX - PC1 connects to UART TX // STM32F3DISCOVERY RX - PD6 connects to UART TX
#define S1W_RX_GPIO GPIOC #define S1W_RX_GPIO GPIOD
#define S1W_RX_PIN GPIO_Pin_1 #define S1W_RX_PIN GPIO_Pin_6