mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 17:34:01 -04:00
AP_Compass: run lsm303d at 91Hz, not 100Hz
Peter and I have discovered an odd behaviour with the lsm303d mag. If you fetch data a bit too soon then it will give a peridic oscillation in the output. Checking the data ready bit in the status register doesn't help. The only fix I've found is to run the sampling at a bit lower rate
This commit is contained in:
parent
0faab853cb
commit
3d9126ec4a
@ -273,8 +273,9 @@ bool AP_Compass_LSM303D::init(enum Rotation rotation)
|
||||
_dev->set_device_type(DEVTYPE_LSM303D);
|
||||
set_dev_id(_compass_instance, _dev->get_bus_id());
|
||||
|
||||
// read at 100Hz
|
||||
_dev->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_LSM303D::_update, void));
|
||||
// read at 91Hz. We don't run at 100Hz as fetching data too fast can cause some very
|
||||
// odd periodic changes in the output data
|
||||
_dev->register_periodic_callback(11000, FUNCTOR_BIND_MEMBER(&AP_Compass_LSM303D::_update, void));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user