Revert "Fix 1wire pass through for F3 + target config changes"
This reverts commit c2b1dd3259
.
This commit is contained in:
parent
c2b1dd3259
commit
42523e4bcb
|
@ -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:
|
||||||
|
|
||||||
* 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 CPU is the cheaper version of the F3 with only 128KB 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.
|
||||||
|
|
|
@ -26,6 +26,7 @@
|
||||||
|
|
||||||
#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] = {
|
||||||
|
@ -96,7 +97,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); // set input no pull up or down
|
gpio_set_mode(BEEP_GPIO, BEEP_PIN, Mode_IN_FLOATING); //GPIO_Mode_IPU
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -137,6 +138,8 @@ 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)
|
||||||
|
@ -187,7 +190,7 @@ void usb1WirePassthrough(uint8_t escIndex)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//Disable all interrupts
|
//Disable all interrupts
|
||||||
__disable_irq();
|
disable_hardware_uart;
|
||||||
|
|
||||||
// reset all the pins
|
// reset all the pins
|
||||||
GPIO_ResetBits(S1W_RX_GPIO, S1W_RX_PIN);
|
GPIO_ResetBits(S1W_RX_GPIO, S1W_RX_PIN);
|
||||||
|
@ -222,11 +225,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) {
|
||||||
<<<<<<< HEAD
|
|
||||||
if (ct > 0) ct--; //count down until 0;
|
if (ct > 0) ct--; //count down until 0;
|
||||||
=======
|
|
||||||
if (ct > 0) ct--; // count down until 0;
|
|
||||||
>>>>>>> 9be5abf... Fix 1wire pass through for F3 + target config changes
|
|
||||||
// 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
|
||||||
|
@ -250,7 +249,6 @@ void usb1WirePassthrough(uint8_t escIndex)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
<<<<<<< HEAD
|
|
||||||
|
|
||||||
// we get here in case ct reached zero
|
// we get here in case ct reached zero
|
||||||
TX_SET_HIGH;
|
TX_SET_HIGH;
|
||||||
|
@ -262,13 +260,6 @@ void usb1WirePassthrough(uint8_t escIndex)
|
||||||
// Wait a bit more to let App read the 0 byte and switch baudrate
|
// 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
|
// 2ms will most likely do the job, but give some grace time
|
||||||
delay(10);
|
delay(10);
|
||||||
=======
|
|
||||||
// we get here in case ct reached zero
|
|
||||||
TX_SET_HIGH;
|
|
||||||
RX_LED_OFF;
|
|
||||||
// Enable all irq (for Hardware UART)
|
|
||||||
__enable_irq();
|
|
||||||
>>>>>>> 9be5abf... Fix 1wire pass through for F3 + target config changes
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1799,32 +1799,13 @@ static bool processInCommand(void)
|
||||||
headSerialReply(0);
|
headSerialReply(0);
|
||||||
tailSerialReply();
|
tailSerialReply();
|
||||||
// wait for all data to send
|
// wait for all data to send
|
||||||
waitForSerialPortToFinishTransmitting(currentPort->port);
|
while (!isSerialTransmitBufferEmpty(mspSerialPort)) {
|
||||||
|
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);
|
||||||
// Wait a bit more to let App read the 0 byte and switch baudrate
|
// MPS uart is active again
|
||||||
// 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
|
||||||
|
|
|
@ -162,10 +162,7 @@
|
||||||
// USART3,
|
// USART3,
|
||||||
#define BIND_PORT GPIOB
|
#define BIND_PORT GPIOB
|
||||||
#define BIND_PIN Pin_11
|
#define BIND_PIN Pin_11
|
||||||
<<<<<<< HEAD
|
|
||||||
|
|
||||||
=======
|
|
||||||
>>>>>>> 9be5abf... Fix 1wire pass through for F3 + target config changes
|
|
||||||
#define USE_SERIAL_1WIRE
|
#define USE_SERIAL_1WIRE
|
||||||
#define ESC_COUNT 8
|
#define ESC_COUNT 8
|
||||||
#define S1W_TX_GPIO GPIOA
|
#define S1W_TX_GPIO GPIOA
|
||||||
|
|
|
@ -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 - PD5 connects to UART RX
|
// STM32F3DISCOVERY TX - PC3 connects to UART RX
|
||||||
#define S1W_TX_GPIO GPIOD
|
#define S1W_TX_GPIO GPIOC
|
||||||
#define S1W_TX_PIN GPIO_Pin_5
|
#define S1W_TX_PIN GPIO_Pin_3
|
||||||
// STM32F3DISCOVERY RX - PD6 connects to UART TX
|
// STM32F3DISCOVERY RX - PC1 connects to UART TX
|
||||||
#define S1W_RX_GPIO GPIOD
|
#define S1W_RX_GPIO GPIOC
|
||||||
#define S1W_RX_PIN GPIO_Pin_6
|
#define S1W_RX_PIN GPIO_Pin_1
|
||||||
|
|
Loading…
Reference in New Issue