mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_ChibiOS: fixed a bug in parity/stop-bit setting on STM32F7 and H7
and add get_options() method
This commit is contained in:
parent
312018898f
commit
bf2cf7834d
@ -50,6 +50,9 @@ UARTDriver *UARTDriver::uart_drivers[UART_MAX_DRIVERS];
|
|||||||
// caller threads
|
// caller threads
|
||||||
#define EVT_DATA EVENT_MASK(0)
|
#define EVT_DATA EVENT_MASK(0)
|
||||||
|
|
||||||
|
// event for parity error
|
||||||
|
#define EVT_PARITY EVENT_MASK(1)
|
||||||
|
|
||||||
#ifndef HAL_UART_MIN_TX_SIZE
|
#ifndef HAL_UART_MIN_TX_SIZE
|
||||||
#define HAL_UART_MIN_TX_SIZE 1024
|
#define HAL_UART_MIN_TX_SIZE 1024
|
||||||
#endif
|
#endif
|
||||||
@ -973,6 +976,12 @@ void UARTDriver::_timer_tick(void)
|
|||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
#if CH_CFG_USE_EVENTS == TRUE
|
||||||
|
if (parity_enabled && ((chEvtGetAndClearFlags(&ev_listener) & SD_PARITY_ERROR))) {
|
||||||
|
// discard bytes with parity error
|
||||||
|
ret = -1;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
if (half_duplex) {
|
if (half_duplex) {
|
||||||
uint32_t now = AP_HAL::micros();
|
uint32_t now = AP_HAL::micros();
|
||||||
if (now - hd_write_us < hd_read_delay_us) {
|
if (now - hd_write_us < hd_read_delay_us) {
|
||||||
@ -1117,26 +1126,47 @@ void UARTDriver::configure_parity(uint8_t v)
|
|||||||
// stop and start to take effect
|
// stop and start to take effect
|
||||||
sdStop((SerialDriver*)sdef.serial);
|
sdStop((SerialDriver*)sdef.serial);
|
||||||
|
|
||||||
|
#ifdef USART_CR1_M0
|
||||||
|
// cope with F7 where there are 2 bits in CR1_M
|
||||||
|
const uint32_t cr1_m0 = USART_CR1_M0;
|
||||||
|
#else
|
||||||
|
const uint32_t cr1_m0 = USART_CR1_M;
|
||||||
|
#endif
|
||||||
|
|
||||||
switch (v) {
|
switch (v) {
|
||||||
case 0:
|
case 0:
|
||||||
// no parity
|
// no parity
|
||||||
sercfg.cr1 &= ~(USART_CR1_PCE | USART_CR1_PS);
|
sercfg.cr1 &= ~(USART_CR1_PCE | USART_CR1_PS | USART_CR1_M);
|
||||||
break;
|
break;
|
||||||
case 1:
|
case 1:
|
||||||
// odd parity
|
// odd parity
|
||||||
// setting USART_CR1_M ensures extra bit is used as parity
|
// setting USART_CR1_M ensures extra bit is used as parity
|
||||||
// not last bit of data
|
// not last bit of data
|
||||||
sercfg.cr1 |= USART_CR1_M | USART_CR1_PCE;
|
sercfg.cr1 |= cr1_m0 | USART_CR1_PCE;
|
||||||
sercfg.cr1 |= USART_CR1_PS;
|
sercfg.cr1 |= USART_CR1_PS;
|
||||||
break;
|
break;
|
||||||
case 2:
|
case 2:
|
||||||
// even parity
|
// even parity
|
||||||
sercfg.cr1 |= USART_CR1_M | USART_CR1_PCE;
|
sercfg.cr1 |= cr1_m0 | USART_CR1_PCE;
|
||||||
sercfg.cr1 &= ~USART_CR1_PS;
|
sercfg.cr1 &= ~USART_CR1_PS;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
sdStart((SerialDriver*)sdef.serial, &sercfg);
|
sdStart((SerialDriver*)sdef.serial, &sercfg);
|
||||||
|
|
||||||
|
#if CH_CFG_USE_EVENTS == TRUE
|
||||||
|
if (parity_enabled) {
|
||||||
|
chEvtUnregister(chnGetEventSource((SerialDriver*)sdef.serial), &ev_listener);
|
||||||
|
}
|
||||||
|
parity_enabled = (v != 0);
|
||||||
|
if (parity_enabled) {
|
||||||
|
chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial),
|
||||||
|
&ev_listener,
|
||||||
|
EVT_PARITY,
|
||||||
|
SD_PARITY_ERROR);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_UART_NODMA
|
#ifndef HAL_UART_NODMA
|
||||||
if(sdef.dma_rx) {
|
if(sdef.dma_rx) {
|
||||||
//Configure serial driver to skip handling RX packets
|
//Configure serial driver to skip handling RX packets
|
||||||
@ -1221,6 +1251,8 @@ bool UARTDriver::set_options(uint8_t options)
|
|||||||
}
|
}
|
||||||
bool ret = true;
|
bool ret = true;
|
||||||
|
|
||||||
|
_last_options = options;
|
||||||
|
|
||||||
#if HAL_USE_SERIAL == TRUE
|
#if HAL_USE_SERIAL == TRUE
|
||||||
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
||||||
uint32_t cr2 = sd->usart->CR2;
|
uint32_t cr2 = sd->usart->CR2;
|
||||||
@ -1299,4 +1331,10 @@ bool UARTDriver::set_options(uint8_t options)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// get optional features
|
||||||
|
uint8_t UARTDriver::get_options(void) const
|
||||||
|
{
|
||||||
|
return _last_options;
|
||||||
|
}
|
||||||
|
|
||||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
@ -55,6 +55,7 @@ public:
|
|||||||
|
|
||||||
// control optional features
|
// control optional features
|
||||||
bool set_options(uint8_t options) override;
|
bool set_options(uint8_t options) override;
|
||||||
|
uint8_t get_options(void) const override;
|
||||||
|
|
||||||
// write to a locked port. If port is locked and key is not correct then 0 is returned
|
// write to a locked port. If port is locked and key is not correct then 0 is returned
|
||||||
// and write is discarded
|
// and write is discarded
|
||||||
@ -183,6 +184,7 @@ private:
|
|||||||
// we remember cr2 and cr2 options from set_options to apply on sdStart()
|
// we remember cr2 and cr2 options from set_options to apply on sdStart()
|
||||||
uint32_t _cr3_options;
|
uint32_t _cr3_options;
|
||||||
uint32_t _cr2_options;
|
uint32_t _cr2_options;
|
||||||
|
uint8_t _last_options;
|
||||||
|
|
||||||
// half duplex control. After writing we throw away bytes for 4 byte widths to
|
// half duplex control. After writing we throw away bytes for 4 byte widths to
|
||||||
// prevent reading our own bytes back
|
// prevent reading our own bytes back
|
||||||
@ -194,6 +196,12 @@ private:
|
|||||||
// set to true for unbuffered writes (low latency writes)
|
// set to true for unbuffered writes (low latency writes)
|
||||||
bool unbuffered_writes;
|
bool unbuffered_writes;
|
||||||
|
|
||||||
|
#if CH_CFG_USE_EVENTS == TRUE
|
||||||
|
// listener for parity error events
|
||||||
|
event_listener_t ev_listener;
|
||||||
|
bool parity_enabled;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_UART_NODMA
|
#ifndef HAL_UART_NODMA
|
||||||
static void rx_irq_cb(void* sd);
|
static void rx_irq_cb(void* sd);
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user