mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: 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:
parent
f2f9349419
commit
3b150d2e4c
|
@ -1333,6 +1333,8 @@ private:
|
|||
uint32_t last_port1_data_ms;
|
||||
uint32_t baud1;
|
||||
uint32_t baud2;
|
||||
uint8_t parity1;
|
||||
uint8_t parity2;
|
||||
uint8_t timeout_s;
|
||||
HAL_Semaphore sem;
|
||||
} _passthru;
|
||||
|
|
|
@ -6638,6 +6638,7 @@ void GCS::update_passthru(void)
|
|||
WITH_SEMAPHORE(_passthru.sem);
|
||||
uint32_t now = AP_HAL::millis();
|
||||
uint32_t baud1, baud2;
|
||||
uint8_t parity1 = 0, parity2 = 0;
|
||||
bool enabled = AP::serialmanager().get_passthru(_passthru.port1, _passthru.port2, _passthru.timeout_s,
|
||||
baud1, baud2);
|
||||
if (enabled && !_passthru.enabled) {
|
||||
|
@ -6647,6 +6648,8 @@ void GCS::update_passthru(void)
|
|||
_passthru.last_port1_data_ms = now;
|
||||
_passthru.baud1 = baud1;
|
||||
_passthru.baud2 = baud2;
|
||||
_passthru.parity1 = parity1 = _passthru.port1->get_parity();
|
||||
_passthru.parity2 = parity2 = _passthru.port2->get_parity();
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Passthru enabled");
|
||||
if (!_passthru.timer_installed) {
|
||||
_passthru.timer_installed = true;
|
||||
|
@ -6665,6 +6668,13 @@ void GCS::update_passthru(void)
|
|||
_passthru.port2->end();
|
||||
_passthru.port2->begin(baud2);
|
||||
}
|
||||
// Restore original parity
|
||||
if (_passthru.parity1 != parity1) {
|
||||
_passthru.port1->configure_parity(parity1);
|
||||
}
|
||||
if (_passthru.parity2 != parity2) {
|
||||
_passthru.port2->configure_parity(parity2);
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Passthru disabled");
|
||||
} else if (enabled &&
|
||||
_passthru.timeout_s &&
|
||||
|
@ -6683,12 +6693,19 @@ void GCS::update_passthru(void)
|
|||
_passthru.port2->end();
|
||||
_passthru.port2->begin(baud2);
|
||||
}
|
||||
// Restore original parity
|
||||
if (_passthru.parity1 != parity1) {
|
||||
_passthru.port1->configure_parity(parity1);
|
||||
}
|
||||
if (_passthru.parity2 != parity2) {
|
||||
_passthru.port2->configure_parity(parity2);
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Passthru timed out");
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
called at 1kHz to handle pass-thru between SERIA0_PASSTHRU port and hal.console
|
||||
called at 1kHz to handle pass-thru between SERIAL_PASS1 and SERIAL_PASS2 ports
|
||||
*/
|
||||
void GCS::passthru_timer(void)
|
||||
{
|
||||
|
@ -6701,7 +6718,7 @@ void GCS::passthru_timer(void)
|
|||
if (_passthru.start_ms != 0) {
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - _passthru.start_ms < 1000) {
|
||||
// delay for 1s so the reply for the SERIAL0_PASSTHRU param set can be seen by GCS
|
||||
// delay for 1s so the reply for the SERIAL_PASS2 param set can be seen by GCS
|
||||
return;
|
||||
}
|
||||
_passthru.start_ms = 0;
|
||||
|
@ -6715,19 +6732,35 @@ void GCS::passthru_timer(void)
|
|||
_passthru.port1->lock_port(lock_key, lock_key);
|
||||
_passthru.port2->lock_port(lock_key, lock_key);
|
||||
|
||||
// Check for requested Baud rates over USB
|
||||
// Check for requested Baud rates and parity over USB
|
||||
uint32_t baud = _passthru.port1->get_usb_baud();
|
||||
if (_passthru.baud2 != baud && baud != 0) {
|
||||
_passthru.baud2 = baud;
|
||||
_passthru.port2->end();
|
||||
_passthru.port2->begin_locked(baud, 0, 0, lock_key);
|
||||
uint8_t parity = _passthru.port1->get_usb_parity();
|
||||
if (baud != 0) { // port1 is USB
|
||||
if (_passthru.baud2 != baud) {
|
||||
_passthru.baud2 = baud;
|
||||
_passthru.port2->end();
|
||||
_passthru.port2->begin_locked(baud, 0, 0, lock_key);
|
||||
}
|
||||
|
||||
if (_passthru.parity2 != parity) {
|
||||
_passthru.parity2 = parity;
|
||||
_passthru.port2->configure_parity(parity);
|
||||
}
|
||||
}
|
||||
|
||||
baud = _passthru.port2->get_usb_baud();
|
||||
if (_passthru.baud1 != baud && baud != 0) {
|
||||
_passthru.baud1 = baud;
|
||||
_passthru.port1->end();
|
||||
_passthru.port1->begin_locked(baud, 0, 0, lock_key);
|
||||
parity = _passthru.port2->get_usb_parity();
|
||||
if (baud != 0) { // port2 is USB
|
||||
if (_passthru.baud1 != baud) {
|
||||
_passthru.baud1 = baud;
|
||||
_passthru.port1->end();
|
||||
_passthru.port1->begin_locked(baud, 0, 0, lock_key);
|
||||
}
|
||||
|
||||
if (_passthru.parity1 != parity) {
|
||||
_passthru.parity1 = parity;
|
||||
_passthru.port1->configure_parity(parity);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t buf[64];
|
||||
|
|
Loading…
Reference in New Issue