mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_Compass: clear DEV_ID for undetected compasses
this prevents user confusion with the number of compasses detected
This commit is contained in:
parent
9cd8745394
commit
e39d070b78
@ -487,6 +487,14 @@ Compass::init()
|
|||||||
hal.scheduler->delay(100);
|
hal.scheduler->delay(100);
|
||||||
read();
|
read();
|
||||||
}
|
}
|
||||||
|
// set the dev_id to 0 for undetected compasses, to make it easier
|
||||||
|
// for users to see how many compasses are detected. We don't do a
|
||||||
|
// set_and_save() as the user may have temporarily removed the
|
||||||
|
// compass, and we don't want to force a re-cal if they plug it
|
||||||
|
// back in again
|
||||||
|
for (uint8_t i=_compass_count; i<COMPASS_MAX_INSTANCES; i++) {
|
||||||
|
_state[i].dev_id.set(0);
|
||||||
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user