Delete unnecessary #includes from the imu driver directory.

This commit is contained in:
mcsauder 2019-07-08 09:21:56 -06:00 committed by Daniel Agar
parent be414f7ab1
commit b495ddbdd3
42 changed files with 178 additions and 327 deletions

View File

@ -42,15 +42,15 @@
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <ecl/geo/geo.h>
#include <perf/perf_counter.h>
#include <drivers/device/spi.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <conversion/rotation.h>
#include <ecl/geo/geo.h>
#include <lib/conversion/rotation.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/barometer/PX4Barometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
#include <perf/perf_counter.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
using namespace time_literals;

View File

@ -33,9 +33,6 @@
#include "ADIS16477.hpp"
#include <px4_config.h>
#include <ecl/geo/geo.h>
#define DIR_READ 0x00
#define DIR_WRITE 0x80

View File

@ -39,12 +39,13 @@
#pragma once
#include <drivers/device/spi.h>
#include <lib/conversion/rotation.h>
#include <perf/perf_counter.h>
#include <ecl/geo/geo.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/conversion/rotation.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
class ADIS16477 : public device::SPI, public px4::ScheduledWorkItem
{

View File

@ -33,8 +33,6 @@
#include "ADIS16477.hpp"
#include <px4_getopt.h>
extern "C" { __EXPORT int adis16477_main(int argc, char *argv[]); }
/**

View File

@ -33,9 +33,6 @@
#include "ADIS16497.hpp"
#include <px4_config.h>
#include <ecl/geo/geo.h>
#define DIR_READ 0x00
#define DIR_WRITE 0x80

View File

@ -39,12 +39,13 @@
#pragma once
#include <drivers/device/spi.h>
#include <lib/conversion/rotation.h>
#include <perf/perf_counter.h>
#include <ecl/geo/geo.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/conversion/rotation.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
// TODO : This is a copy of the NuttX CRC32 table
static constexpr uint32_t crc32_tab[] = {

View File

@ -33,8 +33,6 @@
#include "ADIS16497.hpp"
#include <px4_getopt.h>
extern "C" { __EXPORT int adis16497_main(int argc, char *argv[]); }
/**

View File

@ -33,14 +33,10 @@
#pragma once
#include <drivers/device/integrator.h>
#include <drivers/device/spi.h>
#include <drivers/drv_hrt.h>
#include <lib/conversion/rotation.h>
#include <ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_config.h>
#include <systemlib/conversions.h>
#include <systemlib/err.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#define DIR_READ 0x80

View File

@ -33,8 +33,6 @@
#include "BMI055_accel.hpp"
#include <ecl/geo/geo.h>
/*
list of registers that will be checked in check_registers(). Note
that ADDR_WHO_AM_I must be first in the list.

View File

@ -33,15 +33,9 @@
#pragma once
#include "BMI055.hpp"
#include <drivers/device/spi.h>
#include <drivers/drv_hrt.h>
#include <lib/conversion/rotation.h>
#include <lib/perf/perf_counter.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <px4_config.h>
#include <systemlib/conversions.h>
#include "BMI055.hpp"
#define BMI055_DEVICE_PATH_ACCEL "/dev/bmi055_accel"
#define BMI055_DEVICE_PATH_ACCEL_EXT "/dev/bmi055_accel_ext"

View File

@ -33,15 +33,9 @@
#pragma once
#include "BMI055.hpp"
#include <drivers/device/spi.h>
#include <drivers/drv_hrt.h>
#include <lib/conversion/rotation.h>
#include <lib/perf/perf_counter.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <px4_config.h>
#include <systemlib/conversions.h>
#include "BMI055.hpp"
#define BMI055_DEVICE_PATH_GYRO "/dev/bmi055_gyro"
#define BMI055_DEVICE_PATH_GYRO_EXT "/dev/bmi055_gyro_ext"

View File

@ -34,9 +34,6 @@
#include "BMI055_accel.hpp"
#include "BMI055_gyro.hpp"
#include <px4_config.h>
#include <px4_getopt.h>
/** driver 'main' command */
extern "C" { __EXPORT int bmi055_main(int argc, char *argv[]); }

View File

@ -1,5 +1,37 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "bmi160.hpp"
#include <ecl/geo/geo.h>
/*
list of registers that will be checked in check_registers(). Note

View File

@ -1,15 +1,47 @@
#ifndef BMI160_HPP_
#define BMI160_HPP_
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <px4_config.h>
#include <perf/perf_counter.h>
#include <systemlib/conversions.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <ecl/geo/geo.h>
#include <lib/conversion/rotation.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/conversions.h>
#define DIR_READ 0x80
#define DIR_WRITE 0x00
@ -379,7 +411,3 @@ private:
};
#pragma pack(pop)
};
#endif /* BMI160_HPP_ */

View File

@ -1,9 +1,38 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "bmi160.hpp"
#include <px4_config.h>
#include <px4_getopt.h>
/** driver 'main' command */
extern "C" { __EXPORT int bmi160_main(int argc, char *argv[]); }

View File

@ -33,12 +33,6 @@
#include "FXAS21002C.hpp"
#include <drivers/drv_hrt.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
/* SPI protocol address bits */
#define DIR_READ(a) ((a) | (1 << 7))
#define DIR_WRITE(a) ((a) & 0x7f)

View File

@ -40,14 +40,12 @@
#pragma once
#include <drivers/device/spi.h>
#include <drivers/drv_hrt.h>
#include <lib/conversion/rotation.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
class FXAS21002C : public device::SPI, public px4::ScheduledWorkItem
{
public:

View File

@ -33,10 +33,6 @@
#include "FXAS21002C.hpp"
#include <px4_getopt.h>
#include <px4_config.h>
#include <px4_defines.h>
extern "C" { __EXPORT int fxas21002c_main(int argc, char *argv[]); }
/**

View File

@ -37,48 +37,21 @@
* magnetometer connected via SPI.
*/
#include <px4_config.h>
#include <px4_defines.h>
#include <ecl/geo/geo.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <stdint.h>
#include <stdbool.h>
#include <stddef.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_log.h>
#include <perf/perf_counter.h>
#include <nuttx/arch.h>
#include <nuttx/clock.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/integrator.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/spi.h>
#include <drivers/drv_accel.h>
#include <ecl/geo/geo.h>
#include <lib/conversion/rotation.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)
# include <drivers/drv_mag.h>
#endif
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include <px4_getopt.h>
#include <systemlib/err.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
/* SPI protocol address bits */
#define DIR_READ(a) ((a) & 0x7f)

View File

@ -41,33 +41,9 @@
* based on the mpu6000 driver
*/
#include <px4_config.h>
#include <ecl/geo/geo.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <stddef.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <perf/perf_counter.h>
#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include "mag.h"
#include "gyro.h"
#include "accel.h"
#include "icm20948.h"
ICM20948_accel::ICM20948_accel(ICM20948 *parent, const char *path) :

View File

@ -33,6 +33,10 @@
#pragma once
#include <drivers/device/device.h>
#include <drivers/drv_accel.h>
#include <uORB/uORB.h>
class ICM20948;
/**

View File

@ -40,18 +40,6 @@
* based on the mpu9250 driver
*/
#include <px4_config.h>
#include <lib/perf/perf_counter.h>
#include <drivers/device/spi.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <lib/mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include "mag.h"
#include "gyro.h"
#include "icm20948.h"

View File

@ -33,6 +33,10 @@
#pragma once
#include <drivers/device/device.h>
#include <drivers/drv_gyro.h>
#include <uORB/uORB.h>
class ICM20948;
/**

View File

@ -36,29 +36,9 @@
*
* Driver for the Invensense ICM20948 connected via I2C or SPI.
*
*
* based on the mpu9250 driver
*/
#include <px4_config.h>
#include <px4_time.h>
#include <lib/ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <systemlib/conversions.h>
#include <systemlib/px4_macros.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <lib/mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include "mag.h"
#include "accel.h"
#include "gyro.h"
#include "icm20948.h"
/*

View File

@ -31,30 +31,26 @@
*
****************************************************************************/
#include <stdint.h>
#include <perf/perf_counter.h>
#include <systemlib/conversions.h>
#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include <systemlib/err.h>
#include <lib/ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <sys/types.h>
#include <systemlib/conversions.h>
#include <systemlib/err.h>
#include <systemlib/px4_macros.h>
#include <uORB/uORB.h>
#include <uORB/topics/debug_key_value.h>
#include "mag.h"
#include "accel.h"
#include "gyro.h"
#include "mag.h"
#if defined(PX4_I2C_OBDEV_MPU9250) || defined(PX4_I2C_BUS_EXPANSION)

View File

@ -37,10 +37,7 @@
* I2C interface for ICM20948
*/
#include <px4_config.h>
#include <drivers/device/i2c.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_device.h>
#include "icm20948.h"

View File

@ -41,10 +41,7 @@
* @author David sidrane
*/
#include <px4_config.h>
#include <drivers/device/spi.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_device.h>
#include "icm20948.h"

View File

@ -40,20 +40,6 @@
*
*/
#include <px4_config.h>
#include <px4_log.h>
#include <px4_time.h>
#include <lib/perf/perf_counter.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <lib/mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include "mag.h"
#include "icm20948.h"

View File

@ -33,9 +33,12 @@
#pragma once
#include "drivers/device/ringbuffer.h" // ringbuffer::RingBuffer
#include "drivers/drv_mag.h" // mag_calibration_s
#include <perf/perf_counter.h>
#include <drivers/device/i2c.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/drv_device.h>
#include <drivers/drv_mag.h>
#include <lib/perf/perf_counter.h>
#include <uORB/uORB.h>
/* in 16-bit sampling mode the mag resolution is 1.5 milli Gauss per bit */

View File

@ -37,11 +37,6 @@
* I2C interface for AK8963
*/
#include <px4_config.h>
#include <drivers/device/i2c.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_device.h>
#include "icm20948.h"
#include "mag.h"

View File

@ -39,33 +39,6 @@
* based on the mpu9250 driver
*/
#include <px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include <fcntl.h>
#include <errno.h>
#include <stdio.h>
#include <px4_getopt.h>
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <systemlib/conversions.h>
#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include "icm20948.h"
#define ICM_DEVICE_PATH_ACCEL_EXT "/dev/icm20948_accel_ext"

View File

@ -39,14 +39,12 @@
* also supported by this driver.
*/
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <perf/perf_counter.h>
#include <drivers/device/spi.h>
#include <lib/conversion/rotation.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#define L3GD20_DEVICE_PATH "/dev/l3gd20"

View File

@ -36,43 +36,19 @@
* Driver for the ST LSM303D MEMS accelerometer / magnetometer connected via SPI.
*/
#include <px4_config.h>
#include <px4_defines.h>
#include <ecl/geo/geo.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <stdint.h>
#include <stdbool.h>
#include <stddef.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 <perf/perf_counter.h>
#include <systemlib/err.h>
#include <nuttx/arch.h>
#include <nuttx/clock.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/integrator.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/spi.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_mag.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <ecl/geo/geo.h>
#include <lib/conversion/rotation.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
/* SPI protocol address bits */
#define DIR_READ (1<<7)

View File

@ -55,21 +55,19 @@
* @author David Sidrane
*/
#include <drivers/drv_hrt.h>
#include <lib/cdev/CDev.hpp>
#include <lib/conversion/rotation.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/drivers/device/i2c.h>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_time.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/conversions.h>
#include <systemlib/px4_macros.h>
/*
we set the timer interrupt to run a bit faster than the desired
sample rate and then throw away duplicates by comparing

View File

@ -37,10 +37,7 @@
* I2C interface for MPU6000 /MPU6050
*/
#include <px4_config.h>
#include <drivers/device/i2c.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_device.h>
#include "MPU6000.hpp"

View File

@ -41,15 +41,10 @@
* @author David sidrane
*/
#include <px4_config.h>
#include <drivers/device/spi.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_device.h>
#include "MPU6000.hpp"
#include <string.h>
#define DIR_READ 0x80
#define DIR_WRITE 0x00

View File

@ -40,12 +40,6 @@
*
*/
#include <px4_config.h>
#include <px4_log.h>
#include <px4_time.h>
#include <lib/perf/perf_counter.h>
#include <drivers/drv_hrt.h>
#include "MPU9250_mag.h"
#include "mpu9250.h"

View File

@ -41,17 +41,6 @@
* based on the mpu6000 driver
*/
#include <px4_config.h>
#include <px4_time.h>
#include <lib/ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <systemlib/conversions.h>
#include <systemlib/px4_macros.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <lib/conversion/rotation.h>
#include "MPU9250_mag.h"
#include "mpu9250.h"
/*

View File

@ -31,19 +31,17 @@
*
****************************************************************************/
#include <stdint.h>
#include <perf/perf_counter.h>
#include <systemlib/conversions.h>
#include <drivers/drv_hrt.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/conversion/rotation.h>
#include <lib/ecl/geo/geo.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/uORB.h>
#include <systemlib/conversions.h>
#include <systemlib/px4_macros.h>
#include "MPU9250_mag.h"
#if defined(PX4_I2C_OBDEV_MPU9250) || defined(PX4_I2C_BUS_EXPANSION)
# define USE_I2C
#endif

View File

@ -37,9 +37,7 @@
* I2C interface for MPU9250
*/
#include <px4_config.h>
#include <drivers/device/i2c.h>
#include <drivers/drv_device.h>
#include "mpu9250.h"

View File

@ -42,15 +42,6 @@
* based on the mpu6000 driver
*/
#include <px4_config.h>
#include <px4_getopt.h>
#include <lib/perf/perf_counter.h>
#include <lib/systemlib/conversions.h>
#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <lib/conversion/rotation.h>
#include "mpu9250.h"
#define MPU_DEVICE_PATH "/dev/mpu9250"

View File

@ -41,10 +41,7 @@
* @author David sidrane
*/
#include <px4_config.h>
#include <drivers/device/spi.h>
#include <drivers/drv_device.h>
#include "mpu9250.h"
#define DIR_READ 0x80