mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_Compass: removed unusued compass probes
now only use probe lists
This commit is contained in:
parent
43e011c7a8
commit
bd0760f9d4
@ -872,85 +872,8 @@ void Compass::_detect_backends(void)
|
||||
break;
|
||||
}
|
||||
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)));
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BBBMINI
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO2
|
||||
ADD_BACKEND(DRIVER_LSM9DS1, AP_Compass_LSM9DS1::probe(hal.spi->get_device("lsm9ds1_m"), ROTATION_ROLL_180));
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_OCPOC_ZYNQ
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_AK8963,AP_Compass_AK8963::probe_mpu9250(0, ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_EDGE
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_NONE));
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_NONE));
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR), ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_NONE));
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
|
||||
#ifndef HAL_COMPASS_AK8963_MPU9250_ROTATION
|
||||
#define HAL_COMPASS_AK8963_MPU9250_ROTATION ROTATION_NONE
|
||||
#endif
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, HAL_COMPASS_AK8963_MPU9250_ROTATION));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
|
||||
#ifndef HAL_COMPASS_HMC5843_ROTATION
|
||||
# define HAL_COMPASS_HMC5843_ROTATION ROTATION_NONE
|
||||
#endif
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
false, HAL_COMPASS_HMC5843_ROTATION));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe_mpu6000(ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe(GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR), ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR), ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AERO
|
||||
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(GET_I2C_DEVICE(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR), ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
true, ROTATION_PITCH_180_YAW_90));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_LIS3MDL
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME), false, ROTATION_ROLL_180_YAW_90));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_MAG3110
|
||||
ADD_BACKEND(DRIVER_MAG3110, AP_Compass_MAG3110::probe(GET_I2C_DEVICE(HAL_MAG3110_I2C_BUS, HAL_MAG3110_I2C_ADDR), ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_IST8310
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
true, ROTATION_PITCH_180_YAW_90));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QMC5883L
|
||||
ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(1, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL));
|
||||
ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(0, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
false, HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_LIS3MDL_I2C
|
||||
FOREACH_I2C(i) {
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR), true, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2), true, ROTATION_NONE));
|
||||
}
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
|
||||
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_NONE));
|
||||
ADD_BACKEND(DRIVER_LSM9DS1, AP_Compass_LSM9DS1::probe(hal.spi->get_device("lsm9ds1_m"), ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BMM150_I2C
|
||||
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(GET_I2C_DEVICE(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR), ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_RM3100_SPI
|
||||
ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(hal.spi->get_device("rm3100"), ROTATION_NONE));
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NONE
|
||||
// no compass
|
||||
// no compass, or only external probe
|
||||
#else
|
||||
#error Unrecognised HAL_COMPASS_TYPE setting
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user