mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Compass: add and use AP_COMPASS_IST8310_ENABLED
This commit is contained in:
parent
4d79c6b9d6
commit
b26d771c9f
@ -1168,7 +1168,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_IST8310)
|
||||
#if AP_COMPASS_IST8310_ENABLED
|
||||
// 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) {
|
||||
@ -1195,7 +1195,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif // AP_COMPASS_IST8310_ENABLED
|
||||
|
||||
#if AP_COMPASS_IST8308_ENABLED
|
||||
// external i2c bus
|
||||
@ -1380,6 +1380,7 @@ void Compass::_detect_backends(void)
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_FMUV5:
|
||||
case AP_BoardConfig::PX4_BOARD_FMUV6:
|
||||
#if AP_COMPASS_IST8310_ENABLED
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
true, ROTATION_ROLL_180_YAW_90));
|
||||
@ -1388,6 +1389,7 @@ void Compass::_detect_backends(void)
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
false, ROTATION_ROLL_180_YAW_90));
|
||||
}
|
||||
#endif // AP_COMPASS_IST8310_ENABLED
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_SP01:
|
||||
|
@ -429,7 +429,9 @@ private:
|
||||
DRIVER_LSM9DS1 =4,
|
||||
DRIVER_LIS3MDL =5,
|
||||
DRIVER_AK09916 =6,
|
||||
#if AP_COMPASS_IST8310_ENABLED
|
||||
DRIVER_IST8310 =7,
|
||||
#endif
|
||||
DRIVER_ICM20948 =8,
|
||||
DRIVER_MMC3416 =9,
|
||||
DRIVER_UAVCAN =11,
|
||||
|
@ -18,6 +18,8 @@
|
||||
*/
|
||||
#include "AP_Compass_IST8310.h"
|
||||
|
||||
#if AP_COMPASS_IST8310_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
#include <utility>
|
||||
|
||||
@ -236,3 +238,5 @@ void AP_Compass_IST8310::read()
|
||||
{
|
||||
drain_accumulated_samples(_instance);
|
||||
}
|
||||
|
||||
#endif // AP_COMPASS_IST8310_ENABLED
|
||||
|
@ -16,12 +16,15 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_Compass_config.h"
|
||||
|
||||
#if AP_COMPASS_IST8310_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_IST8310_I2C_ADDR
|
||||
@ -56,3 +59,5 @@ private:
|
||||
bool _ignore_next_sample;
|
||||
bool _force_external;
|
||||
};
|
||||
|
||||
#endif // AP_COMPASS_IST8310_ENABLED
|
||||
|
@ -59,6 +59,10 @@
|
||||
#define AP_COMPASS_IST8308_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_IST8310_ENABLED
|
||||
#define AP_COMPASS_IST8310_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
|
||||
|
Loading…
Reference in New Issue
Block a user