mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: tidy includes into AP_Baro_config.h
This commit is contained in:
parent
33207bb915
commit
750772c349
|
@ -1,23 +1,13 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_Baro_config.h"
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <Filter/DerivativeFilter.h>
|
#include <Filter/DerivativeFilter.h>
|
||||||
#include <AP_MSP/msp.h>
|
#include <AP_MSP/msp.h>
|
||||||
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
|
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
|
||||||
|
|
||||||
#ifndef AP_SIM_BARO_ENABLED
|
|
||||||
#define AP_SIM_BARO_ENABLED AP_SIM_ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef AP_BARO_EXTERNALAHRS_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
|
|
||||||
|
|
||||||
// maximum number of sensor instances
|
// maximum number of sensor instances
|
||||||
#ifndef BARO_MAX_INSTANCES
|
#ifndef BARO_MAX_INSTANCES
|
||||||
#define BARO_MAX_INSTANCES 3
|
#define BARO_MAX_INSTANCES 3
|
||||||
|
@ -31,10 +21,6 @@
|
||||||
#define BARO_TIMEOUT_MS 500 // timeout in ms since last successful read
|
#define BARO_TIMEOUT_MS 500 // timeout in ms since last successful read
|
||||||
#define BARO_DATA_CHANGE_TIMEOUT_MS 2000 // timeout in ms since last successful read that involved temperature of pressure changing
|
#define BARO_DATA_CHANGE_TIMEOUT_MS 2000 // timeout in ms since last successful read that involved temperature of pressure changing
|
||||||
|
|
||||||
#ifndef HAL_BARO_WIND_COMP_ENABLED
|
|
||||||
#define HAL_BARO_WIND_COMP_ENABLED !HAL_MINIMIZE_FEATURES
|
|
||||||
#endif
|
|
||||||
|
|
||||||
class AP_Baro_Backend;
|
class AP_Baro_Backend;
|
||||||
|
|
||||||
class AP_Baro
|
class AP_Baro
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#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
|
#if AP_BARO_BMP085_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#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
|
#if AP_BARO_BMP280_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#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
|
#if AP_BARO_BMP388_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#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:
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#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
|
#if AP_BARO_DPS280_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -6,10 +6,6 @@
|
||||||
|
|
||||||
#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
|
#if AP_BARO_DUMMY_ENABLED
|
||||||
|
|
||||||
class AP_Baro_Dummy : public AP_Baro_Backend
|
class AP_Baro_Dummy : public AP_Baro_Backend
|
||||||
|
|
|
@ -5,8 +5,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#include "AP_Baro_Backend.h"
|
||||||
|
|
||||||
// AP_BARO_EXTERNALAHRS_ENABLED is defined in AP_Baro.h
|
|
||||||
|
|
||||||
#if AP_BARO_EXTERNALAHRS_ENABLED
|
#if AP_BARO_EXTERNALAHRS_ENABLED
|
||||||
|
|
||||||
class AP_Baro_ExternalAHRS : public AP_Baro_Backend
|
class AP_Baro_ExternalAHRS : public AP_Baro_Backend
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#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
|
#if AP_BARO_FBM320_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#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
|
#if AP_BARO_ICM20789_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#include "AP_Baro_Backend.h"
|
||||||
|
|
||||||
#ifndef AP_BARO_ICP101XX_ENABLED
|
|
||||||
#define AP_BARO_ICP101XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if AP_BARO_ICP101XX_ENABLED
|
#if AP_BARO_ICP101XX_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
@ -64,4 +60,4 @@ private:
|
||||||
uint32_t measure_interval = 0;
|
uint32_t measure_interval = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_BARO_ICP101XX_ENABLED
|
#endif // AP_BARO_ICP101XX_ENABLED
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#include "AP_Baro_Backend.h"
|
||||||
|
|
||||||
#ifndef AP_BARO_ICP201XX_ENABLED
|
|
||||||
#define AP_BARO_ICP201XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if AP_BARO_ICP201XX_ENABLED
|
#if AP_BARO_ICP201XX_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
@ -82,4 +78,4 @@ private:
|
||||||
} _forced_meas_trigger{FORCED_MEAS_TRIGGER::FORCE_MEAS_STANDBY};
|
} _forced_meas_trigger{FORCED_MEAS_TRIGGER::FORCE_MEAS_STANDBY};
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_BARO_ICP201XX_ENABLED
|
#endif // AP_BARO_ICP201XX_ENABLED
|
||||||
|
|
|
@ -27,10 +27,6 @@
|
||||||
|
|
||||||
#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
|
#if AP_BARO_KELLERLD_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#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
|
#if AP_BARO_LPS2XH_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#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
|
#if AP_BARO_MS56XX_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#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
|
#if AP_BARO_SPL06_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
|
@ -2,10 +2,6 @@
|
||||||
|
|
||||||
#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
|
#if AP_BARO_UAVCAN_ENABLED
|
||||||
|
|
||||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||||
|
|
|
@ -0,0 +1,82 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
#include <AP_MSP/msp.h>
|
||||||
|
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
|
||||||
|
|
||||||
|
#ifndef HAL_BARO_WIND_COMP_ENABLED
|
||||||
|
#define HAL_BARO_WIND_COMP_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// backend support:
|
||||||
|
#ifndef AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#define AP_BARO_BACKEND_DEFAULT_ENABLED 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_BMP085_ENABLED
|
||||||
|
#define AP_BARO_BMP085_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_BMP280_ENABLED
|
||||||
|
#define AP_BARO_BMP280_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_BMP388_ENABLED
|
||||||
|
#define AP_BARO_BMP388_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_DPS280_ENABLED
|
||||||
|
#define AP_BARO_DPS280_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_DUMMY_ENABLED
|
||||||
|
#define AP_BARO_DUMMY_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_EXTERNALAHRS_ENABLED
|
||||||
|
#define AP_BARO_EXTERNALAHRS_ENABLED HAL_EXTERNAL_AHRS_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_FBM320_ENABLED
|
||||||
|
#define AP_BARO_FBM320_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_ICM20789_ENABLED
|
||||||
|
#define AP_BARO_ICM20789_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_ICP101XX_ENABLED
|
||||||
|
#define AP_BARO_ICP101XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_ICP201XX_ENABLED
|
||||||
|
#define AP_BARO_ICP201XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_KELLERLD_ENABLED
|
||||||
|
#define AP_BARO_KELLERLD_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_LPS2XH_ENABLED
|
||||||
|
#define AP_BARO_LPS2XH_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_MS56XX_ENABLED
|
||||||
|
#define AP_BARO_MS56XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_MSP_ENABLED
|
||||||
|
#define AP_BARO_MSP_ENABLED HAL_MSP_SENSORS_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_SIM_BARO_ENABLED
|
||||||
|
#define AP_SIM_BARO_ENABLED AP_SIM_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_SPL06_ENABLED
|
||||||
|
#define AP_BARO_SPL06_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_BARO_UAVCAN_ENABLED
|
||||||
|
#define AP_BARO_UAVCAN_ENABLED (AP_BARO_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS)
|
||||||
|
#endif
|
Loading…
Reference in New Issue