mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_InertialSensor: sanitize includes
Due to the way the headers are organized changing a single change in an inertial sensor driver would trigger a rebuild for most of the files in the project. Time could be saved by using ccache (since most of the things didn't change) but we can do better, i.e. re-organize the headers so we don't have to re-build everything. With this patch only AP_InertialSensor/AP_InertialSensor.h is exposed to most users. There are some corner cases to integrate with some example code, but most of the places now depend only on this header and this header doesn't depend on the specific backends. Now changing a single header, e.g. AP_InertialSensor_L3G4200D.h triggers a rebuild only of these files: $ waf copter 'copter' finished successfully (0.000s) Waf: Entering directory `/home/lucas/p/dronecode/ardupilot/build/minlure' [ 80/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor.cpp [ 84/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp [310/370] Linking build/minlure/ArduCopter/libArduCopter_libs.a [370/370] Linking build/minlure/bin/arducopter Waf: Leaving directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
This commit is contained in:
parent
1ca03006ad
commit
9c6bd38e91
@ -2,13 +2,24 @@
|
||||
|
||||
#include <assert.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
#include "AP_InertialSensor_Flymaple.h"
|
||||
#include "AP_InertialSensor_HIL.h"
|
||||
#include "AP_InertialSensor_L3G4200D.h"
|
||||
#include "AP_InertialSensor_LSM9DS0.h"
|
||||
#include "AP_InertialSensor_MPU6000.h"
|
||||
#include "AP_InertialSensor_MPU9250.h"
|
||||
#include "AP_InertialSensor_PX4.h"
|
||||
#include "AP_InertialSensor_QURT.h"
|
||||
#include "AP_InertialSensor_SITL.h"
|
||||
#include "AP_InertialSensor_qflight.h"
|
||||
|
||||
/*
|
||||
enable TIMING_DEBUG to track down scheduling issues with the main
|
||||
|
@ -1,7 +1,5 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_H__
|
||||
#define __AP_INERTIAL_SENSOR_H__
|
||||
#pragma once
|
||||
|
||||
// Gyro and Accelerometer calibration criteria
|
||||
#define AP_INERTIAL_SENSOR_ACCEL_TOT_MAX_OFFSET_CHANGE 4.0f
|
||||
@ -20,12 +18,12 @@
|
||||
#define INS_VIBRATION_CHECK_INSTANCES 2
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <AP_AccelCal/AP_AccelCal.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_AccelCal/AP_AccelCal.h>
|
||||
#include "AP_InertialSensor_UserInteract.h"
|
||||
#include <Filter/LowPassFilter.h>
|
||||
#include <Filter/LowPassFilter2p.h>
|
||||
#include <Filter/LowPassFilter.h>
|
||||
|
||||
class AP_InertialSensor_Backend;
|
||||
class AuxiliaryBus;
|
||||
@ -427,19 +425,3 @@ private:
|
||||
|
||||
bool _accel_cal_requires_reboot;
|
||||
};
|
||||
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
#include "AP_InertialSensor_MPU6000.h"
|
||||
#include "AP_InertialSensor_PX4.h"
|
||||
#include "AP_InertialSensor_MPU9250.h"
|
||||
#include "AP_InertialSensor_L3G4200D.h"
|
||||
#include "AP_InertialSensor_Flymaple.h"
|
||||
#include "AP_InertialSensor_LSM9DS0.h"
|
||||
#include "AP_InertialSensor_HIL.h"
|
||||
#include "AP_InertialSensor_SITL.h"
|
||||
#include "AP_InertialSensor_qflight.h"
|
||||
#include "AP_InertialSensor_QURT.h"
|
||||
#include "AP_InertialSensor_UserInteract_Stream.h"
|
||||
#include "AP_InertialSensor_UserInteract_MAVLink.h"
|
||||
|
||||
#endif // __AP_INERTIAL_SENSOR_H__
|
||||
|
@ -21,10 +21,16 @@
|
||||
Note that drivers can implement just gyros or just accels, and can
|
||||
also provide multiple gyro/accel instances.
|
||||
*/
|
||||
#ifndef __AP_INERTIALSENSOR_BACKEND_H__
|
||||
#define __AP_INERTIALSENSOR_BACKEND_H__
|
||||
#pragma once
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
|
||||
class AuxiliaryBus;
|
||||
class DataFlash_Class;
|
||||
|
||||
class AP_InertialSensor_Backend
|
||||
{
|
||||
@ -147,5 +153,3 @@ protected:
|
||||
// function which instantiates an instance of the backend sensor
|
||||
// driver if the sensor is available
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIALSENSOR_BACKEND_H__
|
||||
|
@ -1,15 +1,15 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_FLYMAPLE_H__
|
||||
#define __AP_INERTIAL_SENSOR_FLYMAPLE_H__
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include <Filter/Filter.h>
|
||||
#include <Filter/LowPassFilter2p.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
||||
class AP_InertialSensor_Flymaple : public AP_InertialSensor_Backend
|
||||
{
|
||||
public:
|
||||
@ -34,4 +34,3 @@ private:
|
||||
uint32_t _last_accel_timestamp;
|
||||
};
|
||||
#endif
|
||||
#endif // __AP_INERTIAL_SENSOR_FLYMAPLE_H__
|
||||
|
@ -1,9 +1,8 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __AP_INERTIALSENSOR_HIL_H__
|
||||
#define __AP_INERTIALSENSOR_HIL_H__
|
||||
#pragma once
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
||||
class AP_InertialSensor_HIL : public AP_InertialSensor_Backend
|
||||
{
|
||||
@ -19,5 +18,3 @@ public:
|
||||
private:
|
||||
bool _init_sensor(void);
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIALSENSOR_HIL_H__
|
||||
|
@ -4,12 +4,11 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include <pthread.h>
|
||||
|
||||
#include <Filter/Filter.h>
|
||||
#include <Filter/LowPassFilter2p.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
||||
class AP_InertialSensor_L3G4200D : public AP_InertialSensor_Backend
|
||||
{
|
||||
|
@ -1,11 +1,11 @@
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_LSM9DS0_H__
|
||||
#define __AP_INERTIAL_SENSOR_LSM9DS0_H__
|
||||
#pragma once
|
||||
|
||||
#define LSM9DS0_DEBUG 0
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
||||
class AP_InertialSensor_LSM9DS0 : public AP_InertialSensor_Backend
|
||||
{
|
||||
@ -90,5 +90,3 @@ private:
|
||||
void _dump_registers();
|
||||
#endif
|
||||
};
|
||||
|
||||
#endif /* __AP_INERTIAL_SENSOR_LSM9DS0_H__ */
|
||||
|
@ -12,6 +12,7 @@
|
||||
#include <Filter/LowPassFilter.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
#include "AuxiliaryBus.h"
|
||||
|
||||
// enable debug to see a register dump on startup
|
||||
|
@ -1,13 +1,14 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_MPU9250_H__
|
||||
#define __AP_INERTIAL_SENSOR_MPU9250_H__
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <Filter/Filter.h>
|
||||
#include <Filter/LowPassFilter2p.h>
|
||||
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AuxiliaryBus.h"
|
||||
|
||||
@ -164,5 +165,3 @@ private:
|
||||
|
||||
uint8_t _ext_sens_data = 0;
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIAL_SENSOR_MPU9250_H__
|
||||
|
@ -1,12 +1,11 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_PX4_H__
|
||||
#define __AP_INERTIAL_SENSOR_PX4_H__
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
#include <drivers/drv_accel.h>
|
||||
#include <drivers/drv_gyro.h>
|
||||
#include <uORB/uORB.h>
|
||||
@ -70,5 +69,4 @@ private:
|
||||
float _accel_dt_max[INS_MAX_INSTANCES];
|
||||
#endif // AP_INERTIALSENSOR_PX4_DEBUG
|
||||
};
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif // __AP_INERTIAL_SENSOR_PX4_H__
|
||||
#endif
|
||||
|
@ -1,12 +1,15 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_QURT
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
||||
extern "C" {
|
||||
#undef DEG_TO_RAD
|
||||
#include "mpu9x50.h"
|
||||
#include <mpu9x50.h>
|
||||
}
|
||||
#include <AP_HAL/utility/RingBuffer.h>
|
||||
|
||||
@ -39,4 +42,4 @@ private:
|
||||
ObjectBuffer<mpu9x50_data> buf{100};
|
||||
};
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif
|
||||
|
@ -1,10 +1,10 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#pragma once
|
||||
|
||||
#ifndef __AP_INERTIALSENSOR_SITL_H__
|
||||
#define __AP_INERTIALSENSOR_SITL_H__
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include <SITL/SITL.h>
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
||||
#define INS_SITL_INSTANCES 2
|
||||
|
||||
@ -30,5 +30,3 @@ private:
|
||||
uint8_t gyro_instance[INS_SITL_INSTANCES];
|
||||
uint8_t accel_instance[INS_SITL_INSTANCES];
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIALSENSOR_SITL_H__
|
||||
|
@ -1,6 +1,4 @@
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_H__
|
||||
#define __AP_INERTIAL_SENSOR_USER_INTERACT_H__
|
||||
#pragma once
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
@ -10,6 +8,3 @@ public:
|
||||
virtual bool blocking_read() = 0;
|
||||
virtual void printf(const char *, ...) FMT_PRINTF(2, 3) = 0;
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIAL_SENSOR_USER_INTERACT_H__
|
||||
|
||||
|
@ -1,13 +1,12 @@
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_MAVLINK_H__
|
||||
#define __AP_INERTIAL_SENSOR_USER_INTERACT_MAVLINK_H__
|
||||
|
||||
#include "AP_InertialSensor_UserInteract.h"
|
||||
#pragma once
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
|
||||
#include "AP_InertialSensor_UserInteract.h"
|
||||
|
||||
class GCS_MAVLINK;
|
||||
|
||||
/**
|
||||
@ -23,6 +22,3 @@ public:
|
||||
private:
|
||||
GCS_MAVLINK *_gcs;
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIAL_SENSOR_USER_INTERACT_MAVLINK_H__
|
||||
|
||||
|
@ -1,16 +1,14 @@
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
|
||||
#define __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
|
||||
#pragma once
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_InertialSensor_UserInteract.h"
|
||||
|
||||
/**
|
||||
* AP_InertialSensor_UserInteract, implemented in terms of a BetterStream.
|
||||
*/
|
||||
class AP_InertialSensor_UserInteractStream :
|
||||
public AP_InertialSensor_UserInteract {
|
||||
class AP_InertialSensor_UserInteractStream : public AP_InertialSensor_UserInteract {
|
||||
public:
|
||||
AP_InertialSensor_UserInteractStream(AP_HAL::BetterStream *s) :
|
||||
_s(s) {}
|
||||
@ -20,6 +18,3 @@ public:
|
||||
private:
|
||||
AP_HAL::BetterStream *_s;
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
|
||||
|
||||
|
@ -1,12 +1,14 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
||||
|
||||
#include <AP_HAL_Linux/qflight/qflight_buffer.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
||||
class AP_InertialSensor_QFLIGHT : public AP_InertialSensor_Backend
|
||||
{
|
||||
public:
|
||||
@ -27,4 +29,4 @@ private:
|
||||
DSPBuffer::IMU *imubuf;
|
||||
};
|
||||
|
||||
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user