1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

Add support for the ST LIS3MDL 3-Axis Magnetometer per #6437

This commit is contained in:
Blaine 2018-07-31 01:14:19 -07:00
parent a252b1cb7e
commit eb5af3a161
84 changed files with 295 additions and 15 deletions

View file

@ -0,0 +1,159 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <math.h>
#include "platform.h"
#if defined(USE_MAG_LIS3MDL)
#include "compass.h"
#include "drivers/time.h"
#include "common/axis.h"
#define LIS3MDL_MAG_I2C_ADDRESS 0x1E
#define LIS3MDL_DEVICE_ID 0x3D
#define LIS3MDL_REG_WHO_AM_I 0x0F
#define LIS3MDL_REG_CTRL_REG1 0x20
#define LIS3MDL_REG_CTRL_REG2 0x21
#define LIS3MDL_REG_CTRL_REG3 0x22
#define LIS3MDL_REG_CTRL_REG4 0x23
#define LIS3MDL_REG_CTRL_REG5 0x24
#define LIS3MDL_REG_STATUS_REG 0x27
#define LIS3MDL_REG_OUT_X_L 0x28
#define LIS3MDL_REG_OUT_X_H 0x29
#define LIS3MDL_REG_OUT_Y_L 0x2A
#define LIS3MDL_REG_OUT_Y_H 0x2B
#define LIS3MDL_REG_OUT_Z_L 0x2C
#define LIS3MDL_REG_OUT_Z_H 0x2D
#define LIS3MDL_TEMP_OUT_L 0x2E
#define LIS3MDL_TEMP_OUT_H 0x2F
#define LIS3MDL_INT_CFG 0x30
#define LIS3MDL_INT_SRC 0x31
#define LIS3MDL_THS_L 0x32
#define LIS3MDL_THS_H 0x33
// CTRL_REG1
#define LIS3MDL_TEMP_EN 0x80 // Default 0
#define LIS3MDL_OM_LOW_POWER 0x00 // Default
#define LIS3MDL_OM_MED_PROF 0x20
#define LIS3MDL_OM_HI_PROF 0x40
#define LIS3MDL_OM_ULTRA_HI_PROF 0x60
#define LIS3MDL_DO_0_625 0x00
#define LIS3MDL_DO_1_25 0x04
#define LIS3MDL_DO_2_5 0x08
#define LIS3MDL_DO_5 0x0C
#define LIS3MDL_DO_10 0x10 // Default
#define LIS3MDL_DO_20 0x14
#define LIS3MDL_DO_40 0x18
#define LIS3MDL_DO_80 0x1C
#define LIS3MDL_FAST_ODR 0x02
// CTRL_REG2
#define LIS3MDL_FS_4GAUSS 0x00 // Default
#define LIS3MDL_FS_8GAUSS 0x20
#define LIS3MDL_FS_12GAUSS 0x40
#define LIS3MDL_FS_16GAUSS 0x60
#define LIS3MDL_REBOOT 0x08
#define LIS3MDL_SOFT_RST 0x04
// CTRL_REG3
#define LIS3MDL_LP 0x20 // Default 0
#define LIS3MDL_SIM 0x04 // Default 0
#define LIS3MDL_MD_CONTINUOUS 0x00 // Default
#define LIS3MDL_MD_SINGLE 0x01
#define LIS3MDL_MD_POWERDOWN 0x03
// CTRL_REG4
#define LIS3MDL_ZOM_LP 0x00 // Default
#define LIS3MDL_ZOM_MP 0x04
#define LIS3MDL_ZOM_HP 0x08
#define LIS3MDL_ZOM_UHP 0x0C
#define LIS3MDL_BLE 0x02 // Default 0
// CTRL_REG5
#define LIS3MDL_FAST_READ 0x80 // Default 0
#define LIS3MDL_BDU 0x40 // Default 0
static bool lis3mdlRead(magDev_t * mag, int16_t *magData)
{
uint8_t buf[6];
busDevice_t *busdev = &mag->busdev;
bool ack = busReadRegisterBuffer(busdev, LIS3MDL_REG_OUT_X_L, buf, 6);
if (!ack) {
return false;
}
magData[X] = (int16_t)(buf[1] << 8 | buf[0]) / 4;
magData[Y] = (int16_t)(buf[3] << 8 | buf[2]) / 4;
magData[Z] = (int16_t)(buf[5] << 8 | buf[4]) / 4;
return true;
}
static bool lis3mdlInit(magDev_t *mag)
{
busDevice_t *busdev = &mag->busdev;
busWriteRegister(busdev, LIS3MDL_REG_CTRL_REG2, LIS3MDL_FS_4GAUSS);
busWriteRegister(busdev, LIS3MDL_REG_CTRL_REG1, LIS3MDL_TEMP_EN | LIS3MDL_OM_ULTRA_HI_PROF | LIS3MDL_DO_80);
busWriteRegister(busdev, LIS3MDL_REG_CTRL_REG5, LIS3MDL_BDU);
busWriteRegister(busdev, LIS3MDL_REG_CTRL_REG4, LIS3MDL_ZOM_UHP);
busWriteRegister(busdev, LIS3MDL_REG_CTRL_REG3, 0x00);
delay(100);
return true;
}
bool lis3mdlDetect(magDev_t * mag)
{
busDevice_t *busdev = &mag->busdev;
uint8_t sig = 0;
if (busdev->bustype == BUSTYPE_I2C && busdev->busdev_u.i2c.address == 0) {
busdev->busdev_u.i2c.address = LIS3MDL_MAG_I2C_ADDRESS;
}
bool ack = busReadRegisterBuffer(&mag->busdev, LIS3MDL_REG_WHO_AM_I, &sig, 1);
if (!ack || sig != LIS3MDL_DEVICE_ID) {
return false;
}
mag->init = lis3mdlInit;
mag->read = lis3mdlRead;
return true;
}
#endif

