MPU6000: protect the driver from double initialisation

initialising twice can lockup the driver
This commit is contained in:
Andrew Tridgell 2011-12-27 07:38:36 +11:00
parent 18d26dc74e
commit 6ca613337b
2 changed files with 6 additions and 0 deletions

View File

@ -100,10 +100,13 @@ AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000( uint8_t cs_pin )
_accel.y = 0; _accel.y = 0;
_accel.z = 0; _accel.z = 0;
_temp = 0; _temp = 0;
_initialised = 0;
} }
void AP_InertialSensor_MPU6000::init( AP_PeriodicProcess * scheduler ) void AP_InertialSensor_MPU6000::init( AP_PeriodicProcess * scheduler )
{ {
if (_initialised) return;
_initialised = 1;
hardware_init(); hardware_init();
scheduler->register_process( &AP_InertialSensor_MPU6000::read ); scheduler->register_process( &AP_InertialSensor_MPU6000::read );
} }

View File

@ -64,6 +64,9 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor
/* TODO deprecate _cs_pin */ /* TODO deprecate _cs_pin */
static uint8_t _cs_pin; static uint8_t _cs_pin;
// ensure we can't initialise twice
unsigned _initialised:1;
}; };
#endif // __AP_INERTIAL_SENSOR_MPU6000_H__ #endif // __AP_INERTIAL_SENSOR_MPU6000_H__