mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: tidy AP_Airspeed includes, use AP_AIRSPEED_ENABLED properly
This commit is contained in:
parent
a8102d6662
commit
c88a53b662
|
@ -16,6 +16,10 @@
|
|||
* AP_Airspeed.cpp - airspeed (pitot) driver
|
||||
*/
|
||||
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
|
||||
#include "AP_Airspeed.h"
|
||||
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
@ -921,3 +925,5 @@ AP_Airspeed *airspeed()
|
|||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // AP_AIRSPEED_ENABLED
|
||||
|
|
|
@ -2,9 +2,15 @@
|
|||
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#if AP_AIRSPEED_MSP_ENABLED
|
||||
#include <AP_MSP/msp.h>
|
||||
#endif
|
||||
|
||||
class AP_Airspeed_Backend;
|
||||
|
||||
class AP_Airspeed_Params {
|
||||
|
@ -328,3 +334,5 @@ private:
|
|||
namespace AP {
|
||||
AP_Airspeed *airspeed();
|
||||
};
|
||||
|
||||
#endif // AP_AIRSPEED_ENABLED
|
||||
|
|
|
@ -14,11 +14,7 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_ASP5033_ENABLED
|
||||
#define AP_AIRSPEED_ASP5033_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ASP5033_ENABLED
|
||||
|
||||
|
|
|
@ -17,6 +17,10 @@
|
|||
backend driver class for airspeed
|
||||
*/
|
||||
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Airspeed.h"
|
||||
|
@ -63,3 +67,5 @@ void AP_Airspeed_Backend::set_bus_id(uint32_t id)
|
|||
{
|
||||
frontend.param[instance].bus_id.set_and_save(int32_t(id));
|
||||
}
|
||||
|
||||
#endif // AP_AIRSPEED_ENABLED
|
||||
|
|
|
@ -18,6 +18,10 @@
|
|||
backend driver class for airspeed
|
||||
*/
|
||||
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <AP_HAL/Semaphores.h>
|
||||
|
@ -126,3 +130,5 @@ private:
|
|||
AP_Airspeed &frontend;
|
||||
uint8_t instance;
|
||||
};
|
||||
|
||||
#endif // AP_AIRSPEED_ENABLED
|
||||
|
|
|
@ -17,11 +17,7 @@
|
|||
// backend driver for AllSensors DLVR differential airspeed sensor
|
||||
// currently assumes a 5" of water, noise reduced, sensor
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_DLVR_ENABLED
|
||||
#define AP_AIRSPEED_DLVR_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_DLVR_ENABLED
|
||||
|
||||
|
|
|
@ -1,10 +1,6 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_DRONECAN_ENABLED
|
||||
#define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_DRONECAN_ENABLED
|
||||
|
||||
|
|
|
@ -1,3 +1,7 @@
|
|||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
|
||||
#include "AP_Airspeed.h"
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
@ -120,3 +124,5 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
|
|||
}
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
}
|
||||
|
||||
#endif // AP_AIRSPEED_ENABLED
|
||||
|
|
|
@ -14,11 +14,7 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_MS4525_ENABLED
|
||||
#define AP_AIRSPEED_MS4525_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_MS4525_ENABLED
|
||||
|
||||
|
|
|
@ -18,11 +18,7 @@
|
|||
backend driver for airspeed from I2C
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_MS5525_ENABLED
|
||||
#define AP_AIRSPEED_MS5525_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_MS5525_ENABLED
|
||||
|
||||
|
|
|
@ -3,18 +3,14 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <AP_MSP/msp.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_MSP_ENABLED
|
||||
#define AP_AIRSPEED_MSP_ENABLED HAL_MSP_SENSORS_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_MSP_ENABLED
|
||||
|
||||
#include "AP_Airspeed_Backend.h"
|
||||
|
||||
#include <AP_MSP/msp.h>
|
||||
|
||||
class AP_Airspeed_MSP : public AP_Airspeed_Backend
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -1,11 +1,6 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
// note additional vehicle restrictions are made in the .cpp file!
|
||||
#ifndef AP_AIRSPEED_NMEA_ENABLED
|
||||
#define AP_AIRSPEED_NMEA_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_NMEA_ENABLED
|
||||
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
|
||||
#include "AP_Airspeed.h"
|
||||
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
@ -138,3 +142,5 @@ AP_Airspeed_Params::AP_Airspeed_Params(void) {};
|
|||
const AP_Param::GroupInfo AP_Airspeed_Params::var_info[] = { AP_GROUPEND };
|
||||
|
||||
#endif
|
||||
|
||||
#endif // AP_AIRSPEED_ENABLED
|
||||
|
|
|
@ -14,11 +14,7 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_SDP3X_ENABLED
|
||||
#define AP_AIRSPEED_SDP3X_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_SDP3X_ENABLED
|
||||
|
||||
|
|
|
@ -3,12 +3,7 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_SITL_ENABLED
|
||||
#define AP_AIRSPEED_SITL_ENABLED AP_SIM_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_SITL_ENABLED
|
||||
|
||||
|
|
|
@ -1,10 +1,6 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_ANALOG_ENABLED
|
||||
#define AP_AIRSPEED_ANALOG_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ANALOG_ENABLED
|
||||
|
||||
|
|
|
@ -2,16 +2,59 @@
|
|||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <AP_MSP/msp.h>
|
||||
#include <AP_MSP/AP_MSP_config.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_ENABLED
|
||||
#define AP_AIRSPEED_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_MSP_ENABLED
|
||||
#define AP_AIRSPEED_MSP_ENABLED (AP_AIRSPEED_ENABLED && HAL_MSP_SENSORS_ENABLED)
|
||||
#ifndef AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED AP_AIRSPEED_ENABLED
|
||||
#endif
|
||||
|
||||
// backends
|
||||
#ifndef AP_AIRSPEED_ANALOG_ENABLED
|
||||
#define AP_AIRSPEED_ANALOG_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_ASP5033_ENABLED
|
||||
#define AP_AIRSPEED_ASP5033_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_DLVR_ENABLED
|
||||
#define AP_AIRSPEED_DLVR_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_DRONECAN_ENABLED
|
||||
#define AP_AIRSPEED_DRONECAN_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_MS4525_ENABLED
|
||||
#define AP_AIRSPEED_MS4525_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_MS5525_ENABLED
|
||||
#define AP_AIRSPEED_MS5525_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_MSP_ENABLED
|
||||
#define AP_AIRSPEED_MSP_ENABLED (AP_AIRSPEED_BACKEND_DEFAULT_ENABLED && HAL_MSP_SENSORS_ENABLED)
|
||||
#endif
|
||||
|
||||
// note additional vehicle restrictions are made in the .cpp file!
|
||||
#ifndef AP_AIRSPEED_NMEA_ENABLED
|
||||
#define AP_AIRSPEED_NMEA_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_SDP3X_ENABLED
|
||||
#define AP_AIRSPEED_SDP3X_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_AIRSPEED_SITL_ENABLED
|
||||
#define AP_AIRSPEED_SITL_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED
|
||||
#endif
|
||||
|
||||
// other AP_Airspeed options:
|
||||
#ifndef AIRSPEED_MAX_SENSORS
|
||||
#define AIRSPEED_MAX_SENSORS 2
|
||||
#endif
|
||||
|
|
|
@ -5,6 +5,10 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include "AP_Airspeed_config.h"
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
@ -185,3 +189,5 @@ void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground)
|
|||
(const char *)&packet);
|
||||
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
}
|
||||
|
||||
#endif // AP_AIRSPEED_ENABLED
|
||||
|
|
Loading…
Reference in New Issue