AP_Baro: allow baro backends to be individually compiled out

This commit is contained in:
Peter Barker 2022-01-27 14:58:56 +11:00 committed by Andrew Tridgell
parent d5e282c5a1
commit b863f8a331
33 changed files with 247 additions and 59 deletions

View File

@ -29,6 +29,7 @@
#include <AP_BoardConfig/AP_BoardConfig.h> #include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_CANManager/AP_CANManager.h> #include <AP_CANManager/AP_CANManager.h>
#include <AP_Vehicle/AP_Vehicle_Type.h> #include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_HAL/I2CDevice.h>
#include "AP_Baro_SITL.h" #include "AP_Baro_SITL.h"
#include "AP_Baro_BMP085.h" #include "AP_Baro_BMP085.h"
@ -42,9 +43,7 @@
#include "AP_Baro_DPS280.h" #include "AP_Baro_DPS280.h"
#include "AP_Baro_BMP388.h" #include "AP_Baro_BMP388.h"
#include "AP_Baro_Dummy.h" #include "AP_Baro_Dummy.h"
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#include "AP_Baro_UAVCAN.h" #include "AP_Baro_UAVCAN.h"
#endif
#include "AP_Baro_MSP.h" #include "AP_Baro_MSP.h"
#include "AP_Baro_ExternalAHRS.h" #include "AP_Baro_ExternalAHRS.h"
@ -169,7 +168,7 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = {
// @Increment: 1 // @Increment: 1
AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT), AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT),
#if defined(HAL_PROBE_EXTERNAL_I2C_BAROS) || defined(HAL_MSP_BARO_ENABLED) #if defined(HAL_PROBE_EXTERNAL_I2C_BAROS) || defined(AP_BARO_MSP_ENABLED)
// @Param: _PROBE_EXT // @Param: _PROBE_EXT
// @DisplayName: External barometers to probe // @DisplayName: External barometers to probe
// @Description: This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on GND_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in GND_EXT_BUS. // @Description: This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on GND_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in GND_EXT_BUS.
@ -545,14 +544,14 @@ void AP_Baro::init(void)
} }
#endif #endif
#if HAL_ENABLE_LIBUAVCAN_DRIVERS && !AP_SIM_BARO_ENABLED #if AP_BARO_UAVCAN_ENABLED
// Detect UAVCAN Modules, try as many times as there are driver slots // Detect UAVCAN Modules, try as many times as there are driver slots
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
ADD_BACKEND(AP_Baro_UAVCAN::probe(*this)); ADD_BACKEND(AP_Baro_UAVCAN::probe(*this));
} }
#endif #endif
#if HAL_EXTERNAL_AHRS_ENABLED #if AP_BARO_EXTERNALAHRS_ENABLED
const int8_t serial_port = AP::externalAHRS().get_port(); const int8_t serial_port = AP::externalAHRS().get_port();
if (serial_port >= 0) { if (serial_port >= 0) {
ADD_BACKEND(new AP_Baro_ExternalAHRS(*this, serial_port)); ADD_BACKEND(new AP_Baro_ExternalAHRS(*this, serial_port));
@ -563,7 +562,7 @@ void AP_Baro::init(void)
#define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device(bus, address) #define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device(bus, address)
#if AP_SIM_BARO_ENABLED #if AP_SIM_BARO_ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR)))); std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR))));
#endif #endif
@ -577,7 +576,7 @@ void AP_Baro::init(void)
#elif AP_FEATURE_BOARD_DETECT #elif AP_FEATURE_BOARD_DETECT
switch (AP_BoardConfig::get_board_type()) { switch (AP_BoardConfig::get_board_type()) {
case AP_BoardConfig::PX4_BOARD_PX4V1: case AP_BoardConfig::PX4_BOARD_PX4V1:
#ifdef HAL_BARO_MS5611_I2C_BUS #if AP_BARO_MS56XX_ENABLED && defined(HAL_BARO_MS5611_I2C_BUS)
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(GET_I2C_DEVICE(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR)))); std::move(GET_I2C_DEVICE(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR))));
#endif #endif
@ -588,32 +587,41 @@ void AP_Baro::init(void)
case AP_BoardConfig::PX4_BOARD_AUAV21: case AP_BoardConfig::PX4_BOARD_AUAV21:
case AP_BoardConfig::PX4_BOARD_PH2SLIM: case AP_BoardConfig::PX4_BOARD_PH2SLIM:
case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO: case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
#if AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
#endif
break; break;
case AP_BoardConfig::PX4_BOARD_PIXHAWK2: case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
case AP_BoardConfig::PX4_BOARD_SP01: case AP_BoardConfig::PX4_BOARD_SP01:
#if AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME)))); std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
#endif
break; break;
case AP_BoardConfig::PX4_BOARD_MINDPXV2: case AP_BoardConfig::PX4_BOARD_MINDPXV2:
#if AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
#endif
break; break;
case AP_BoardConfig::PX4_BOARD_AEROFC: case AP_BoardConfig::PX4_BOARD_AEROFC:
#if AP_BARO_MS56XX_ENABLED
#ifdef HAL_BARO_MS5607_I2C_BUS #ifdef HAL_BARO_MS5607_I2C_BUS
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(GET_I2C_DEVICE(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)), std::move(GET_I2C_DEVICE(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)),
AP_Baro_MS56XX::BARO_MS5607)); AP_Baro_MS56XX::BARO_MS5607));
#endif #endif
#endif // AP_BARO_MS56XX_ENABLED
break; break;
case AP_BoardConfig::VRX_BOARD_BRAIN54: case AP_BoardConfig::VRX_BOARD_BRAIN54:
#if AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
@ -622,6 +630,7 @@ void AP_Baro::init(void)
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_IMU_NAME)))); std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_IMU_NAME))));
#endif #endif
#endif // AP_BARO_MS56XX_ENABLED
break; break;
case AP_BoardConfig::VRX_BOARD_BRAIN51: case AP_BoardConfig::VRX_BOARD_BRAIN51:
@ -630,20 +639,26 @@ void AP_Baro::init(void)
case AP_BoardConfig::VRX_BOARD_CORE10: case AP_BoardConfig::VRX_BOARD_CORE10:
case AP_BoardConfig::VRX_BOARD_UBRAIN51: case AP_BoardConfig::VRX_BOARD_UBRAIN51:
case AP_BoardConfig::VRX_BOARD_UBRAIN52: case AP_BoardConfig::VRX_BOARD_UBRAIN52:
#if AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
#endif // AP_BARO_MS56XX_ENABLED
break; break;
case AP_BoardConfig::PX4_BOARD_PCNC1: case AP_BoardConfig::PX4_BOARD_PCNC1:
#if AP_BARO_ICM20789_ENABLED
ADD_BACKEND(AP_Baro_ICM20789::probe(*this, ADD_BACKEND(AP_Baro_ICM20789::probe(*this,
std::move(GET_I2C_DEVICE(1, 0x63)), std::move(GET_I2C_DEVICE(1, 0x63)),
std::move(hal.spi->get_device(HAL_INS_MPU60x0_NAME)))); std::move(hal.spi->get_device(HAL_INS_MPU60x0_NAME))));
#endif
break; break;
case AP_BoardConfig::PX4_BOARD_FMUV5: case AP_BoardConfig::PX4_BOARD_FMUV5:
case AP_BoardConfig::PX4_BOARD_FMUV6: case AP_BoardConfig::PX4_BOARD_FMUV6:
#if AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
#endif
break; break;
default: default:
@ -666,14 +681,19 @@ void AP_Baro::init(void)
// can optionally have baro on I2C too // can optionally have baro on I2C too
if (_ext_bus >= 0) { if (_ext_bus >= 0) {
#if APM_BUILD_TYPE(APM_BUILD_ArduSub) #if APM_BUILD_TYPE(APM_BUILD_ArduSub)
#if AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5837_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5837)); std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5837_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5837));
#endif
#if AP_BARO_KELLERLD_ENABLED
ADD_BACKEND(AP_Baro_KellerLD::probe(*this, ADD_BACKEND(AP_Baro_KellerLD::probe(*this,
std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_KELLERLD_I2C_ADDR)))); std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_KELLERLD_I2C_ADDR))));
#endif
#else #else
#if AP_BARO_MS56XX_ENABLED
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR)))); std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR))));
#endif
#endif #endif
} }
@ -681,7 +701,7 @@ void AP_Baro::init(void)
_probe_i2c_barometers(); _probe_i2c_barometers();
#endif #endif
#if HAL_MSP_BARO_ENABLED #if AP_BARO_MSP_ENABLED
if ((_baro_probe_ext.get() & PROBE_MSP) && msp_instance_mask == 0) { if ((_baro_probe_ext.get() & PROBE_MSP) && msp_instance_mask == 0) {
// allow for late addition of MSP sensor // allow for late addition of MSP sensor
msp_instance_mask |= 1; msp_instance_mask |= 1;
@ -720,6 +740,7 @@ void AP_Baro::init(void)
void AP_Baro::_probe_i2c_barometers(void) void AP_Baro::_probe_i2c_barometers(void)
{ {
uint32_t probe = _baro_probe_ext.get(); uint32_t probe = _baro_probe_ext.get();
(void)probe; // may be unused if most baros compiled out
uint32_t mask = hal.i2c_mgr->get_bus_mask_external(); uint32_t mask = hal.i2c_mgr->get_bus_mask_external();
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) { if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {
// for the purpose of baro probing, treat CubeBlack internal i2c as external. It has // for the purpose of baro probing, treat CubeBlack internal i2c as external. It has
@ -731,12 +752,15 @@ void AP_Baro::_probe_i2c_barometers(void)
if (ext_bus >= 0) { if (ext_bus >= 0) {
mask = 1U << (uint8_t)ext_bus; mask = 1U << (uint8_t)ext_bus;
} }
#if AP_BARO_BMP085_ENABLED
if (probe & PROBE_BMP085) { if (probe & PROBE_BMP085) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_BMP085::probe(*this, ADD_BACKEND(AP_Baro_BMP085::probe(*this,
std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP085_I2C_ADDR)))); std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP085_I2C_ADDR))));
} }
} }
#endif
#if AP_BARO_BMP280_ENABLED
if (probe & PROBE_BMP280) { if (probe & PROBE_BMP280) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_BMP280::probe(*this, ADD_BACKEND(AP_Baro_BMP280::probe(*this,
@ -745,6 +769,8 @@ void AP_Baro::_probe_i2c_barometers(void)
std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP280_I2C_ADDR2)))); std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP280_I2C_ADDR2))));
} }
} }
#endif
#if AP_BARO_SPL06_ENABLED
if (probe & PROBE_SPL06) { if (probe & PROBE_SPL06) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_SPL06::probe(*this, ADD_BACKEND(AP_Baro_SPL06::probe(*this,
@ -753,6 +779,8 @@ void AP_Baro::_probe_i2c_barometers(void)
std::move(GET_I2C_DEVICE(i, HAL_BARO_SPL06_I2C_ADDR2)))); std::move(GET_I2C_DEVICE(i, HAL_BARO_SPL06_I2C_ADDR2))));
} }
} }
#endif
#if AP_BARO_BMP388_ENABLED
if (probe & PROBE_BMP388) { if (probe & PROBE_BMP388) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_BMP388::probe(*this, ADD_BACKEND(AP_Baro_BMP388::probe(*this,
@ -761,6 +789,8 @@ void AP_Baro::_probe_i2c_barometers(void)
std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP388_I2C_ADDR2)))); std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP388_I2C_ADDR2))));
} }
} }
#endif
#if AP_BARO_MS56XX_ENABLED
if (probe & PROBE_MS5611) { if (probe & PROBE_MS5611) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
@ -783,6 +813,8 @@ void AP_Baro::_probe_i2c_barometers(void)
AP_Baro_MS56XX::BARO_MS5637)); AP_Baro_MS56XX::BARO_MS5637));
} }
} }
#endif // AP_BARO_MS56XX_ENABLED
#if AP_BARO_FBM320_ENABLED
if (probe & PROBE_FBM320) { if (probe & PROBE_FBM320) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_FBM320::probe(*this, ADD_BACKEND(AP_Baro_FBM320::probe(*this,
@ -791,6 +823,8 @@ void AP_Baro::_probe_i2c_barometers(void)
std::move(GET_I2C_DEVICE(i, HAL_BARO_FBM320_I2C_ADDR2)))); std::move(GET_I2C_DEVICE(i, HAL_BARO_FBM320_I2C_ADDR2))));
} }
} }
#endif
#if AP_BARO_DPS280_ENABLED
if (probe & PROBE_DPS280) { if (probe & PROBE_DPS280) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_DPS280::probe(*this, ADD_BACKEND(AP_Baro_DPS280::probe(*this,
@ -799,19 +833,25 @@ void AP_Baro::_probe_i2c_barometers(void)
std::move(GET_I2C_DEVICE(i, HAL_BARO_DPS280_I2C_ADDR2)))); std::move(GET_I2C_DEVICE(i, HAL_BARO_DPS280_I2C_ADDR2))));
} }
} }
#endif
#if AP_BARO_LPS2XH_ENABLED
if (probe & PROBE_LPS25H) { if (probe & PROBE_LPS25H) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_LPS2XH::probe(*this, ADD_BACKEND(AP_Baro_LPS2XH::probe(*this,
std::move(GET_I2C_DEVICE(i, HAL_BARO_LPS25H_I2C_ADDR)))); std::move(GET_I2C_DEVICE(i, HAL_BARO_LPS25H_I2C_ADDR))));
} }
} }
#endif
#if APM_BUILD_TYPE(APM_BUILD_ArduSub) #if APM_BUILD_TYPE(APM_BUILD_ArduSub)
#if AP_BARO_KELLERLD_ENABLED
if (probe & PROBE_KELLER) { if (probe & PROBE_KELLER) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_KellerLD::probe(*this, ADD_BACKEND(AP_Baro_KellerLD::probe(*this,
std::move(GET_I2C_DEVICE(i, HAL_BARO_KELLERLD_I2C_ADDR)))); std::move(GET_I2C_DEVICE(i, HAL_BARO_KELLERLD_I2C_ADDR))));
} }
} }
#endif
#if AP_BARO_MS56XX_ENABLED
if (probe & PROBE_MS5837) { if (probe & PROBE_MS5837) {
FOREACH_I2C_MASK(i,mask) { FOREACH_I2C_MASK(i,mask) {
ADD_BACKEND(AP_Baro_MS56XX::probe(*this, ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
@ -819,6 +859,7 @@ void AP_Baro::_probe_i2c_barometers(void)
} }
} }
#endif #endif
#endif
} }
bool AP_Baro::should_log() const bool AP_Baro::should_log() const
@ -966,7 +1007,7 @@ void AP_Baro::set_pressure_correction(uint8_t instance, float p_correction)
} }
} }
#if HAL_MSP_BARO_ENABLED #if AP_BARO_MSP_ENABLED
/* /*
handle MSP barometer data handle MSP barometer data
*/ */
@ -985,7 +1026,7 @@ void AP_Baro::handle_msp(const MSP::msp_baro_data_message_t &pkt)
} }
#endif #endif
#if HAL_EXTERNAL_AHRS_ENABLED #if AP_BARO_EXTERNALAHRS_ENABLED
/* /*
handle ExternalAHRS barometer data handle ExternalAHRS barometer data
*/ */
@ -995,7 +1036,7 @@ void AP_Baro::handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt)
drivers[i]->handle_external(pkt); drivers[i]->handle_external(pkt);
} }
} }
#endif #endif // AP_BARO_EXTERNALAHRS_ENABLED
namespace AP { namespace AP {

View File

@ -10,8 +10,12 @@
#define AP_SIM_BARO_ENABLED AP_SIM_ENABLED #define AP_SIM_BARO_ENABLED AP_SIM_ENABLED
#endif #endif
#ifndef HAL_MSP_BARO_ENABLED #ifndef AP_BARO_EXTERNALAHRS_ENABLED
#define HAL_MSP_BARO_ENABLED HAL_MSP_SENSORS_ENABLED #define AP_BARO_EXTERNALAHRS_ENABLED HAL_EXTERNAL_AHRS_ENABLED
#endif
#ifndef AP_BARO_MSP_ENABLED
#define AP_BARO_MSP_ENABLED HAL_MSP_SENSORS_ENABLED
#endif #endif
// maximum number of sensor instances // maximum number of sensor instances
@ -190,11 +194,10 @@ public:
return _rsem; return _rsem;
} }
#if HAL_MSP_BARO_ENABLED #if AP_BARO_MSP_ENABLED
void handle_msp(const MSP::msp_baro_data_message_t &pkt); void handle_msp(const MSP::msp_baro_data_message_t &pkt);
#endif #endif
#if AP_BARO_EXTERNALAHRS_ENABLED
#if HAL_EXTERNAL_AHRS_ENABLED
void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt); void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt);
#endif #endif
@ -216,9 +219,7 @@ private:
bool init_done; bool init_done;
#if HAL_MSP_BARO_ENABLED
uint8_t msp_instance_mask; uint8_t msp_instance_mask;
#endif
// bitmask values for GND_PROBE_EXT // bitmask values for GND_PROBE_EXT
enum { enum {

View File

@ -14,6 +14,8 @@
*/ */
#include "AP_Baro_BMP085.h" #include "AP_Baro_BMP085.h"
#if AP_BARO_BMP085_ENABLED
#include <utility> #include <utility>
#include <stdio.h> #include <stdio.h>
@ -345,3 +347,5 @@ bool AP_Baro_BMP085::_data_ready()
return AP_HAL::millis() - _last_press_read_command_time > conversion_time_msec; return AP_HAL::millis() - _last_press_read_command_time > conversion_time_msec;
} }
#endif // AP_BARO_BMP085_ENABLED

