mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-06 16:49:51 +08:00
Organize, alphabetize, and deprecate unneeded #includes from the barometer drivers.
This commit is contained in:
@@ -36,40 +36,8 @@
|
||||
* Driver for the BMP280 barometric pressure sensor connected via I2C TODO or SPI.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_log.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <board_config.h>
|
||||
#include "bmp280.h"
|
||||
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
|
||||
|
||||
enum BMP280_BUS {
|
||||
BMP280_BUS_ALL = 0,
|
||||
BMP280_BUS_I2C_INTERNAL,
|
||||
|
||||
@@ -38,6 +38,23 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <math.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <drivers/device/spi.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <px4_config.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
|
||||
#define BMP280_ADDR_CAL 0x88 /* address of 12x 2 bytes calibration data */
|
||||
#define BMP280_ADDR_DATA 0xF7 /* address of 2x 3 bytes p-t data */
|
||||
|
||||
|
||||
@@ -37,12 +37,8 @@
|
||||
* SPI interface for BMP280
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include "bmp280.h"
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#if defined(PX4_I2C_OBDEV_BMP280) || defined(PX4_I2C_EXT_OBDEV_BMP280)
|
||||
|
||||
|
||||
@@ -37,12 +37,8 @@
|
||||
* SPI interface for BMP280
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include "bmp280.h"
|
||||
#include <drivers/device/spi.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
/* SPI protocol address bits */
|
||||
#define DIR_READ (1<<7) //for set
|
||||
|
||||
@@ -39,8 +39,6 @@
|
||||
|
||||
#include "LPS22HB.hpp"
|
||||
|
||||
#include <cstring>
|
||||
|
||||
/* Max measurement rate is 25Hz */
|
||||
#define LPS22HB_CONVERSION_INTERVAL (1000000 / 25) /* microseconds */
|
||||
|
||||
|
||||
@@ -33,22 +33,19 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <cstring>
|
||||
|
||||
#include <drivers/device/Device.hpp>
|
||||
#include <px4_config.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
|
||||
#include <perf/perf_counter.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/device/spi.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <drivers/drv_device.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include <float.h>
|
||||
|
||||
static constexpr uint8_t WHO_AM_I = 0x0F;
|
||||
static constexpr uint8_t LPS22HB_ID_WHO_AM_I = 0xB1;
|
||||
|
||||
@@ -39,15 +39,6 @@
|
||||
|
||||
#include "LPS22HB.hpp"
|
||||
|
||||
#include <cstring>
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_device.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#define LPS22HB_ADDRESS 0x5D
|
||||
|
||||
device::Device *LPS22HB_I2C_interface(int bus);
|
||||
|
||||
@@ -39,13 +39,6 @@
|
||||
|
||||
#include "LPS22HB.hpp"
|
||||
|
||||
#include <cstring>
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/spi.h>
|
||||
#include <drivers/drv_device.h>
|
||||
|
||||
#ifdef PX4_SPIDEV_LPS22HB
|
||||
|
||||
/* SPI protocol address bits */
|
||||
|
||||
@@ -33,10 +33,6 @@
|
||||
|
||||
#include "LPS22HB.hpp"
|
||||
|
||||
#include <px4_getopt.h>
|
||||
|
||||
#include <cstring>
|
||||
|
||||
extern "C" __EXPORT int lps22hb_main(int argc, char *argv[]);
|
||||
|
||||
enum LPS22HB_BUS {
|
||||
|
||||
@@ -37,44 +37,6 @@
|
||||
* Driver for the LPS25H barometer connected via I2C or SPI.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <drivers/device/Device.hpp>
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <drivers/drv_device.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include <float.h>
|
||||
#include <px4_getopt.h>
|
||||
|
||||
#include "lps25h.h"
|
||||
|
||||
/*
|
||||
|
||||
@@ -39,6 +39,21 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include <drivers/device/Device.hpp>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <drivers/device/spi.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <systemlib/err.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
|
||||
#define ADDR_WHO_AM_I 0x0F
|
||||
|
||||
#define ID_WHO_AM_I 0xBD
|
||||
|
||||
@@ -37,28 +37,8 @@
|
||||
* I2C interface for LPS25H
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_mag.h>
|
||||
#include <drivers/drv_device.h>
|
||||
|
||||
#include "lps25h.h"
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#define LPS25H_ADDRESS 0x5D
|
||||
|
||||
device::Device *LPS25H_I2C_interface(int bus);
|
||||
|
||||
@@ -37,26 +37,7 @@
|
||||
* SPI interface for LPS25H
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/device/spi.h>
|
||||
#include <drivers/drv_mag.h>
|
||||
#include <drivers/drv_device.h>
|
||||
|
||||
#include "lps25h.h"
|
||||
#include <board_config.h>
|
||||
|
||||
#ifdef PX4_SPIDEV_HMC
|
||||
|
||||
|
||||
@@ -37,44 +37,8 @@
|
||||
* Driver for the MPL3115A2 barometric pressure sensor connected via I2C.
|
||||
*/
|
||||
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <drivers/device/Device.hpp>
|
||||
#include <px4_config.h>
|
||||
#include <px4_log.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
#include <px4_getopt.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include "mpl3115a2.h"
|
||||
|
||||
|
||||
|
||||
enum MPL3115A2_BUS {
|
||||
MPL3115A2_BUS_ALL = 0,
|
||||
MPL3115A2_BUS_I2C_INTERNAL,
|
||||
|
||||
@@ -38,6 +38,40 @@
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <semaphore.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <sys/types.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <board_config.h>
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/device/Device.hpp>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/clock.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_log.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#define MPL3115A2_REG_WHO_AM_I 0x0c
|
||||
#define MPL3115A2_WHO_AM_I 0xC4
|
||||
|
||||
@@ -37,25 +37,8 @@
|
||||
* I2C interface for MPL3115A2
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include "mpl3115a2.h"
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#define MPL3115A2_ADDRESS 0x60
|
||||
|
||||
device::Device *MPL3115A2_i2c_interface(uint8_t busnum);
|
||||
|
||||
@@ -36,32 +36,6 @@
|
||||
* Driver for the MS5611 and MS5607 barometric pressure sensor connected via I2C or SPI.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <platforms/px4_getopt.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
|
||||
#include "ms5611.h"
|
||||
|
||||
enum MS56XX_DEVICE_TYPES {
|
||||
|
||||
@@ -37,6 +37,24 @@
|
||||
* Shared defines for the ms5611 driver.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <drivers/device/spi.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <platforms/px4_getopt.h>
|
||||
#include <px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <systemlib/err.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
|
||||
#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
|
||||
|
||||
|
||||
@@ -37,26 +37,8 @@
|
||||
* I2C interface for MS5611
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
#include <px4_time.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include "ms5611.h"
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
|
||||
#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
|
||||
|
||||
|
||||
@@ -37,23 +37,7 @@
|
||||
* SPI interface for MS5611
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <px4_time.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/device/spi.h>
|
||||
|
||||
#include "ms5611.h"
|
||||
#include "board_config.h"
|
||||
|
||||
/* SPI protocol address bits */
|
||||
#define DIR_READ (1<<7)
|
||||
|
||||
Reference in New Issue
Block a user