From 532b82b3a3f03ee85b449393e976e2857d31d958 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 29 May 2019 20:57:28 +1000 Subject: [PATCH] AP_Compass: use DRIVER_HMC5843 to match driver name --- libraries/AP_Compass/AP_Compass.cpp | 42 ++++++++++++++--------------- libraries/AP_Compass/AP_Compass.h | 2 +- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 51d93bdd20..7d39ef75e1 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -613,7 +613,7 @@ void Compass::_probe_external_i2c_compasses(void) 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), + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_ROLL_180)); } @@ -621,7 +621,7 @@ void Compass::_probe_external_i2c_compasses(void) AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_AEROFC) { // internal i2c bus FOREACH_I2C_INTERNAL(i) { - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR), + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR), all_external, all_external?ROTATION_ROLL_180:ROTATION_YAW_270)); } } @@ -777,11 +777,11 @@ void Compass::_detect_backends(void) break; case AP_BoardConfig::VRX_BOARD_BRAIN54: { // external i2c bus - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR), + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_ROLL_180)); } // internal i2c bus - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR), + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR), false, ROTATION_YAW_270)); break; @@ -792,7 +792,7 @@ void Compass::_detect_backends(void) case AP_BoardConfig::VRX_BOARD_UBRAIN51: case AP_BoardConfig::VRX_BOARD_UBRAIN52: { // external i2c bus - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR), + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_ROLL_180)); } break; @@ -802,7 +802,7 @@ void Compass::_detect_backends(void) } switch (AP_BoardConfig::get_board_type()) { case AP_BoardConfig::PX4_BOARD_PIXHAWK: - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(hal.spi->get_device(HAL_COMPASS_HMC5843_NAME), + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(hal.spi->get_device(HAL_COMPASS_HMC5843_NAME), false, ROTATION_PITCH_180)); ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME))); break; @@ -859,7 +859,7 @@ void Compass::_detect_backends(void) break; case AP_BoardConfig::PX4_BOARD_MINDPXV2: - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR), + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR), false, ROTATION_YAW_90)); ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270)); break; @@ -869,35 +869,35 @@ void Compass::_detect_backends(void) } #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR))); + 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_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0)); ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1)); #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)); - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); + 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)); - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); + 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_OCPOC_ZYNQ - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR))); + 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_EDGE - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); #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)); - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); #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))); - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0)); - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); + 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_AK8963_MPU9250 #ifndef HAL_COMPASS_AK8963_MPU9250_ROTATION #define HAL_COMPASS_AK8963_MPU9250_ROTATION ROTATION_NONE @@ -907,17 +907,17 @@ void Compass::_detect_backends(void) #ifndef HAL_COMPASS_HMC5843_ROTATION # define HAL_COMPASS_HMC5843_ROTATION ROTATION_NONE #endif - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), + 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_HMC5883, AP_Compass_HMC5843::probe_mpu6000()); + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe_mpu6000()); #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))); #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))); #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))); - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true)); 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 @@ -933,7 +933,7 @@ void Compass::_detect_backends(void) ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(0, HAL_COMPASS_QMC5883L_I2C_ADDR), false, HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL)); #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR))); + 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)); ADD_BACKEND(DRIVER_LSM9DS1, AP_Compass_LSM9DS1::probe(hal.spi->get_device("lsm9ds1_m"))); #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BMM150_I2C @@ -949,7 +949,7 @@ void Compass::_detect_backends(void) /* for chibios external board coniguration */ #ifdef HAL_EXT_COMPASS_HMC5843_I2C_BUS - ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_EXT_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), + ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_EXT_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_ROLL_180)); #endif diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index 8026603e70..d5d0f9bb0b 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -358,7 +358,7 @@ private: // enum of drivers for COMPASS_TYPEMASK enum DriverType { - DRIVER_HMC5883 =0, + DRIVER_HMC5843 =0, DRIVER_LSM303D =1, DRIVER_AK8963 =2, DRIVER_BMM150 =3,