View File

@ -1,12 +1,18 @@
#pragma once #pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_BMP085_ENABLED
#define AP_BARO_BMP085_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_BMP085_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
#include <AP_HAL/utility/OwnPtr.h> #include <AP_HAL/utility/OwnPtr.h>
#include <Filter/Filter.h> #include <Filter/Filter.h>
#include "AP_Baro_Backend.h"
#ifndef HAL_BARO_BMP085_I2C_ADDR #ifndef HAL_BARO_BMP085_I2C_ADDR
#define HAL_BARO_BMP085_I2C_ADDR (0x77) #define HAL_BARO_BMP085_I2C_ADDR (0x77)
#endif #endif
@ -62,3 +68,5 @@ private:
uint8_t _vers; uint8_t _vers;
uint8_t _type; uint8_t _type;
}; };
#endif // AP_BARO_BMP085_ENABLED

View File

@ -14,6 +14,8 @@
*/ */
#include "AP_Baro_BMP280.h" #include "AP_Baro_BMP280.h"
#if AP_BARO_BMP280_ENABLED
#include <utility> #include <utility>
extern const AP_HAL::HAL &hal; extern const AP_HAL::HAL &hal;
@ -203,3 +205,5 @@ void AP_Baro_BMP280::_update_pressure(int32_t press_raw)
_pressure_sum += press; _pressure_sum += press;
_pressure_count++; _pressure_count++;
} }
#endif // AP_BARO_BMP280_ENABLED

