AP_Compass: create and use AP_COMPASS_IST8308_ENABLED

This commit is contained in:
Peter Barker 2023-01-05 09:47:39 +11:00 committed by Andrew Tridgell
parent 51bef52041
commit e60e646a4e
5 changed files with 39 additions and 16 deletions

View File

@ -1065,7 +1065,7 @@ void Compass::_probe_external_i2c_compasses(void)
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
bool all_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
#endif
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) || defined(HAL_USE_I2C_MAG_HMC5843)
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_HMC5843)
// external i2c bus
FOREACH_I2C_EXTERNAL(i) {
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
@ -1084,7 +1084,7 @@ void Compass::_probe_external_i2c_compasses(void)
#endif
#endif
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) || defined(HAL_USE_I2C_MAG_QMC5883L)
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_QMC5883L)
//external i2c bus
FOREACH_I2C_EXTERNAL(i) {
ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
@ -1127,7 +1127,7 @@ void Compass::_probe_external_i2c_compasses(void)
#endif
#endif // HAL_BUILD_AP_PERIPH
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) || defined(HAL_USE_I2C_MAG_LIS3MDL)
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_LIS3MDL)
// lis3mdl on bus 0 with default address
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
FOREACH_I2C_INTERNAL(i) {
@ -1154,7 +1154,7 @@ void Compass::_probe_external_i2c_compasses(void)
}
#endif
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) || defined(HAL_USE_I2C_MAG_AK09916)
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_AK09916)
// 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),
@ -1168,7 +1168,7 @@ void Compass::_probe_external_i2c_compasses(void)
#endif
#endif
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) || defined(HAL_USE_I2C_MAG_IST8310)
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_IST8310)
// IST8310 on external and internal bus
if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV5 &&
AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV6) {
@ -1197,7 +1197,7 @@ void Compass::_probe_external_i2c_compasses(void)
}
#endif
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) || defined(HAL_USE_I2C_MAG_IST8308)
#if AP_COMPASS_IST8308_ENABLED
// external i2c bus
FOREACH_I2C_EXTERNAL(i) {
ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),
@ -1209,9 +1209,9 @@ void Compass::_probe_external_i2c_compasses(void)
all_external, ROTATION_NONE));
}
#endif
#endif
#endif // AP_COMPASS_IST8308_ENABLED
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) || defined(HAL_USE_I2C_MAG_MMC3416)
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_MMC3416)
// external i2c bus
FOREACH_I2C_EXTERNAL(i) {
ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR),
@ -1225,7 +1225,7 @@ void Compass::_probe_external_i2c_compasses(void)
#endif
#endif
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) || defined(HAL_USE_I2C_MAG_RM3100)
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_RM3100)
#ifdef HAL_COMPASS_RM3100_I2C_ADDR
const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR };
#else
@ -1251,7 +1251,7 @@ void Compass::_probe_external_i2c_compasses(void)
#endif
#endif
#if !defined(HAL_DISABLE_I2C_MAGS_BY_DEFAULT) && !defined(STM32F1)
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED && !defined(STM32F1)
// BMM150 on I2C, not on F1 to save flash
FOREACH_I2C_EXTERNAL(i) {
for (uint8_t addr=BMM150_I2C_ADDR_MIN; addr <= BMM150_I2C_ADDR_MAX; addr++) {

View File

@ -29,6 +29,8 @@
#include <AP_MSP/msp.h>
#endif
#include <AP_Math/AP_Math.h>
class Compass; // forward declaration
class AP_Compass_Backend
{

View File

@ -16,6 +16,8 @@
*/
#include "AP_Compass_IST8308.h"
#if AP_COMPASS_IST8308_ENABLED
#include <stdio.h>
#include <utility>
@ -224,3 +226,5 @@ void AP_Compass_IST8308::read()
{
drain_accumulated_samples(_instance);
}
#endif // AP_COMPASS_IST8308_ENABLED

View File

@ -16,12 +16,14 @@
*/
#pragma once
#include "AP_Compass_config.h"
#if AP_COMPASS_IST8308_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_Math/AP_Math.h>
#include "AP_Compass.h"
#include "AP_Compass_Backend.h"
#ifndef HAL_COMPASS_IST8308_I2C_ADDR
@ -53,3 +55,5 @@ private:
uint8_t _instance;
bool _force_external;
};
#endif // AP_COMPASS_IST8308_ENABLED

View File

@ -9,18 +9,31 @@
#endif
// Backend support
#ifndef AP_COMPASS_BACKEND_DEFAULT_ENABLED
#define AP_COMPASS_BACKEND_DEFAULT_ENABLED 1
#endif
#ifndef AP_COMPASS_EXTERNALAHRS_ENABLED
#define AP_COMPASS_EXTERNALAHRS_ENABLED HAL_EXTERNAL_AHRS_ENABLED
#define AP_COMPASS_EXTERNALAHRS_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_EXTERNAL_AHRS_ENABLED)
#endif
#ifndef AP_COMPASS_MSP_ENABLED
#define AP_COMPASS_MSP_ENABLED HAL_MSP_SENSORS_ENABLED
#define AP_COMPASS_MSP_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_MSP_SENSORS_ENABLED)
#endif
#ifndef AP_COMPASS_SITL_ENABLED
#define AP_COMPASS_SITL_ENABLED AP_SIM_ENABLED
#define AP_COMPASS_SITL_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED)
#endif
#ifndef AP_COMPASS_UAVCAN_ENABLED
#define AP_COMPASS_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS
#define AP_COMPASS_UAVCAN_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS)
#endif
// i2c-based compasses:
#ifndef AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#define AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED AP_COMPASS_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_COMPASS_IST8308_ENABLED
#define AP_COMPASS_IST8308_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#endif