mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_InertialSensor: disable fast sampling on 2nd IMU on Pixracer
it also hosts a mag, and gets lots of FIFO resets if we try to run it at 8kHz
This commit is contained in:
parent
9f5e01d20a
commit
febe414766
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user