Browse Source

HAL_ChibiOS: CANSerialRouter unlock the port in timer

master
Siddharth Purohit 6 years ago committed by Andrew Tridgell
parent
commit
f6d165d8c1
  1. 3
      libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp

3
libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp

@ -76,6 +76,7 @@ void SLCANRouter::timer() @@ -76,6 +76,7 @@ void SLCANRouter::timer()
}
if (AP_HAL::millis() - _last_active_time > (_slcan_rt_timeout * 1000) && _slcan_rt_timeout != 0) {
chSysLock();
_port->lock_port(0, 0);
_thread_suspended = true;
chSysUnlock();
}
@ -113,7 +114,6 @@ void SLCANRouter::slcan2can_router_trampoline(void) @@ -113,7 +114,6 @@ void SLCANRouter::slcan2can_router_trampoline(void)
chSysLock();
_s2c_thd_ref = nullptr;
if (_thread_suspended) {
_port->lock_port(0, 0);
chThdSuspendS(&_s2c_thd_ref);
}
chSysUnlock();
@ -134,7 +134,6 @@ void SLCANRouter::can2slcan_router_trampoline(void) @@ -134,7 +134,6 @@ void SLCANRouter::can2slcan_router_trampoline(void)
chSysLock();
_c2s_thd_ref = nullptr;
if (_thread_suspended) {
_port->lock_port(0, 0);
chThdSuspendS(&_c2s_thd_ref);
}
chSysUnlock();

Loading…
Cancel
Save