forked from Archive/PX4-Autopilot
Delete unnecessary #includes in the differential_pressure drivers directory.
This commit is contained in:
parent
2a3b98a463
commit
2ef6e18640
|
@ -40,22 +40,8 @@
|
|||
|
||||
#include <float.h>
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#include <parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <px4_getopt.h>
|
||||
|
||||
#include <drivers/drv_airspeed.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/differential_pressure.h>
|
||||
#include <drivers/airspeed/airspeed.h>
|
||||
#include <px4_getopt.h>
|
||||
|
||||
/* I2C bus address */
|
||||
#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
|
||||
|
|
|
@ -49,22 +49,8 @@
|
|||
* - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf)
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_getopt.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#include <parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
|
||||
#include <mathlib/math/filter/LowPassFilter2p.hpp>
|
||||
|
||||
#include <drivers/drv_airspeed.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/differential_pressure.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <uORB/topics/system_power.h>
|
||||
|
||||
#include <drivers/airspeed/airspeed.h>
|
||||
|
|
|
@ -35,15 +35,9 @@
|
|||
#define DRIVERS_MS5525_AIRSPEED_HPP_
|
||||
|
||||
#include <drivers/airspeed/airspeed.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_airspeed.h>
|
||||
#include <math.h>
|
||||
#include <mathlib/math/filter/LowPassFilter2p.hpp>
|
||||
#include <px4_config.h>
|
||||
#include <sys/types.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <uORB/topics/differential_pressure.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <px4_getopt.h>
|
||||
|
||||
/* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */
|
||||
static constexpr uint8_t I2C_ADDRESS_1_MS5525DSO = 0x76;
|
||||
|
|
|
@ -33,10 +33,6 @@
|
|||
|
||||
#include "MS5525.hpp"
|
||||
|
||||
#include <px4_getopt.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
// Driver 'main' command.
|
||||
extern "C" __EXPORT int ms5525_airspeed_main(int argc, char *argv[]);
|
||||
|
||||
|
|
|
@ -31,8 +31,6 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "SDP3X.hpp"
|
||||
|
||||
/**
|
||||
* @file SDP3X.hpp
|
||||
*
|
||||
|
@ -40,6 +38,8 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include "SDP3X.hpp"
|
||||
|
||||
int
|
||||
SDP3X::probe()
|
||||
{
|
||||
|
|
|
@ -43,15 +43,9 @@
|
|||
#define DRIVERS_SDP3X_AIRSPEED_HPP_
|
||||
|
||||
#include <drivers/airspeed/airspeed.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_airspeed.h>
|
||||
#include <math.h>
|
||||
#include <mathlib/math/filter/LowPassFilter2p.hpp>
|
||||
#include <px4_config.h>
|
||||
#include <sys/types.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <uORB/topics/differential_pressure.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <px4_getopt.h>
|
||||
|
||||
#define I2C_ADDRESS_1_SDP3X 0x21
|
||||
#define I2C_ADDRESS_2_SDP3X 0x22
|
||||
|
|
|
@ -33,10 +33,6 @@
|
|||
|
||||
#include "SDP3X.hpp"
|
||||
|
||||
#include <px4_getopt.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
// Driver 'main' command.
|
||||
extern "C" __EXPORT int sdp3x_airspeed_main(int argc, char *argv[]);
|
||||
|
||||
|
|
Loading…
Reference in New Issue