mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
STM32F3 - Support hardware serial inversion.
Tested on the Sparky board with an FrSky X4RSB without external hardware inverter.
This commit is contained in:
parent
2825eec39d
commit
916aa60254
2 changed files with 36 additions and 19 deletions
|
@ -3,6 +3,7 @@
|
||||||
The Sparky is a very low cost and very powerful board.
|
The Sparky is a very low cost and very powerful board.
|
||||||
|
|
||||||
* 3 hardware serial ports.
|
* 3 hardware serial ports.
|
||||||
|
* Built-in serial port inverters which allows SBUS receivers to be used without external inverters.
|
||||||
* USB (can be used at the same time as the serial ports).
|
* USB (can be used at the same time as the serial ports).
|
||||||
* 10 PWM outputs.
|
* 10 PWM outputs.
|
||||||
* Dedicated PPM/SerialRX input pin.
|
* Dedicated PPM/SerialRX input pin.
|
||||||
|
@ -16,11 +17,11 @@ Flyable!
|
||||||
Tested with revision 1 board.
|
Tested with revision 1 board.
|
||||||
|
|
||||||
## TODO
|
## TODO
|
||||||
* Mag
|
* Baro - detection works but getting bad readings, disabled for now.
|
||||||
* Baro
|
|
||||||
* Led Strip
|
* Led Strip
|
||||||
* ADC
|
* ADC
|
||||||
* Display
|
* Sonar
|
||||||
|
* Display (via Flex port)
|
||||||
* Softserial - though having 3 hardware serial ports makes it a little redundant.
|
* Softserial - though having 3 hardware serial ports makes it a little redundant.
|
||||||
|
|
||||||
# Flashing
|
# Flashing
|
||||||
|
@ -46,10 +47,12 @@ Flashing cleanflight will erase the TauLabs bootloader, this is not a problem an
|
||||||
| Value | Identifier | RX | TX | Notes |
|
| Value | Identifier | RX | TX | Notes |
|
||||||
| ----- | ------------ | --------- | ---------- | ------------------------------------------------------------------------------------------- |
|
| ----- | ------------ | --------- | ---------- | ------------------------------------------------------------------------------------------- |
|
||||||
| 1 | USB VCP | RX (USB) | TX (USB) | |
|
| 1 | USB VCP | RX (USB) | TX (USB) | |
|
||||||
| 2 | USART1 | RX / PB7 | TX / PB6 | Conn1 / Flexi Port |
|
| 2 | USART1 | RX / PB7 | TX / PB6 | Conn1 / Flexi Port. |
|
||||||
| 3 | USART2 | RX / PA3 | PWM6 / PA2 | On RX is on INPUT header. Best port for Serial RX input. |
|
| 3 | USART2 | RX / PA3 | PWM6 / PA2 | On RX is on INPUT header. Best port for Serial RX input |
|
||||||
| 4 | USART3 | RX / PB11 | TX / PB10 | RX/TX is on one end of the 6-pin header about the PWM outputs. |
|
| 4 | USART3 | RX / PB11 | TX / PB10 | RX/TX is on one end of the 6-pin header about the PWM outputs. |
|
||||||
|
|
||||||
USB VCP *can* be used at the same time as other serial ports (unlike Naze32).
|
USB VCP *can* be used at the same time as other serial ports (unlike Naze32).
|
||||||
|
|
||||||
|
All USART ports all support automatic hardware inversion which allows direct connection of serial rx receivers like the FrSky X4RSB - no external inverter needed.
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -39,6 +39,31 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode);
|
||||||
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode);
|
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode);
|
||||||
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode);
|
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode);
|
||||||
|
|
||||||
|
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||||
|
#ifdef INVERTER
|
||||||
|
if (uartPort->port.inversion == SERIAL_INVERTED && uartPort->USARTx == INVERTER_USART) {
|
||||||
|
// Enable hardware inverter if available.
|
||||||
|
INVERTER_ON;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F303xC
|
||||||
|
uint32_t inversionPins = 0;
|
||||||
|
|
||||||
|
if (uartPort->port.mode & MODE_TX) {
|
||||||
|
inversionPins |= USART_InvPin_Tx;
|
||||||
|
}
|
||||||
|
if (uartPort->port.mode & MODE_RX) {
|
||||||
|
inversionPins |= USART_InvPin_Rx;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Note: inversion when using MODE_BIDIR not supported yet.
|
||||||
|
|
||||||
|
USART_InvPinCmd(uartPort->USARTx, inversionPins, uartPort->port.inversion == SERIAL_INVERTED ? ENABLE : DISABLE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
static void uartReconfigure(uartPort_t *uartPort)
|
static void uartReconfigure(uartPort_t *uartPort)
|
||||||
{
|
{
|
||||||
USART_InitTypeDef USART_InitStructure;
|
USART_InitTypeDef USART_InitStructure;
|
||||||
|
@ -63,22 +88,16 @@ static void uartReconfigure(uartPort_t *uartPort)
|
||||||
USART_InitStructure.USART_Mode |= USART_Mode_Tx | USART_Mode_Rx;
|
USART_InitStructure.USART_Mode |= USART_Mode_Tx | USART_Mode_Rx;
|
||||||
|
|
||||||
USART_Init(uartPort->USARTx, &USART_InitStructure);
|
USART_Init(uartPort->USARTx, &USART_InitStructure);
|
||||||
|
|
||||||
|
usartConfigurePinInversion(uartPort);
|
||||||
|
|
||||||
USART_Cmd(uartPort->USARTx, ENABLE);
|
USART_Cmd(uartPort->USARTx, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion)
|
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion)
|
||||||
{
|
{
|
||||||
UNUSED(inversion);
|
|
||||||
|
|
||||||
uartPort_t *s = NULL;
|
uartPort_t *s = NULL;
|
||||||
|
|
||||||
#ifdef INVERTER
|
|
||||||
if (inversion == SERIAL_INVERTED && USARTx == INVERTER_USART) {
|
|
||||||
// Enable hardware inverter if available.
|
|
||||||
INVERTER_ON;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (USARTx == USART1) {
|
if (USARTx == USART1) {
|
||||||
s = serialUSART1(baudRate, mode);
|
s = serialUSART1(baudRate, mode);
|
||||||
#ifdef USE_USART2
|
#ifdef USE_USART2
|
||||||
|
@ -101,12 +120,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
||||||
s->port.callback = callback;
|
s->port.callback = callback;
|
||||||
s->port.mode = mode;
|
s->port.mode = mode;
|
||||||
s->port.baudRate = baudRate;
|
s->port.baudRate = baudRate;
|
||||||
|
|
||||||
#if 1 // FIXME use inversion on STM32F3
|
|
||||||
s->port.inversion = SERIAL_NOT_INVERTED;
|
|
||||||
#else
|
|
||||||
s->port.inversion = inversion;
|
s->port.inversion = inversion;
|
||||||
#endif
|
|
||||||
|
|
||||||
uartReconfigure(s);
|
uartReconfigure(s);
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue