Skip to content

Commit

Permalink
AP_HAL_ChibiOS: allow setup for low noise clock mismatch tolerant UAR…
Browse files Browse the repository at this point in the history
…T line
  • Loading branch information
bugobliterator committed Jul 24, 2024
1 parent 5c5319e commit 85eb69d
Show file tree
Hide file tree
Showing 3 changed files with 26 additions and 5 deletions.
7 changes: 7 additions & 0 deletions libraries/AP_HAL_ChibiOS/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -455,6 +455,13 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
sercfg.cr3 |= USART_CR3_DMAT;
}
sercfg.irq_cb = rx_irq_cb;
#if HAL_HAVE_LOW_NOISE_UART
if (sdef.low_noise_line) {
// we can mark UART to sample on one bit instead of default 3 bits
// this allows us to be slightly less sensitive to clock differences
sercfg.cr3 |= USART_CR3_ONEBIT;
}
#endif
#endif // HAL_UART_NODMA
if (!(sercfg.cr2 & USART_CR2_STOP2_BITS)) {
sercfg.cr2 |= USART_CR2_STOP1_BITS;
Expand Down
7 changes: 7 additions & 0 deletions libraries/AP_HAL_ChibiOS/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,10 @@
// enough for serial0 to serial9, plus IOMCU
#define UART_MAX_DRIVERS 11

#ifndef HAL_HAVE_LOW_NOISE_UART
#define HAL_HAVE_LOW_NOISE_UART 0
#endif

class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
public:
UARTDriver(uint8_t serial_num);
Expand Down Expand Up @@ -79,7 +83,10 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
uint8_t get_index(void) const {
return uint8_t(this - &_serial_tab[0]);
}

#if HAL_HAVE_LOW_NOISE_UART
bool low_noise_line;
#endif
};

bool wait_timeout(uint16_t n, uint32_t timeout_ms) override;
Expand Down
17 changes: 12 additions & 5 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -1865,6 +1865,7 @@ def write_UART_config(self, f):
OTG2_index = None
devlist = []
have_rts_cts = False
have_low_noise = False
crash_uart = None

# write config for CrashCatcher UART
Expand Down Expand Up @@ -1904,12 +1905,12 @@ def write_UART_config(self, f):

if dev.startswith('OTG2'):
f.write(
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, UINT8_MAX}\n' % dev) # noqa
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, UINT8_MAX, false}\n' % dev) # noqa
OTG2_index = serial_list.index(dev)
self.dual_USB_enabled = True
elif dev.startswith('OTG'):
f.write(
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, UINT8_MAX}\n' % dev) # noqa
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, UINT8_MAX, false}\n' % dev) # noqa
else:
need_uart_driver = True
f.write(
Expand Down Expand Up @@ -1948,9 +1949,15 @@ def get_RTS_alt_function():
if s not in lib.AltFunction_map:
return "UINT8_MAX"
return lib.AltFunction_map[s]

f.write("%s}\n" % get_RTS_alt_function())

low_noise = 'false'
rx_port = dev + '_RX'
if rx_port in self.bylabel and self.bylabel[rx_port].has_extra('LOW_NOISE'):
low_noise = 'true'
have_low_noise = True
f.write("%s, %s}\n" % (get_RTS_alt_function(), low_noise))

if have_low_noise:
f.write('#define HAL_HAVE_LOW_NOISE_UART 1\n')
if have_rts_cts:
f.write('#define AP_FEATURE_RTSCTS 1\n')
if OTG2_index is not None:
Expand Down

0 comments on commit 85eb69d

Please sign in to comment.