AP_Compass: add and use AP_COMPASS_AK09916_ENABLED

This commit is contained in:
Peter Barker 2023-02-20 12:05:04 +11:00 committed by Andrew Tridgell
parent 1abce258e4
commit ad9521c1c4
5 changed files with 22 additions and 2 deletions

View File

@ -1107,6 +1107,7 @@ void Compass::_probe_external_i2c_compasses(void)
#ifndef HAL_BUILD_AP_PERIPH
// AK09916 on ICM20948
#if AP_COMPASS_AK09916_ENABLED
FOREACH_I2C_EXTERNAL(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),
@ -1126,6 +1127,7 @@ void Compass::_probe_external_i2c_compasses(void)
all_external, ROTATION_PITCH_180_YAW_90));
}
#endif
#endif // AP_COMPASS_AK09916_ENABLED
#endif // HAL_BUILD_AP_PERIPH
#if AP_COMPASS_LIS3MDL_ENABLED
@ -1155,7 +1157,7 @@ void Compass::_probe_external_i2c_compasses(void)
}
#endif // AP_COMPASS_LIS3MDL_ENABLED
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_AK09916)
#if AP_COMPASS_AK09916_ENABLED
// AK09916. This can be found twice, due to the ICM20948 i2c bus pass-thru, so we need to be careful to avoid that
FOREACH_I2C_EXTERNAL(i) {
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
@ -1167,7 +1169,7 @@ void Compass::_probe_external_i2c_compasses(void)
all_external, all_external?ROTATION_YAW_270:ROTATION_NONE));
}
#endif
#endif
#endif // AP_COMPASS_AK09916_ENABLED
#if AP_COMPASS_IST8310_ENABLED
// IST8310 on external and internal bus
@ -1378,7 +1380,9 @@ void Compass::_detect_backends(void)
// first MPU9250 to run without disturbance at high rate
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270));
#endif
#if AP_COMPASS_AK09916_ENABLED
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90));
#endif
break;
case AP_BoardConfig::PX4_BOARD_FMUV5:

View File

@ -432,7 +432,9 @@ private:
#if AP_COMPASS_LIS3MDL_ENABLED
DRIVER_LIS3MDL =5,
#endif
#if AP_COMPASS_AK09916_ENABLED
DRIVER_AK09916 =6,
#endif
#if AP_COMPASS_IST8310_ENABLED
DRIVER_IST8310 =7,
#endif

View File

@ -17,6 +17,8 @@
*/
#include "AP_Compass_AK09916.h"
#if AP_COMPASS_AK09916_ENABLED
#include <assert.h>
#include <AP_HAL/AP_HAL.h>
#include <utility>
@ -491,3 +493,5 @@ uint32_t AP_AK09916_BusDriver_Auxiliary::get_bus_id(void) const
{
return _bus->get_bus_id();
}
#endif // AP_COMPASS_AK09916_ENABLED

View File

@ -14,6 +14,10 @@
*/
#pragma once
#include "AP_Compass_config.h"
#if AP_COMPASS_AK09916_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
@ -191,3 +195,5 @@ private:
AuxiliaryBusSlave *_slave;
bool _started;
};
#endif // AP_COMPASS_AK09916_ENABLED

View File

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