diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index b58420b7a9..ccd6a67c41 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -100,10 +100,13 @@ AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000( uint8_t cs_pin ) _accel.y = 0; _accel.z = 0; _temp = 0; + _initialised = 0; } void AP_InertialSensor_MPU6000::init( AP_PeriodicProcess * scheduler ) { + if (_initialised) return; + _initialised = 1; hardware_init(); scheduler->register_process( &AP_InertialSensor_MPU6000::read ); } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 844719b232..b6044c36d5 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -64,6 +64,9 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor /* TODO deprecate _cs_pin */ static uint8_t _cs_pin; + + // ensure we can't initialise twice + unsigned _initialised:1; }; #endif // __AP_INERTIAL_SENSOR_MPU6000_H__