View File

@ -1,11 +1,17 @@
#pragma once #pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_BMP280_ENABLED
#define AP_BARO_BMP280_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_BMP280_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
#include <AP_HAL/utility/OwnPtr.h> #include <AP_HAL/utility/OwnPtr.h>
#include "AP_Baro_Backend.h"
#ifndef HAL_BARO_BMP280_I2C_ADDR #ifndef HAL_BARO_BMP280_I2C_ADDR
#define HAL_BARO_BMP280_I2C_ADDR (0x76) #define HAL_BARO_BMP280_I2C_ADDR (0x76)
#endif #endif
@ -42,3 +48,5 @@ private:
int16_t _t2, _t3, _p2, _p3, _p4, _p5, _p6, _p7, _p8, _p9; int16_t _t2, _t3, _p2, _p3, _p4, _p5, _p6, _p7, _p8, _p9;
uint16_t _t1, _p1; uint16_t _t1, _p1;
}; };
#endif // AP_BARO_BMP280_ENABLED

View File

@ -14,6 +14,8 @@
*/ */
#include "AP_Baro_BMP388.h" #include "AP_Baro_BMP388.h"
#if AP_BARO_BMP388_ENABLED
#include <utility> #include <utility>
extern const AP_HAL::HAL &hal; extern const AP_HAL::HAL &hal;
@ -238,3 +240,5 @@ bool AP_Baro_BMP388::read_registers(uint8_t reg, uint8_t *data, uint8_t len)
memcpy(data, &b[2], len); memcpy(data, &b[2], len);
return true; return true;
} }
#endif // AP_BARO_BMP388_ENABLED

