From 1c079855188e740a28e83c8e19c3fbccefe304b1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?V=C3=ADctor=20Mayoral=20Vilches?= Date: Mon, 5 May 2014 17:52:09 +0200 Subject: [PATCH] AP_InertialSensor_MPU9150: Comment the suspend_timer_procs It causes the driver to hang. This matter should be inspected. --- libraries/AP_InertialSensor/AP_InertialSensor_MPU9150.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9150.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9150.cpp index d501925706..2f15c5ed5d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9150.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9150.cpp @@ -1133,10 +1133,10 @@ bool AP_InertialSensor_MPU9150::update(void) _previous_accel[0] = _accel[0]; - hal.scheduler->suspend_timer_procs(); + // hal.scheduler->suspend_timer_procs(); _accel[0] = _accel_filtered; _gyro[0] = _gyro_filtered; - hal.scheduler->resume_timer_procs(); + // hal.scheduler->resume_timer_procs(); // add offsets and rotation _accel[0].rotate(_board_orientation);