View file

@ -0,0 +1,25 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "drivers/io_types.h"
bool lis3mdlDetect(magDev_t* mag);

View file

@ -126,7 +126,7 @@ const char * const lookupTableBaroHardware[] = {
#if defined(USE_SENSOR_NAMES) || defined(USE_MAG)
// sync with magSensor_e
const char * const lookupTableMagHardware[] = {
"AUTO", "NONE", "HMC5883", "AK8975", "AK8963", "QMC5883"
"AUTO", "NONE", "HMC5883", "AK8975", "AK8963", "QMC5883", "LIS3MDL"
};
#endif
#if defined(USE_SENSOR_NAMES) || defined(USE_RANGEFINDER)

View file

@ -38,6 +38,7 @@
#include "drivers/compass/compass_fake.h"
#include "drivers/compass/compass_hmc5883l.h"
#include "drivers/compass/compass_qmc5883l.h"
#include "drivers/compass/compass_lis3mdl.h"
#include "drivers/io.h"
#include "drivers/light_led.h"
@ -183,6 +184,22 @@ bool compassDetect(magDev_t *dev)
#endif
FALLTHROUGH;
case MAG_LIS3MDL:
#if defined(USE_MAG_LIS3MDL)
if (busdev->bustype == BUSTYPE_I2C) {
busdev->busdev_u.i2c.address = compassConfig()->mag_i2c_address;
}
if (lis3mdlDetect(dev)) {
#ifdef MAG_LIS3MDL_ALIGN
dev->magAlign = MAG_LIS3MDL_ALIGN;
#endif
magHardware = MAG_LIS3MDL;
break;
}
#endif
FALLTHROUGH;
case MAG_QMC5883:
#ifdef USE_MAG_QMC5883
if (busdev->bustype == BUSTYPE_I2C) {

View file

@ -34,7 +34,8 @@ typedef enum {
MAG_HMC5883 = 2,
MAG_AK8975 = 3,
MAG_AK8963 = 4,
MAG_QMC5883 = 5
MAG_QMC5883 = 5,
MAG_LIS3MDL = 6
} magSensor_e;
typedef struct mag_s {

View file

@ -67,6 +67,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_LIS3MDL
#define USE_BARO
#define USE_BARO_SPI_BMP280

View file

@ -17,4 +17,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -67,6 +67,7 @@
#define USE_MAG
#define USE_MAG_AK8963
#define MAG_AK8963_ALIGN CW180_DEG_FLIP
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1 // Not connected - TX (PB6) RX PB7 (AF7)

View file

@ -6,4 +6,5 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6050.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/compass/compass_lis3mdl.c \
drivers/compass/compass_ak8963.c

View file

@ -59,6 +59,7 @@
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_AK8963
#define USE_MAG_LIS3MDL
#define MAG_AK8963_ALIGN CW180_DEG_FLIP

View file

@ -8,5 +8,6 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -59,6 +59,7 @@
#define USE_MAG_QMC5883
#define USE_MAG_AK8963
#define USE_MAG_SPI_AK8963
#define USE_MAG_LIS3MDL
#define HMC5883_CS_PIN PC15
#define HMC5883_SPI_INSTANCE SPI3

View file

@ -9,4 +9,5 @@ TARGET_SRC = \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -131,6 +131,7 @@
// MAG
#define USE_MAG
#define USE_MAG_AK8963
#define USE_MAG_LIS3MDL
#define MAG_AK8963_ALIGN CW0_DEG
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH

View file

@ -22,6 +22,7 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_lis3mdl.c \
drivers/flash_m25p16.c \
drivers/max7456.c \
io/osd.c

View file

@ -58,6 +58,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2

View file

@ -9,4 +9,5 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -67,6 +67,7 @@
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
//#define USE_MAG_AK8963
#define USE_MAG_LIS3MDL
#define HMC5883_I2C_INSTANCE I2CDEV_1
#define USE_BARO

View file

@ -6,5 +6,5 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -88,6 +88,7 @@
#define USE_MAG
#define USE_MAG_AK8975
#define USE_MAG_LIS3MDL
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define USE_VCP

View file

@ -3,6 +3,7 @@ FEATURES = VCP SDCARD
TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu3050.c \
drivers/accgyro/accgyro_mpu6050.c \

View file

@ -57,6 +57,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define MAG_INT_EXTI PC1

View file

@ -6,4 +6,5 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -74,6 +74,7 @@
#define USE_MAG_QMC5883
#define USE_MAG_AK8963
#define USE_MAG_AK8975
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1

View file

@ -13,5 +13,6 @@ TARGET_SRC = \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -100,6 +100,7 @@
#define USE_MAG
#define USE_MPU9250_MAG // Enables bypass configuration on the MPU9250 I2C bus
#define USE_MAG_AK8963
#define USE_MAG_LIS3MDL
#define MAG_AK8963_ALIGN CW270_DEG
#define USE_EXTI

View file

@ -5,3 +5,4 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_lis3mdl.c

View file

@ -76,6 +76,7 @@
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
//ON BOARD FLASH -----------------------------------
#define USE_SPI_DEVICE_2

View file

@ -9,4 +9,5 @@ TARGET_SRC = \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -70,6 +70,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1

View file

@ -8,6 +8,7 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -54,6 +54,7 @@
#define USE_MAG
#define USE_MAG_AK8963
#define USE_MAG_LIS3MDL
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
#define USE_VCP

View file

@ -6,4 +6,5 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/compass/compass_ak8963.c
drivers/compass/compass_ak8963.c \
drivers/compass/compass_lis3mdl.c

View file

@ -54,6 +54,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_BARO

View file

@ -5,4 +5,5 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -101,6 +101,7 @@
#define USE_MAG
#define USE_MAG_HMC5883 //External, connect to I2C1
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW180_DEG
#define USE_BARO

View file

@ -8,6 +8,7 @@ TARGET_SRC = \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c
ifeq ($(TARGET), FLYWOOF405)

View file

@ -149,6 +149,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_I2C_INSTANCE I2C_DEVICE
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO)

View file

@ -12,6 +12,7 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \
drivers/max7456.c

View file

@ -59,6 +59,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW180_DEG
#define MAG_I2C_INSTANCE I2CDEV_1

View file

@ -7,4 +7,5 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -66,6 +66,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
// *************** Baro **************************
#define USE_I2C

View file

@ -10,4 +10,5 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -82,6 +82,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
// *************** SD Card **************************
#define USE_SDCARD

View file

@ -10,4 +10,5 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -65,6 +65,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW180_DEG
#define USE_UART1

View file

@ -7,4 +7,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -53,6 +53,7 @@
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW270_DEG
#define USE_MAG_DATA_READY_SIGNAL

View file

@ -9,4 +9,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -56,6 +56,7 @@
#define USE_FAKE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_BARO

View file

@ -8,4 +8,5 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_fake.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -56,6 +56,7 @@
#define USE_FAKE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_BARO

View file

@ -9,5 +9,6 @@ TARGET_SRC = \
drivers/compass/compass_fake.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c

View file

@ -118,6 +118,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_BARO

View file

@ -9,5 +9,6 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -75,6 +75,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_BARO

View file

@ -9,4 +9,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -216,6 +216,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO)
//ADC---------------------------------------

View file

@ -14,6 +14,7 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \
drivers/max7456.c

View file

@ -78,6 +78,7 @@
#define USE_MAG
#define MAG_I2C_INSTANCE (I2CDEV_1)
#define USE_MAG_HMC5883
#define USE_MAG_LIS3MDL
#define USE_BARO
#define USE_BARO_SPI_LPS

View file

@ -23,4 +23,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -67,6 +67,7 @@
#define USE_MAG
#define USE_MAG_AK8975
#define USE_MAG_HMC5883 // External
#define USE_MAG_LIS3MDL
#define MAG_AK8975_ALIGN CW180_DEG

View file

@ -7,6 +7,7 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_lis3mdl.c \
drivers/display_ug2864hsweg01.c \
drivers/serial_usb_vcp.c \
drivers/flash_m25p16.c

View file

@ -142,6 +142,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_BARO

View file

@ -13,4 +13,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -71,6 +71,7 @@
#define USE_MAG
#define MAG_I2C_INSTANCE (I2CDEV_1)
#define USE_MAG_HMC5883
#define USE_MAG_LIS3MDL
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13

View file

@ -8,4 +8,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -58,6 +58,7 @@
#define USE_MAG
//#define USE_MAG_HMC5883
#define USE_MAG_AK8963
#define USE_MAG_LIS3MDL
//#define MAG_HMC5883_ALIGN CW180_DEG
#define MAG_AK8963_ALIGN CW270_DEG

View file

@ -6,4 +6,5 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_hmc5883l.c
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_lis3mdl.c

View file

@ -57,6 +57,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
// *************** Baro **************************
#define USE_I2C

View file

@ -8,4 +8,5 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c

View file

@ -154,6 +154,7 @@
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW270_DEG
#define USE_MAG_DATA_READY_SIGNAL

View file

@ -8,7 +8,8 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c
ifeq ($(TARGET), FLIP32F3OSD)
TARGET_SRC += \

View file

@ -80,6 +80,7 @@
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1

View file

@ -9,6 +9,7 @@ TARGET_SRC = \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c \
drivers/vtx_rtc6705.c

View file

@ -86,6 +86,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1

View file

@ -10,6 +10,7 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c \
drivers/vtx_rtc6705_soft_spi.c

View file

@ -178,6 +178,7 @@
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define USE_VCP
#define USE_UART1

View file

@ -20,5 +20,6 @@ TARGET_SRC = \
drivers/compass/compass_fake.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/flash_m25p16.c \
drivers/max7456.c

View file

@ -60,6 +60,7 @@
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_BARO

View file

@ -116,6 +116,7 @@
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_QMC5883
#define MAG_QMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_LIS3MDL
// *************** OSD *****************************
#define USE_MAX7456

View file

@ -6,4 +6,5 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/max7456.c