AP_InertialSensor: standardize inclusion of libaries headers

This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
This commit is contained in:
Gustavo Jose de Sousa 2015-08-11 16:28:43 +10:00 committed by Randy Mackay
parent 94cafc8a51
commit 785dc36f20
27 changed files with 125 additions and 125 deletions

View File

@ -1,13 +1,13 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_Progmem.h>
#include <AP_Progmem/AP_Progmem.h>
#include "AP_InertialSensor.h"
#include <AP_Common.h>
#include <AP_HAL.h>
#include <AP_Notify.h>
#include <AP_Vehicle.h>
#include <AP_Math.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_Math/AP_Math.h>
/*
enable TIMING_DEBUG to track down scheduling issues with the main

View File

@ -26,10 +26,10 @@
#include <stdint.h>
#include <AP_HAL.h>
#include <AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include "AP_InertialSensor_UserInteract.h"
#include <LowPassFilter.h>
#include <Filter/LowPassFilter.h>
class AP_InertialSensor_Backend;

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor.h"
#include "AP_InertialSensor_Backend.h"

View File

@ -21,7 +21,7 @@
// ITG3205 Gyroscope http://www.sparkfun.com/datasheets/Sensors/Gyro/PS-ITG-3200-00-01.4.pdf
// ADXL345 Accelerometer http://www.analog.com/static/imported-files/data_sheets/ADXL345.pdf
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
#include "AP_InertialSensor_Flymaple.h"

View File

@ -3,12 +3,12 @@
#ifndef __AP_INERTIAL_SENSOR_FLYMAPLE_H__
#define __AP_INERTIAL_SENSOR_FLYMAPLE_H__
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
#include "AP_InertialSensor.h"
#include <Filter.h>
#include <LowPassFilter2p.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
class AP_InertialSensor_Flymaple : public AP_InertialSensor_Backend
{

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor_HIL.h"
const extern AP_HAL::HAL& hal;

View File

@ -28,10 +28,10 @@ Datasheets:
L3G4200D gyro http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00265057.pdf
*/
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <AP_Math.h>
#include <AP_Math/AP_Math.h>
#include "AP_InertialSensor_L3G4200D.h"
#include <stdio.h>
#include <unistd.h>

View File

