mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
HAL_ChibiOS: added UART inversion options
support GPIO pins or STM32F7
This commit is contained in:
parent
bd117f1548
commit
acf03980ca
@ -1081,4 +1081,57 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
|
||||
return last_receive_us;
|
||||
}
|
||||
|
||||
// set optional features, return true on success
|
||||
bool UARTDriver::set_options(uint8_t options)
|
||||
{
|
||||
if (options == 0) {
|
||||
return true;
|
||||
}
|
||||
if (sdef.is_usb) {
|
||||
return false;
|
||||
}
|
||||
#if defined(STM32F7) && HAL_USE_SERIAL == TRUE
|
||||
// F7 has built-in support for inversion in all uarts
|
||||
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
||||
uint32_t cr2 = sd->usart->CR2;
|
||||
bool was_enabled = (sd->usart->CR1 & USART_CR1_UE);
|
||||
if (options & OPTION_RXINV) {
|
||||
cr2 |= USART_CR2_RXINV;
|
||||
} else {
|
||||
cr2 &= ~USART_CR2_RXINV;
|
||||
}
|
||||
if (options & OPTION_TXINV) {
|
||||
cr2 |= USART_CR2_TXINV;
|
||||
} else {
|
||||
cr2 &= ~USART_CR2_TXINV;
|
||||
}
|
||||
if (was_enabled) {
|
||||
sd->usart->CR1 &= ~USART_CR1_UE;
|
||||
}
|
||||
sd->usart->CR2 = cr2;
|
||||
if (was_enabled) {
|
||||
sd->usart->CR1 |= USART_CR1_UE;
|
||||
}
|
||||
return true;
|
||||
#else
|
||||
// external pin based inversion control, relying on TXINV and RXINV lines in hwdef.dat
|
||||
bool ret = true;
|
||||
if (options & OPTION_RXINV) {
|
||||
if (sdef.rxinv_gpio >= 0) {
|
||||
hal.gpio->write(sdef.rxinv_gpio, sdef.rxinv_polarity);
|
||||
} else {
|
||||
ret = false;
|
||||
}
|
||||
}
|
||||
if (options & OPTION_TXINV) {
|
||||
if (sdef.txinv_gpio >= 0) {
|
||||
hal.gpio->write(sdef.txinv_gpio, sdef.txinv_polarity);
|
||||
} else {
|
||||
ret = false;
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
@ -52,6 +52,9 @@ public:
|
||||
// lock a port for exclusive use. Use a key of 0 to unlock
|
||||
bool lock_port(uint32_t key) override;
|
||||
|
||||
// control optional features
|
||||
bool set_options(uint8_t options) override;
|
||||
|
||||
// write to a locked port. If port is locked and key is not correct then 0 is returned
|
||||
// and write is discarded
|
||||
size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override;
|
||||
@ -66,6 +69,10 @@ public:
|
||||
uint8_t dma_tx_stream_id;
|
||||
uint32_t dma_tx_channel_id;
|
||||
ioline_t rts_line;
|
||||
int8_t rxinv_gpio;
|
||||
uint8_t rxinv_polarity;
|
||||
int8_t txinv_gpio;
|
||||
uint8_t txinv_polarity;
|
||||
uint8_t get_index(void) const {
|
||||
return uint8_t(this - &_serial_tab[0]);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user