mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: support probing RM3100 on all 4 addresses
This commit is contained in:
parent
8a01a8cddb
commit
a7a27d62a0
|
@ -1116,14 +1116,25 @@ void Compass::_probe_external_i2c_compasses(void)
|
|||
true, ROTATION_NONE));
|
||||
}
|
||||
|
||||
#ifdef HAL_COMPASS_RM3100_I2C_ADDR
|
||||
const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR };
|
||||
#else
|
||||
// RM3100 can be on 4 different addresses
|
||||
const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR1,
|
||||
HAL_COMPASS_RM3100_I2C_ADDR2,
|
||||
HAL_COMPASS_RM3100_I2C_ADDR3,
|
||||
HAL_COMPASS_RM3100_I2C_ADDR4 };
|
||||
#endif
|
||||
// external i2c bus
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, HAL_COMPASS_RM3100_I2C_ADDR),
|
||||
true, ROTATION_NONE));
|
||||
for (uint8_t j=0; j<ARRAY_SIZE(rm3100_addresses); j++) {
|
||||
ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, rm3100_addresses[j]), true, ROTATION_NONE));
|
||||
}
|
||||
}
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, HAL_COMPASS_RM3100_I2C_ADDR),
|
||||
all_external, ROTATION_NONE));
|
||||
for (uint8_t j=0; j<ARRAY_SIZE(rm3100_addresses); j++) {
|
||||
ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, rm3100_addresses[j]), all_external, ROTATION_NONE));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -23,7 +23,10 @@
|
|||
#include "AP_Compass_Backend.h"
|
||||
|
||||
#ifndef HAL_COMPASS_RM3100_I2C_ADDR
|
||||
# define HAL_COMPASS_RM3100_I2C_ADDR 0x20
|
||||
# define HAL_COMPASS_RM3100_I2C_ADDR1 0x20
|
||||
# define HAL_COMPASS_RM3100_I2C_ADDR2 0x21
|
||||
# define HAL_COMPASS_RM3100_I2C_ADDR3 0x22
|
||||
# define HAL_COMPASS_RM3100_I2C_ADDR4 0x23
|
||||
#endif
|
||||
|
||||
class AP_Compass_RM3100 : public AP_Compass_Backend
|
||||
|
|
Loading…
Reference in New Issue