View File

@ -1,11 +1,17 @@
#pragma once #pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_BMP388_ENABLED
#define AP_BARO_BMP388_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_BMP388_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
#include <AP_HAL/utility/OwnPtr.h> #include <AP_HAL/utility/OwnPtr.h>
#include "AP_Baro_Backend.h"
#ifndef HAL_BARO_BMP388_I2C_ADDR #ifndef HAL_BARO_BMP388_I2C_ADDR
#define HAL_BARO_BMP388_I2C_ADDR (0x76) #define HAL_BARO_BMP388_I2C_ADDR (0x76)
#endif #endif
@ -80,3 +86,5 @@ private:
void scale_calibration_data(void); void scale_calibration_data(void);
bool read_registers(uint8_t reg, uint8_t *data, uint8_t len); bool read_registers(uint8_t reg, uint8_t *data, uint8_t len);
}; };
#endif // AP_BARO_BMP388_ENABLED

View File

@ -1,4 +1,5 @@
#include "AP_Baro_Backend.h" #include "AP_Baro_Backend.h"
#include <stdio.h> #include <stdio.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;

View File

@ -2,6 +2,10 @@
#include "AP_Baro.h" #include "AP_Baro.h"
#ifndef AP_BARO_BACKEND_DEFAULT_ENABLED
#define AP_BARO_BACKEND_DEFAULT_ENABLED 1
#endif
class AP_Baro_Backend class AP_Baro_Backend
{ {
public: public:
@ -24,11 +28,11 @@ public:
bool pressure_ok(float press); bool pressure_ok(float press);
uint32_t get_error_count() const { return _error_count; } uint32_t get_error_count() const { return _error_count; }
#if HAL_MSP_BARO_ENABLED #if AP_BARO_MSP_ENABLED
virtual void handle_msp(const MSP::msp_baro_data_message_t &pkt) {} virtual void handle_msp(const MSP::msp_baro_data_message_t &pkt) {}
#endif #endif
#if HAL_EXTERNAL_AHRS_ENABLED #if AP_BARO_EXTERNALAHRS_ENABLED
virtual void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt) {} virtual void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt) {}
#endif #endif

