mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_InertialSensor: fixed flood of log with fast fifo reset
This commit is contained in:
parent
b3f9c212a9
commit
1b9088918a
@ -472,6 +472,7 @@ bool AP_InertialSensor_Invensense::update() /* front end */
|
||||
#if HAL_LOGGING_ENABLED
|
||||
if (last_fast_reset_count != fast_reset_count) {
|
||||
AP::logger().Write_MessageF("IMU%u fast fifo reset %u", _gyro_instance, fast_reset_count);
|
||||
last_fast_reset_count = fast_reset_count;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user