AP_Compass: add and use AP_COMPASS_LIS3MDL_ENABLED

This commit is contained in:
Peter Barker 2023-02-15 22:53:48 +11:00 committed by Peter Barker
parent 67ff7d5eb2
commit 7d244e3451
6 changed files with 24 additions and 3 deletions

View File

@ -112,6 +112,7 @@ BUILD_OPTIONS = [
Feature('Compass', 'BMM150', 'AP_COMPASS_BMM150_ENABLED', 'Enable BMM150 compasses', 1, None),
Feature('Compass', 'HMC5843', 'AP_COMPASS_HMC5843_ENABLED', 'Enable HMC5843 compasses', 1, None),
Feature('Compass', 'IST8308', 'AP_COMPASS_IST8308_ENABLED', 'Enable IST8308 compasses', 1, None),
Feature('Compass', 'LIS3MDL', 'AP_COMPASS_LIS3MDL_ENABLED', 'Enable LIS3MDL compasses', 1, None),
Feature('Compass', 'LSM303D', 'AP_COMPASS_LSM303D_ENABLED', 'Enable LSM303D compasses', 1, None),
Feature('Compass', 'LSM9DS1', 'AP_COMPASS_LSM9DS1_ENABLED', 'Enable LSM9DS1 compasses', 1, None),

View File

@ -1127,7 +1127,7 @@ void Compass::_probe_external_i2c_compasses(void)
#endif
#endif // HAL_BUILD_AP_PERIPH
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_LIS3MDL)
#if AP_COMPASS_LIS3MDL_ENABLED
// lis3mdl on bus 0 with default address
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
FOREACH_I2C_INTERNAL(i) {
@ -1152,7 +1152,7 @@ void Compass::_probe_external_i2c_compasses(void)
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
true, ROTATION_YAW_90));
}
#endif
#endif // AP_COMPASS_LIS3MDL_ENABLED
#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
@ -1277,7 +1277,9 @@ void Compass::_detect_backends(void)
#if AP_FEATURE_BOARD_DETECT
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {
// default to disabling LIS3MDL on pixhawk2 due to hardware issue
_driver_type_mask.set_default(1U<<DRIVER_LIS3MDL);
#if AP_COMPASS_LIS3MDL_ENABLED
_driver_type_mask.set_default(1U<<DRIVER_LIS3MDL);
#endif
}
#endif
@ -1402,8 +1404,10 @@ void Compass::_detect_backends(void)
#if AP_COMPASS_AK8963_ENABLED
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
#endif
#if AP_COMPASS_LIS3MDL_ENABLED
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
false, ROTATION_NONE));
#endif // AP_COMPASS_LIS3MDL_ENABLED
break;
case AP_BoardConfig::PX4_BOARD_PHMINI:

View File

@ -429,7 +429,9 @@ private:
#if AP_COMPASS_LSM9DS1_ENABLED
DRIVER_LSM9DS1 =4,
#endif
#if AP_COMPASS_LIS3MDL_ENABLED
DRIVER_LIS3MDL =5,
#endif
DRIVER_AK09916 =6,
#if AP_COMPASS_IST8310_ENABLED
DRIVER_IST8310 =7,

View File

@ -19,6 +19,8 @@
*/
#include "AP_Compass_LIS3MDL.h"
#if AP_COMPASS_LIS3MDL_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <utility>
#include <AP_Math/AP_Math.h>
@ -171,3 +173,5 @@ void AP_Compass_LIS3MDL::read()
{
drain_accumulated_samples(compass_instance);
}
#endif // AP_COMPASS_LIS3MDL_ENABLED

View File

@ -14,6 +14,10 @@
*/
#pragma once
#include "AP_Compass_config.h"
#if AP_COMPASS_LIS3MDL_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h>
@ -58,3 +62,5 @@ private:
bool force_external;
enum Rotation rotation;
};
#endif // AP_COMPASS_LIS3MDL_ENABLED

View File

@ -63,6 +63,10 @@
#define AP_COMPASS_IST8310_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_COMPASS_LIS3MDL_ENABLED
#define AP_COMPASS_LIS3MDL_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_COMPASS_LSM303D_ENABLED
#define AP_COMPASS_LSM303D_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#endif