From fb6e5c5e6a6660ac0b37df36339f3b54dc20471d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 13:20:20 +1100 Subject: [PATCH] GCS_MAVLink: correct resetting of parity after passthhru is done this might have worked if parity1 and parity2 were static values - but theyr're not. I'm guessing the code evolved --- libraries/GCS_MAVLink/GCS_Common.cpp | 21 ++++++++++----------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 743b8b7e61..d4a3c0156d 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -6858,7 +6858,6 @@ 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) { @@ -6868,8 +6867,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(); + _passthru.parity1 = _passthru.port1->get_parity(); + _passthru.parity2 = _passthru.port2->get_parity(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Passthru enabled"); if (!_passthru.timer_installed) { _passthru.timer_installed = true; @@ -6889,11 +6888,11 @@ void GCS::update_passthru(void) _passthru.port2->begin(baud2); } // Restore original parity - if (_passthru.parity1 != parity1) { - _passthru.port1->configure_parity(parity1); + if (_passthru.parity1 != _passthru.port1->get_parity()) { + _passthru.port1->configure_parity(_passthru.parity1); } - if (_passthru.parity2 != parity2) { - _passthru.port2->configure_parity(parity2); + if (_passthru.parity2 != _passthru.port2->get_parity()) { + _passthru.port2->configure_parity(_passthru.parity2); } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Passthru disabled"); } else if (enabled && @@ -6914,11 +6913,11 @@ void GCS::update_passthru(void) _passthru.port2->begin(baud2); } // Restore original parity - if (_passthru.parity1 != parity1) { - _passthru.port1->configure_parity(parity1); + if (_passthru.parity1 != _passthru.port1->get_parity()) { + _passthru.port1->configure_parity(_passthru.parity1); } - if (_passthru.parity2 != parity2) { - _passthru.port2->configure_parity(parity2); + if (_passthru.parity2 != _passthru.port2->get_parity()) { + _passthru.port2->configure_parity(_passthru.parity2); } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Passthru timed out"); }