Browse Source

MPU6k: added suspend/resume on init

master
Andrew Tridgell 13 years ago
parent
commit
2dd655d87d
  1. 2
      libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

2
libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

@ -111,7 +111,9 @@ void AP_InertialSensor_MPU6000::init( AP_PeriodicProcess * scheduler ) @@ -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 );
}

Loading…
Cancel
Save