From 5e420e2adfc7913f289edceac32b0b73f86fe298 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 21 Mar 2019 17:48:40 +1100 Subject: [PATCH] AP_IneertialSensor: fixed startup race in SITL --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 435258e2c3..6371a89c9e 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -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) { // check for clipping + if (_backends[instance] == nullptr) { + return; + } if (fabsf(accel.x) > _backends[instance]->get_clip_limit() || fabsf(accel.y) > _backends[instance]->get_clip_limit() || fabsf(accel.z) > _backends[instance]->get_clip_limit()) {