AP_Compass: add and use AP_COMPASS_AK8963_ENABLED

This commit is contained in:
Peter Barker 2023-02-01 23:53:43 +11:00 committed by Andrew Tridgell
parent 7a7f84adee
commit 22feb3c08a
5 changed files with 31 additions and 1 deletions

View File

@ -1368,9 +1368,11 @@ void Compass::_detect_backends(void)
#if AP_COMPASS_LSM303D_ENABLED #if AP_COMPASS_LSM303D_ENABLED
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270)); ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270));
#endif #endif
#if AP_COMPASS_AK8963_ENABLED
// we run the AK8963 only on the 2nd MPU9250, which leaves the // we run the AK8963 only on the 2nd MPU9250, which leaves the
// first MPU9250 to run without disturbance at high rate // first MPU9250 to run without disturbance at high rate
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270)); ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270));
#endif
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90)); ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90));
break; break;
@ -1387,25 +1389,35 @@ void Compass::_detect_backends(void)
break; break;
case AP_BoardConfig::PX4_BOARD_SP01: case AP_BoardConfig::PX4_BOARD_SP01:
#if AP_COMPASS_AK8963_ENABLED
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE)); ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE));
#endif
break; break;
case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO: case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
#if AP_COMPASS_AK8963_ENABLED
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90)); ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
#endif
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME), ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
false, ROTATION_NONE)); false, ROTATION_NONE));
break; break;
case AP_BoardConfig::PX4_BOARD_PHMINI: case AP_BoardConfig::PX4_BOARD_PHMINI:
#if AP_COMPASS_AK8963_ENABLED
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180)); ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180));
#endif
break; break;
case AP_BoardConfig::PX4_BOARD_AUAV21: case AP_BoardConfig::PX4_BOARD_AUAV21:
#if AP_COMPASS_AK8963_ENABLED
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90)); ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
#endif
break; break;
case AP_BoardConfig::PX4_BOARD_PH2SLIM: case AP_BoardConfig::PX4_BOARD_PH2SLIM:
#if AP_COMPASS_AK8963_ENABLED
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270)); ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270));
#endif
break; break;
case AP_BoardConfig::PX4_BOARD_MINDPXV2: case AP_BoardConfig::PX4_BOARD_MINDPXV2:

View File

@ -420,7 +420,9 @@ private:
#if AP_COMPASS_LSM303D_ENABLED #if AP_COMPASS_LSM303D_ENABLED
DRIVER_LSM303D =1, DRIVER_LSM303D =1,
#endif #endif
#if AP_COMPASS_AK8963_ENABLED
DRIVER_AK8963 =2, DRIVER_AK8963 =2,
#endif
DRIVER_BMM150 =3, DRIVER_BMM150 =3,
DRIVER_LSM9DS1 =4, DRIVER_LSM9DS1 =4,
DRIVER_LIS3MDL =5, DRIVER_LIS3MDL =5,

View File

@ -12,13 +12,17 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_Compass_AK8963.h"
#if AP_COMPASS_AK8963_ENABLED
#include <assert.h> #include <assert.h>
#include <utility> #include <utility>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_Compass_AK8963.h"
#include <AP_InertialSensor/AP_InertialSensor_Invensense.h> #include <AP_InertialSensor/AP_InertialSensor_Invensense.h>
#define AK8963_I2C_ADDR 0x0c #define AK8963_I2C_ADDR 0x0c
@ -400,3 +404,5 @@ uint32_t AP_AK8963_BusDriver_Auxiliary::get_bus_id(void) const
{ {
return _bus->get_bus_id(); return _bus->get_bus_id();
} }
#endif // AP_COMPASS_AK8963_ENABLED

View File

@ -1,5 +1,9 @@
#pragma once #pragma once
#include "AP_Compass_config.h"
#if AP_COMPASS_AK8963_ENABLED
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
@ -136,3 +140,5 @@ private:
AuxiliaryBusSlave *_slave; AuxiliaryBusSlave *_slave;
bool _started; bool _started;
}; };
#endif // AP_COMPASS_AK8963_ENABLED

View File

@ -34,6 +34,10 @@
#define AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED AP_COMPASS_BACKEND_DEFAULT_ENABLED #define AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED AP_COMPASS_BACKEND_DEFAULT_ENABLED
#endif #endif
#ifndef AP_COMPASS_AK8963_ENABLED
#define AP_COMPASS_AK8963_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_COMPASS_HMC5843_ENABLED #ifndef AP_COMPASS_HMC5843_ENABLED
#define AP_COMPASS_HMC5843_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED #define AP_COMPASS_HMC5843_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#endif #endif