5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-03 22:48:29 -04:00

AP_Compass: add and use AP_COMPASS_MMC3416

This commit is contained in:
Peter Barker 2023-02-20 12:05:08 +11:00 committed by Andrew Tridgell
parent 927055784d
commit b6e2586f50
5 changed files with 18 additions and 2 deletions

View File

@ -1214,7 +1214,7 @@ void Compass::_probe_external_i2c_compasses(void)
#endif #endif
#endif // AP_COMPASS_IST8308_ENABLED #endif // AP_COMPASS_IST8308_ENABLED
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_MMC3416) #if AP_COMPASS_MMC3416_ENABLED
// external i2c bus // external i2c bus
FOREACH_I2C_EXTERNAL(i) { FOREACH_I2C_EXTERNAL(i) {
ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR), ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR),
@ -1226,7 +1226,7 @@ void Compass::_probe_external_i2c_compasses(void)
all_external, ROTATION_NONE)); all_external, ROTATION_NONE));
} }
#endif #endif
#endif #endif // AP_COMPASS_MMC3416_ENABLED
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || 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 #ifdef HAL_COMPASS_RM3100_I2C_ADDR

View File

@ -441,7 +441,9 @@ private:
#if AP_COMPASS_ICM20948_ENABLED #if AP_COMPASS_ICM20948_ENABLED
DRIVER_ICM20948 =8, DRIVER_ICM20948 =8,
#endif #endif
#if AP_COMPASS_MMC3416_ENABLED
DRIVER_MMC3416 =9, DRIVER_MMC3416 =9,
#endif
#if AP_COMPASS_UAVCAN_ENABLED #if AP_COMPASS_UAVCAN_ENABLED
DRIVER_UAVCAN =11, DRIVER_UAVCAN =11,
#endif #endif

View File

@ -17,6 +17,8 @@
*/ */
#include "AP_Compass_MMC3416.h" #include "AP_Compass_MMC3416.h"
#if AP_COMPASS_MMC3416_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <utility> #include <utility>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
@ -301,3 +303,5 @@ void AP_Compass_MMC3416::read()
{ {
drain_accumulated_samples(compass_instance); drain_accumulated_samples(compass_instance);
} }
#endif // AP_COMPASS_MMC3416_ENABLED

View File

@ -14,6 +14,10 @@
*/ */
#pragma once #pragma once
#include "AP_Compass_config.h"
#if AP_COMPASS_MMC3416_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>
@ -72,3 +76,5 @@ private:
enum Rotation rotation; enum Rotation rotation;
}; };
#endif // AP_COMPASS_MMC3416_ENABLED

View File

@ -82,3 +82,7 @@
#ifndef AP_COMPASS_LSM9DS1_ENABLED #ifndef AP_COMPASS_LSM9DS1_ENABLED
#define AP_COMPASS_LSM9DS1_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED #define AP_COMPASS_LSM9DS1_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#endif #endif
#ifndef AP_COMPASS_MMC3416_ENABLED
#define AP_COMPASS_MMC3416_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
#endif