View File

@ -18,6 +18,8 @@
#include "AP_Baro_DPS280.h" #include "AP_Baro_DPS280.h"
#if AP_BARO_DPS280_ENABLED
#include <utility> #include <utility>
#include <stdio.h> #include <stdio.h>
@ -305,3 +307,5 @@ void AP_Baro_DPS280::update(void)
temperature_sum = 0; temperature_sum = 0;
count=0; count=0;
} }
#endif // AP_BARO_DPS280_ENABLED

View File

@ -1,11 +1,17 @@
#pragma once #pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_DPS280_ENABLED
#define AP_BARO_DPS280_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_DPS280_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
#include <AP_HAL/utility/OwnPtr.h> #include <AP_HAL/utility/OwnPtr.h>
#include "AP_Baro_Backend.h"
#ifndef HAL_BARO_DPS280_I2C_ADDR #ifndef HAL_BARO_DPS280_I2C_ADDR
#define HAL_BARO_DPS280_I2C_ADDR 0x76 #define HAL_BARO_DPS280_I2C_ADDR 0x76
#endif #endif
@ -67,3 +73,4 @@ public:
}; };
#endif // AP_BARO_DPS280_ENABLED

View File

@ -1,5 +1,7 @@
#include "AP_Baro_Dummy.h" #include "AP_Baro_Dummy.h"
#if AP_BARO_DUMMY_ENABLED
AP_Baro_Dummy::AP_Baro_Dummy(AP_Baro &baro) : AP_Baro_Dummy::AP_Baro_Dummy(AP_Baro &baro) :
AP_Baro_Backend(baro) AP_Baro_Backend(baro)
{ {
@ -11,3 +13,5 @@ void AP_Baro_Dummy::update(void)
{ {
_copy_to_frontend(0, 91300, 21); _copy_to_frontend(0, 91300, 21);
} }
#endif // AP_BARO_DUMMY_ENABLED

View File

@ -6,6 +6,12 @@
#include "AP_Baro_Backend.h" #include "AP_Baro_Backend.h"
#ifndef AP_BARO_DUMMY_ENABLED
#define AP_BARO_DUMMY_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_DUMMY_ENABLED
class AP_Baro_Dummy : public AP_Baro_Backend class AP_Baro_Dummy : public AP_Baro_Backend
{ {
public: public:
@ -18,3 +24,5 @@ public:
private: private:
uint8_t _instance; uint8_t _instance;
}; };
#endif // AP_BARO_DUMMY_ENABLED

View File

@ -1,6 +1,6 @@
#include "AP_Baro_ExternalAHRS.h" #include "AP_Baro_ExternalAHRS.h"
#if HAL_EXTERNAL_AHRS_ENABLED #if AP_BARO_EXTERNALAHRS_ENABLED
AP_Baro_ExternalAHRS::AP_Baro_ExternalAHRS(AP_Baro &baro, uint8_t port) : AP_Baro_ExternalAHRS::AP_Baro_ExternalAHRS(AP_Baro &baro, uint8_t port) :
AP_Baro_Backend(baro) AP_Baro_Backend(baro)
@ -32,4 +32,4 @@ void AP_Baro_ExternalAHRS::handle_external(const AP_ExternalAHRS::baro_data_mess
count++; count++;
} }
#endif // HAL_EXTERNAL_AHRS_ENABLED #endif // AP_BARO_EXTERNALAHRS_ENABLED

View File

@ -5,7 +5,9 @@
#include "AP_Baro_Backend.h" #include "AP_Baro_Backend.h"
#if HAL_EXTERNAL_AHRS_ENABLED // AP_BARO_EXTERNALAHRS_ENABLED is defined in AP_Baro.h
#if AP_BARO_EXTERNALAHRS_ENABLED
class AP_Baro_ExternalAHRS : public AP_Baro_Backend class AP_Baro_ExternalAHRS : public AP_Baro_Backend
{ {
@ -21,5 +23,4 @@ private:
uint16_t count; uint16_t count;
}; };
#endif // HAL_EXTERNAL_AHRS_ENABLED #endif // AP_BARO_EXTERNALAHRS_ENABLED

View File

@ -18,6 +18,8 @@
#include "AP_Baro_FBM320.h" #include "AP_Baro_FBM320.h"
#if AP_BARO_FBM320_ENABLED
#include <utility> #include <utility>
#include <stdio.h> #include <stdio.h>
@ -221,3 +223,5 @@ void AP_Baro_FBM320::update(void)
temperature_sum = 0; temperature_sum = 0;
count=0; count=0;
} }
#endif // AP_BARO_FBM320_ENABLED

