mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: setup baudrates for passthru serial ports
This commit is contained in:
parent
d0db3eef58
commit
9c74474196
@ -1017,6 +1017,8 @@ private:
|
||||
uint32_t start_ms;
|
||||
uint32_t last_ms;
|
||||
uint32_t last_port1_data_ms;
|
||||
uint32_t baud1;
|
||||
uint32_t baud2;
|
||||
uint8_t timeout_s;
|
||||
HAL_Semaphore sem;
|
||||
} _passthru;
|
||||
|
@ -4937,7 +4937,8 @@ void GCS::update_passthru(void)
|
||||
WITH_SEMAPHORE(_passthru.sem);
|
||||
uint32_t now = AP_HAL::millis();
|
||||
|
||||
bool enabled = AP::serialmanager().get_passthru(_passthru.port1, _passthru.port2, _passthru.timeout_s);
|
||||
bool enabled = AP::serialmanager().get_passthru(_passthru.port1, _passthru.port2, _passthru.timeout_s,
|
||||
_passthru.baud1, _passthru.baud2);
|
||||
if (enabled && !_passthru.enabled) {
|
||||
_passthru.start_ms = now;
|
||||
_passthru.last_ms = 0;
|
||||
@ -4983,6 +4984,8 @@ void GCS::passthru_timer(void)
|
||||
return;
|
||||
}
|
||||
_passthru.start_ms = 0;
|
||||
_passthru.port1->begin(_passthru.baud1);
|
||||
_passthru.port2->begin(_passthru.baud2);
|
||||
}
|
||||
|
||||
// while pass-thru is enabled lock both ports. They remain
|
||||
|
Loading…
Reference in New Issue
Block a user