AP_Compass: fixed devid for 2nd compass

This commit is contained in:
Andrew Tridgell 2015-03-13 20:46:32 +11:00
parent 7b51c907f5
commit 8f6982860f

View File

@ -80,11 +80,11 @@ bool AP_Compass_PX4::init(void)
}
for (uint8_t i=0; i<_num_sensors; i++) {
_instance[i] = register_compass();
// get device id
set_dev_id(_instance[i], ioctl(_mag_fd[i], DEVIOCGDEVICEID, 0));
_instance[i] = register_compass();
// average over up to 20 samples
if (ioctl(_mag_fd[i], SENSORIOCSQUEUEDEPTH, 20) != 0) {
hal.console->printf("Failed to setup compass queue\n");