From f6d165d8c12449af26597852cdcfd239704bfdba Mon Sep 17 00:00:00 2001 From: Siddharth Purohit Date: Fri, 18 Jan 2019 15:09:36 +0800 Subject: [PATCH] HAL_ChibiOS: CANSerialRouter unlock the port in timer --- libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp b/libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp index de256ae70f..9912eeff47 100644 --- a/libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp +++ b/libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp @@ -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) 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) chSysLock(); _c2s_thd_ref = nullptr; if (_thread_suspended) { - _port->lock_port(0, 0); chThdSuspendS(&_c2s_thd_ref); } chSysUnlock();