AP_Compass: add and use AP_COMPASS_BMM150_ENABLED
This commit is contained in:
parent
0b127e0437
commit
feb809fbb7
@ -1251,15 +1251,15 @@ void Compass::_probe_external_i2c_compasses(void)
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED && !defined(STM32F1)
|
#if AP_COMPASS_BMM150_ENABLED
|
||||||
// BMM150 on I2C, not on F1 to save flash
|
// BMM150 on I2C
|
||||||
FOREACH_I2C_EXTERNAL(i) {
|
FOREACH_I2C_EXTERNAL(i) {
|
||||||
for (uint8_t addr=BMM150_I2C_ADDR_MIN; addr <= BMM150_I2C_ADDR_MAX; addr++) {
|
for (uint8_t addr=BMM150_I2C_ADDR_MIN; addr <= BMM150_I2C_ADDR_MAX; addr++) {
|
||||||
ADD_BACKEND(DRIVER_BMM150,
|
ADD_BACKEND(DRIVER_BMM150,
|
||||||
AP_Compass_BMM150::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE));
|
AP_Compass_BMM150::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // HAL_BUILD_AP_PERIPH
|
#endif // AP_COMPASS_BMM150_ENABLED
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -1320,8 +1320,10 @@ void Compass::_detect_backends(void)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case AP_BoardConfig::PX4_BOARD_PCNC1:
|
case AP_BoardConfig::PX4_BOARD_PCNC1:
|
||||||
|
#if AP_COMPASS_BMM150_ENABLED
|
||||||
ADD_BACKEND(DRIVER_BMM150,
|
ADD_BACKEND(DRIVER_BMM150,
|
||||||
AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), false, ROTATION_NONE));
|
AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), false, ROTATION_NONE));
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
case AP_BoardConfig::VRX_BOARD_BRAIN54:
|
case AP_BoardConfig::VRX_BOARD_BRAIN54:
|
||||||
case AP_BoardConfig::VRX_BOARD_BRAIN51: {
|
case AP_BoardConfig::VRX_BOARD_BRAIN51: {
|
||||||
|
@ -423,7 +423,9 @@ private:
|
|||||||
#if AP_COMPASS_AK8963_ENABLED
|
#if AP_COMPASS_AK8963_ENABLED
|
||||||
DRIVER_AK8963 =2,
|
DRIVER_AK8963 =2,
|
||||||
#endif
|
#endif
|
||||||
|
#if AP_COMPASS_BMM150_ENABLED
|
||||||
DRIVER_BMM150 =3,
|
DRIVER_BMM150 =3,
|
||||||
|
#endif
|
||||||
DRIVER_LSM9DS1 =4,
|
DRIVER_LSM9DS1 =4,
|
||||||
DRIVER_LIS3MDL =5,
|
DRIVER_LIS3MDL =5,
|
||||||
DRIVER_AK09916 =6,
|
DRIVER_AK09916 =6,
|
||||||
|
@ -16,6 +16,8 @@
|
|||||||
*/
|
*/
|
||||||
#include "AP_Compass_BMM150.h"
|
#include "AP_Compass_BMM150.h"
|
||||||
|
|
||||||
|
#if AP_COMPASS_BMM150_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#include <utility>
|
#include <utility>
|
||||||
@ -325,3 +327,5 @@ void AP_Compass_BMM150::read()
|
|||||||
drain_accumulated_samples(_compass_instance);
|
drain_accumulated_samples(_compass_instance);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif // AP_COMPASS_BMM150_ENABLED
|
||||||
|
@ -16,6 +16,10 @@
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_Compass_config.h"
|
||||||
|
|
||||||
|
#if AP_COMPASS_BMM150_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>
|
||||||
@ -70,3 +74,5 @@ private:
|
|||||||
enum Rotation _rotation;
|
enum Rotation _rotation;
|
||||||
bool _force_external;
|
bool _force_external;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_COMPASS_BMM150_ENABLED
|
||||||
|
@ -38,6 +38,10 @@
|
|||||||
#define AP_COMPASS_AK8963_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
#define AP_COMPASS_AK8963_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_COMPASS_BMM150_ENABLED
|
||||||
|
#define AP_COMPASS_BMM150_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED && !defined(STM32F1)
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef AP_COMPASS_HMC5843_ENABLED
|
#ifndef AP_COMPASS_HMC5843_ENABLED
|
||||||
#define AP_COMPASS_HMC5843_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
#define AP_COMPASS_HMC5843_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user