AP_IneertialSensor: fixed startup race in SITL

This commit is contained in:
Andrew Tridgell 2019-03-21 17:48:40 +11:00
parent cd178a6c4f
commit 5e420e2adf

View File

@ -1659,6 +1659,9 @@ AuxiliaryBus *AP_InertialSensor::get_auxiliary_bus(int16_t backend_id, uint8_t i
void AP_InertialSensor::calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt) void AP_InertialSensor::calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt)
{ {
// check for clipping // check for clipping
if (_backends[instance] == nullptr) {
return;
}
if (fabsf(accel.x) > _backends[instance]->get_clip_limit() || if (fabsf(accel.x) > _backends[instance]->get_clip_limit() ||
fabsf(accel.y) > _backends[instance]->get_clip_limit() || fabsf(accel.y) > _backends[instance]->get_clip_limit() ||
fabsf(accel.z) > _backends[instance]->get_clip_limit()) { fabsf(accel.z) > _backends[instance]->get_clip_limit()) {