mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_InertialSensor: temporarily disable fast sampling
a problem has been found with the filtering with fast sampling on ICM-20608 and MPU9250. Disable until it is solved.
This commit is contained in:
parent
ae2dc5570e
commit
c0303ffe8a
@ -663,10 +663,14 @@ void AP_InertialSensor_MPU6000::_set_filter_register(void)
|
||||
config = 0;
|
||||
#endif
|
||||
|
||||
if (_is_icm_device && _dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
|
||||
#if 0
|
||||
// temporarily disable fast sampling
|
||||
_fast_sampling = (_is_icm_device && _dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI);
|
||||
#endif
|
||||
|
||||
if (_fast_sampling) {
|
||||
// this gives us 8kHz sampling on gyros and 4kHz on accels
|
||||
config |= BITS_DLPF_CFG_256HZ_NOLPF2;
|
||||
_fast_sampling = true;
|
||||
} else {
|
||||
// limit to 1kHz if not on SPI
|
||||
config |= BITS_DLPF_CFG_188HZ;
|
||||
|
@ -213,7 +213,8 @@ AP_InertialSensor_MPU9250::AP_InertialSensor_MPU9250(AP_InertialSensor &imu,
|
||||
, _temp_filter(1000, 1)
|
||||
, _rotation(rotation)
|
||||
, _dev(std::move(dev))
|
||||
, _fast_sampling(fast_sampling)
|
||||
// fast sampling disabled for now
|
||||
, _fast_sampling(false)
|
||||
{
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user