diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 1e838129c5..2fe140eed4 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -775,6 +775,12 @@ AP_InertialSensor::detect_backends(void) ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270)); break; + case AP_BoardConfig::PX4_BOARD_SP01: + _fast_sampling_mask.set_default(1); + ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_EXT_NAME), ROTATION_NONE)); + ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_NONE)); + break; + case AP_BoardConfig::PX4_BOARD_PIXRACER: // only do fast samplng on ICM-20608. The MPU9250 doesn't handle high rate well when it has a mag enabled _fast_sampling_mask.set_default(1);