AP_Compass: rename variable for more buses
"all_external" reflects better the fact that we can have more than 2 buses (and now we are using the foreach macro).
This commit is contained in:
parent
de535dc573
commit
cd9b08dbae
@ -583,7 +583,7 @@ bool Compass::_have_i2c_driver(uint8_t bus, uint8_t address) const
|
||||
*/
|
||||
void Compass::_probe_external_i2c_compasses(void)
|
||||
{
|
||||
bool both_i2c_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
|
||||
bool all_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
|
||||
// external i2c bus
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
@ -595,7 +595,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
// internal i2c bus
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_YAW_270));
|
||||
all_external, all_external?ROTATION_ROLL_180:ROTATION_YAW_270));
|
||||
}
|
||||
}
|
||||
|
||||
@ -608,8 +608,8 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
//internal i2c bus
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
both_i2c_external,
|
||||
both_i2c_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL));
|
||||
all_external,
|
||||
all_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL));
|
||||
}
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
@ -623,19 +623,19 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
|
||||
both_i2c_external, ROTATION_PITCH_180_YAW_90));
|
||||
all_external, ROTATION_PITCH_180_YAW_90));
|
||||
}
|
||||
|
||||
// lis3mdl on bus 0 with default address
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
|
||||
both_i2c_external, both_i2c_external?ROTATION_YAW_90:ROTATION_NONE));
|
||||
all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
|
||||
}
|
||||
|
||||
// lis3mdl on bus 0 with alternate address
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
|
||||
both_i2c_external, both_i2c_external?ROTATION_YAW_90:ROTATION_NONE));
|
||||
all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
|
||||
}
|
||||
|
||||
// external lis3mdl on bus 1 with default address
|
||||
@ -657,7 +657,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
}
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
both_i2c_external, both_i2c_external?ROTATION_YAW_270:ROTATION_NONE));
|
||||
all_external, all_external?ROTATION_YAW_270:ROTATION_NONE));
|
||||
}
|
||||
|
||||
// IST8310 on external and internal bus
|
||||
@ -677,7 +677,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
both_i2c_external, default_rotation));
|
||||
all_external, default_rotation));
|
||||
}
|
||||
}
|
||||
#endif // HAL_MINIMIZE_FEATURES
|
||||
|
Loading…
Reference in New Issue
Block a user