mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: Decrease LIS3MDL ODR and timer
This commit is contained in:
parent
16a96b0643
commit
17f2393c1b
|
@ -98,7 +98,7 @@ bool AP_Compass_LIS3MDL::init()
|
|||
|
||||
dev->setup_checked_registers(5);
|
||||
|
||||
dev->write_register(ADDR_CTRL_REG1, 0x62, true); // 155Hz, UHP
|
||||
dev->write_register(ADDR_CTRL_REG1, 0xFC, true); // 80Hz, UHP
|
||||
dev->write_register(ADDR_CTRL_REG2, 0, true); // 4Ga range
|
||||
dev->write_register(ADDR_CTRL_REG3, 0, true); // continuous
|
||||
dev->write_register(ADDR_CTRL_REG4, 0x0C, true); // z-axis ultra high perf
|
||||
|
@ -124,7 +124,7 @@ bool AP_Compass_LIS3MDL::init()
|
|||
set_dev_id(compass_instance, dev->get_bus_id());
|
||||
|
||||
// call timer() at 155Hz
|
||||
dev->register_periodic_callback(1000000U/155U,
|
||||
dev->register_periodic_callback(1000000U/80U,
|
||||
FUNCTOR_BIND_MEMBER(&AP_Compass_LIS3MDL::timer, void));
|
||||
|
||||
return true;
|
||||
|
|
Loading…
Reference in New Issue