mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
AP_Compass: fixed devid for 2nd compass
This commit is contained in:
parent
7b51c907f5
commit
8f6982860f
@ -80,11 +80,11 @@ bool AP_Compass_PX4::init(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
for (uint8_t i=0; i<_num_sensors; i++) {
|
for (uint8_t i=0; i<_num_sensors; i++) {
|
||||||
|
_instance[i] = register_compass();
|
||||||
|
|
||||||
// get device id
|
// get device id
|
||||||
set_dev_id(_instance[i], ioctl(_mag_fd[i], DEVIOCGDEVICEID, 0));
|
set_dev_id(_instance[i], ioctl(_mag_fd[i], DEVIOCGDEVICEID, 0));
|
||||||
|
|
||||||
_instance[i] = register_compass();
|
|
||||||
|
|
||||||
// average over up to 20 samples
|
// average over up to 20 samples
|
||||||
if (ioctl(_mag_fd[i], SENSORIOCSQUEUEDEPTH, 20) != 0) {
|
if (ioctl(_mag_fd[i], SENSORIOCSQUEUEDEPTH, 20) != 0) {
|
||||||
hal.console->printf("Failed to setup compass queue\n");
|
hal.console->printf("Failed to setup compass queue\n");
|
||||||
|
Loading…
Reference in New Issue
Block a user