View File

@ -1,11 +1,17 @@
#pragma once #pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_FBM320_ENABLED
#define AP_BARO_FBM320_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_FBM320_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
#include <AP_HAL/utility/OwnPtr.h> #include <AP_HAL/utility/OwnPtr.h>
#include "AP_Baro_Backend.h"
#ifndef HAL_BARO_FBM320_I2C_ADDR #ifndef HAL_BARO_FBM320_I2C_ADDR
#define HAL_BARO_FBM320_I2C_ADDR 0x6C #define HAL_BARO_FBM320_I2C_ADDR 0x6C
#endif #endif
@ -46,3 +52,5 @@ private:
uint32_t C4, C5, C7; uint32_t C4, C5, C7;
} calibration; } calibration;
}; };
#endif // AP_BARO_FBM320_ENABLED

View File

@ -13,13 +13,16 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_Baro_ICM20789.h"
#if AP_BARO_ICM20789_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
#include <utility> #include <utility>
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_BoardConfig/AP_BoardConfig.h> #include <AP_BoardConfig/AP_BoardConfig.h>
#include "AP_Baro_ICM20789.h"
#include <stdio.h> #include <stdio.h>
@ -360,3 +363,4 @@ void AP_Baro_ICM20789::update()
} }
} }
#endif // AP_BARO_ICM20789_ENABLED

