mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Compass: probe more addresses for IST8310
IST8310 can be on 4 possible i2c addresses
This commit is contained in:
parent
1edd1034f9
commit
1cb775e2c2
@ -708,15 +708,18 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
} else {
|
||||
default_rotation = ROTATION_PITCH_180;
|
||||
}
|
||||
// probe all 4 possible addresses
|
||||
const uint8_t ist8310_addr[] = { 0x0C, 0x0D, 0x0E, 0x0F };
|
||||
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
true, default_rotation));
|
||||
}
|
||||
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
all_external, default_rotation));
|
||||
for (uint8_t a=0; a<ARRAY_SIZE(ist8310_addr); a++) {
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
|
||||
true, default_rotation));
|
||||
}
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
|
||||
all_external, default_rotation));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user