Skip to content

Commit

Permalink
AP_InertialSensor: fix continuing after ins init fail in AP_Periph
Browse files Browse the repository at this point in the history
  • Loading branch information
bugobliterator committed Oct 15, 2024
1 parent 3ba4e8e commit 9d5e2f4
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 2 deletions.
6 changes: 5 additions & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -854,9 +854,11 @@ void AP_InertialSensor::_start_backends()
_backends[i]->start();
}

#ifndef HAL_BUILD_AP_PERIPH
if (_gyro_count == 0 || _accel_count == 0) {
AP_HAL::panic("INS needs at least 1 gyro and 1 accel");
}
#endif

// clear IDs for unused sensor instances
for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
Expand Down Expand Up @@ -949,7 +951,7 @@ AP_InertialSensor::init(uint16_t loop_rate)
}

// calibrate gyros unless gyro calibration has been disabled
if (gyro_calibration_timing() != GYRO_CAL_NEVER) {
if (gyro_calibration_timing() != GYRO_CAL_NEVER && _gyro_count > 0) {
init_gyro();
}

Expand Down Expand Up @@ -1324,8 +1326,10 @@ AP_InertialSensor::detect_backends(void)
#else
DEV_PRINTF("INS: unable to initialise driver\n");
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "INS: unable to initialise driver");
#ifndef HAL_BUILD_AP_PERIPH
AP_BoardConfig::config_error("INS: unable to initialise driver");
#endif
#endif
}
}

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#endif

#ifndef AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
#define AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED AP_INERTIALSENSOR_ENABLED
#define AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED (AP_INERTIALSENSOR_ENABLED && !defined(HAL_BUILD_AP_PERIPH))
#endif

#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
Expand Down

0 comments on commit 9d5e2f4

Please sign in to comment.