mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-25 17:23:56 -04:00
AP_Compass_PX4: removed MAGIOCSSAMPLERATE call
This commit is contained in:
parent
d000cd2320
commit
229841052a
@ -48,14 +48,8 @@ bool AP_Compass_PX4::init(void)
|
||||
return false;
|
||||
}
|
||||
|
||||
/* set the mag internal poll rate to at least 150Hz */
|
||||
if (0 != ioctl(_mag_fd, MAGIOCSSAMPLERATE, 150)) {
|
||||
hal.console->printf("Failed to setup compass sample rate\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
/* set the driver to poll at 150Hz */
|
||||
if (0 != ioctl(_mag_fd, SENSORIOCSPOLLRATE, 150)) {
|
||||
/* set the driver to poll at 100Hz */
|
||||
if (0 != ioctl(_mag_fd, SENSORIOCSPOLLRATE, 100)) {
|
||||
hal.console->printf("Failed to setup compass poll rate\n");
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user