MPU6k: added suspend/resume on init

This commit is contained in:
Andrew Tridgell 2012-04-30 16:12:12 +10:00
parent ae1702c20b
commit 76a3fd9a4e

View File

@ -111,7 +111,9 @@ void AP_InertialSensor_MPU6000::init( AP_PeriodicProcess * scheduler )
{
if (_initialised) return;
_initialised = 1;
scheduler->suspend_timer();
hardware_init();
scheduler->resume_timer();
scheduler->register_process( &AP_InertialSensor_MPU6000::read );
}