Browse Source

AP_IneertialSensor: fixed startup race in SITL

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
4a334d0ed7
  1. 3
      libraries/AP_InertialSensor/AP_InertialSensor.cpp

3
libraries/AP_InertialSensor/AP_InertialSensor.cpp

@ -1613,6 +1613,9 @@ AuxiliaryBus *AP_InertialSensor::get_auxiliary_bus(int16_t backend_id, uint8_t i @@ -1613,6 +1613,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()) {

Loading…
Cancel
Save