AP_HAL: Add support for parity to Serial passthrough

Add code to reflect USB ACM parity setting to the passthrough port alongside existing support for ACM baud rate changes.  Some use cases for serial passthrough require specific parity settings.

For example, even parity is used and required by the USART protocol used in the STM32 system bootloader. This enhancement allows the use of standard flash programming tools such as STM32CubeProgrammer to flash connected STM based peripherals such as Receivers and Telemetry radios via serial passthrough.  Some examples of such peripherals include the FrSky R9 receivers as well as various other STM based LoRa modules used by the mLRS project.
This commit is contained in:
Brad Bosch 2024-05-25 17:46:35 -05:00 committed by Andrew Tridgell
parent da3a9c1cc6
commit f2f9349419
10 changed files with 57 additions and 0 deletions

View File

@ -179,6 +179,11 @@ bool AP_HAL::UARTDriver::flow_control_enabled(enum flow_control flow_control_set
return false;
}
uint8_t AP_HAL::UARTDriver::get_parity(void)
{
return AP_HAL::UARTDriver::parity;
}
#if HAL_UART_STATS_ENABLED
// Take cumulative bytes and return the change since last call
uint32_t AP_HAL::UARTDriver::StatsTracker::ByteTracker::update(uint32_t bytes)

View File

@ -79,6 +79,9 @@ public:
// read buffer from a locked port. If port is locked and key is not correct then -1 is returned
ssize_t read_locked(uint8_t *buf, size_t count, uint32_t key) WARN_IF_UNUSED;
// get current parity for passthrough use
uint8_t get_parity(void);
// control optional features
virtual bool set_options(uint16_t options) { _last_options = options; return options==0; }
virtual uint16_t get_options(void) const { return _last_options; }
@ -189,6 +192,9 @@ public:
// return true requested baud on USB port
virtual uint32_t get_usb_baud(void) const { return 0; }
// return requested parity on USB port
virtual uint8_t get_usb_parity(void) const { return parity; }
// disable TX/RX pins for unusued uart
virtual void disable_rxtx(void) const {}
@ -213,6 +219,8 @@ protected:
uint32_t lock_write_key;
uint32_t lock_read_key;
uint8_t parity;
/*
backend begin method
*/

View File

@ -672,6 +672,19 @@ uint32_t UARTDriver::get_usb_baud() const
return 0;
}
/*
get the requested usb parity. Valid if get_usb_baud() returned non-zero.
*/
uint8_t UARTDriver::get_usb_parity() const
{
#if HAL_USE_SERIAL_USB
if (sdef.is_usb) {
return ::get_usb_parity(sdef.endpoint_id);
}
#endif
return 0;
}
uint32_t UARTDriver::_available()
{
if (!_rx_initialised || _uart_owner_thd != chThdGetSelfX()) {
@ -1429,6 +1442,7 @@ void UARTDriver::configure_parity(uint8_t v)
// not possible
return;
}
UARTDriver::parity = v;
#if HAL_USE_SERIAL == TRUE
// stop and start to take effect
sdStop((SerialDriver*)sdef.serial);

View File

@ -38,6 +38,7 @@ public:
bool is_initialized() override;
bool tx_pending() override;
uint32_t get_usb_baud() const override;
uint8_t get_usb_parity() const override;
// disable TX/RX pins for unusued uart
void disable_rxtx(void) const override;

View File

@ -251,6 +251,18 @@ uint32_t get_usb_baud(uint16_t endpoint_id)
}
return 0;
}
/*
get the requested usb parity. Valid if get_usb_baud() returned non-zero
*/
uint8_t get_usb_parity(uint16_t endpoint_id)
{
if (endpoint_id == 0) {
return linecoding.bParityType;
}
return 0;
}
#endif
/**
* @brief IN EP1 state.

View File

@ -46,6 +46,7 @@ extern SerialUSBDriver SDU2;
extern const SerialUSBConfig serusbcfg2;
#endif //HAL_HAVE_DUAL_USB_CDC
uint32_t get_usb_baud(uint16_t endpoint_id);
uint8_t get_usb_parity(uint16_t endpoint_id);
#endif
#define USB_DESC_MAX_STRLEN 100
void setup_usb_strings(void);

View File

@ -315,6 +315,19 @@ uint32_t get_usb_baud(uint16_t endpoint_id)
}
return 0;
}
/*
get the requested usb parity. Valid if get_usb_baud() returned non-zero
*/
uint8_t get_usb_parity(uint16_t endpoint_id)
{
for (uint8_t i = 0; i < ARRAY_SIZE(linecoding); i++) {
if (endpoint_id == ep_index[i]) {
return linecoding[i].bParityType;
}
}
return 0;
}
#endif
/**
* @brief IN EP1 state.

View File

@ -417,6 +417,7 @@ void UARTDriver::_timer_tick(void)
}
void UARTDriver::configure_parity(uint8_t v) {
UARTDriver::parity = v;
_device->set_parity(v);
}

View File

@ -161,6 +161,7 @@ private:
// statistics
uint32_t _tx_stats_bytes;
uint32_t _rx_stats_bytes;
};
#endif

View File

@ -73,6 +73,7 @@ void HALSITL::UARTDriver::configure_parity(uint8_t v)
if (_fd < 0) {
return;
}
UARTDriver::parity = v;
#ifdef USE_TERMIOS
struct termios t;