diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 4d640292f7..a358f5970a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -739,7 +739,8 @@ AP_InertialSensor::detect_backends(void) break; case AP_BoardConfig::PX4_BOARD_PIXRACER: - _fast_sampling_mask.set_default(3); + // 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); _add_backend(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_NAME), ROTATION_ROLL_180_YAW_90)); _add_backend(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180_YAW_90)); break;