AP_InertialSensor: PX4: don't call calc_vibration_and_clipping()

That calculation will be unified.
This commit is contained in:
Gustavo Jose de Sousa 2015-08-28 14:03:58 -03:00 committed by Andrew Tridgell
parent 6aa973dd47
commit 77a4f10d89

View File

@ -283,9 +283,6 @@ void AP_InertialSensor_PX4::_new_accel_sample(uint8_t i, accel_report &accel_rep
// publish a temperature (for logging purposed only)
_publish_temperature(frontend_instance, accel_report.temperature);
// check noise
_imu.calc_vibration_and_clipping(frontend_instance, accel, dt);
#ifdef AP_INERTIALSENSOR_PX4_DEBUG
_accel_dt_max[i] = max(_accel_dt_max[i],dt);