View File

@ -2,6 +2,12 @@
#include "AP_Baro_Backend.h" #include "AP_Baro_Backend.h"
#ifndef AP_BARO_ICM20789_ENABLED
#define AP_BARO_ICM20789_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_ICM20789_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Semaphores.h> #include <AP_HAL/Semaphores.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
@ -64,3 +70,5 @@ private:
const float quadr_factor = 1 / 16777216.0; const float quadr_factor = 1 / 16777216.0;
const float offst_factor = 2048.0; const float offst_factor = 2048.0;
}; };
#endif // AP_BARO_ICM20789_ENABLED

View File

@ -15,6 +15,8 @@
#include "AP_Baro_KellerLD.h" #include "AP_Baro_KellerLD.h"
#if AP_BARO_KELLERLD_ENABLED
#include <utility> #include <utility>
#include <stdio.h> #include <stdio.h>
@ -319,3 +321,5 @@ void AP_Baro_KellerLD::update()
_copy_to_frontend(_instance, pressure, temperature); _copy_to_frontend(_instance, pressure, temperature);
} }
#endif // AP_BARO_KELLERLD_ENABLED

View File

@ -27,6 +27,12 @@
#include "AP_Baro_Backend.h" #include "AP_Baro_Backend.h"
#ifndef AP_BARO_KELLERLD_ENABLED
#define AP_BARO_KELLERLD_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_KELLERLD_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Semaphores.h> #include <AP_HAL/Semaphores.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
@ -87,3 +93,6 @@ private:
bool read_cal(); bool read_cal();
bool read_mode_type(); bool read_mode_type();
}; };
#endif // AP_BARO_KELLERLD_ENABLED

View File

@ -12,11 +12,13 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_Baro_LPS2XH.h"
#if AP_BARO_LPS2XH_ENABLED
#include <utility> #include <utility>
#include <stdio.h> #include <stdio.h>
#include "AP_Baro_LPS2XH.h"
#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h> #include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>
extern const AP_HAL::HAL &hal; extern const AP_HAL::HAL &hal;
@ -274,3 +276,5 @@ void AP_Baro_LPS2XH::_update_pressure(void)
_pressure_sum += Pressure_mb; _pressure_sum += Pressure_mb;
_pressure_count++; _pressure_count++;
} }
#endif // AP_BARO_LPS2XH_ENABLED

View File

@ -1,11 +1,17 @@
#pragma once #pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_LPS2XH_ENABLED
#define AP_BARO_LPS2XH_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_LPS2XH_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
#include <AP_HAL/utility/OwnPtr.h> #include <AP_HAL/utility/OwnPtr.h>
#include "AP_Baro_Backend.h"
#define HAL_BARO_LPS25H_I2C_BUS 0 #define HAL_BARO_LPS25H_I2C_BUS 0
#ifndef HAL_BARO_LPS25H_I2C_ADDR #ifndef HAL_BARO_LPS25H_I2C_ADDR
@ -51,3 +57,5 @@ private:
enum LPS2XH_TYPE _lps2xh_type; enum LPS2XH_TYPE _lps2xh_type;
}; };
#endif // AP_BARO_LPS2XH_ENABLED

View File

@ -1,4 +1,5 @@
#include "AP_Baro.h" #include "AP_Baro.h"
#include <AP_Logger/AP_Logger.h> #include <AP_Logger/AP_Logger.h>
void AP_Baro::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance) void AP_Baro::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance)

View File

@ -14,6 +14,8 @@
*/ */
#include "AP_Baro_MS5611.h" #include "AP_Baro_MS5611.h"
#if AP_BARO_MS56XX_ENABLED
#include <utility> #include <utility>
#include <stdio.h> #include <stdio.h>
@ -490,3 +492,5 @@ void AP_Baro_MS56XX::_calculate_5837()
_copy_to_frontend(_instance, (float)pressure, temperature); _copy_to_frontend(_instance, (float)pressure, temperature);
} }
#endif // AP_BARO_MS56XX_ENABLED

View File