@ -3,14 +3,14 @@
#ifndef __AP_INERTIAL_SENSOR_L3G4200D_H__
#define __AP_INERTIAL_SENSOR_L3G4200D_H__
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <pthread.h>
#include "AP_InertialSensor.h"
#include <Filter.h>
#include <LowPassFilter2p.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
class AP_InertialSensor_L3G4200D : public AP_InertialSensor_Backend
{

View File

@ -15,7 +15,7 @@
* -- Adapted from Victor Mayoral Vilches's legacy driver under folder LSM9DS0
*/
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX

View File

@ -4,7 +4,7 @@
#define LSM9DS0_DEBUG 0
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor.h"
class AP_InertialSensor_LSM9DS0 : public AP_InertialSensor_Backend

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor_MPU6000.h"
extern const AP_HAL::HAL& hal;

View File

@ -4,9 +4,9 @@
#define __AP_INERTIAL_SENSOR_MPU6000_H__
#include <stdint.h>
#include <AP_HAL.h>
#include <AP_Math.h>
#include <AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Progmem/AP_Progmem.h>
#include "AP_InertialSensor.h"
// enable debug to see a register dump on startup
@ -20,8 +20,8 @@
#endif
#if MPU6000_FAST_SAMPLING
#include <Filter.h>
#include <LowPassFilter2p.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
#endif
#define MPU6000_SAMPLE_SIZE 12

View File

@ -25,10 +25,10 @@
unmaintained
*/
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <AP_Math.h>
#include <AP_Math/AP_Math.h>
#include "AP_InertialSensor_MPU9150.h"
#include <stdio.h>
#include <unistd.h>

View File

@ -3,13 +3,13 @@
#ifndef __AP_INERTIAL_SENSOR_MPU9150_H__
#define __AP_INERTIAL_SENSOR_MPU9150_H__
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <AP_Progmem.h>
#include <AP_Progmem/AP_Progmem.h>
#include "AP_InertialSensor.h"
#include <Filter.h>
#include <LowPassFilter2p.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
class AP_InertialSensor_MPU9150 : public AP_InertialSensor_Backend

View File

@ -16,7 +16,7 @@
-- Coded by Victor Mayoral Vilches --
*/
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include "AP_InertialSensor_MPU9250.h"

View File

@ -4,11 +4,11 @@
#define __AP_INERTIAL_SENSOR_MPU9250_H__
#include <stdint.h>
#include <AP_HAL.h>
#include <AP_Math.h>
#include <AP_Progmem.h>
#include <Filter.h>
#include <LowPassFilter2p.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Progmem/AP_Progmem.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
#include "AP_InertialSensor.h"
// enable debug to see a register dump on startup

View File

@ -1,10 +1,10 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
#include "AP_InertialSensor_Oilpan.h"
#include <AP_ADC.h>
#include <AP_ADC/AP_ADC.h>
const extern AP_HAL::HAL& hal;

View File

@ -3,7 +3,7 @@
#ifndef __AP_INERTIAL_SENSOR_OILPAN_H__
#define __AP_INERTIAL_SENSOR_OILPAN_H__
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor.h"
class AP_InertialSensor_Oilpan : public AP_InertialSensor_Backend

View File

@ -1,13 +1,13 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#include "AP_InertialSensor_PX4.h"
const extern AP_HAL::HAL& hal;
#include <DataFlash.h>
#include <DataFlash/DataFlash.h>
#include <sys/types.h>
#include <sys/stat.h>

View File

@ -3,18 +3,18 @@
#ifndef __AP_INERTIAL_SENSOR_PX4_H__
#define __AP_INERTIAL_SENSOR_PX4_H__
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#include <AP_Progmem.h>
#include <AP_Progmem/AP_Progmem.h>
#include "AP_InertialSensor.h"
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <Filter.h>
#include <LowPassFilter2p.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
class AP_InertialSensor_PX4 : public AP_InertialSensor_Backend
{

View File

@ -2,7 +2,7 @@
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_H__
#define __AP_INERTIAL_SENSOR_USER_INTERACT_H__
#include <AP_Progmem.h>
#include <AP_Progmem/AP_Progmem.h>
/* Pure virtual interface class */
class AP_InertialSensor_UserInteract {

View File

@ -1,10 +1,10 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <stdarg.h>
#include <AP_HAL.h>
#include <GCS_MAVLink.h>
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include "AP_InertialSensor_UserInteract_MAVLink.h"
#include <GCS.h>
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal;

View File

@ -2,8 +2,8 @@
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_MAVLINK_H__
#define __AP_INERTIAL_SENSOR_USER_INTERACT_MAVLINK_H__
#include <AP_HAL.h>
#include <GCS_MAVLink.h>
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include "AP_InertialSensor_UserInteract.h"
class GCS_MAVLINK;

View File

@ -1,5 +1,5 @@
#include <stdarg.h>
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor_UserInteract_Stream.h"
extern const AP_HAL::HAL& hal;

View File

@ -2,7 +2,7 @@
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
#define __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor_UserInteract.h"
/**

View File

@ -5,41 +5,41 @@
//
#include <stdarg.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_FLYMAPLE.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Empty.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <StorageManager.h>
#include <AP_ADC.h>
#include <AP_InertialSensor.h>
#include <AP_Notify.h>
#include <AP_GPS.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <DataFlash.h>
#include <GCS_MAVLink.h>
#include <AP_Mission.h>
#include <StorageManager.h>
#include <AP_Terrain.h>
#include <AP_AHRS.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_NavEKF.h>
#include <AP_HAL_Linux.h>
#include <AP_Rally.h>
#include <AP_Scheduler.h>
#include <AP_BattMonitor.h>
#include <AP_RangeFinder.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
#include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <AP_ADC/AP_ADC.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <Filter/Filter.h>
#include <DataFlash/DataFlash.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission/AP_Mission.h>
#include <StorageManager/StorageManager.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_Declination/AP_Declination.h>
#include <AP_NavEKF/AP_NavEKF.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;

View File

@ -5,39 +5,39 @@
//
#include <stdarg.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Empty.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <AP_ADC.h>
#include <AP_InertialSensor.h>
#include <AP_Notify.h>
#include <AP_GPS.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <DataFlash.h>
#include <GCS_MAVLink.h>
#include <AP_Mission.h>
#include <StorageManager.h>
#include <AP_Terrain.h>
#include <AP_AHRS.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Compass.h>
#include <AP_Scheduler.h>
#include <AP_Declination.h>
#include <AP_Notify.h>
#include <AP_NavEKF.h>
#include <AP_BattMonitor.h>
#include <AP_RangeFinder.h>
#include <AP_Rally.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_ADC/AP_ADC.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <Filter/Filter.h>
#include <DataFlash/DataFlash.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission/AP_Mission.h>
#include <StorageManager/StorageManager.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_Declination/AP_Declination.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_NavEKF/AP_NavEKF.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Rally/AP_Rally.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4