HAL_ChibiOS: flush serial bus during switching to and from SLCAN
This commit is contained in:
parent
664c952460
commit
a6b01901f1
@ -77,6 +77,7 @@ void SLCANRouter::timer()
|
|||||||
if (AP_HAL::millis() - _last_active_time > (_slcan_rt_timeout * 1000) && _slcan_rt_timeout != 0) {
|
if (AP_HAL::millis() - _last_active_time > (_slcan_rt_timeout * 1000) && _slcan_rt_timeout != 0) {
|
||||||
chSysLock();
|
chSysLock();
|
||||||
_port->lock_port(0, 0);
|
_port->lock_port(0, 0);
|
||||||
|
_port->flush();
|
||||||
_thread_suspended = true;
|
_thread_suspended = true;
|
||||||
chSysUnlock();
|
chSysUnlock();
|
||||||
}
|
}
|
||||||
@ -115,6 +116,7 @@ void SLCANRouter::slcan2can_router_trampoline(void)
|
|||||||
_s2c_thd_ref = nullptr;
|
_s2c_thd_ref = nullptr;
|
||||||
if (_thread_suspended) {
|
if (_thread_suspended) {
|
||||||
chThdSuspendS(&_s2c_thd_ref);
|
chThdSuspendS(&_s2c_thd_ref);
|
||||||
|
_port->flush();
|
||||||
}
|
}
|
||||||
chSysUnlock();
|
chSysUnlock();
|
||||||
_slcan_if.reader();
|
_slcan_if.reader();
|
||||||
|
Loading…
Reference in New Issue
Block a user