ACM: only call the fast loop if the imu has new data

this prevents us spinning waiting for the sensors to gather some data
This commit is contained in:
Andrew Tridgell 2012-03-03 18:34:24 +11:00
parent e39c3cb9d2
commit 9bff4e2c4c
1 changed files with 1 additions and 1 deletions

View File

@ -844,7 +844,7 @@ void loop()
uint32_t timer = micros(); uint32_t timer = micros();
// We want this to execute fast // We want this to execute fast
// ---------------------------- // ----------------------------
if ((timer - fast_loopTimer) >= 4000) { if ((timer - fast_loopTimer) >= 4000 && imu.new_data_available()) {
//Log_Write_Data(13, (int32_t)(timer - fast_loopTimer)); //Log_Write_Data(13, (int32_t)(timer - fast_loopTimer));
//PORTK |= B00010000; //PORTK |= B00010000;