@ -2,6 +2,12 @@
#include "AP_Baro_Backend.h" #include "AP_Baro_Backend.h"
#ifndef AP_BARO_MS56XX_ENABLED
#define AP_BARO_MS56XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_MS56XX_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Semaphores.h> #include <AP_HAL/Semaphores.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
@ -90,3 +96,5 @@ private:
enum MS56XX_TYPE _ms56xx_type; enum MS56XX_TYPE _ms56xx_type;
}; };
#endif // AP_BARO_MS56XX_ENABLED

View File

@ -1,6 +1,6 @@
#include "AP_Baro_MSP.h" #include "AP_Baro_MSP.h"
#if HAL_MSP_BARO_ENABLED #if AP_BARO_MSP_ENABLED
AP_Baro_MSP::AP_Baro_MSP(AP_Baro &baro, uint8_t _msp_instance) : AP_Baro_MSP::AP_Baro_MSP(AP_Baro &baro, uint8_t _msp_instance) :
AP_Baro_Backend(baro) AP_Baro_Backend(baro)
@ -33,4 +33,4 @@ void AP_Baro_MSP::handle_msp(const MSP::msp_baro_data_message_t &pkt)
count++; count++;
} }
#endif // HAL_MSP_BARO_ENABLED #endif // AP_BARO_MSP_ENABLED

View File

@ -5,9 +5,11 @@
#include "AP_Baro_Backend.h" #include "AP_Baro_Backend.h"
#define MOVING_AVERAGE_WEIGHT 0.20f // a 5 samples moving average // AP_BARO_MSP_ENABLED is defined in AP_Baro.h
#if HAL_MSP_BARO_ENABLED #if AP_BARO_MSP_ENABLED
#define MOVING_AVERAGE_WEIGHT 0.20f // a 5 samples moving average
class AP_Baro_MSP : public AP_Baro_Backend class AP_Baro_MSP : public AP_Baro_Backend
{ {
@ -24,4 +26,4 @@ private:
uint16_t count; uint16_t count;
}; };
#endif // HAL_MSP_BARO_ENABLED #endif // AP_BARO_MSP_ENABLED

View File

@ -14,6 +14,8 @@
*/ */
#include "AP_Baro_SPL06.h" #include "AP_Baro_SPL06.h"
#if AP_BARO_SPL06_ENABLED
#include <utility> #include <utility>
extern const AP_HAL::HAL &hal; extern const AP_HAL::HAL &hal;
@ -246,3 +248,5 @@ void AP_Baro_SPL06::_update_pressure(int32_t press_raw)
_pressure_sum += press_comp; _pressure_sum += press_comp;
_pressure_count++; _pressure_count++;
} }
#endif // AP_BARO_SPL06_ENABLED

View File

@ -1,11 +1,17 @@
#pragma once #pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_SPL06_ENABLED
#define AP_BARO_SPL06_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_SPL06_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h> #include <AP_HAL/Device.h>
#include <AP_HAL/utility/OwnPtr.h> #include <AP_HAL/utility/OwnPtr.h>
#include "AP_Baro_Backend.h"
#ifndef HAL_BARO_SPL06_I2C_ADDR #ifndef HAL_BARO_SPL06_I2C_ADDR
#define HAL_BARO_SPL06_I2C_ADDR (0x76) #define HAL_BARO_SPL06_I2C_ADDR (0x76)
#endif #endif
@ -45,3 +51,5 @@ private:
int32_t _c00, _c10; int32_t _c00, _c10;
int16_t _c0, _c1, _c01, _c11, _c20, _c21, _c30; int16_t _c0, _c1, _c01, _c11, _c20, _c21, _c30;
}; };
#endif // AP_BARO_SPL06_ENABLED

View File

@ -1,9 +1,7 @@
#include <AP_HAL/AP_HAL.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#include "AP_Baro_UAVCAN.h" #include "AP_Baro_UAVCAN.h"
#if AP_BARO_UAVCAN_ENABLED
#include <AP_CANManager/AP_CANManager.h> #include <AP_CANManager/AP_CANManager.h>
#include <AP_UAVCAN/AP_UAVCAN.h> #include <AP_UAVCAN/AP_UAVCAN.h>
@ -192,5 +190,4 @@ void AP_Baro_UAVCAN::update(void)
} }
} }
#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS #endif // AP_BARO_UAVCAN_ENABLED

View File

@ -2,6 +2,12 @@
#include "AP_Baro_Backend.h" #include "AP_Baro_Backend.h"
#ifndef AP_BARO_UAVCAN_ENABLED
#define AP_BARO_UAVCAN_ENABLED (AP_BARO_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS)
#endif
#if AP_BARO_UAVCAN_ENABLED
#include <AP_UAVCAN/AP_UAVCAN.h> #include <AP_UAVCAN/AP_UAVCAN.h>
class PressureCb; class PressureCb;
@ -44,3 +50,5 @@ private:
static HAL_Semaphore _sem_registry; static HAL_Semaphore _sem_registry;
}; };
#endif // AP_BARO_UAVCAN_ENABLED